From cf1a0125b0d4319a8301c86ae6dce6e2ee0ceb81 Mon Sep 17 00:00:00 2001 From: askuric Date: Sat, 11 Apr 2020 15:55:19 +0200 Subject: [PATCH 01/65] created minimal arduino code --- .github/workflows/ccpp.yml | 13 -- examples/HMBGC_example/HMBGC_example.ino | 123 --------------- examples/angle_control/angle_control.ino | 127 ---------------- .../angle_control_serial.ino | 142 ------------------ examples/encoder_example/encoder_example.ino | 33 ---- examples/minimal_example/minimal_example.ino | 48 ------ .../velocity_control/velocity_control.ino | 118 --------------- .../velocity_control_serial.ino | 137 ----------------- .../velocity_ultraslow_control_serial.ino | 137 ----------------- examples/voltage_control/voltage_control.ino | 112 -------------- extras/ArduinoFOCShieldV12.pdf | Bin 511087 -> 0 bytes extras/Images/AFSV11_bottom.png | Bin 103904 -> 0 bytes extras/Images/AFSV11_side.png | Bin 212429 -> 0 bytes extras/Images/AFSV11_top.png | Bin 150264 -> 0 bytes extras/Images/arduino_connection.png | Bin 322737 -> 0 bytes extras/Images/ebay.jpg | Bin 20098 -> 0 bytes extras/Images/ebay2.jpg | Bin 123479 -> 0 bytes extras/Images/hmbgc_connection.png | Bin 800471 -> 0 bytes extras/Images/pinout.jpg | Bin 211009 -> 0 bytes extras/Images/position.png | Bin 28731 -> 0 bytes extras/Images/setup1.jpg | Bin 154392 -> 0 bytes extras/Images/setup2.jpg | Bin 53955 -> 0 bytes extras/Images/velocity.png | Bin 21237 -> 0 bytes extras/Images/velocity_ultraslow_loop.png | Bin 21432 -> 0 bytes extras/Images/voltage.png | Bin 15230 -> 0 bytes keywords.txt | 60 -------- library.properties | 10 -- {src => minimal_example}/ArduinoFOC.h | 0 {src => minimal_example}/BLDCMotor.cpp | 0 {src => minimal_example}/BLDCMotor.h | 0 {src => minimal_example}/Encoder.cpp | 0 {src => minimal_example}/Encoder.h | 0 .../minimal_example.ino | 2 +- 33 files changed, 1 insertion(+), 1061 deletions(-) delete mode 100644 .github/workflows/ccpp.yml delete mode 100644 examples/HMBGC_example/HMBGC_example.ino delete mode 100644 examples/angle_control/angle_control.ino delete mode 100644 examples/angle_control_serial/angle_control_serial.ino delete mode 100644 examples/encoder_example/encoder_example.ino delete mode 100644 examples/minimal_example/minimal_example.ino delete mode 100644 examples/velocity_control/velocity_control.ino delete mode 100644 examples/velocity_control_serial/velocity_control_serial.ino delete mode 100644 examples/velocity_ultraslow_control_serial/velocity_ultraslow_control_serial.ino delete mode 100644 examples/voltage_control/voltage_control.ino delete mode 100644 extras/ArduinoFOCShieldV12.pdf delete mode 100644 extras/Images/AFSV11_bottom.png delete mode 100644 extras/Images/AFSV11_side.png delete mode 100644 extras/Images/AFSV11_top.png delete mode 100644 extras/Images/arduino_connection.png delete mode 100644 extras/Images/ebay.jpg delete mode 100644 extras/Images/ebay2.jpg delete mode 100644 extras/Images/hmbgc_connection.png delete mode 100644 extras/Images/pinout.jpg delete mode 100644 extras/Images/position.png delete mode 100644 extras/Images/setup1.jpg delete mode 100644 extras/Images/setup2.jpg delete mode 100644 extras/Images/velocity.png delete mode 100644 extras/Images/velocity_ultraslow_loop.png delete mode 100644 extras/Images/voltage.png delete mode 100644 keywords.txt delete mode 100644 library.properties rename {src => minimal_example}/ArduinoFOC.h (100%) rename {src => minimal_example}/BLDCMotor.cpp (100%) rename {src => minimal_example}/BLDCMotor.h (100%) rename {src => minimal_example}/Encoder.cpp (100%) rename {src => minimal_example}/Encoder.h (100%) rename examples/change_direction/change_direction.ino => minimal_example/minimal_example.ino (99%) diff --git a/.github/workflows/ccpp.yml b/.github/workflows/ccpp.yml deleted file mode 100644 index abe046f4..00000000 --- a/.github/workflows/ccpp.yml +++ /dev/null @@ -1,13 +0,0 @@ -name: Library Compile -on: push -jobs: - build: - name: Test compiling examples for UNO - runs-on: ubuntu-latest - steps: - - name: Checkout - uses: actions/checkout@master - - name: Compile all examples - uses: ArminJo/arduino-test-compile@v1.0.0 - with: - libraries: PciManager diff --git a/examples/HMBGC_example/HMBGC_example.ino b/examples/HMBGC_example/HMBGC_example.ino deleted file mode 100644 index 483514da..00000000 --- a/examples/HMBGC_example/HMBGC_example.ino +++ /dev/null @@ -1,123 +0,0 @@ -#include -#include -#include - - -// BLDCMotor( int phA, int phB, int phC, int pp, int en) -// - phA, phB, phC - motor A,B,C phase pwm pins -// - pp - pole pair number -// - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11); -// Encoder(int encA, int encB , int cpr, int index) -// - encA, encB - encoder A and B pins -// - ppr - impulses per rotation (cpr=ppr*4) -// - index pin - (optional input) -Encoder encoder = Encoder(A1, A0, 600); -// interrupt ruotine intialisation -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} - -// encoder interrupt init -PciListenerImp listenerA(encoder.pinA, doA); -PciListenerImp listenerB(encoder.pinB, doB); - -void setup() { - // debugging port - Serial.begin(115200); - - // check if you need internal pullups - // Pullup::EXTERN - external pullup added - dafault - // Pullup::INTERN - needs internal arduino pullup - encoder.pullup = Pullup::INTERN; - // initialise encoder hardware - encoder.init(); - - // interrupt intitialisation - PciManager.registerListener(&listenerA); - PciManager.registerListener(&listenerB); - - // set driver type - // DriverType::unipolar - // DriverType::bipolar - default - motor.driver = DriverType::unipolar; - - // power supply voltage - // default 12V - motor.power_supply_voltage = 12; - - // set FOC loop to be used - // ControlType::voltage - // ControlType::velocity - // ControlType::velocity_ultra_slow - // ControlType::angle - motor.controller = ControlType::velocity; - - // velocity PI controller parameters - // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 1; - motor.PI_velocity.Ti = 0.003; - - // link the motor to the sensor - motor.linkEncoder(&encoder); - - // intialise motor - motor.init(); - // align encoder and start FOC - motor.initFOC(); - - Serial.println("Motor ready."); - delay(1000); -} - -float velocity_sp; - -void loop() { - // iterative state calculation calculating angle - // and setting FOC pahse voltage - // the faster you run this funciton the better - // in arduino loop it should have ~1kHz - // the best would be to be in ~10kHz range - motor.loopFOC(); - - // 0.5 hertz sine weve - velocity_sp = sin( micros()*1e-6 *2*M_PI * 0.5 ); - - // iterative function setting the outter loop target - // velocity, position or voltage - // this funciton can be run at much lower frequency than loopFOC funciton - // it can go as low as ~50Hz - motor.move(velocity_sp); - - - // function intended to be used with serial plotter to monitor motor variables - // significantly slowing the execution down!!!! - motor_monitor(); -} - -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void motor_monitor() { - switch (motor.controller) { - case ControlType::velocity_ultra_slow: - case ControlType::velocity: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_velocity_sp); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - case ControlType::angle: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_angle_sp); - Serial.print("\t"); - Serial.println(motor.shaft_angle); - break; - case ControlType::voltage: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - } -} - diff --git a/examples/angle_control/angle_control.ino b/examples/angle_control/angle_control.ino deleted file mode 100644 index 3394bb7b..00000000 --- a/examples/angle_control/angle_control.ino +++ /dev/null @@ -1,127 +0,0 @@ -#include - -// Only pins 2 and 3 are supported -#define arduinoInt1 2 // Arduino UNO interrupt 0 -#define arduinoInt2 3 // Arduino UNO interrupt 1 - -// BLDCMotor( int phA, int phB, int phC, int pp, int en) -// - phA, phB, phC - motor A,B,C phase pwm pins -// - pp - pole pair number -// - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); -// Encoder(int encA, int encB , int cpr, int index) -// - encA, encB - encoder A and B pins -// - ppr - impulses per rotation (cpr=ppr*4) -// - index pin - (optional input) -Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 4); -// interrupt ruotine intialisation -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} - -void setup() { - // debugging port - Serial.begin(115200); - - // check if you need internal pullups - // Pullup::EXTERN - external pullup added - dafault - // Pullup::INTERN - needs internal arduino pullup - encoder.pullup = Pullup::EXTERN; - - // initialise encoder hardware - encoder.init(doA, doB); - - // set driver type - // DriverType::unipolar - // DriverType::bipolar - default - motor.driver = DriverType::bipolar; - - // power supply voltage - // default 12V - motor.power_supply_voltage = 12; - - // set FOC loop to be used - // ControlType::voltage - // ControlType::velocity - // ControlType::velocity_ultra_slow - // ControlType::angle - motor.controller = ControlType::angle; - - // velocity PI controller parameters - // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 0.5; - motor.PI_velocity.Ti = 0.01; - // angle P controller - // default K=70 - motor.P_angle.K = 20; - // maximal velocity of the poisiiton control - // default 20 - motor.P_angle.velocity_limit = 10; - - // link the motor to the sensor - motor.linkEncoder(&encoder); - - // intialise motor - motor.init(); - // align encoder and start FOC - motor.initFOC(); - - - Serial.println("Motor ready."); - delay(1000); -} - -// angle target variable -float target_angle; - -void loop() { - - // iterative state calculation calculating angle - // and setting FOC pahse voltage - // the faster you run this funciton the better - // in arduino loop it should have ~1kHz - // the best would be to be in ~10kHz range - motor.loopFOC(); - - - // 0.5 hertz sine wave - target_angle = sin( micros()*1e-6 *2*M_PI * 0.5 ); - - // iterative function setting the outter loop target - // velocity, position or voltage - // this funciton can be run at much lower frequency than loopFOC funciton - // it can go as low as ~50Hz - motor.move(target_angle); - - - // function intended to be used with serial plotter to monitor motor variables - // significantly slowing the execution down!!!! - motor_monitor(); -} - -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void motor_monitor() { - switch (motor.controller) { - case ControlType::velocity_ultra_slow: - case ControlType::velocity: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_velocity_sp); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - case ControlType::angle: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_angle_sp); - Serial.print("\t"); - Serial.println(motor.shaft_angle); - break; - case ControlType::voltage: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - } -} - diff --git a/examples/angle_control_serial/angle_control_serial.ino b/examples/angle_control_serial/angle_control_serial.ino deleted file mode 100644 index 394b5d36..00000000 --- a/examples/angle_control_serial/angle_control_serial.ino +++ /dev/null @@ -1,142 +0,0 @@ -#include - -// Only pins 2 and 3 are supported -#define arduinoInt1 2 // Arduino UNO interrupt 0 -#define arduinoInt2 3 // Arduino UNO interrupt 1 - -// angle set point variable -float target_angle = 0; - -// BLDCMotor( int phA, int phB, int phC, int pp, int en) -// - phA, phB, phC - motor A,B,C phase pwm pins -// - pp - pole pair number -// - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); -// Encoder(int encA, int encB , int cpr, int index) -// - encA, encB - encoder A and B pins -// - ppr - impulses per rotation (cpr=ppr*4) -// - index pin - (optional input) -Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 4); -// interrupt ruotine intialisation -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} - -void setup() { - // debugging port - Serial.begin(115200); - - // check if you need internal pullups - // Pullup::EXTERN - external pullup added - dafault - // Pullup::INTERN - needs internal arduino pullup - encoder.pullup = Pullup::EXTERN; - - // initialise encoder hardware - encoder.init(doA, doB); - // set driver type - // DriverType::unipolar - // DriverType::bipolar - default - motor.driver = DriverType::bipolar; - - // power supply voltage - // default 12V - motor.power_supply_voltage = 12; - - // set FOC loop to be used - // ControlType::voltage - // ControlType::velocity - // ControlType::velocity_ultra_slow - // ControlType::angle - motor.controller = ControlType::angle; - - // velocity PI controller parameters - // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 0.5; - motor.PI_velocity.Ti = 0.01; - // angle P controller - // default K=70 - motor.P_angle.K = 20; - // maximal velocity of the poisiiton control - // default 20 - motor.P_angle.velocity_limit = 10; - - // link the motor to the sensor - motor.linkEncoder(&encoder); - - // intialise motor - motor.init(); - // align encoder and start FOC - motor.initFOC(); - - Serial.println("Motor ready."); - Serial.println("Set the target angle using serial terminal:"); - delay(1000); -} - -void loop() { - // iterative state calculation calculating angle - // and setting FOC pahse voltage - // the faster you run this funciton the better - // in arduino loop it should have ~1kHz - // the best would be to be in ~10kHz range - motor.loopFOC(); - - // iterative function setting the outter loop target - // velocity, position or voltage - // this funciton can be run at much lower frequency than loopFOC funciton - // it can go as low as ~50Hz - motor.move(target_angle); - - - // function intended to be used with serial plotter to monitor motor variables - // significantly slowing the execution down!!!! - // motor_monitor(); -} - -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void motor_monitor() { - switch (motor.controller) { - case ControlType::velocity_ultra_slow: - case ControlType::velocity: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_velocity_sp); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - case ControlType::angle: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_angle_sp); - Serial.print("\t"); - Serial.println(motor.shaft_angle); - break; - case ControlType::voltage: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - } -} - -// Serial communication callback function -// gets the target value from the user -void serialEvent() { - // a string to hold incoming data - static String inputString; - while (Serial.available()) { - // get the new byte: - char inChar = (char)Serial.read(); - // add it to the inputString: - inputString += inChar; - // if the incoming character is a newline - // end of input - if (inChar == '\n') { - target_angle = inputString.toFloat(); - Serial.print("Tagret angle: "); - Serial.println(target_angle); - inputString = ""; - } - } -} - diff --git a/examples/encoder_example/encoder_example.ino b/examples/encoder_example/encoder_example.ino deleted file mode 100644 index 10de5d06..00000000 --- a/examples/encoder_example/encoder_example.ino +++ /dev/null @@ -1,33 +0,0 @@ -#include - -// Only pins 2 and 3 are supported -#define arduinoInt1 2 // Arduino UNO interrupt 0 -#define arduinoInt2 3 // Arduino UNO interrupt 1 - -Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192); -// interrupt ruotine intialisation -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} - -void setup() { - // debugging port - Serial.begin(115200); - - // check if you need internal pullups - // Pullup::EXTERN - external pullup added - dafault - // Pullup::INTERN - needs internal arduino pullup - encoder.pullup = Pullup::EXTERN; - - // initialise encoder hardware - encoder.init(doA, doB); - - Serial.println("Encoder ready"); - delay(1000); -} - -void loop() { - // display the angle and the angular velocity to the terminal - Serial.print(encoder.getAngle()); - Serial.print("\t"); - Serial.println(encoder.getVelocity()); -} diff --git a/examples/minimal_example/minimal_example.ino b/examples/minimal_example/minimal_example.ino deleted file mode 100644 index fd225765..00000000 --- a/examples/minimal_example/minimal_example.ino +++ /dev/null @@ -1,48 +0,0 @@ -#include - -// This example gives you a minimal code needed to run the FOC algorithm -// All the configuration is set to defualt values -// motor.power_supply_voltage= 12V -// motor.driver = DriverType::bipolar -// encoder.pullup = Pullup::EXTERN -// motor.PI_velocity.K = 1 -// motor.PI_velocity.Ti = 0.003 - -// BLDCMotor( phA, phB, phC, pole_pairs, enable) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); -// Encoder(encA, encB , ppr, index) -Encoder encoder = Encoder(2, 3, 8192, 4); - -// interrupt ruotine intialisation -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} - -void setup() { - // debugging port - Serial.begin(115200); - - // initialise encoder hardware - encoder.init(doA, doB); - // link the motor to the sensor - motor.linkEncoder(&encoder); - // velocity control - motor.controller = ControlType::velocity; - - // intialise motor - motor.init(); - // align encoder and start FOC - motor.initFOC(); - - Serial.println("Motor ready."); - delay(1000); -} - -// target velocity variable -float target_velocity = 2; - -void loop() { - // foc loop - motor.loopFOC(); - // control loop - motor.move(target_velocity); -} diff --git a/examples/velocity_control/velocity_control.ino b/examples/velocity_control/velocity_control.ino deleted file mode 100644 index c1bf8914..00000000 --- a/examples/velocity_control/velocity_control.ino +++ /dev/null @@ -1,118 +0,0 @@ -#include - -// Only pins 2 and 3 are supported -#define arduinoInt1 2 // Arduino UNO interrupt 0 -#define arduinoInt2 3 // Arduino UNO interrupt 1 - -// BLDCMotor( int phA, int phB, int phC, int pp, int en) -// - phA, phB, phC - motor A,B,C phase pwm pins -// - pp - pole pair number -// - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); -// Encoder(int encA, int encB , int cpr, int index) -// - encA, encB - encoder A and B pins -// - ppr - impulses per rotation (cpr=ppr*4) -// - index pin - (optional input) -Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 4); -// interrupt ruotine intialisation -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} - -void setup() { - // debugging port - Serial.begin(115200); - - // check if you need internal pullups - // Pullup::EXTERN - external pullup added - dafault - // Pullup::INTERN - needs internal arduino pullup - encoder.pullup = Pullup::EXTERN; - - // initialise encoder hardware - encoder.init(doA, doB); - - // set driver type - // DriverType::unipolar - // DriverType::bipolar - default - motor.driver = DriverType::bipolar; - - // power supply voltage - // default 12V - motor.power_supply_voltage = 12; - - // set FOC loop to be used - // ControlType::voltage - // ControlType::velocity - // ControlType::velocity_ultra_slow - // ControlType::angle - motor.controller = ControlType::velocity; - - // velocity PI controller parameters - // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 1; - motor.PI_velocity.Ti = 0.003; - - // link the motor to the sensor - motor.linkEncoder(&encoder); - // intialise motor - motor.init(); - // align encoder and start FOC - motor.initFOC(); - - - Serial.println("Motor ready."); - delay(1000); -} - -// target velocity variable -float target_velocity; - -void loop() { - // iterative state calculation calculating angle - // and setting FOC pahse voltage - // the faster you run this funciton the better - // in arduino loop it should have ~1kHz - // the best would be to be in ~10kHz range - motor.loopFOC(); - - // 0.5 hertz sine wave - target_velocity = sin( micros()*1e-6 *2*M_PI * 0.5 ); - - // iterative function setting the outter loop target - // velocity, position or voltage - // this funciton can be run at much lower frequency than loopFOC funciton - // it can go as low as ~50Hz - motor.move(target_velocity); - - - // function intended to be used with serial plotter to monitor motor variables - // significantly slowing the execution down!!!! - motor_monitor(); -} - -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void motor_monitor() { - switch (motor.controller) { - case ControlType::velocity_ultra_slow: - case ControlType::velocity: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_velocity_sp); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - case ControlType::angle: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_angle_sp); - Serial.print("\t"); - Serial.println(motor.shaft_angle); - break; - case ControlType::voltage: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - } -} - diff --git a/examples/velocity_control_serial/velocity_control_serial.ino b/examples/velocity_control_serial/velocity_control_serial.ino deleted file mode 100644 index ef0848af..00000000 --- a/examples/velocity_control_serial/velocity_control_serial.ino +++ /dev/null @@ -1,137 +0,0 @@ -#include - -// Only pins 2 and 3 are supported -#define arduinoInt1 2 // Arduino UNO interrupt 0 -#define arduinoInt2 3 // Arduino UNO interrupt 1 - -// velocity set point variable -float target_velocity = 0; - - -// BLDCMotor( int phA, int phB, int phC, int pp, int en) -// - phA, phB, phC - motor A,B,C phase pwm pins -// - pp - pole pair number -// - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); -// Encoder(int encA, int encB , int cpr, int index) -// - encA, encB - encoder A and B pins -// - ppr - impulses per rotation (cpr=ppr*4) -// - index pin - (optional input) -Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 4); -// interrupt ruotine intialisation -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} - -void setup() { - // debugging port - Serial.begin(115200); - - // check if you need internal pullups - // Pullup::EXTERN - external pullup added - // Pullup::INTERN - needs internal arduino pullup - encoder.pullup = Pullup::EXTERN; - - // initialise encoder hardware - encoder.init(doA, doB); - - // set driver type - // DriverType::unipolar - // DriverType::bipolar - default - motor.driver = DriverType::bipolar; - - // power supply voltage - // default 12V - motor.power_supply_voltage = 12; - - // set FOC loop to be used - // ControlType::voltage - // ControlType::velocity - // ControlType::velocity_ultra_slow - // ControlType::angle - motor.controller = ControlType::velocity; - - // velocity PI controller parameters - // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 1; - motor.PI_velocity.Ti = 0.003; - - // link the motor to the sensor - motor.linkEncoder(&encoder); - - // intialise motor - motor.init(); - // align encoder and start FOC - motor.initFOC(); - - Serial.println("Motor ready."); - Serial.println("Set the target velocity using serial terminal:"); - delay(1000); -} - -void loop() { - // iterative state calculation calculating angle - // and setting FOC pahse voltage - // the faster you run this funciton the better - // in arduino loop it should have ~1kHz - // the best would be to be in ~10kHz range - motor.loopFOC(); - - // iterative function setting the outter loop target - // velocity, position or voltage - // this funciton can be run at much lower frequency than loopFOC funciton - // it can go as low as ~50Hz - motor.move(target_velocity); - - - // function intended to be used with serial plotter to monitor motor variables - // significantly slowing the execution down!!!! - // motor_monitor(); -} - -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void motor_monitor() { - switch (motor.controller) { - case ControlType::velocity_ultra_slow: - case ControlType::velocity: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_velocity_sp); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - case ControlType::angle: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_angle_sp); - Serial.print("\t"); - Serial.println(motor.shaft_angle); - break; - case ControlType::voltage: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - } -} - -// Serial communication callback function -// gets the target value from the user -void serialEvent() { - // a string to hold incoming data - static String inputString; - while (Serial.available()) { - // get the new byte: - char inChar = (char)Serial.read(); - // add it to the inputString: - inputString += inChar; - // if the incoming character is a newline - // end of input - if (inChar == '\n') { - target_velocity = inputString.toFloat(); - Serial.print("Tagret velocity: "); - Serial.println(target_velocity); - inputString = ""; - } - } -} diff --git a/examples/velocity_ultraslow_control_serial/velocity_ultraslow_control_serial.ino b/examples/velocity_ultraslow_control_serial/velocity_ultraslow_control_serial.ino deleted file mode 100644 index 15349486..00000000 --- a/examples/velocity_ultraslow_control_serial/velocity_ultraslow_control_serial.ino +++ /dev/null @@ -1,137 +0,0 @@ -#include - -// Only pins 2 and 3 are supported -#define arduinoInt1 2 // Arduino UNO interrupt 0 -#define arduinoInt2 3 // Arduino UNO interrupt 1 - -// velocity set point variable -float target_velocity = 0; - - -// BLDCMotor( int phA, int phB, int phC, int pp, int en) -// - phA, phB, phC - motor A,B,C phase pwm pins -// - pp - pole pair number -// - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); -// Encoder(int encA, int encB , int cpr, int index) -// - encA, encB - encoder A and B pins -// - ppr - impulses per rotation (cpr=ppr*4) -// - index pin - (optional input) -Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 4); -// interrupt ruotine intialisation -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} - -void setup() { - // debugging port - Serial.begin(115200); - - // check if you need internal pullups - // Pullup::EXTERN - external pullup added - dafault - // Pullup::INTERN - needs internal arduino pullup - encoder.pullup = Pullup::EXTERN; - - // initialise encoder hardware - encoder.init(doA, doB); - - // set driver type - // DriverType::unipolar - // DriverType::bipolar - default - motor.driver = DriverType::bipolar; - - // power supply voltage - // default 12V - motor.power_supply_voltage = 12; - - // set FOC loop to be used - // ControlType::voltage - // ControlType::velocity - // ControlType::velocity_ultra_slow - // ControlType::angle - motor.controller = ControlType::velocity_ultra_slow; - - // velocity PI controller parameters - // default K=120.0 Ti = 100.0 - motor.PI_velocity_ultra_slow.K = 120; - motor.PI_velocity_ultra_slow.Ti = 100; - - // link the motor to the sensor - motor.linkEncoder(&encoder); - - // intialise motor - motor.init(); - // align encoder and start FOC - motor.initFOC(); - - Serial.println("Motor ready."); - Serial.println("Set the target velocity using serial terminal:"); - delay(1000); -} - -void loop() { - // iterative state calculation calculating angle - // and setting FOC pahse voltage - // the faster you run this funciton the better - // in arduino loop it should have ~1kHz - // the best would be to be in ~10kHz range - motor.loopFOC(); - - // iterative function setting the outter loop target - // velocity, position or voltage - // this funciton can be run at much lower frequency than loopFOC funciton - // it can go as low as ~50Hz - motor.move(target_velocity); - - - // function intended to be used with serial plotter to monitor motor variables - // significantly slowing the execution down!!!! - // motor_monitor(); -} - -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void motor_monitor() { - switch (motor.controller) { - case ControlType::velocity_ultra_slow: - case ControlType::velocity: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_velocity_sp); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - case ControlType::angle: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_angle_sp); - Serial.print("\t"); - Serial.println(motor.shaft_angle); - break; - case ControlType::voltage: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - } -} - -// Serial communication callback function -// gets the target value from the user -void serialEvent() { - // a string to hold incoming data - static String inputString; - while (Serial.available()) { - // get the new byte: - char inChar = (char)Serial.read(); - // add it to the inputString: - inputString += inChar; - // if the incoming character is a newline - // end of input - if (inChar == '\n') { - target_velocity = inputString.toFloat(); - Serial.print("Tagret velocity: "); - Serial.println(target_velocity); - inputString = ""; - } - } -} \ No newline at end of file diff --git a/examples/voltage_control/voltage_control.ino b/examples/voltage_control/voltage_control.ino deleted file mode 100644 index e097f9cc..00000000 --- a/examples/voltage_control/voltage_control.ino +++ /dev/null @@ -1,112 +0,0 @@ -#include - -// Only pins 2 and 3 are supported -#define arduinoInt1 2 // Arduino UNO interrupt 0 -#define arduinoInt2 3 // Arduino UNO interrupt 1 - -// BLDCMotor( int phA, int phB, int phC, int pp, int en) -// - phA, phB, phC - motor A,B,C phase pwm pins -// - pp - pole pair number -// - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); -// Encoder(int encA, int encB , int cpr, int index) -// - encA, encB - encoder A and B pins -// - ppr - impulses per rotation (cpr=ppr*4) -// - index pin - (optional input) -Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 4); -// interrupt ruotine intialisation -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} - -void setup() { - // debugging port - Serial.begin(115200); - - // check if you need internal pullups - // Pullup::EXTERN - external pullup added - dafault - // Pullup::INTERN - needs internal arduino pullup - encoder.pullup = Pullup::EXTERN; - - // initialise encoder hardware - encoder.init(doA, doB); - - // set driver type - // DriverType::unipolar - // DriverType::bipolar - default - motor.driver = DriverType::bipolar; - - // power supply voltage - // default 12V - motor.power_supply_voltage = 12; - - // set FOC loop to be used - // ControlType::voltage - // ControlType::velocity - // ControlType::velocity_ultra_slow - // ControlType::angle - motor.controller = ControlType::voltage; - - // link the motor to the sensor - motor.linkEncoder(&encoder); - - // intialise motor - motor.init(); - // align encoder and start FOC - motor.initFOC(); - - - Serial.println("Motor ready."); - delay(1000); -} - -// uq voltage -float voltage_Uq = 5; - -void loop() { - - // iterative state calculation calculating angle - // and setting FOC pahse voltage - // the faster you run this funciton the better - // in arduino loop it should have ~1kHz - // the best would be to be in ~10kHz range - motor.loopFOC(); - - // iterative function setting the outter loop target - // velocity, position or voltage - // this funciton can be run at much lower frequency than loopFOC funciton - // it can go as low as ~50Hz - motor.move(voltage_Uq); - - - // function intended to be used with serial plotter to monitor motor variables - // significantly slowing the execution down!!!! - motor_monitor(); -} - -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void motor_monitor() { - switch (motor.controller) { - case ControlType::velocity_ultra_slow: - case ControlType::velocity: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_velocity_sp); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - case ControlType::angle: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_angle_sp); - Serial.print("\t"); - Serial.println(motor.shaft_angle); - break; - case ControlType::voltage: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - } -} - diff --git a/extras/ArduinoFOCShieldV12.pdf b/extras/ArduinoFOCShieldV12.pdf deleted file mode 100644 index 2039b2e4f5f1fb6d60ac657f678d603c4e2a7a48..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 511087 zcmd42cU)7;);E4ViXKHoATY%6*Kt(_Vi3&(33Ifu5 z2~}#OCDK9%5l9e10t7+{A#e1Qd(XY^`@GMu{PFA$d+)W^tXZ?>J8RaO%-#s!SHCMR zB_Vr4`0G4w=!BGzq!853RYe706y)UqP_y;5b%#0u?%O&!z=Wh(g$95J4n8m!s3$;5 zLII%T;A?Bok`a>oUIYR;c-pgSpZG5LFIs-o2B<;(Jbi_v09r2gFd=i9?-eZns`35t z-)gXw+q>A_h6b8TvI^yZLW;7M00XG6t*?U+P?BYmj{{5J?>61?^o07t%;o>CRQ4~W zcl90!Ny$q{O9Sp30(4wF0fv5dzTZ1||1S%^_uzL6{wy=q(f%EUKYIz#cJOrabrzD6 z0V;q%Fkc@BTaObe;6N{1h?|42ke!2*i>K=4%R(;ps+UdVbR>1W)Et~$ehc<-Fbvi; zf&{xkfcBTcpc5*AN`W3;9xUvH0zKS4VM>9jmu*?VIViE{?`*(j&VV8`}%q*0RRC30TKZ+5>Ou}fD{l21V~B)q@~4K65_BRPhZ-fVQ53j!(@`OqJFiipi^#BCgda;IG@(=TV zucgB3ijo=&3SX#?5fthUy5;Wc;^!g6YR|>V)4@kbN>M^mLP0_rD5C=SciDe7{zHup z)ZWE0NS!spAZbZyNpVS8aY+RuDMck|IVD-e8|KCQ!9`e^fc=`Fb{}^w32*APJ!Gq=e zFxFs5{e3X(Axe%=9}in!kgb=Oy9>nj`*;Jq>>X7A|1A2K-m;j!F23##e;WA5n0_~( zHI9Gh{%OCv%Xf!Va<}z#QoS4~Ztvh|>*wx!8Fb6X-p|DodRI?P;y%Pq9SZp!26vag ztNES#ckMr{`*%ZBSjItqcdUQY@ZCH^2k*ag|7jlRziRmJ^?o$`pN)KP+Wwyt=I;&t z7{tHZ|1YrppU{y}7h;84A*iF!|5u#;H-`QH=5Q=e`OD+}HuYHrEN_$fySK5JO80%B z_I?ltpFih4tCOs*Is|$_eS95!RKEM(KV|;Q`SE)vSn-Y(Apw7dNY=w&5tfx+R4)g7 z51}mTkNEpX%K0Ap|0RL^NCB=tQ78nDO*LXxcOEmkVL1-P#VPzT&s0~p;F^7Zj^0O;QTaR-4|5}LoW?hE}$ zX@BJtg})ob(&yq305H|PuKxRc5d~=e3$4RSO8_-#6LWD^tdvxcl4Mo?Cn5RcU~%OB zgZNAM-;4gKNL)%@US38~URvT0J>oz)pgd6KuV;CApp=x1EGtg`I4l8bdO|>1d1;o6 z{2x4ku7QxFtvk#Ca9iWg#et0aZH>PmHdF(s83NQD{9Pap1{${kYUZp&@#7Hs4}z8U z0r!QzXJ-R|w&6e3X}dT%`?`2K8A6;{@$E0wYPZxutmBV?R{THVY6SKAf$5L?Kk@vl zb;&>N`A_1%Bg0xG{m~y8NqJeIyyTzI2+1fYNXg6n1=YVp_dgrX?=#|G=FLCd^fuJj z7wYi?(Lc$*K>Z7f|Ag`{&i^Bs{~M&@|K^VWvoV$W9%TNvplUlf`u>3Qcj7NV|KFkZ zUqCD_&sw7@$VmS=r~kuA|7`JpIFkSNdxRCp|6H9Lv*-u6%)f_O1EKFh!9eJ{FB=H` zK;J;f67VB}|FLA3lT?tEl?2>%ac3nZz+HFN5>wp)0=0MeYaJgr(U);NU2lZR#JJbA zo|b{|({=k|%PCqup3SeX9zU+B{=vTV7qb&)l^U_an!i;N}?;wb4KzB@ab zP7g-8@i?ltFt^u}oAoHTm1Z2h5r=j{Z-5m*^JJc@0OJ<+Cnx98qYX{(c>KdKncdl;NU|!tar|39sA+ec z9qR-V5MQo_=i1db*sHn1r?y&T$L`;~!P(`JG(d_VAnQ*j47BYgNo^-YtUaCcLEvxBV-S#Fsw&iMbr}>#tILiJM%L=d zh212kqlVwPAfM`t4rB}Xa>Q_uMn<%kDngsi4JI1EP@HZrB#0aQb<^)cJMXch? z8^C%*-d_#*$$Ri`Au2QOPRg724xH2)(r=%&-Z=KH?-^=8sWm&GVa6Z5x~J%kMAw4M zECvo5F{>zQwh3wX%QwCNjRdl%VMU3%5_R+nCTfJdzcPiES+=12bRVh~&eO{ASl(J1 z%G20ZhD{vA;RG!o%8XTyfSS@9eM)3e?~^A^Jwy0B500O-3UJwR0a$Y)`YI?roR_#V*##NWq1}^oC>3o%=yF`;l`jq( zO`lz-;RO924rTZF#x|b!2Gy^I!}IX%sv6Td0gKzk%5wW&YDeK0)^shOzte(0rz}-+ zkYzOF0&l{M!ha!rIO>v|&8uP)=PCsI#h-W}kgs*!mvhu9sYhuOy?2gMuIoWL*w+_1 z7xNotHN(vqlYSf81TS75oP`xH50k-~q>LbrpkJ-j1oW)b$Qh$AWeIW%hk`hE^{Dkj z-Y+}f7g{0XDAS3v0^9f;nWT)@uaA}jYH1isp#9V+st?do6MUV^60}=+soKN5BG<6} zUBSTmKYFvVRmEjam2P2aP(U1q10OO#l$^LrF5Pr7Dev)sm_Ns$C%!Z#RQ(=@cIq4P+jau<`y+%!t88ohZP@Z9k zH}D@jwJe7lu0G|<=~t5McDmo{TOg7a*v&u}atL&;%?CER?Y~p4o=0kh;np$vW*gT! z$m{0}#^-MYs@m%sE>pI7=jrd?>k#WDEy-o)p6KGj2g;N1CzGAdg6t8y?RaVboojcn zqNwzdq8RuCXiGp8=X$VB7^h}_OO#RIcS0>J3Ei4Gqf+qR=a5w=@l36bGw;N;&Gj0c zrSQpXo1n^$@QG`(93EHF`XBf=Q{Qhic2hs#(#mA3bjIdA(#nq2>X<$!>U18f(J|$n zxGP^`NlM?;Nvf~;mPTeN%VEjoU?$}g1*YT^4cyaSvgE$=gnN#DvAZQU+R%Tn3TitB zt8z2;BZAs?r>0LJ7lMDvnDJA6Ecl)l{KOnJxOD`7S`fcZTf3gzbI#xvF3PHfto05Y zHJeS@*49kJqL1%GWkLg-*u%V9IQ6`nKkR=D70iqb71T|!_TkBQOF1dP^jR&S`+c(X z7$C4*)tJ5PV&wZ_qT1jXQO#h0$ZX)>WY9wvWjA+wbi3395UA4qFCgn(Yu2;N5;c*@ zNe@{%yce>R?Rv<+{d2-zh%+xe#955RVTvG{@A2-1oD-RUhit}~1bLxKHvoGfi7Z`W z%qRqibcl88SO25I*7P0%bn^x4JjdcN<3ZMP9Ej$E`1LZ4Sz;lm4rjvPMl`#!bd50E zLDt_6A({t&w0BQ*YxkZDiJHi=^acZiI1u#q#w3oO5T!U!@VW7MCo1^9(N!7+vnI7cwCe?geUTIwQ~-d&V;pUI)Ye ztT&&2Ci6M)%04p*ctw^20XE9x*Ne`prf_q_8pD=%%(uVM-{mjSMQ0R$J|1Q>%c-L_ zn^bJ>1ZOi6PDHdk-@YP{)W)*GmSsa5%LZGfoy7?)mI3Fp-!M?mj53wZ2q5h&3icm) z=WndOSi9bp(<6%1N*q#@FxKs?yJ`~tTnS?6`ugJL+Wg=^!X7NAfqpP4>bmuUu>gH@ zRhXm15<9Xx-;6aim<^w6KeyxlDR?FcZ4{EdN2jX1(Lm|y<$T_~0aQ38_?cu_Q9k=&(_uujmUs<3UA`v1aGaRTFaV_=`}v#O|h4@&HmV zkwRut-hUXWy}4C8c;GQZ8JHJ?=j1YHw9-2{A5 ze-11E%?m?BRtQV41x224e6f6heM_%QXjYH}-eEMg$T++1&LYBuIvHjo4Y%!48P8ov^mB#-+st_ic1o)G zsftaAw*Y-{yGKwzPK_Kt&x+oPSI+@Y?cxM#b+PNGFlvq=6suC5iRl%ym6GkjZ#Pcu zvD29n(`KaQ**Q~UW5N}5-WL$A4p-0ge$5P^6lX6aFit@K7Ggj`daAJ7GCc4kAh|yM_V#_?w2+5u z-igu4$!W$-TVjJ8QlcTn&q>z4^bRSwT(KEEVh^?ncU87K@3^h7|bg+pb zP|gam|<^X4nJIF(LerqyLX&|Q z)#@8lh4L={6MTuqUqVm?_D%Nw0eJeqalT$9T0gZE|k!2`uM1P+on1VU#UqrmDj z?S?4INfka$R*BRm*PB!fd40CD2ghlfU}3 zAK;3OGH2e?7umb92U?lxoG5WvVIF4 zNq9v})up7kQEiuDtDtK+7L_$S7XqX=-b;@LsT^z_R5~#Bwx`1;P~Zth-uxPwkr(o^ zhmpt1tBgEDnUJbgDX_nH0JB)o2j>>SPaam;IMB-5CbbaShqtY_r9`)^@#h82v4O8r zEs{0^?ct2)`C}_4Au23ldzM8!YYOc&B5yeiU#HKiqy@kQIT33YIQp|G^Y6BKviqZ4 zmge7a3S^s^hfMV!6u#+kH-TT>7EB+}GZh;RvqicwxM^>ZrS$Uo`KF- z(HDemgE^7d{18rmVpJ%n{OHpefi3vvvTp!5Y_|p{czNYu5(Y+0wg3`#*py}$j@_-& zLQc-g1YjVNk?u-V6?4sR;Dp~%Gd)bqAmPdeWmM|?H2`mn#-A$BFZ~rqv676YaftWk_(?GYyY~C}vn)@@=vA*K!w3zD>*IzC01o z<$LL!iO2rCzNkLKMWe-hpXWgZA*CwoluOiKQVUcfa+C8ue-#jAQZ7LX5(<*VaxNI= zC_^Ud-syTAsM>4iyEeT1Wl~~6z(e8vd8PrkVO^0(-)H}p57Kk#3Tie!7B494Wxz6>s%NbIZ zRhYaOrfckp{N#dAE2+*^1vl_!-MC01%Mf~O8scEJ&ddtG7tC6fC5Oag?luYjs=`4o1MlA?={MA`LJ7OR zKH?MOeL0(O{TU~d0(}iVF{IKiufsIjfYI!ow+7{^;^$=sR3i*WC?j-DkqBzlAT59p zQtFd5LUY|>p6|!d17i61Z>50m=tX9Rmc$*He?3$=wbL1Nr z%6LhUz>i#^0>j5CdyAC^|2ed-I-_v)O?aw0Iov)RL=SM|`f`WkY9Y-C}!jTTI z74=3%ukzj~dpXt`%M&cUxj9tfaVh#(pHGyZ_|^4CJj9wAxbZAsy-sl)-1z>Kz}%Ds zh_7(6a3%_Fyp|NXZH&j@1H9p-h@Q%|*|wx+1)6VM(=9S$+2SQ(F>yQJ@uHs@TPoSm ziRR1z$8YC1N5~0Q>}JgqODWs=Yvk0tpjB=rHI8B!Jx%+$K~C<38+;{~ZX7!=xSxEfqLRO{`@SFX5`!)?XZBSl>=jBaVkw(R1sFEYZ( z@d65W3*tDc5SH2cS(M3;gr4zsFAFVx+<;xSak~QN2?a03u7Ii?b+k#wPAj9?cdwFP z%~*taJqgq*i1@GyICVk%By%{yQs$oJEd0J~)iH+3!=9fii*62N=M>4CG`}9Rn%qw0 zokgG|S6;8WK6Tz8A@2ip#znL__DK>&s~M{h3@~&9pO#kwEN7HEXS&YwHEc}pp2a=Z zr*?p4H^-fZLaH~yo7&Ve>Z2T^UqUoqSP3m2SV12ruqh)#%K{(o9FeI>SKSt)IBjj^6z3OTSi!Fku=^eGS7=A`P27f~N z!-4nSNKwTx|0{rFN- zK|gPQuOr#m`%vm+XtRmmOcwf;Y8ZKKAY?ADY1wEGVUXl!mCBwlUizFeG9^8K%MX|o z2b%}c`Ix=HfUHv=q{7^2jX}R|jfMP*H6)ZlYQn`V%gSX?LmPrd)`~=%5j*)&yh_W? zEjh87M57q5@f0ofEpg&>7-0gNn06khNJS&z} zyS)hg4=cSGM&;oyl-Dk)J4c3`CJlxj93fS|J8N9KzII{B9`L!M$ z<|maAkD*IEQF=jwuf6M1vN4L;&G0ZE|#d?sd@M=ONawTH!fo1<#e}o5C1^O+_oyvP3Y^L3|ui_bQ3NjSGrt!X1K^ zmx>V}#T0*an1tYZi_;UN+!FnY!Gk6WCp%Qs*R+R!Vzn&6*a110kr|b9bHaRF>T_J+ zf!Bq_L6M%V>qWf?+6^xAM9#CuFZh&duf2P!OAfIMJoi1~$~)G)Pj@yzm|#QD4f{Ke<1 zUz6r@cR1_3)XJ@FY9sw-X9&4=@W(Q67y8>`g>#cw`l5Lj4``Opyz;B~z$OWyWk;*t zirrlrGk2vQ&Hl#wUXIQytO;uEgQfLoz7AV>9K7&&b*F9Z;&TtxuA0i?Ga~57-{-q$ zW|-C=^S%76rr4m1q2#30#wo`J>!O$MYk-XNezvo}p31QvpZBQMdL=#ch7@eHvl1~8 znu{|Uum}w;c(~D_Z|nLcPphnEv=S*kx6^9MxQD&2I{H*cUvBc7kBMXYWe|5_dKOkk zQA`_E&Yt(1Sq2H>rihVuk-n4YnU7xjB3huIaYg!|A!X5S-^t8ouhrsX#m7-@XLz{Q zkbTBc!bI-3OqU8>>XfpfIIfroDpeYC5MS_+8GUM7?euA)bo-N80f|o)SyUvWC2Qll zH^%#h-4SicjeYG?es_9<<~`S?k!|0!Y)+^v(lwlxO&Er1E^jd@3J0 zU{US37lwuSZ-GkVd#B=>o#(yJ;+WDQCCf(A!Cf?yQtz*@sR{41YBJ_}%5^oco6A^; zJ~vHRl5XJA&`i?09)q~xXD6yMXGG|dU*8?o=J;xhws{jXW-8(HNpaFW z`4Uj&VDDu2#bkeHXIxrP?g9tjtZrr4x0Jy+XmN7MwbIX+Q^|^!`;Rz%<+M>Yaqy&; z)RG!GMX^xDT;sLmccAHF)&5Gpv+@FvA1k-JbXW*mhQY17Ce{B{$~4HHF8u zsIp5jq&>$W?)Y2);#kR9h0=59KqCA)wG-Xq30*DNgbN=tPeD|sRysH( zh?{D$FJcAxF6OQBr)HYaOO_h_;2Vu6_9napxM#1g6m1uzoA@1;MV9(o6*uNn1rG>8 zBTiYBv>irc{Z0uei3{}G{fj-W^r6FNhhK-JMl~h9JvuyU(fAGMH$GqzxRJipn%K+F z^}^|WW)e~ll!w(;xklQKuLZvBZwNm-8+f{h{tP_!Z+_m4hUywule!omw;Dr`w z`;o0Vz51eNG~gM+CB0ljHRzV=N(VKwINDDZC)f0Luq8}embwk3J{!H`qU<0u=}U}Y zUv9EYHDPAHJ=z3UPnLonbX9Tp*v*IqGzz7P$;&{+k=FOwl=;pmPc}t(IJLNbv+ID_ zmq$~}+8qEP5=8gKX;k5O&M9_kdc?JjvKdNxKF|tl?KKtbfdYm#ruV8I)A^;pZEk*X z>=}XU4p${St4|p^9*k8!7n*W?y>YYqYD&OcV&I61-Rr)0(73d#u5mqhcSOr z9^Efp1q#DaX)Ai&na-Oe!wSxVFF_A!I+pIL+Yi*tGtXNYPB?#U$T$xc9OvDGO46%H z)^F#m=65~~RcO$Ca4zFR{pIMbV-K14-dz|7-0S=_b4(jGP!lOtTf}wcpf#4LiZiU( z=ArboKkLi0FFiuAa!KetMF8EfTM&&t)Thduye@>A;=GKT8afB?eYjqKC>cX2gt3TQ zt@={S(PH&FS^-G?xoPC_+GonwQok<;XSlMZ8&8YwKTfKdbq=~qvY9Z!fmn@gR{FN{ ztaCb|)s6`lc=X40ZylM)p4BwsNS8W2%2i+d{4B^^@!qCZy&HK~FKfAMbj=UoG!0*R zGlqzo`bC+Rr{b^KbX9J}xc^`z-l+KuHgHEjYcH@M&K8bRPyEt%=5W-tg7r(OQOF-l z6xQ0cuO6D5`r$;$fJLBY)}H*YR7xe6@i*~QlY{gRT|3U9ekNHD(+`q|BhZYhWu0@C z8dUtptJO+Lag|>+;Yel@p`8fLKOd&N($%La<_k+84W+bC@5T?m`Kb#VvX`i1;F08P zb=no?(f>H{wNd5I{gW53=0AP#Z_AVI1t(x}XJ-{kOAYq00s9RE8|W;9X|Di5d9nIm z%15%FVu1S?PN0J}eaB9h2h80;tdjN^0M&w1w7Mp_&@i*!3~$8=$GGlj3ePE$^QLig zk8r4Gqf^|fG$?5+s+N%CNOc)rl7D^f+LFS|8CGD<&!&HC$itOhV@|WygZRs4# zP9wevdS}jyD)surt84>$!L<7UqEPKPOG|B7NJPkB?s)G)ynp_fIBJv2`NHJD^6q=6 z%8)c_GbLBPQi4ib;GU_v)Up$O&*ayAwRQ*sy1>oco%rSD0Vkr#MG313{pDpaVx;*| zy4$l9-j43Zh_Urb@zWxch50dO4)b^$pr|3CZoj5wpS_590)}1imX5NiVf$*2ZKVLy z%R8maP`IKXZTzaapy$7lr59^59zE0-yP8oMRy*3*u2S8kv*tabFgRX0Ne}Egtc>)qTB#$wd(#wP zMEfOib?e$T@0>i0^C#u)UmUt@?d>JBF(ROuIKtzpH6>32`MNNh4L&hvM_f;6b!zY%)11|zLb|Di@?*H4g33xeq%Hl1_f6vG0QjD1=l0zbu!Bwn z-`+7pBwT5eGZ%N`PE*cJ$@x~swLR8ZGX8P%aIWBz*?F>>l)NP5;>%w1kSF;X=*{D~ zxU(0VisZvsCMkcFt$n!Su-bA~crmw-S6syxdwgIt27F1%BJ|S3ouPLkSD{s?i6wFW zg(wU@c^+b{RDz~!3%Z$ID+ZU1_x8l=ZI@qjYb-*l%5hh(=Cr`@7bhEwLafsiHH?4~ z=?-x<(B1alhgNEn01CB&S7(sM-_TgJ#ZirDKMpATQ0e%yB4pGpFkx8O`2(R-rm^@E zz?o4q0D4dvtwgv5rJE{e4oOkSL`bJfX;7D>pqqKP^EZ*cIYCHB5ne{`S;nr4OgHA< z^-{UQyggIyQ8zfw1%zLJJuzcnf|Lts=@y3^mXY7F7x>tB*au7VI6$NN3|FJ*-TQ0= zKJSC)s6GUcYu`RpMX_6t(3-PV@hP;??BJ#}v<(Z;#Kl zE$lyl_)@b+eFMUUY|p|ZiR%xoFL%&ya*PiL&=?b!~k4HJYn0 zh}JD~SlCf=RK;}C3)H!9fFHkNBQQR%tiOZZTjq+WFp<$b~(<-p(|2*B##=~9C_e-fHB-YpUV_rTL4*y5t~B)6W$ zgIYaN4NB_wrZGxe5r~D6>nUm)z*wMnj!eysG+@g|tdyYJYaqRUYMF5>p~zOziJ>x| z+!rwEcmceE7l=pWD0@;a*-}!N_m&@vw^tOw&HmcP^j?eCJRmCM9Z4zBH6s*SA$gjD2P_t4wu_nto-FROogkC(c17%U*)KGIq!wytC@^T~t zZ&^Da+-7Z^PPO)lf1LyV)hffv%17t#J+cUzI7sT zeDI)vN7aarqC9&0xtXW2d_MPRosSRe{v37&VL=-%7R!9ekVdlM7`v=FJKY$%EXo5j zl}H9j5y~ti85HfGD{@N*h&H_+gjUwfQ&9m@Bu`a@9kiiewD9(Q&uEb$8FcZZyL)4U zC_;_Zn7_ehtOv6fT^uf$@fxuhnICD!O%k5g29IeCa*inl8PHxAU9q#7@wy2)JQN2> z36or50~Y}ZMMvebB5JY9m#EVkL^%`l6(?ha=))bH?F2}8kdK{Ep3D_Q%3TvF%2cQ# zY-&9vF;*mCVU>DYHMiy`c2 zQCdRi7;kj&Uq7xq&zX^GX?IW)<{ym-s~HGCoW75=U~xXmjV&7Mv72PV@0D0u$Bpj$ z_8Pj{77n#-r8if-bBG-)eG_+v{^f;~t6w7)_hnq_D|mO$X~fXrL4ScrghF5R8=qsH z8d_$Tigiyw1$o6C2I4L_YnW|@S9taTMMq6|a1(1k;p@Uv%|Glv_;xbVB`VUN)E|U> z!v0246b{R*48juQVfOg)kgv!3U`Mo3U-ZP(d&>4=Z~enkAGMhn%>mBnu8`++{9NQ{g@;hOpu~l zEMM;h8|bE9Y{xgptuSr zg2e*CWiIPfi@aovobQfkz7|OXI0v%d z_e#{c1i;*h4?ET{Ak<@rg4=n6b3I=~6=MCfSZZhurRwwo0tbAaC*!V#f zb-#UVGI>t`iZq_gtiQhBA>lC#3@&=UJw&_pY#hja+NmlkP8^0gBX*O>Hpd(0+`lAo z#VGC{9)b?A$=NE^i8$a=(uI62n`im+pN}hnA*A}E8#!{X{4Hs*AaOsJ{W+KD+5X`c z7Yx(Kzx|A1HG#81LXb4jc>l%yLn+vwYiCNSX8Vleua8Mm%W`^;bcbV7kH1!vge|S( zjmn`|urUk9qo^OdQ>gM*ku4kinS<_Q=XDYlTQ?0os7BFT+9*?4g&r%zeZIGoaqg+_Z|@ck`MM#MZ=2{&O1eMR=sjJnRjP=G1k&F$tS%dHJ-?ge?!fnE>@!>m- zjJ=j>tQJLXA^Iy^9AQnq_KAO<60) z)nc6ZX_U>LMTYIW9nzaJoyASXw7%M-?uOpnetrGH9){;4)6eOwlz6uRfGXF$(}Jb1 zS=C`*DiX(|t&L*Nt+(MC6micL(Zo8mdJ!pHvDV60ip0lR4z)XIO&4rs=kG$?B?xYx zw?-&EAd8c2nB^&}5pE!R3+^ldL>hySS0HBPwg_vx>EY?#pD6wp;8I;j9s9;&SbI!( zw-qgL{%H}MvfKW9`N+-_+a>Q;)`iIXuEj6NyqEnnA z7@;Gn!9*RjjevP)Smn-<$|4S`eBmvbYMif!eBns=3&gjRdEj&f{|;?bG_~fplQvyt zdyVUFAVS+(en7{KUZsdDA~kW zGTj;_dwF4=;T=P@{STt4?WxxUB?;%=?C_GG5PLY&wO*CO62u7+=&qiCp z(s;L`2arPI0+LdUj%*usB4pN*p6WlZf8qA|c6OFLITt2$NBzZsbvz87^ z8)lpT__npYZ8IE}zIzL8Kh-|XZbBJ5jS+Ut{H2KrkW4Q zR=O*!i}xFT^zE3NN*5>j94}yM$hIR)@v_y14C6_8sn>Eu{gBA=4A7M5{j=PnyoI@c?UEYnHUwIb1Kqz#6F%+ zBGkJ&-Efxmtvd1N4G+6cNa9+*6oGq8%h5}`15Jx05!vx6DoHH1 zh39?cq>=SaV9HRCL^~ETs?aY?D-(25Ox;?n}dvM2OXm$>1K`@Z$jFNnIc z@6+)`SG><2#+5pAL;8R1s(%t%R`NEih-Zmwk*&1Hg{c^jtjp ziJkyEs^|*-VqZ{y)?>Wh%GXZpet3#t5g3-MciK~#)>w3>kgNz;!GT(jx7F@tCT)qV z+Dw!myw{UN*oogmm6Cd0{mjB{VaHFfodl2|f#&f?<{Y{E%jeIhC%K*S;IuxSDgU)G zy^{5NK!7O62>-@4`nXU;_>-T_MC;)b@TjirSy1s(2G-k?^z3s4_Cfxf+&|BhxFy~_qnxw{><4G!dh*h zFMxTdc)$w*^jDb1r%RNmHY_~9F0YT6@KRxh%E8`$8K-!wonEY;X|@m~GG$GW(Z|)- zQGab0Y;@djBvf3{-P^~=6n5~OPcSC$`rkttXR5(3X*@s&Ol_l!eDrvNX8;mbR|}^! z4jLUFpj%XC9A}VSd>X7ju(R79h7SXg!VHA@2$pzm_MMwZ*nTTjx(*7BZ?4fJ2Kh;@ zG*oImK`;oQ#+DSb0(cN$%4;AC0F>BLuo4%3m$|rc0%2smGt1)aUhxDB11eyVgRx8d;h@LN@DaZZhSH2P{la0?#W0uHoi&k;zzM= zY%1qRWtRj;IhKx%9=jm34=cKhwt%&PG5(UHZ?4D0R(#MfixuP*fL8?xthAL;&mQjm z3C152n0&(`#wOFd=?UxzsSlVObQjLhr$1Q;dn^;0^+NH@SK!Fbd#yIr2CLUjW+)49 z%}lcwVqRu-E%jGNjh&?h=0YqMP+=)mOxvmOP_f2!4;y`wuleB7$K0r$XAX^A2r4|l3*gudTmuUtf2DWhgw?YB(#n0HU?4x0Ux znFw2;BLla8o^?Ay*min1x9uwOKJCVA_7SQwTD%DT^_Vte2-=spEhJZ-LYZ3+W!y-F z63$tcvcpDlaDE8AjMTz{Bi841qGEN^>Nmfb@WX9NON|!wN`6*2g{O7cTIb7)S1}^{ z0m>)gbLW#fb!V!)OBw^%q^O9SHmqN0h-b4Vuk|FUOx={yt4zf=z^VOF6R}b*aNym$ z{Vf26@;e{}J=Q032eyxc#4g{(oadI;6Sk04d7Fzh?mbC0W=`*o5k1I6FZxgyXU|^U zN8veb)DnmpWl64Sk+^5Jc^o@#JUMzU8K461QZasqHx`WvcK&qO8U=88Z1$jZj+#^S zEY14EYLu^KR#x7JQz<8hPI0VeT+}lTE0vilNFd0U>KGqF$ZnrZ$x6lJ%eTVXb`BxY zfp?NYtuhi82@s^ZbEwakUq;@p8qZx2IoLtHU`_L9DXgu)psh*Gvogt2@KBJZomCLz z_4oJWkmsEr0F_h2IF+5Q56yn1Cj@7G)k-g6rVZQ_oXI2fHw86ouh)ueq0dl)5-VfP zUc0;2xC?UVA{xa{=PR3JY#mD$QY>yOAVGV`IJaK1bisGEr|C zv~_k&Xudi6#4*T%i|&ib3=!N-y5Y0>q0!H{gj>8fP^W}j=VbG>(U?!Bkod4qFOB2a zV4$|ZCCV#=U92~=EWj&FFBB@&hvY}wB4YP6JjI7g$v$zfO#pox zQ|6aEV6&=&dR$oXaMc=pb;YaeALKgI)5bk=TFFCUPWXa&1N-Q7UDhG_QZ zc&K8k^g>e$-z2q&r6#v3VYS%^1;%m!Ewlb~l}9e6Nj9W*X6lW_J#^fillFbyMRY^9 z=GXN$ti9#qxq^LWeVjeQ+x>C|t0g&zH~cCFBcI-_RKwanOp@ANS3obzSFR5jS*zS@ z`qro1V6pcc9B06EbFD*;`l)8}@#mCS*IjF5EcUjU@YBE2vPZy894OzeT44$0odk$A zbI;jtanY?!IUVSU{W2hCE$V@CgM~)fq9|4TBq|@7w&Lvfd7aY}Zc3zObP~qSEE`6* zXn)Kr=nXDTxlc2!c2Bb<5FZTY73}>~+~NY0i<04!3BCW|iio2mY@@`Iy!Ncu;5_0< z3K4qMtEtYcw*`29VaTY|_EOay0fvtj|xgf;mO@3tg<$!dw6?sV^Id`^T)w@!X@KJ2RiW=%&qFXDPqh zG_4`RnoBq4XSnQjVgiIdfBz1^X8K5wwQw?}cD+YYKduvg)RY|iF#i3`v2R=yzPEak z5H*3F<};)SPS3i_@VRr?z!=00j8zD6b4q)<^Z^v>;DFHBo-D-^E2NR1X}wM`vvz+A zE{2%~(n)eko1Bm~{%+`rXRTic9`nMTdhiP6Q*3L z$uwr4mD7e})rcLSr8eNms0>1y=rc|a%rvn)dhx)i1y7Rjwqm15Tev5edU;3T`oX39 zm>lj?bhAlZ1BqzqkAvb0e`+6O=bp`39Wcig=1f;H-uKTcSxkYV9zfUh2zC-B7ekE` z6+i6mm20_X^}OlR8g>}5k022EOQsyb^um@kW$4A31T*TVwHrR9iDr}GLbz;g8AID^ zKSY7_JeUk@A6TpqfyI@Uet6xwQEGDIVsesBNE~e~NhN+g4r4*jTAW5Q7>jhn+FWEDyIMz^-&=l)I?QJ$2coHj`zegSo%XLjc1i<>VfZz37 z2=BgxJF2n^5@)#I-<0firBm5N*&*{grq(YM+xh-vae#a!r z8xW3eQ%%*;D2dMSYi&B&#Yy13(6@DQ!Y*vue9&rrP9cJ7ffh|YQLeDS^JR8&_O(i2 zV$&tuKZZDcsw>)cZ1-A~wU0uF_xg){%wMq2oMz&3WEzPt)T3?pd(=gfg4gtK=uaeB zh|D;@7igPzbK$AO+(W~NdV%vTl#pzj*CE?MPF5b6rVaUTgJz9UGdpy1 zA25S(D|`3-qxx()oHwMwetJ@dhmn=b|;; zmWV_QDJ$5czJA-Zb(XIuk#J)zd|nsmMNPV>)&qx*B!#DG%wR*BH3|B;5^0M>qt&uV zH^#y1d}nxYqU)wAhU(0298fv5jMJ{~Gt{(Tl2>X+)gjq`Cy#$N-XSc;n$N}qTClnX zF3OpkJC$9;b3?ASY}ECU0nSn1Nn#HVMi4knlax+p0ulU^*3yB3~|jF z!8=TwWqoVb)}BZvkDKhIail5^FPVX3usg-Jq)J{nRy19H=3MHuyXU#dm21-Y+Tjc%}dZe(6MRe z1JQ1ZE;QeKa?7Uc5nXZfxN2`3<4o5-a*u9nydkZh&lT*@>r$3IMOsfNub<>?pSH9h z-c{nMMXpLU&L`u)1m#)JN_E{4Abl9;``H5g0GPHoEFHRGPo zWaGgJ4RDg9%Zef-ILNm?gS)8NaBcJ}Kfg)iig`1yLBk%zt{FfyDb}aEj`Ox^k3-Y> zdf7UWjk{L>(T^Q29VMLT2~f43 z;5~n@F3%k_qFMj{p@baGtkPi3gl)O;k3U%%=V0= ziQ=2`R%YcaJenEN-?Ydl_-fiY708=DKlvs|(+o~XgT09T{+Ay58ddDK&-!0Quh0Q7 zHXr-=8fOFE@ntex4=V&D$pf>;Cb8Yuy_+qB!-pLfts|+v-PgBL6(z!#CKZE+-2$AC z=9}1epELkSXRcnIAJ^S$O-*rVA`E^3>g{1Bs*||D_?cK9oEL4q=PED$3@*$+HU1X9 zK2{JH_Q3ir4=!XzyA;{USgHidA_Jr*p2XICDR*YyvsfB@D}I4<;)(aQ*-HQAXWlnm zZ0^pPpMn%Y8os398U-CsI|{7r6H}99ena=2>&ZE~D9zc8ODd5I9YeK}sB7KL94Hd= zSqhPTpK7{8L?0%gA5{c`o&W{elmbIeLcrN|OF!3-D(7d7o%+5A5tZ|v#m}nV64;sM8jita zS(!O@bt^0FAnp!FEVk*Y&P?B8ItW!FTQaTxymT$ zwz3<0by|e=l}i|e7AWfWTUuarB|ZdltkUXJqB68m_rfmuc6Hq|0ZxdyxY7UO>b;|y zTB60_t6b$O3JNMB%>ts*r1#`nX+f@{A~i}c(!|h{sHlh_D2Q}oBY-sNok)#HiAd-r zK#&L_gcuS+8o%+q_s6%swIIov*|Xcs?6dctnR6kjHysekG7#;O)!94FQj zA`6C(+Lji*f?VdVrNnBzj~8~2Re3>Aj27cUd@HdgCpJcB)KHh*#uz_j8p6!(&B(+@ zcAAnY0(EaCiDy+T(N;+n-cC1ijVJJ+-9E@y&=jbu6<1@&vXnM0?)L3+^VgrWU+FtG z?;+ezAtl*%_SACtUq}6dG?2MaAIj)*0wnXXb<}3UVxQ_n-fYW7o3C_D=hm89s8dut zXZ$K6{@Yq+ZFzkyO!xDU$_jB|kMN3~j8}#y@}|%v-g{%^!Z+M&2)ipJZsFFN>b8kI z0Tl`IBT%UVx)jtboR;d|mZ-i?xlqTTAFL*XRA8OYBE1^!eA@xeDae{Cq>az(#9bKm z?beA?EY)G(tgBWaXywIg<6S4yEk{tJR9?K`lRK1g?~p19p2dL8mi$ALA}9x%mdX&6 zQDe6h6R7WlpaqdH6GGI9{icVga&N@SLe#5DLa~R|Qft;%FxtD!+5Jk?wJ06!9)wHx zuGQa-i`&9Lk_djHfSpV^T%-tAknd^D-`4>v++dr$gqxS?2WKNf)S2^os1XMVdcuFH ze!dFc%mv5pRit(Di(Gy6|LEufT71Hx!k@}|$#O0KB9FXlh~aOqA^Y~{1_<_&#u!PX1DG*K^&6OBbXV$pC}Avd6)Is=WqBcpp?&VwiFt9 z-FrNd4ow{^Z~hedI05si?%x+kM=GVI>EF#hJ)^rEm&-*>PGpnOh38p~AEd1sZu>2d z!!QA~O;y6{#P-B@)ABi^gX?>4eXQ*3Kef41H?WY|%&*z>V`DNs^UUZuxEn5ec&mCU#oEQf()PEPo9C^q`+$? z3Dr%X0#<&G@+>Exs1uF{Of+0Sv_xPX@^~dQ{TRQPlAYKpxaf|L=ykVl()~3F?bFLT zVu{jTY6(4GrM z1*^Zd#ByUEp)vC+l?hChxt+IqF+0LNOBM;C_n<{@j-aY;DMm?u{<^8zeNo`%$6D_r za-}6#Cs4nZ4i7%?#ppvWf7>3E`zdlITT7CW2`e>B#F40Q#opr2P3jKB`U!y|zvDq774!Odf2 zhp;COZu1f>g;w!m|NgTSde}fbf@f{QHgTIs-($nCDX9!J9UX*szlg_qq_XBVGWniJ z&J0ypITH0D8CO#Cwf>4lcleD6HA8$?iS`?9{lto6X_dQl^gI7Gaho(yE-u;lC92hI zdc3&v`^X*VR3$R+G?5&wT5IWF7JO{d*mVUwtSbC4AmoP@-rp48&=|EXnRa02lx5PVsq{0 zx9u|4ZF1IVQr*AZ*E+vc)FrhHeB4R3O&b0Ra{ncljB4ElJq%oK!hQ*gO=nN!$FA2- zzhS32`9)ci>?UQx5c^xM5`kqF!hd6I{KE)cPP%phe|V8uF^E&{VWL#-&MdAqDE~`pe}cl9xS9v zf(>=@M(-5*ybH9Fxrf|o~NQzR~>6z8*_f$qi+yb zK5#7bKG)gytDIo!y_~jrsuuX$x`zAiiRVuSdx~dCdLsW?dqP@TTlMUV!r$zS0BhQ8Oi#a#5J{{jj(J&y_Xyjujig+ekuA5a~BAhIFhO1+q3iSsF{B&p(LAjh&Kb z>V)<2G}B&X_?q{5bi($!t-4Ni!fei&EPf^QTJ-fDbA#OI>4cfgdo%%4sZ~Y$ZZK9J zyf>2uPJED~v?t|9Uyh@{tmxD~g_)FH9TLZ)ork>8v3UZi(M$)8j3dt8UJbXoGB-~q zBi2)|aa+BE6{x+^B9EgHs>)ebdes6qvgwpbC51|pXnEWn!NjlZQ;*q91r7%QlImZ8sZxvNS2X4-CxhKZSpze!%C6=U`0NNQ80L zn_-dCS2v6oBb7x;p=WkH_quM=FHg(h>FeW@!o~~4_q>j}Dw4N2cGbMrg+Kc* zb!e_TkK_5a`YJU5+-N4Uj#PJ%qV+bYGDj=YmV=U}p~t>_yXwkpytHj(#4<~we&y>y znTGd^&wE=Vi+syZR*96tu0CwPtC<`WdyzS~a#U65_x7ybT2*jqEtK}#?tbzTv`#zI z{e-U=Hu1Cxf9fymH_r)h6q-H9$TPzRzNne;!I9qV)mWD zky?6cnc*!GG%dN$Uww|?GfBj5y3G*bQ=j*OLH)ZqI-Fd0g~KD?7HUN12NAx~)5seo zn@wZjS|7#C!X><@G} zx9J3ZKZ{{#c3KPD`nEL5iHc`g`O-4b+guW3`4)>^JRvOZN6JAq`)(aH`j1)SkNM;^ z5HU7COn4oxI*l%CHCWW=wHt(r+3(Rd{VpS+sxN;6-)iiYcxEkck*WdJ9FY4^>8fw) zU%;;NV;(+O)4x_eFeW}Tx3;>|eRy@wk$I)IVtGdareihQnyHY!GiRpa!)k8A!Xd%K zti`cs0gJZ`>|&iuZ}~@ANx{bJzh$_QAg6{olHt^ekfyG@JMPQW_&965og;F z;gEFss^PhBJMhK=oa_AGH;6^NIBS)!M%#IX5&hIRR}MfGUYvZsm|h{(C6OU~=WQw? zrDD|wHUeG#U`B#@Vs$vAJ=tB8Q4Sp5=dnshbHF^P@VW=le#k_Y2wWiBA)ATHd1e=ekdBf}u z_5?XWVZ!x}+e@F4W8E|3uFPiA_0UV{i#``$>alG<^i0^|zvoxCbn~uGeh?GAC6M-+ zaXR&7qUK^1rbWZ0-kKUW;ZOc$okeL?yd5xJs8^A{y_D8E(K_U+TA6fv1$d$=fXrc9YRi&+^SJ?IR=9$&qb0hg-6ASO!9!YKhNB=tFFm z>Fp)-t+Pko$eN!0GErfKAtq?4;3hq4Hv_x41(+4Z-VfdlvX?W)tXdR(T!PuegcYRaz-;sTJ541*rSFc}PE2aTJ;$bsPGpJBJ-Um()+c;&f@oW z#!&Am#J^}TcE@+*oY3#yN39I6C41~arrdMz$LNREPWx+I7CLDBhEqyuZCSwESD!<_6$961*(02|a`#9HNQ`9^Rh&9y;MFlqY+) znJ<;5YWhJl^ZNgsF_Q}OYivzzTOR2=+iNVmx-*`Veo3YiJ>=UhjfJh zS$-vhyp(;_?H9-U^5B;%n9p|1p`VG8DjA-`zx$OKf2;l8zhwtD+HV>k+=nGBCd6E- z3jb98a}f97v(F;Oky7TfwRDqfT>~5ohbGNT`s$6!T)4e)Z`}L9Fn(Yo;i?qYC;D+eJY4N4 zj0Yz6CzdY_#}w20pBq_!{5U!%W7df*?rX6R*Ig%5FC zM%|^Ic~@PUd;_|Cu(5T{f=WnG$pR&=J>)%M`plJkvYU5u7NE(!Gw*LS`wmqy-aBk~HCOX~ zKV3k^-Ys4>YKynKxnmlu z67)+EBhbKSwLShUw0$l4_b=#q7ACC|Z# z>Ek*_^{#<`5?pU`<2y%>5T5(UtMx&?FT0Sv*A2;{Z1p5Tt}06MLjO`XG()T0aYe;* z$LjA?!w@yv*IlexKb4%24-d*zE?GLMV!ORLpWpiI z?pHsB?{3u9MA?7;6gK0d{d3f`G5j1g_m+IescaeBq@*3CUoc_`m?LD}V#H+;FBeDB znNx^3fm3>JB*(=1SkH~OLC1R3SNhbK2gY7Xy~z%6`P{jL8(0YF3~H04yua3VbNJJx ze3vLl{-z>NE^745nSfUf(OP$kgS7@VQC7^An{6X_kv;Tp?~Fp==PJTgUH)5nhQSAZ zb^glzl()!S5_7mp@DFs-7|WWviC>EzyiMKk)-!*-xAu{>zlOcm*zPlT=BLK{gW2s_ zm@>(`@@TtITw~kK&6uq08xpmR?2)OrzMu63yZYg#(s$LrIb2`X){0x)y(H#nv(u+m zW0IC(k6((cf6KZF?Js@58!TY?Ys8ejJxD6fs6HLanW}ko^XDUQBoI7|&Lc8>(7Cti zrC#-;#RPrQO5tWW?)=T6tpDGcz;OSnf2lT5n)&eF>YMj9j_1%m4px^G)4En#wtNd( zXJZf6nEBp$d&4(#1S+eblw}~cGhRS$Ja@CTA}hN|H_uko!87!bR6j{1QMfX2ynVmF zZg?HCEV8KZb@s6~kPZ2k-(tCHp|}2qtw`Qq1mQOp2G3Twz29~C1Fg&P;-{aP&&4pD z|0c~KI;bziI!q8qLT!D}!4tD;xWZ^0?A51!4~i=;U~8}fm#1+JF=g+ltNuY(BABtT z|J8El&HTqE2L}n)J4+L;8y&A+e1bbMJh(4F(NOhT0O|@=44ZJx6Fr!9Q=`8g_u+A! z=Gm;rF#PaBk2pN}+LK)vSJ8W>V|)E{d?>8ynxsnT6GIiH*C~d+=6COko&96; zdcSGD&o6aC?Nblf?d5c#19Ene?z5zGo1JOEw|x$LZxgG$1Hk#l%ejoph<*vk3EjtJ zh0)!#&2cwpg2!Voc_v}O!q}n@_wONeJ<;1zxc>bc_wnMrn%&Rk zL$$zyrfGj(xx*p1+jkF(IGCT+J1hY{1xFRSpGFNTWJEssbhGK>s>rV18)=;Rc9Y#{ z2l~rRYRulv?H<07b|A0OVKRJ=7U-|^+{*KRIxO}o^jT{#MzK>It8j!Hxk*v{=zO-f zbiTon|DXty<6Q&%+pQ_A>_s>5KF&HH>?_*4xgogKz+)khl~!sYgpUOahd*aoRYVyEwtbEaUK%IL>h37~4@$~OWXNc7&cnT9qf1ic#On-ke z8tLyl_*-W3+rkJhLWTjYf5U)&eB&#&$j(YA*4$lbx=3wk%Iddd>Kf!7^gxh&MmjJy z>c^?UWrPX^Y)eCLQq9J~rvZh{{G;Py4;mKXP`$5ybr*OWXz17HYOdE;+^K#uvp*i- zhxJ18=y%t1XAB@0_=z+9#J8@9ADPCjXFomTOdWK&c<*<5M?GdB`of=&%k`KmCadq5 zdHer-jAkgtEZ4FLnS*+?jirn(Y_BW#qhCDTwUOBD$K8l2^*)C4qgG=Bj zUrGBO=Wcxc53kOI$r})KqI1Z~R=<#)#DA$L2$F8){M^OwVmnF@)2z+bGoK#Z_!zQl zF6@Q%bFa`l0gBQdbb;ub11RpU0NX+tH87>Zqfg!fQwj|NgEk?`U|F9}Lb?p7ye-0HM-L8K+<=Xb=$B(+~K5lj5=+V>DKXx*p-WY;Ts1OP- zXBrcD(F0S_tGQzh9V>n_>S`9* zf=_`%BaJq^nHzP!1lx!6T~ZWvXbrM2=9cZUtQLV--F)EOzSDxqOBoR{> zF`s2{?~*GtIiNQa5~5Q+Nut1@+36b=qoG*b@G%F9@lh7hv_X=IHXxkK4Px$EU`M{= zRgN}CVI~|$-~9F|>zpvgrKnaY@TLZ1UR23PUsw{WE{JraWn za%6Nyqe?N&xlrW#$NBgTc9fG7E~EV7e5g^bJJeuka$jDc?yPbN#Dsh>4Q zGe+>(jqb}9nL4<;57+hUo~!)!U0_#TETwtJ8{<){1$FAOW_k4*wKcBN_GanL8duO; z5%XNGb1^xdN*ysvE)cBUsT`q_Zb;-=h)ro^77B>6yK^k=;#XC_A-(-ugf%^PG7(9FvdTa_3V*9E2uCQHtPWjFHhIGlelF`DY4id>W`}t4i*q-Um6tiyAL8jc zLB?p^it?P;JXN{9q1UVmEMu4fq+t84aJ7;9}Qta&N!~!pNG`c%;*Q@4#o3`sMZ1ksqKm& zXtFDwdeli1ETY;YL*^Ur_EdMp`)fE+_3Rs#tfeAzm#rl?OE^C+286bZ6cYn2=eeuP z)ynbyjhoUb4b#{ecKeh3_?mIY(JTX7dCTmzmtGWF4N>;NGQ%i|LjOP3Lqbx=O%a{R3Z=0e{eO5T$b)r?5(R8nNgmkVr zBiz9aS39!V<)>!t?_~db{)*X2gy+2R;7F9faEpF0-oKAu)H~#wr$h;LnL8LC8o{J{ zxYmz9uiju=LVi5~B|iRUgjk!>(dO9Pm~UO6#Y|)GO{KCM0W({Do1GJ%t~b8?%G@wa zFHGMH8_@hWa1__X+q_7NraHTsY(ZX5E!r#(B$vaeF_gRSAtNr!3VJuOHZG?Stum@Z zjueyhLQUP&nDxZr_^FYsI=(-`ExUFkK)=8GWQ9%B(+gs${w5ZJo)5i}$)eGuC34$H z)}&FE0p_zBBcr+oa#B_e{w4x8F}dvC1A(s_xseiTe`fWLha%xi`vG_~=&jpU*$BB+t3>tW5^12$vLmG-+*t zUon(AxpGazh*XM5GJ_&_s}P1i2lXn|E+xFS$#Fs}HI&QZURy4V7SZURsic_N8lk!m zZ=;$OWIl;AYxS`-WPl60^`tXp3}=}~zHP`bs7Czht_k}2UmJTBrVm@>5T<)YmQ>=> zEQyE{KP5xgO$j{JmwA-7d-0C+^1g6UsYw}ErHp#;G}42xzKVvxp+#dA+UkE%AA(YA zR{fE${&O>f=Rc90)P(C~PCC~4Qho)TXt@xN0M`9G5_Zo7@AX*H--l?Dli?mZjqOJa zBx=od8iR>?=B!T6EdoJIzo5VQG=jU{?>l-$g-X5BQqV+XjRanat~pm3m}aS?>*_)FIzpC61E@?9pVL8_BN(ch~`c|#1XGIc^h{vv*)Zw8gu0hYCmpT zS(&v8M=nCD)<&vRt9q6E!Uw*$r9g#)Bh|5YNh6HblmcOkUg?5fkvXzjT}x$jW+A}9 ztVUgnGO!*Hua~UPMD%NxOuq>$yENXJb5O+dN}X_0it@R*h&7c*tu+f7phbS)WScrS zpP^7Xf2jKo8UN<-t^|%2)wpC2$j}zlHv+A5LY=4$m8>D6X6uu=huu;B2sZ9*l4@w?J7ktK0 zm-*TQIVI>ao9vNN*u0Lbz+gXbyj*DVtdvEvS@Fg>P7+XvR>6w>mP#c z*Mh#LNhCq0C!m!bd6ZGrvDjEku_=X~SmCm2!}_!8A_p;JL9Foe^n4zAaE^2)eVg#|2Ij0hGkQDlW8fWOLZ*l!yadx zYJFij6v+5D3Vi6ANKJ3LX713jIL#2JXgF0a8VYGX8;PT$ zs`@8$!op(4I|;4lLqDQCM;5CkNpEcUD^3kH&hJ}w>Yd$Cc%y5iv_|F9<#!%t_2opd zYjrBWwMYRr3v9%VASdcins0!Yg;_p@U9DvuF{3_{GqNJ;aG@zPduYZ@P;n`HC@khE zVqiFX2qpiPTZN<2;&EYI?haAGvIrNIx_7)wysR4 zj8wqKJ1caTR1vL|TI{sxDFhWeIn=o4C8DgS#*Ee~a&4nADB7_r_FA-GfGy9>zM+#K zZ5HQ}6=Z9|yrMnIG%B}5rbZ< zVIp8NRNIkveFr6zD~d+HDbF~~2rPb&A&oKThEZT?T@4-hJ8Z4DJQ{g{ zU4K8oKqc}=f%7LNO2A_kTzVF;4}GfrtuZ* zm9CJScv$XmwHns5d%Un}cEwP3;2gG9mhxpI<4tdMj-dfUBS)0d9T}n!qdAbkd{x9G z$JGCo*?3grf!M2q!AW&TH(lhsZ{jb(RPRn8>rWx>I48n##iT=%4ARLd*tD~yh8mY# zwx@UJ2g_(99GrKicX)<8?+8HR> z8MN;Wao0xZ3}t1F{9SO>pv$H&w!FgkMWx%~M;+n5Ozs_RM5s3FM7*V5 zMJY;zk8J5T2IfH##!F|GK=<*x^Cfl3S zlwt6wPiT+?6BuPinPx_9Cu7L*9?Oz; z*lk_Jx+bIBp=4HsNG4ahc^ldsD@?l^8@eSpkHzB#jaqGpvJ5Y6)*)@y&E_5SvjI)M zlWRf5NyZgzmPWG_{iNMiQaIVnW4R?lVkT%p5lib3E!_GNXJg_qaW3XDcb`y7vCX`P zi2q8&Gqhs1E8#W@=IS%cAmmRnC!2 zu5l)JCwVl78Q#G-R_Q;$aB(+@;upwm*9pp3 zt?rGJ-wqVfZ`(fi@Y7@mZ=+eig3<60xi2U=*ejU47ILh5U(&U>5VcF%2swPP-*XQw z@2!y{Ln+=h@9xatLpkFP7{s9*Jy0z^)T&_h%X z4sn)D|B_#bXukg(41Vo;U5$j^*?Rz2Z-E82m9&1)ruczsrf?gDzwiO|mp!)Zaq&kB zY}xbTS-<*ERa<^Z#Q?7CVX+CduI! zutLo4D)u6B@S&HwsU{ocEfTV`-Pj-x#|u+^>ozw2kA`e8-8qRgyMnp6`cm#3XwuK< z;JgCg$@AuG?nL96<3JbIQ`_s>)mbrF*w~e7ILN>`|S|30({b@lC zi&rqgan!brE8segAr5xx4C4#doC5v2BvXcP)EjXl5NPsizOX#K$lHMkm;#!c$QD;#S5^WcN z$|O22FoI3@;A~6DiXXqq$#3mLKY+F?&L@L9bjtBe?hs({#9BdwlEOptxmOXo3QtIu zuV7{;fl!kXdlbC6V4f#H3xs=;0q17hlJQcEzfE`9-e0s0Gkp@JEd;7#5dn^&wd)jN z<&DY&t#RcRgk&GF1ABiE<)vp)wIW%rZ3Uo6>Y*Y4i> zx8=xI2B^{y4jN%X<+nVz2yAH=wP14Ik@0wu%OcJft)JA#0cT22El7XcxsHLvD_ zL2Z*jc|ky)mJ^^n=yXaz2nr=wq@e%cU(jS(4hHbQHIH6HbKo&L0L7nK!B%`tAM^KE(PL-4nYSFUJ=R+fVOwC? z?iiH@s6SLZLdj0lET!mz;j<2f9^(FF55K0FXXHY2ZA9OR%n5}_7Y~_H0@hYfJxRx| zU|!8oXJGjiEO)PW*LaA2POKxI&IV(K5Kr%J2)+`N44MTddn}s*RC^;z3;U^;wxv=G z)D_7)ikK#KbsEpaB9-h&abk1r9EkJZ(%qLr_ItOCTnf<|DQ+D-k=a-e5bOd7niHkN z2ZAgqF^Ar2#M43!1v_`I=i8`0>AjZT{nHfK3G%)AM*#Mc^EOhl>bxi@D$Z!F^i2!C z0q*o!pa$W*cXZ9-X8$-2vDfyupt1#9+$(^mBB>GT&O^YwsXI>sdSy%04EEbVOrv<9 z4|gYa82_RWn1=fOf%9O}5dnZq;Patiot#xLjb55-vpP7(rsSZBif#Rj4?xD`Ir9)P z!0sFHyA<%?M7~*Hx-=QF(Co=KEeMRA41o+MM+39;P!Uf9S~i&lZ+-*JsZ0$v;Eat{ zR{+|N;98{Hgj`UF>9hr~;cd3$GAw$e+B?`_**heBYVXFH1r{Z~@x=^az~Ie7Gyz5F zU`_sez>qbT?(P`Gf4;=aVr#FOPfKrX0N{fg_;R3VoG%yL>E$KXzd}T3XNa0}b)U;9 z0sKQKQQQkrP%qIPyVe9)zp&Oc5EW;LBAm#KItA>)|5=3OI1>t?!0P*c z*Fdf(R=ukjhWk-{FhY-I)x5L38wv*f)-&`Me?WW`=wYjqdY5^ap(~SGqGrVG$6F`htM3bC?ued2LQ{tn7#Fm(sn-4^KBqd?+l(j#0 zqEkADT-W++Yo0TV2b$9aq~KtZL%wm8WBS+aZJHjH+rhgG))4$UKo|DbYnQY1FNy?&p@ zGdj}>tKr8zjy>4jRhTe451RgQBz~wmgaGG7Ipj1uU*m=KoOXS66@;o?Ujk_E7)m!N zl`FGwQTQJtu_maO1l|PO3S0I_mHY`H7!JPSJgu79h+XnGq!wAYh(LX~6WHN)M4>;q zv0l6^jylf;V0(j+Q{MsD{=jFl(aQe6N=6&CYN;hl^_ffAAR>TzaPJTOSnD7z)i>Dx zZx}!X(D_SF8SKM>v@~RGyG>#Coc^uRp+j|Tv|uNGJphy9giOrC3DC(6 zHlLCSZ?~Nv;GE`v3`Lb-+HFHoL>Hh048sbG8Uf(NKrVx+gW>q;UO0Wc&dlb2i z1>y4C6q@jAi2kK zF{OxGOoIs;0a_cjeXd~d*-cq&%aV;Nbj<(hLykH~D6qKlxGs(fKo<)*5sd~RMuI5$ z7{`U52jutf9BhQt6}6-zQ1Q zXuoA!7%zjdAA}5pSVhkX3)81j2NV+Uvjl)2KSx;mdnnm}7Haw`$~5n>%6w0RWZpdB zaYx>x0w9lVhaKa7xrbdYxhgM-7V;v@bZA|t`JSsbWb19-L)=14k$0rB9RYN6UaU8{ z9H7K?!{-_}{`|dp#mV7--AIlTKNkpmgIQnb=IE)QC`NPdsoufmbcivI^UYinrRS7^ zMAkr}bbv||-@8s}a4=W)Hd8$eAK+L46gMK2U0>MG=>ah4tRBalFXBo~gS8B(W^z@U z#mn)~ISgoR5TR^mzsOOT<>+U}r25L{Zp!v(m(_uqx_R{hVM*P5z=~}P7=cluGf8ML zz-N|#oS=(Y8i2+$K#n`xDn{25(6>U-CC9<7+d$w-VVI^zX$oVb6ldsZFyvo!yeMN^ z&~HY}cg8V=UeO$U9qSmsU@18x?69JNKx-&zUW$lcvjhlFaFifjY+@YabW9eqhya+w zu&l607H5({pZ+iKSkR5B-$k%k`Jx4zrtu;TO2 zY_$;w%!B(>GL4hm4Xc)PGT%I}`p>)FA>>fb|G5<%Dw*8C91+U8C3fIR=zMex2r{xD zz&0>ih>^h%jK?zHP*Gzx6_&e8`U~(ZjPRHxbhnsMD|j!f#!4#8rEmR`jq0NWJLxWE z(AIihvi>!o>g&8ay)8e)0kq$Z)eLepa(>ll+DZb%w#7ip7E)JGz>uWfpW@4%rt?jU z`dSgqyUSKe2#veTmI2a^^*K{B4Ovjj1?ffft_kXhUq*z$I}#Ib%c)dRg!+ zG$z?7@F9!i$W`+Hm4kVciv_;Gv=Q#9Ete(Mg(cyN$$><|{3@h}Xa-b* z=`ahn1xP?jf&YF9ezsJ4)kd&=H8z@@9<0c(1j>SAJdim|_i1Tdd&AWYrsc?}5!&Ue zc3F85Z_XYNfinU7^0=p>8A6+(nJ*$mq|TtZhnxU_G<$d4XIBF`)>~CBG z2|z0Za_?aGcF{q^p~wMV#53p@#ZB-HI!v%jco_X0+V%kk{ZYL?LYHO1&s@T1>F-Sb zppXE?lh+~u+FgKmDL`3eE8&IG>|6pDMuA4O5z;OboBLV!MfaBp3#bkrxv%DGc zY6)i$aLg4ZFms(xg|!^eZ0iMTODB6qq%GNJ)ow4xy2g)kl$@5PW}@~A+f>GnfUyIe zRUF4el>*+3n-6U*fOc)`(Ck`;t@8pMVOo^P%w4VxHlTA7h8wO{kBD2U(@`Ol3X1B; zr25jR0?_PFJ^`>Ql&5z`7b0T7^kG4orMDh#+~Lg>zh?^lp=9(~6qxbsTM~w~buFX@ z!MTCBq(5%Np_qRZ7pIDnfo9WnCe?c(+GRmVZF77wSIJJX!<-QU#I(ageJ6IsWO0=s z685TLm%$5<#! z3SQNW#@K(&$_b(fJ2*B&Tiz2m&LI|>qu=_3K0C>c`@#oa6%&smo<>#hVyr_}7zyY> zs?*Ax#Dh&xB|!BMx8XdNkBZOk6QBPK*G6=L9k9#kFnOjmwzgbC3opA?9)(d#CzcsN+rTh0Oa=&D zb3{qhbXYC{AchXaiE)(eq}Q#n8VjIIUb=nU(3ORhYij&Md%yExY2ZX_JWZIN2N?2U z@E_HZ^|}a4kW=jT6o5!$uCo69l4{1ynQ>HPWg-;;ShvEWzf|)=JeNg-4?4@(gZ5=l zi|3c?kCdG&CF==**8S(QKvMCEBA{AEPKUXW)>*LP1lj*aJNAZ%pnp?rWhe~NGse?I z1Ge?Z_i?y8K8%ErGq_{s$7`JE46y@5dK0PCAf07wV!@`eT>)8_5(8Pt!EuQacfjkY z<)LoeMXXt(Vt!zf6L`UaZ}OZzHYmVRb?Qx{USQnhJRY!)S+m9l($itn+v@Q0A)-^e z!aLOq5quD9t@cd}+j5odpie-|!BhU9n8O?N4F-s^>cuTX870eL!v72Jnl{3@qb+)7YJ6>ctx)(S!ujAPx#L%2384ltrPC&4JdZgo~CGyYk&U9&LV zp8Ok7d0{@M1+o=jAP8iDa{=563IHYp#i-0OB97-hD9Aun`lhZ)6H{|(4(PeNLCxeP zEXHf%x@m0GkvvcCp9G}09Xg&eJI+xBe3pZzI4yxQZbgO66j=tQgAE-W->OTZ0Orwg zlsQdCcm$*-NfYSZ^_lc6opHYTA9S)b`BKC#*Ti(7?{qSy$Q7!_?3I&;C#BEbz`}he zb~k55DZ7F}A`o$nMXy`eb~_M~lhVogTvR+O%?s%-123bO!(7{C;FNSDmFoy(@YR0)&FDL7GXRgI+F4WQF~uh=n{$p6%e+f|?H;+h!5PE_~tE{Umgp z4(i9c3d|(Q_A2H}0dOF8V!FK&cu@>Z5m5f?*OBMTncFQX4{fq6QCQlvrAKMa5rz@y*_+f-Yh z1o84m7$&HmKx1_9Bv<@O8&|Z+%y36^g(&Z{!Am|WyPqh0;IaG{n|xIKHgDRHdQ^M| zuzriI4@%{VbKp7kjDN(*r;=t5C(TFvtBvpj|5yOux2=chusx-y3S={62cB1nD%nx~ z0a1|2(agpJc*jTNe)r!~*lBVfE>4Xc1v#3@bIUMNRcJ&RK(ZYm*&&ir z6sqm|7s;D@en7DQoyGwR2xcV|8+>$=>kfB+K0A-q^m4rF{HQS_PjM)Hk3}9M@-KuX zviU6B7cgYxd?+3NGkAxeeEH#*FeJ3>nc|lXs=#vUK$y@?zKlGjVfF~IL9`cmc{$eIs$fT06U6%KwdOfu@ey@@2m+(pa6+j z(DdoHo@GNk>3fKt^CiWgMbiVJ1Lh~Xi?ssr&ke~hM1aN0&T6&%_g)Lqy)uy?0>gMY z>P$_oOJuY6p&oPZ@O}Q(X1Q~&P8|n0l>_Hi%Ja!yhVpgojd>&W2Ln6Uj`Owkdr?#C zwC(pyrqTWYhg2a*c>s9CUx`!K#ZCHZ?IGPC)jCT z)&PGf$C^?CGv;T?oIg?bf~I5auhExKgG2tTQMH1s|nm>=9T_?H$y zhX>l=4!nd3?g5cWKxF%1_>=_h5f5}P?g%J%{8ziitoH5z14KC40}R%Cl$69rg$JbF zAYUSjdqQdpBA?^Pdz;0|P1bmXkLVcwA>d+qSfY(Szp=KD!YL(nTrfhhWC4R6VEDxS zK|H`Y%YU~7JxfFK_p?MfWI)#z)Iqy2vjUH0WCS#5~VZ1|x zg1k6spdZanv9*neW3F!8F06WcuMMuRIzM6uOS@V7=>MbZy~CQyx<}y|8)E|z6_FAZ zfw4dYMmmWdm8PPiw2UGmB3&dvNK_Q0MnLIJQHq7AARVGo0!9;*5~T%5AVP!?AP^uV zcg6Sj-h032KHndNle71#XYX}ZJ10N%+(SEe^Pk_kygN&9f%Ngk4|0h0{AiM!8QW{MX!fp~6 zLy81aBJwyj#4xs9(a1p12pGvg7db$l7=mNZeDbxfjiT}qpVXVZN@Sa4{@jYX2+4<# z1p*%}B*TmhAsV-u+0M0}3V3&GYD!?hD&I_2cwprv;W!1U6fD!Q3%!$ARQr8cDMvB2 z&nI0j(h9LglM$5kZiSMZzS_rx+{>fCjn0ash4T0T>`A@ARq?DdoiAt`9$ICkIr#Vx zHA+}}RB}vq)9#cEyfiYUMFjN!`W_k3Uu_&Tnt1^H7$Cq~c_N>t`p_zjG%}T*EW^oz zI;pg>0_YAn{h|1AIX|r3#Kq|EfEzV`>BPniZm&2GLwq29Iv?rbu+k~LYKKm^CF^ZP zEDHabg=z}e%9^^9`*|np7b(-Vnl~6vEm3_hO@enxx zwcD6O+7PI5oml;l^*o;hfwEH^ghDpX8ySB=3PtImmGf#w!#h81(Z4`B3y@S*#G^1@ zf|2Y@Nyve;JeD9lu}HapzTzT`OT!}B6ZzhElvxlK+31JqyVtA?)EB)TLFj3#8W!OH zLa&G7>EHNe=mDv2e_q%ugJqZq+pj9XG$5jB)j`7&)RIx`}_DA|jbX?9_I31nS2&I-D)u4KF zP;ky_I0Zs1nvF+=4nVpD6pvg1=@Q^_T;U;H?@c!ml%xsH{A^eF;BolmTh51E%T}Dr z;#i=Q$d?>2O&I;f7x@B;PpUX@_%hCA|Dp*#sr$JMtP#02kgtj1|0x^;y#y7?3?2aV zq`?E&z1*|X?1@15rX(NUjc_Z@1el`ED%U z8Bfm5jx7MOY(d=Y_<{i?n5xfTW7a)gVzscI{y6&{`D4HYL%7?_5H5U1?q!TIBz=`d z+MJ{2$iIIW(&jRbCHpN}o6FJVPUO3+duUa=4*5RDn%rE<|G3QqYcEgbNCpTlLG4nX@_}l5C2I3`#U1S ztz`lwvFYDwRezv!1R{urnDF{O$p^`D4LfFoWWZ6VS*QB&SAIaM*dV!~$8jJ}?R25f4#w9*x zATb|#(ZSCtx@wt@D$J6GLWlkn3gKWfbXnLpY=ms;cKofeNA-^;mR9(~>5Wc5E)aXK zoOSx2L`hm*{*>silZ=KyD@m@$J3r@98Nb>Gmq+I-)VyzTS^wVxY+=UW^n=UR;D{Hn zA`d1$lkV`p(4WN}Uk)XjvtLrGjLSSde+lKUWl63c17BoYOS|@jYsI4x$B0BU#%8i4 zUxVdk&1@>|e9T^ubY50sDmEcT1qK0v`F_8i_&M9VJM79Sw*9gd=FoM~Zv*gIAX3g6 z$YSi;kv2a9jOjpmuVb2?KC@=rd)}Ki-(?4uLfU?D5Hg$eve2v?A9E!F4Jt~uBHXdJ z*|hmrIh5M-r1^UQtXL$NnK|!rBa=<3&YYH%_*+1A8^lFp&Lqr_$NoVVb33X zyNx#X3ZkKHEfK~GC2GZVt(k(d*|Rzv@u!%npHN$C@wy?76fPB=0zFYc&j0jf5ciJR znKe!4Su5Y8oF+Eq47|ZQ!2}L8Qy~(q%(v}G3)#+MK>)Q9yPj)Dh}IftdFgDf0X)V4 z2Sx2wwH|=04Rq$-KY~pjA^+p0nQgtO@jJ%~V*NMAY7I!sh03C=5sq=WBt0ZspV`SY z?v`}&ab*QA>k@yP4<@Wlr0(LSwoL=i+GF_sZOGNfv-x3!Q8(=JsgB)1#2&OnYI-rT zrDls{|0@<67B(1+!9eV*I`q(7pd6i)vl&AXhKLlz#;_p_%fB>^8Qz7G2pExm>wMaI|K*kE{ln=}y*93m@}Y+oGb%grH~)oRiy-b%COdKFDnkEUUFiyt}+>Qs#qd z|pSfsKVC(g#)x&FZ8VSxWL5=#{#yg=R`*QsW69 z(29qOl3Scbai9kvm38baTRFh<)0;`w2yoCdmMS zZ!JPVpfuRsZi1I#HU-@qGB80e?>2+DWe=E^WUH~&mQd?O{KvG&4s4Z;)UdPg-E2`0 zOS)=Ix6xO#tss39C9TNrO|6ff@hnlbB;f5&qp6My@LZ{cz`h8#acQM@sXHaej*F$e zhN6v;R-Fvz<9|)gpqa1_&f+e%w9omWoc`bh#WU3o9dNpDB2y=)`0*Z4in$93n6>|t zWvSS#BcE*LthXo4M1R&Ib0P1{`QZ%#@#KfBB|;acEsF2md_5p2`Y==&*fVb0@q-K; zebUF1M|P*5`xCw2S>E0t?AdF!QV#N@{l~MZq~a}rO?yvTl}T}gXa8u0=DYarcNUof z#wv)iNpYS7MpJp82@m*Pv5XILgH^z$uD9}60#QynOymw6&G)(Lu(T(&YTIw$1jfJk z+GTD^w#tfcn>f^NBKAG6C&hj^$_+vA1e+_fL^Q#XfJ)f3MD-w0XZC*`U2)p>5gkRg1b=TGq@Tr8dHyqqN^G zU+a^t7Ol?f1*Wnpv(o73k8kPjS&QZa!gE*Blm~^?5pMDELG{jl?mcUR3Oe~}z~BFg zg$7-O!J;MO_b_W9Z=(v-WFQGMfD#t(8RlHv6s!V1$-k2+)?6x<{Q7cO79}PN@h@KT z8X{wRKZ0lrek0lD70U;%4mpbXe(6L8b}Ix#AD8mGh1wz;5IYwx><8>RyrNta)QE+( z@bxh;P(N|fOhpdfG(0fCp8Aq)n}g4OFI15|!Bav9DQ0_<1m z`851X57!B78^OEF$X#p%p`zkPNXZO>-O2v>iy4wwC(-9L5RP{y#1X#%4u ziXJMBUz9KTSh^Ft1!AHQz$q;ludy`f4Hkd7AzF`@Cq!XBmQ18z4YKcXPI84#Z3M3_ zd!h0ui64}ob_ita+;e&a@huj|K-ZIZ<1UT6~Am@C@(maB=EKK znb*5CYaWH@_rcn$RrRSi1=a}lrW4XV=Zw|rgX_B}P2PZFrOBH*I1R}gTvqb)$!_)A7tf+qbb(;757! zxQ-VRXJ?&-H#eb3d#7mWH{<6NCxUVE&{uK~+?`dH`E{|#f!&}md)Ut;={a}t#@|ID zFenlQU=1mjktilxh3Nwao9d!`SdK#3x>r2H_CeDS{F^WOC?sH+ISjT?HpcwBGL)Pj zy>s%5=S7#)-AdyaexX1pa43Jd-(8ctdGamoc$G%ovVxg`&G9A3z-xygb#ot5H&P!6 z+E03?e^^nY15Ucv8(R~C4o}8L?iTbKDNc3F0)9^Xv3y#10ILSD%nsHVA?g%4uydBk zgDDHb>huoIoq51t5~~;uIUlKk;)hin1N>hB|0Mu1{DPP48$-`vGWnNcQ|=$j*NL+1 z|CW#3n80eEO32wGP5pfnqGx6e7j`QrKrTi$rEy3-v1m7t{;yl~2h^L7z*k7zNE5_y zkd(PNKbn8GeqYfGmP3VRu_|;IY%PxC0t`bsO2Mi+Zt=%P_7k9Y#`3o5Zi4RUphu2Nn<$TSTsh-|nN$Nxt&C;6xxmF!$DNk{pI8 zig+wvtVE)a)5VHy2K{mESLO>nhZu-$MIohEtWlr3Q{5nHG0|rC! zpRhmMCRqpDmrsPj+}}0=D4ud!ma;d@uPu5YvAxl+sPJ-QR<~oy$7gwokNjtRoVTQ0 zB#gd=`9r=JoKU;c=J9Rz|Gc_0B`n;Z%nz20ACP&C!tWZ8nK*!V;c_j93gJe)t3t0V zfMhcDLeJ$M{~Ew{0K1;RCnFY;EcZMIP4Wq?rCk--BU}^i3oBw>-95}#)_tE!lVi&td*ACGG!U+ALwh@z_GE+iA~hbsmFYmdaAzCZ z!@*tj5A?HIp3!^fyrAK}NZ;Gnc!8%MKi1W4f=_0h3Ig2Y5!Hj^AdR_ikjM!%M=!kG zn>E!D4(2nq@G{+)vJe|k*L@PLU@gYILmz@T>d9$I0fSee$U+{4BuqS@fcR;5CY_o| zPua|?7g7P+qLn1tBaHtavqBSzp*JxPPW$vT@>&)zkZ&_D6Gs1p6H6hQItPMvpK4iQ z#0~4_o5IO(SVx$PB2}}7X@R_$n z2uO+V)$CcP?cPOf8;YV( zM1kb(_A>H)1bi$-5CK7m zRD>nb&15?Ee;4cId}&{uM*agzPlHE5@EEvuDgBLD51{q7P}&@?DM@-Jpu6q-FL-4uSN*}jLFo*&s&HTAoa`2nV@6M z`__RhtNU&dK>EJ>gvJceZh1OB#v_AoFsh9;?TZKkj-Vy3AHnyL)}J^+!i^>`AI`6j zp;nS=k7_<5pXuJ^Qj-&cKmo3>b>P4N4ms8#npjrq=k%+eXSgCv3C6@6^pC!aO~gSo z->(f3^XcXdiAA%XxHf0r2&Dv&t8yBkB30YhP>{8lIx5@}(}fFv;<-BN!s|xu^rQ5AG0CZh*`u zgZGa)1MZwO%GwB&l$jrIjuDKwwo$!-3{}%jtf_mcm#_I)>Agd0O1oUXdxw%s7WZ2X z|HQ77@xAXrsn-RkLtdrnYwG3E^H#sR?RUkqtaMx2(_FzSHSDl+Z@l1J2BW{=oU!lC z%(m$u3foA4yW6aXBIeSfcu|m&iQ|0;_Vvy*)J&W2gSj}NOQy6r&KK{rS2GQIUhebi z@A(b@D+?8+#2?!$Dn??`&TUA^)rqidf{NHj4Zjfp`){9p#U33Zbzl_`+~~I)M*z0m z+U)hl{&c!mwf=XHJ&bffrD&-=Wgl<}wQS*mHpWeFOjcDHMDubc-K3!k*>3P$j_3bw zk%RehR?ODY6&1RHhkBM7Hd*^A^sF&#^r%p>AwnwSFUaZe55dzho6&bNSQdPBq3$(R zpWBFfZC8KgEas~6hF3tRyT7v{YoxpBa&=YqCfM2a?PC)PfO-tZOhHpYvB&er@0t$M zDirW~pot<7seo@+u^PVx9bVn<4%4a!-TkD^aX@tZHY9E?B^HGaawdZD_@886?Z1;Q z`Q~(COna>_4`5LhhWMR;$4#_;Tp4;$R*lC%YfI+T54sA#3I zqU7VzKqwrD$^n;X-9<`%*j@B9@#fzxv;YY$v}PunX(4OW;wW&%%BNE~Wga;Le!4|o z$$Xv!tHNRdpcZJswn1THhnc)>JaoFO2ijkz?W`A;(EnLn)0S^KRgmO{BclM(Ch@l) zIf6ZA8H+_6fFj)E^pgMsosTom(5UPqW$`P4ta}V_%C0vcFTjFiUQ5sqiGAxQP2p;xVsIo4u&yIr_hk3dY>pYGmOTk%IA%4x68|F#XM+7xwP?bW$BKbXI< zUZW_6b=t2b+O)ew=bj}+WA_mBxc#G3FYa(-B|f^@>FT_x``yMsr+5cW3NTc>4jNeG z?R{w^^YU5Nr+m`ouB8>L0yUgA+JEQ(241kPRjeqE_iO^6<>Nj-FQ?V$%>bbV)aypL zY3CFT^}-IdZRu}nU+ZVrW;kG=#GtlY`#SfmDR|=*7y{3A9RhvGu_Aq^Knx4Oh={WU z=LF!F=85)_^X@j!Xe4=vg?&Wr7S!+2ebj5nU8WM~q4OAR-pX~I)YW2ssCxA?a| z+mk`U#haiCQ=ymH-#Td_d)4kT8^ihQuBj4`IsrF&iUqGr`X0xUDZ(4O!SYK!5`S< z0Mr%J?E1>op-cqV7+X9-HW=G2S}R}(9ih!u5qMI~j^qGN)O{a+K$N z$|+X0kmI%Z-g&WX*1`#H?|6|63Kn@7Y?%3Vknjbz5g#H2!U_57yhyYvVsL>k^L7W1 z6h{-{#bGxQEQ&S0z0@@}=by!>3bqo-wq0v_@vo_ln~tGbV_ET#SVV{0vPwV}&cp?r zT28$pv|U}2Qo;zg*KGhw#z1LR9X!ahTPRhu03=j~>AxT1fnx#-LautrpkqE+DFxCF zez*6q=CdHJq5!b=&xOznV?Y0id?Z&6ETdQ>^tGeyid>ECp8qG0az~%_vgkjNQ7D{Jfn#2i@oV$WUK)S+vdFtB z;2C&!^*z0x$qaU|HI?<5ehBVG9GLg}XXf zCT6|-`^34UmfL=qhKlIiP#4~8n1rB4oH8PDxS65j3z-4DMI5b`!EwwGU2YEj7}#Q) zXy@$0d=|pq92hofw~g0f$iJ1d-SFQ%A8nJAQ?Vc5^R(rh{x;r9!&Sky6}px3N|YJf zVWAir#r*^9c^6XB-{4pK2l!k1ubx~|-g_|Rrr!eRU|syf^6h8~Z`H}{i75asUkSk4 z+;UCwes4>>F57(ICY&W7_O`$q!Qfj$Fm8i42V~i7MvKqg8ZD9L z+}cTZCmsJET3S+%oLEMB5+fkC}92m$!tqEFSDr5T|)bnr9XwajH8BS^yr@ z!h0YC;ARiZZi&=_w+5dCMTG+awS#I__#CslX8*vfi@*}mcTPrUtrqdA_1y$3!a|$VRUk{UDO~IPUmk(y|x+l3OaHP_u zQ8`u9MNa5L_?)R`gq^KAUCYvJb@NmU=7D0fU_0=5gnf_Q2;`C5kOq7mU6C6IV%dU8 zByUG*Ak_&+#OXDkW95XNlm79FY!7r%g71OG7p`+StL^Cs~{2t)Tswc2EcaSw0zToV}So8_U^FMZOlD1~Msd zwZ%kS8cqXr@d8j{)G-=N-#NhpUO_CyBgBInHmb~agaM`|b31bze69tWGBbg@7cz8y zagPOu=!r@NXk&9@onPhySbr7c+bXs;YeH>}8i!hRG!pbrYbEI?=qKt&)@o(m%S=;Q z1w&S{3F;SlE8PQv&!s$J|7yR`V*IgBfp(mBfVOca+t=G)$3Oe^?A@uvsRvWlW;vF# z4_2S#s4MPJ+^PuRLKpvS{ud`}*$aiwYL0zpBup-}9BDq%GMf~0uU5+`(<#>J4tyqd zD{7$k>m0{F5dBfPVeWvxhyPChG(byDq&`5b3MIuxA#@+8)M(dp23ePVe z!>2l>Icb0_&)K`!*MLiVEqitJ`kCwrmJZ?bGm946ljx(x2k>{C^kI?%JDuGHlNj3= znrJ29JuHP0P^4r0s7lTFsEr0%D$deL_$BZ9J_YY%_;iug_t1}+YVK#fl(LDCwuZSl zr)!@l^8o`|8K#y1dl^X?366JbwR#eJ?ub+>H7Ym0dsr^J0Q<T&0wt*lSEA3_~G$`__&^Z!1LRc+0}{F zZ&dJIi=<_wXEmWx6{@kv_Yksr!h57ronG0epmRv4ai;IDP@O~Y8pIV`vQ!chU=2+Q zO;`Z-YQCzbC_8oSp;IsPMGpBSEhH|0_Iq-Ah$7ia^qgr~?Y1rL7QI0iP_08tKZ+|J zvdTBsmJ0q6?4Qg9G%`st36T$El9+O#w%Ds6RDJWImim_ZX2gTYBn!ZAmS}dzEZQtl zbP)z!ox};2c`dF*=9@~%TX6K z0FMTI_KEfn>|wYjy(YRQq9$DwM`ff>cC>r8aGk}kEV-A>oa?r!yhN7=Xjj31nR4YO z6W^Qx>mIzT(Ro{My&7Yn$7{~0{}8fKq#A4q)Eq&|zV~yIZjuz*SIEPzyE!xJs$97!HR| z=Fq~&4-2Vh=e&ne$%udF#J&^wp+Dl|`-GO|teRve>zuq_@ z)5>N$X-M>PSoHKT-1_LpY__>aV{JE2CAI7wUX|^8rIUV`c93Qzd!$B7B_3;QbWk=a zPae!u92_ef?>06yRyLM_Pc8UVGjY?L0O0(73z|WqjWgldJ1cXcr9jiL6LGytcc4+gF=3w;?Q$HiEakC{g ze^Fx+d0L9F;6{ZtD;uQj+CuZ^VNiZBRSh63ExAwHT0}mF46vt_{5yK=sp;C zx9zY^Ep-%DW|x!hujoz*5Fe6fB9-WuroUxV>{8V2?_+H%wpT8xTwnP_iFhJncfg)q z>HI(KHSGg~H>Rj*+UFG?ELH;s)!CzLix%R89N#&Xj``8zp~-Zej;)OR;^V~%d>89B zwF=p}mix1#slxZRiClllN5S^K&~FV(i!F{`x7}Q9t1Ylo?^B2e{fRahANBq@S>Swa zKR#mK!(SoA@Me*G<<3CY$r5%x`wD2mkO*8YuQUeBc28tpeSh|@BLMa^4biLH(?w6H z7~i5-Ma*QEuEl#WhS^@Ozp#{i7@xMF;Ee!Yce7{MvVewV_F?X{_J)S;4-d&(_}P2= ztc#ig_Kb;FQ88}8?kPe3Me1|=Ms3(SY(}#)a5uh*pY0puZ|E=QA2i7Y1hcVNTj5%N z+sO>JVY5#HbH^+!iVDL@#Y)?T(Av-ZPKqxR7*Lj4wo1|1eYAJmIOP=CdYsO>Ak2ah zrUv2VYwQ=o!@D*$f_7@XKUd2&)l2cgENXMTep z<(_NvO(y!!9ZNa-0R2?$xSA?V`RzpkFj%;4#2BnC)+|^hSZe3C!{_>LWy@@4~_`vukm6GU4OoZ^OsFz&2+8VB59?GzYZg zB%;;nkH|rwi3tunm^}xikXym%9dOz2@@w*lj`j}1$fU+*LZ6&UPQPHi5^)*W&0`bU z6Q{i;8o>^CX77@Rh1x7(*hYTfQ{0I=98xnCD2q*CO%Jh2ExV;`9Cz8qbeA4jyJ#%9 z;w&{#DM;O#RDnHp_6ulDF@cea?M$B`KX%#8YMdcoUf^yAADUq4V&NjazAGj}CXY_8 zm<-Zk{`#glxoPwZ`xWp>unTnEf2)27ohCFmDLLFXG?}HdXw_$3 zn^Y57lTl*`GcnDfU-)FY3bVR!HsR~IPJM-UfBM@T(F>|v)s0&sWx;_-9$=On5NC

Z?Ue0fn4{tIERK{m>bQWtqr;! z2sGAuEYsR-j42fFmPA7EbE+=gLxE6(f>{Mnd zO^4CPjeM50&CRe};9DR8o?m;zpsCW;NNA1S40GXaIgvc2MT;E->SLB?Fl`MLL^n-; zpACZ^yR^hKe*g?h%o_`@TO^%TT5Q_%uLD5s?ah{$R}I^l`-rMU*~MLz5^hRBzO(X} zn>vt-R08e}iIT^5!=z?3h~md~!X#%@h+@Y?N6^{`?;+GNzUkPp3U$Gkm6uvQOIlTJ zEbEp_JO@uE+KLzy|9TYqkmM^kB5VHitl(%)G^F*>zxkDTxhb=IeAP|gOZib_`={>z zN3Ygl=4q8ddO{Sn6YB&&&o2zx5pwh{>fP4Qv1=9feAVEtI(qmryrRtCaRW529F5Ru zVp|^O-aB1}{kb;5)7%HW$!0+yz5aQ^16?rW3 zJLz?IyH~!m{Vw~%!Z6aTWTJ@#xOu=yalgZz(Wt zE{zGR*`Owo&D(RO&-fvi+N@dU4240D^n}Jbr|2f*P7^%mfmgri9%K(X?4qbPt}rii z05xjTV}c95tcSWCJFEVriY4xRT7drR{Eo~&H?XAjL~X%yK9S|?i-RkH~nX%(YFX_V_$T>zFvZW0IA0+TAAlcB9F(tR=XJ&*0gI*FERJec2$M2*cy ztj=e|nitDZ5B1QTbv;(gf2I2VZPR~1ch}$F@VdTKsL{jy2_17^e|ZHd2db4Vmq7(dOim85ib)*l0-9)WB1|9$Z2Y@!PDFcvE=UM$4c3HSi zj0G38j_^z3T+ZyB#u>+-&~_mdb$0>xeamv) zFydI!vd;^irylAqbdMANSj0i1E;JgIUD=5miCXuh*SQFzesl-4LSwNxq#s02diV2P z0$AHIp#?DpqQp6&C_LT?PWTVu82yjECp~1#0WgUWj`~Nee7-G?K99mJVWYj4Q-wWC z&}gqHv=qvC1sW{~5*!s8q1w9>0C3TWwFa8wci|&?CcTo?&9>Joe?7Y+cX!mkocdFM z$FCjeJ%jrO_n>q=I3>M%21N!B4vGo2JvceNVuRv?qUUy?E_iSf)pnfQjnZlXb41Sm zQw(`;HmkT!Gdp*p3;bXzT(aRzg8{E9X@Ge>U@m3$$iE!usS)D-#sdwtF7`5WymgfM zxmb$w2zq~`NrT*b!L6QS?Z>`vd6`uJjvtG$M>Y*-&;H9%J>@9kxMu{~(>R-*R2Df< zZ)rP6|6ccfi+mXjaslR5Cl{J#jsE436`(sRM2oQppNaS*{LTGE{FQ*zoz1`m`dhQg6h=^2to?ob)%|nMGak$>F=zE=8SBzFp%wMuA5%Q} zXK;T@R-{4>Eh^zh-goI&%fgp7DDj1g*>nGL0u@G}B8{RA%`W!hb7Sk7m)riqTelqt zy!M#3OGm=nK_ZR%4blzbJf);%tpf1|5D%2JEM5R&9bsuHi0^&R3)Q`H zz%;e~pu3(ES;ucNOb5u#{TA4|KyLqafvpGRP|Z(}Z;k1uLP94hK+HtMBUK2g7!)yz zo%bOvX#Nwubxy&xNmt^(pT3o(x1z!=Gg@oNYpZK!FOpta-L&|p)hfmc_SWr+MY#0g zn`%UONWL+bhs{l;&k(1wnnNC8YzQZ*uyRq<0{xx`73RBJe=AI5GqD!?)Z9g+PZ3tY z_m?G|xFO}ll_h*fvrMGes*}(y$<^fo4Q-}<_Q_{`9TKr0r&Ye*F(mgwPm#D5B8^OEn7`YVxfSM; z!qCs&ImUSXt!Jnf3*T3JD(y=C6>fc|nXH-9!bGhwQ09M!thuV`=D;D3la*Pb6@TgX z7EVusS`{aE_bF<9;Nzf{vX`6|uGC_~E}GDTB5q9%n&f9COcDTap?}5xfTg9fy6q$X zwEdSuMgD;PCbaEJ#INLM_bG}OYz&@%k|-8iPRi@}?u3vB2y{pLM8y9HrFO#zdGZH- z=hc^i9FxIidY5_ki$Jc4lvB55_bWP})BlJ_I@?4l>^v2kFYXuanH<()Ai3@J`pVMA zQs!qNpyWh*tQBANL2_7xvB-A4$Lf8KqY={haPAPfs>dkbcqgwK=bjv75^|*B#s3JV z^}0GZ@ygi7RO#%G|3_4Qzw$q5jU(+p5%SVZK8*znSV8|IO$Vre3oE#Pq&EO6P+~=V zAFu;~#tJ&MV!uy%3!p+SuO#jRdWXs`g{bD@nOG7ttW%@R1eh*p+%oHw>!i0F{ zDS8B$M&`(SigMUi>>J2cF_rv*HJHXf%BaA=+z3Pl+#gx7*eA=!}6 zqFMO*+!A)olcX@juT$BTrTeq+c)1Vk{IkG;L2$O#m)%)-=4t`Ecz;s=Q1}N|UFe-d z)fJ$#;xm_9M10;oZyh?6Ev_!+gqLmIJ9DiibxiioZko!BEhYYJB=ZRE)ArTMNTwvM zWcw=Yh4>Lr(Y6KbrMM)hc-#D9dv|o=PY|EUL!%pveZ4s|v&c!|o2l3at!1u)AL?PU=wb0oC+e{(2+jGKZ=aUAk)qy0 z`Dc*%mqnl#wUIGb=ne7eTs78yy`4`U_Fv3YCpWOr-u}+nu6RlY^Nf{ww~8Y?xMo1p&6kjKn1c>z!n`2~5Ib#7szGoT0^TMI~_dRSE<-WYv4@MdS=zt$t& zk*UukPHdXYTMVlz_*u_qjMJSP_Y6OV7hMc6@vSRjSRJX;KXOV{qF#j`k(HCW;S9)d zN-C^iklcIkTvd^)&9d~1%)dN^g`b_VR>FhBNNbJFkWS*Mcw>-qpi`$9&<09O;6~0= z&^qOIokL3smZ|E292UONU5oheYtIps7|;(gp>GB&FAMTR4VO`uCOsY|J07XDI1$oz zW9eaZW_w1l{ocwk_O%}MXvbuv@^A&vzUIdLq5yKFM@6!M44|eH>*0BzS1sA0CztVx z)V&Xr^^d@S3c&VDP0{%88O6jMf}3Q>sY=xu3r@UMbJo2D%}(c}t~~LyMx*(IfS&Xt z>z8@53!s?#6r|X2@!?pW!(jAKF+ zzp;kWlG`=}xW{ zR@z(qaBM^pOJTTyqHm6kie>^JAv*+nTEsVz^X5g6=-SdwMUV%Ut5>xv5c`#5*Q5UD@w6-H@u4i z@aVTl++k3prY&lJgjB??&1>^IMUePfa`Y9zgS%rV_N;?u=}9Q1HY*M>nQ^452N<#cL!h?>f5X}Z7`*jt z*=%f*P@&C?({IJSSk*(1AuGjWETxV>Uwy4CHGP&oDeI^JRd%!D_!JN+1wz?QMdE2G zw$!}^LT3u&&?oH9HnFxn>_Z!V!$gZoc&DQ98c!9_65JfijDZ1K!ipkyv>jxh+dvEp zV`{}?t_WgTTK~xak{|*i3J>%2S>OfH&O|Gr^e`B>Bti42q%K#K9EYFDIt4)No)vyi zR1n(ow3daJCsjKYAifSNtCj87whQ9-beWypf|2qhp&d&TIp(A_0(c)J4j4wqO?#&s%UEqF%&hI(^sR`dv9@VI{l z4-D>LUzxWlLhbXeIUJjtZlDe@V9l`;(KhFyb)26r3k1n3QWU73{YR0JG}#Q;KV z{Dz&I*8rLbd=VH~b9vA%H+IV~Sx>yGCoF~zn5)2KD<{!F6i|c7Y-W3-0$F7c2+nGi zgTA-0t8)*aC$v0A(<)aKql-YUtItLxK~>IKadufbN8elc(fI~21|q;*#JVIj$PG8p{R)Vioyx%Ynz;wN_uRq80|8;f zndXxeV8+!3G!ur!%Qs$ek-}6sz%A|(WEW3SHeSQL;R|2MIJEGUmaC`jNDUR<8osqQ zTH}rr)WL&}-S*y)3KgCpkxPV!^u}nO`8CwlzN!izctr|EkA8F5JQSf$|3f>B9c#ay9AGF9Bu#OUPW0S?V&zwY( zUnGMpG7f2NrY3jHUylkQK3<4ZzaE9>4)%cj)KAWYS0tAST#QUe8cOx1H;s7X{z~|k zyGFbKVTCxsynWt5Q9(z=jp$7-ymzn6)0e9B*P`X(eFBsna4p*|6dY zuMXb%V#E6W>FS_lO0)Tz%P9}9v}8xDn+gyG@T!}1N~U?6i>60Sr;M|Tv(S**r=*>^ z-`>P0fe;W>x-QZkui@GDWqzl+J^axRlY` zPs;Cz3y6_BzT|Qows5ixW6b4b8zd7jhRe@X8n%ahxmU?~Q~RE_<`P?moFc$82chSE zBOSB@%|gd+u+i71|JuaZ`uDH9t?HFHI4G4o9ba9|PMXaiq|z{kbcnq_<>3N8C+`kw zPOhzWIK#YZRsAc@?rZvBK~|T(VRskfntw-siEv`#qDFgu)Cpwq4|&zLoDK5u*1%x4 zejJZlXFFI?Z|n9JJ-wj20^8K~+j`{HBi>biWP^~`CKeC-sp1z{t#M&dfkE54;O)=_ z3w{PW@13|cv*bJTWYa+TN%P2~l#M{VGd!2uKM+uMh_JLu@K}w_vk{Hw%Q#?+MM&}d zt3gbIDxY}%CqBk-8>!ErBu=i~PCT!tUbGf?PWM8XT(dWNGGr$kVob6>~_x%Za(^|Z_b#KnYO0R9vySCd9JjF_-ZGyenGNh7m6UU#d zq)$Vay+&mMsfl@8u{BFA8)5XnRJ$5)@(cZz3aB> zfB}i{b2}=p%IjA^&hsgfudRDR4(XTHAbWAC!SNX_q@w$M?Xjow!7I;ox;3$XKhXa^ zZ;?e!FWx5C5aY$2l^EmU6D{6}sX93u4?5`3+!@({Dk-T6nw+<%uL{|4<@Ayc;7!y2 zPigJ=xJ$Y)y2kt4M!{Hd!ZlqG*;@a1rq-9VIO-r$>fSfbb`qbs-K zAg$Kadh&zxR&L(A={Uae!33j=V=_5nc}jzys(_y59x@sdb~Xpw-3G7b8k*wjhy^PF z!0Xqg#%@3DrG}BZrm8^f)CE;k7>QhaqSTIC(DkVGf@NOx$u7HXq-CxO^aSdQyz%48 z(so&KL+Mv4e(@?%dDrnvje6Dx4AxvKy;kFR^Y2^r2)cH4MObtZK{`%Werl4ZWtRyQoAw!+F4ApmDW{8Dd|s;p*-8lH|!=$@;!5u;!pGVV-l= zN40`?!fOgjpE3!)A24Nz)*DQ(;b;1yPb$w`!{9Ravs3bd(C=I1qKzKWZaPdBO>+H~ zC8F{QpgAp_h}ynJkmqIttLLWIzuu{p1DSV?m(9svSrd=h5+(Ls27&hD?^h29$J2zR zi8k`?yF7pRc-mud&Add%aj%CNBkH*(*73L)Z^sF)@XO_>yru_TI34LkW0|rOIS9$S z#siZws9`^&C69p<bZ@+>ZLSDDv=Gu~t(vPr zuraKys2=k^_8{V3#OC|dr;%z=u|w*4{pvQ;rtHPE)(U0|cE)@5S0Ep9_sjw=f)psw z?aoz`P-$7tPaRBf2`J|Is1Wpqe+blb5!`s8jC^GP19Ac1|F>v_As8uN-wTIm=mi%B z{#(;a;;pIY9h!(kt1a3YOv68vKYiV&ny6OxN8H{ZNAG>$zgH_p82L%+r0^26)Uc;* z+0)LRG<3-c-{*SUdUH4dc)7)Yn1!xJ#Mk_WZRRh{c*7I>0s~tELvwoZ`H7B3ZyW~d zh-V*uqThN-vQM5=&5cnj20o28^`pr;*p&yqt9|dqBZ4*`d`JehMfAa?fahpv2T4c% zUlV)SW_1Ba1`c|9_us;il~)^v+QIR3-^|j=J*noN2G8>;9dECfLxdY9N83Y=;$ z132wci*r^@Tlmul2Z>QOPIVK3lNqDc9VK~M71=G0$G>$=q!PxbLe}D1^~d5}Xspew zS|%tjVC|SLZX>R-ew<;Raln~M-#`*T)H(arGGRx)V3uH7(fWI^4z`645? zG#nP+s#Qm8nOVNkJ8l!!FacJVy)7JaQ=$?oYjB0vy@43X1D!Y381in9hxWou!XEV@}-5Cn^GJE1#n}zywI&#Ru3_e&#*d zitcn)eOpZ3GbGVh7D}=*hR%QHS2-5?MI>Kzp&w)S?#{XEQCC^rbrUU$Jr;g7!k|0d z;n33nu*p*oX!}>YJXqY6VE!2y*uQyq%>CM=dX5)?MNW`K8EsFI`kuKYm(ld+EQi;E zJ@-k6O{_g85RW<$gip})Pm3S6KZi*;(G?N5zG@{yPfGZqLzr)`63Dd7vO=oPr_Qd& z++4&1ms&sB1F&O$1f5u6>@ytBg}55RXgx{oyVEWA3=?sbn%}`Tl7H6pNcY)W8EziK z`=cMo%c^wCp@dH^tuVpo!h9wOrHtEw-t?*ZYdXDKTdq7 zVY=W!IqXLW8aaDBtS>hSVq54(Aep^K|8l&vMA0w2mHScy5PGoUjhD$oRsQMCva4-H=dMcn(Sj0# zuTHexO0`{T=)k|_K+WC#xDI``-5`sxji`sx@vx8zSjhcF-9`U0?{_+n5CEWy{9mkf z7Dvi!f%BMq-~?up<$@x~lkY!Eqgv+LT@)B#qd4KMjslqu{6-q+2fG?beBRw-w{jP*+{6&mC^=^cu<-4J?%1VGO}h@n5W|Umf9W{E z?jB}FE@YtU1~l|hE#jOmyF;%2M)J{;wUNi%DeRpexrCC37z5bTXbi4WskbXCJgT0+ zyN=Q${(a2V7!U80D>Gj^S~4Je0W*E%;+ZbYM*egh21gNu4Kz0S{E;eQrab2Q4hOn* z9o)K~w6WV%=y{+3K|W4cn;bEo1RJ{=!4D*w#490{I40FCWV75b$+!!n91H?l9D|Nz`KZ>Bq~Hhp zj$i5M0nouW^Qyugbl)#oi@JbuEnmak$}6`wd>?jLTY!(S#$0- zUw_Yio1nZxH=C3{QsJIh=9BH7j;)*Q4f4yN1mgQjs5(|%Q|~Z(0S`&`MtizDo4`dC z5Yp892b;Gr?ECoQt(wj4i`}CEcF93Jy3NnygbL%}_S~}mV7ZV(GrD2FYM!R+Ed0>G zKWc9)@yoI%Vi4{m=RS7oV2tGu#` z;D?^>*iL3y-Yd(2##Y_XA8LlZER*Wh`y~rmPLEukZg|5r`^Tea)IH)BElQ6QFfFW? zz1Hb1C357CY8`Q|j)v1wKeMa(I99RyU|w)m;Bs%XYVJPNRRUvf{#MuE7jPNX^mTk`huH)MR1=9I&`=qMOcU)Wc^LvfM0bjB=mrdu= zwxOICUjuX2uWFTJaKWG547vv)@0^|j3*FTG?rR3 zJXW_=x6M9B`Uuo?Avd~UiSu>Csk-%%=K+gKCm9h5rzNM1LFfbYPwlr($Zw5p&ssBm zE45@Qe|zP|$y{&vMRJj8`QcqPo~tTukN!r+#6kY@?{+mX>MtV45W*xsNKZqV8%=xW zBkrLL!Q{?Fn*CQT1|j%EToy&gx@+$?ScP5qH$QsJJiXi972})w-!IUsZTKPFR`RTEWFmP0W~Y9;NuwG*feeG0fWg$$3C5 zvER9ajQp{OP%k*`BwFpqOsdis%W*i2DJ8)$ObNL58qxNLqxu7EnQfNgwfJ|h>#B|} zGC-O;W%EXZDqQn!YO4N~+NE(mESWt5uezGS{{5!VXyRFFpuIG^$ zin{c367zVwqQ;l|WR_W_m&mM9oveCuM5mZg^`^V zrkam1%wRB;q%9`fcr}ueeo#SgGszF?Htz!kPxoHH2xr0ril{jGdq=#vw6BM3Yx&I2 zn>*`~n>Bw7v!41i@AgHK44=kc$Lp0CNFo?=u8N@4N0(fMYyRY$=g~mAyu8mX@ z!^o14mi6YY9@9>&r*{0gZ0?8VPrko^IauSq>QC^3RRw(8OZq= zOqBQn$d}+N`s_d*e@k*2xL>xv#J?p3!=H7(WMnxjk*o-!LdLRzGd>e6>qV%DPZ6EK zjC?w1?hE3%Q7$kVA%ed11X0>L9714JpinPb?E>XM4+!z}4$%p{-nWD1zF4kV>IDYR ze)Ynn8_lOpc4@mA`_~KCDnh$5j@;Um*~gF%D!%)XYAOCS^Gr%vzsmNowmS zCR525(zHa|hoRQ53NFE6xdz5VjKUH>t6CtvSOrW{ltEs12maxyxFp@_y zY-^cwTu0!1&h@U-aFDT{?|UjVq=A5E#73bL>iw1sl|{$F&nT1hRnybBUlI&(@EYj> zCNa0r>myYO-IMQumbULxonXv-f{9L&t(*2V4R5iFmc$nik`)Kuu#31`ipCRnby z6=YJCU`-G}hB6D)aZ1?`t;UaNh+1sJ3M{PXjhoc7>FO8Fbq?^_FqQ2cMTxNjTp*H2Mb|raverU^O?Vsa;)xuswhLJ7e zJi$%O6NbYCx)~1RYWWwvqtIt%$bDXVwm}u6(KURHJT0HGXT|X&9~Ms=OREI`d4!Sf zHqvbBylbq7dS6AeuFm7QB zRqTYiBUFyEH-0f3Hy+0~9SX~RJih=vKT@HVg87>x_NZ|Vhfy}TIbf6P{nLHbNXAtZUSj&Q$(s7%zwoS&Y8XN|CGjvwRC16ZmLC&TGClRGrd-$%RWlEcBaf zbs~MW%^S(2sLy?UOi8R5HK{l4t?)_F`%=-Ks<$Ew#FUT^%JbUHKkY>yJL3$lR~f7c z8`{pjmDsfR(wZytNTDy=_`*#L4>TQLLC86_25a=JRzYE7a1fhwBQ5 zEAbaU$(=)lxjJzCS&y5ML6fyZ!L1p!VOuWg!G#rSUpb2w&Be9Xg#p2~rQ-l|DdH+2 zs3@RNWiqHp_4-vH4N~fw2r5dsi%%W|=?+yW`8gU6S13*Yd79hWR;2lrV&&tP^$35z zr{Q&lNb-iLspBWxGV+%=RREui{qMTs`N)ck@f024Oig}pk*no>PLFPL!tHsA(Xbf| zSLVR>TjmU3 zwSF{t(PT4sw9ac7{AXKdvt{Jsr@}zndY}iXMLtPIrXMI)Wff>|Jhi9h4nCQoWrVL7 zN!_^Qs-r?RZFTH1h^Z(@2~Gg4l-yRK^p!he14k!cka9J?U&nW8-fJ`I9d36W1f|{7 z1{eBRf{Lk+@CkjP$rUI4^ebXrwa&Uz5R_M>uKUZ>Um!>1Myt7!Y3SxL;K(p#;#Ex0(CcJ zRh&$(y66g1pgKWPh)*kCmW1`YblnbW{o8tOdiDNqPo40|i;sp6 z{UImBH7+;(4s=igFu;Tq5B!_KsB+Thrs6HZx3FN>zonB1YWPqCiaZ%qkolu&qRxNV zZPdr1>+18?$6cBm!SR3dGvSkUA4oZt<8>djE6OMnMXq0bERDhKA`8f#mTbc{38H+G}JjilZ6(dW7Y{pZAX=rD3@`=hAd z_BWsFWUl0@sRN*v*1tRqVwG>%74h8GySSge8a}je!PSpz$+2i^)9tU^#}FvEYlIK< z0ZXb9ZM%=Or32z`DECLM7YNEL)bfZWQLZ5zTJt_eqXNm7W0TC@)vDSbnptuAU{PYd z&-Jp_-`y3))AT1FTWP%wscrVpg*QL8W_Ye%sSJ=w9oqg}w)gZnIXg~rW&51FR+C*2 zPJJWzt9KzYd_1^x%Q+}-CI4IuBMb<+!N{XnlmHRw2H(H4jcA(d8FL1g=r5TtD>F`3@b7eP#glG9j@!aG{pk9bcaDg!?qp zD8Cv}Z(C+J-sT+pUI~N6zz7!zP)R55<0F>b$0>KYo)4j1m-$FWO{YE8t2dwyq8#=| zkk;IGl&`h{thiFNsQSIe;ghfw?IEVR=gbXa=}{+QX$qU4qbBJtMbCl2zHF*=&< z>4g76?^mQuRTPbeJ*cV-Y&R*<2)uWnmU+Z@GF;k;+8^L*KR-M^!Y8I=RVfp+VM~L|N6u89)(S_Z@>W`{dHCv;b^k`qvT>xkuM?HfJe6^0vyqA^ zKi!rw`s0WiKzz*@#ggjBt50x|)tY6!4)ivC}nVU3n)8VV{S2_Xn3=v`^{K z?-GZFi_F?;(bEQb5kip%eclq{m0cxa5&>x=O8H#BLw|K%KvQV2*8-i$nitUPg_W~8 z=NEme(S;GDUAdCE2Xn=MR2E1@fm9ku#dD>3+6Ev42+Pxdr#})1ro0o_Z18HkZ#{BX9!ptdT zRA1#z-!@C0JTI8p_W}z#g1W@^driWtR#>uOak@bHAIMazu0L;YC#dj1T8BjUwDV4H z9{}{es-A)G19Jq?PSAH%CZWb4*mOR;CyGmTV#~Ki)W}br@RpU-SB0b7vBjP7YFNKn z`@s3Dw~>Cy7+|9n^*g$QC9$0DLI_0NgIemE#@cc1g1DWd6#E53%7fTmYB=m2af?yZh zpLyiRg+E9Xd&Z>CrcpiO?%Jz}24YH-ur<2*Ci}qa3Q*`_9?f-jq3n<_yuF?KZ8vI{!YLck|n5e5k_enGo~$T+L9nn@Qh|M%B$y zlO2nnr_g6WL(eRR$VGszo8)fl$ak;UPRTCLBCX}Y;;Qn8jMwVtZtgXYzLLK? z{{Y`&zG{Ky(WBH3ogYWUSk5){AtaWNvhrcF)+Py?#>c$7B@)d|n9l2)t)YKjZYrcj zZa)5!Xw`Z0VE$h8AMA2Z>QczwP@|1|uhr~N3BBgWJEEiJj(h)Ry!*(Y+WakkS-8ku zdrUfmGXubeq_rO%#$A;gwSNg+tDk%T-?g!O{Pz~D&~*{XJ<0gk9&jf1S`j+R;ES}Y z$+F~OOG633aI<>oy7S)a{roYt1lP!W3zacf+;#}|hUM9D8W)6SY=L3K4Iub0+xeAt z&Sevk;AvQ1Kl67$f?A@bd>Zyg*eAJbWTKfI{M@paBG7|F1v%mZ`5;Malc*IRHQz6- zo>pax8zR0wVdpH7(kaM8t9``%Y10<(&~dtb>Jr7km(JNp#X%9abG$)#%f&NTSPb?P zukz~Dry~1T=(YOaH&yS0D2GG98xd)dyswtLy3Q)#GITv8%uE%)&%%aa7IKTW|2PN$ zS?YU|nV}Dp>kn6c*qnIRGzo0(*}tLv1&5xcJefbZAPi<<^I4)_i0DQ5+-H$R&|!PF zaa!}{iL=5y1I!riT&|Y7753=10;+kDJ9|cHvGpH^nW*!1%!97j=Hy_JP{?NScG!;Y z`&U~IEG{99~(+%|y;yzpv3mrBgf3i&YWeQ z>B|ODE9@TcDcH-xxLeUzz_uH)Bdnj-;_e((MW%OY4Spw2cQ)VD+6<-v$5p`(OX+110D+3SvOuIcyGczp{?8t*j-#|yjh!3&p#(ft3B*hixnGK{7 zR`^2G6nk!NJm(r#a{D7E^>$n4VdiO;c7&ZWLgECf>2+1H;!(&ka9P{&cuUuPeCSWZ zzsMZPMO4C8_YK$=h~*+;k9XqB%EAM+CQlV$qS4|C;%oKo54eXvLEeSm;-C5x$)yI! zIpZ=3pJR=Sh~l8zLgP`qYno7b-ugC@dE-%u6)Jx)v-!A~hSi4s-0?437Nj>J51hNj zgq`elQ5HC&)s7?fTrh2!uL}`h0J=|!Nti#=-(Ms=wq3-Ly*(rT!Pq)Ns@or{nZTRb zBaGK>G3PX=2`!IXk8X^1f2PS6X=91DC&J_A=V0=*+qVXzJXL0KzlNcLnIz??2QT}UZBAK=YQqGy{~BnpdG?va$;GA zi%85^35?-PD-n`X=Y$wV8tz9-ukpHCIt zhUgebZa6GB7$V-2QBvb@wO^!f=V`qDU4|#OoH}fPE;u%4o^)>oEL-(=E21Z1v-cA3 z*85DX-0W(nQx7)xfr@xG)@5B;C*ba;mh^MO_QnnynJ5Whd%8j|_k(byjO2{TgB+*|%--1C^tjrt(eKu2Nvz$F3PJAXoRz}gyOX$Yw zH@xnn(iJGY0onDN{IUeza)fmd>qB?tJ9e%~rT)TuFA)Fo)la0vz7fPKmG5pib8o@%8nBg6 z<5vz^{hG_!EoY-G=v#)_xv2A=$<{+|eU&$P`)4<6rJpHJiZ$+M*jCuUPda{TO@KzZ zyk}%rT!$-T_f=el4@iG#O)4|5xbBk9_*l79c=j;X7H--<(?e6RaauT0>&R)2F614e z*15AMs^;TL#@+GE){7gKwT{iJtuuSWZU~YXioye% zmYtv>w^cuLEcO3Lx)N|GySJYtWamY)jHN=d6dA%uLJ}&KWSNlURVGQcS(H85LX?<9 zv=WMld4vp7BfBue*wKj(KZ=l5?}CjSL}ToJ!=dZL6rZrD5fRxvzk)~iv9tmiWEdrAZ3-35VME~=c%NUoOa@a+=7 zsDMOx@S!YRDG6OF;7TOvZs*G6yvzi+U6mnI6|dEo!;~zk9Slc3+0?zo(Px)LOwsB?Y?f=Re7`HQcmP z4|;Q$?|x7t%OnaWUJvXdBmy3(x*jp7zK`4_zn#TMB8$#&6=vJ`CEmzHw9Yu6y2;239ioOf~hJ1S1KAPDf;MA<)Ba38u z(LXnk+(%4Nk)jAR3#`A?ymfBg|^LNb$;T4Ho26^eDMZMQ63N zz#dWn^ZDr)r})MXjGa5+xfoJ18n9O}a6vC9q#Ko3l=NWqk*w#@ax4a_u-ikerc0vr z=M?88`9~fWk}YuP*m%n=NI`oh@^il%*aPqT4xabRFqu0h7O{}kcJ|qRIo`09MQ z;6V?<;NEzugPWG0J7194#L{TC+2oiaFYu1Ov;9Lkp%%p#4QhNGZJ1BFKYCS$sK}no zh`8W2i})TV8)dKryxxdZo`vXvOt;|K_hSI(Ttld{aTBi`?zDy3!5Vi%%KG=D$j<*3 zybK$bLzJ?gFyDfw?*%VEKp$o$KC>84b07-C9?}0gaD_8Vo6~z{_V$MzXzAc3ZN3_p zfJqCa!&<$evlNx(qNJwcBJhw0S{um3+=$VKUv`-cBK96Gs=Eqn#DTOrI0oa zN+s|RLB7ICbHIt$}(#tbYs_!7hlH7g|HSxXX3yxCCIaZlt5pvLC%vq-an5raP$VFPe!M++iyUze z=E9B3BjNjg2?>Nbm>fP_ML`$+&?Ez+6mrp4HT)tbnA4` zj-x52k-0+)HH3vBPxHaxy_;jGgT_~huP~=aJfyKSFW#>-x(wSI^jb~%z&sqU!WvQY zS7On#$uBa=E)%Q&*sAAO-YMzB_}zhFyFD)V1CK3wjJ12!N!u!rAz&wL=35DZRr<~S z@ZH!m#&?bGeD9+eSm@@z#+k~e8yTv*XXa;YhMVJw>~3?)7GX0c0sXnVAXg0H)Lb}u-3^(&Wh^X&ZUp5R`r-ag|a>A%iIEjB## z%e|H(@xXw6R%KoXrG@pxRNJ8yeZ*r3GF6hkLj48h^tXv$U+bas`vfZ;m*nPu6JA#B z$;DZd-{35Uf`in)nT3ZO%K8^JAb5Ym=UJv;cjl#>&F)3hLx3Yo84X6tb>HhCemD!1 z$a+Ag$=se#Z@Gt%cNbJo0*IM?myA-6UP6obuY(UCy!fkpKEvwG_|XoX#J)X7(8DWb5M z1hxkuxaZCOaOcsBeA%E6hnt!@5beoaOV~_ABzf7QqP7bXA5>yT=V;KZF7l63E-0Ai zuUz1_Ps2eAcouGPy%-2drQbZo70OTPeQz;~?frRrauJz9jk^dxs=Oa(*)i>30&Mxa zFNE$3M4w)%JaWAl5pIInD9suTrkAR@u|lK-s`8k9^DKef{QFJjFO!C{xk<^|-?l?C z-H;@{>IqU`a9iG7%f*pOELO-1?#wW-#Y60RmObVgqVXAVHP}cjKaLzA2fYk9O+1{k`}k zP;4&%;a0X{Lealx65Na@Q3uZsFvNJ3Jeb#?Zd&h6`DKQWJ| zn=P%plK>BO(5Dgl8Y0V9PqpaLW(doiM14LOmSF~_&+d?MqBYc0PRfpPH^e9ol#h-qWwl zUJ1wvRv>g9o5tDBnELlbXhmt4*t0Db=j8~mnKW=J*}Jgf9&Ve@Oy% zJWfV|?Yox^-{q&q_I+s4LrUfYI(+HyO|I{wh*5Qd49`e{CpdAKewVuE1t%d@`Oj9i zB-~S8H%IXPB=CMZx3()iO<6O89?(PB$E?l1GK**pofa@U4CLlBDLU)gU~XCbNIP(; zgY0sYc8HD;=6cz4ZSo7KSLwkzJz+a&dkzs?Er!pK^FL`}Y{^$hvgysz%_`y0_=Xb= z53kH-OnrpqR$eFH))Sr^N-aAa4t)S>9y@3|njn=YhB*xPQqo$f0Q=o)YGq$Q4rUkS z6xv(?@rn+Xw_ZtgAnqhe2`;2IoZ~a5m{zG!57t@|1(oWdXUjPWaL(W8A(Pw!{@gx5 zJTn)ygHO>W+OcfKCY1tmq7r1LuN3`y-rr7dnXj6+)48$9^q{`%Cbo~t!k$XbGv{Bu- zN;$@knl7i-VC4MX*yg%Eb&&bKXq}rxP@6HK`H!AcVo5Sb`Y17ZIkjMFS=I#>cMoen z6RO7fhvr3J*h!Ci&fK3*pmY`0FWe~mIGV8;tOxGzfC9FR%Y8t%bU{Av*^o!tIB`{3 z7?t`VtN|==<}l3*Oy9FV35=Xe?s)=8biCq#nP`WA6cv4YJE1cA_)Kp~HMrXrr$GLW4M=^e`c11Qoi z+=M310W?5aeh1L;CUfsE5*b>gUABpchE&QEK&F(Vz%3xm(#*e%Xq5h1`Hk&jTK+Zb z5on&}^Bvg0X#s@%hOaRvfOkc;x=(R@$(%ea5WZSERryH(WvcYhHI}eCnYG9dOP1k< zwi&$m0n@ys;S>U*XAxASu@89YTu;O5coOqyUbG%tbDzMx7~Uo~h>=XT_y~bLfS)L| z0(M}K9TzUkpfqet=@MCx?f=%^4{CyHeEc_r~S(y)c`FoO~nk{%q8c1IkU#ip0yn7im5+GfK^m0O`#XAP8 zh21+14SF+IBz)KWjvMpU+%tu{yB8y-k<^3;PKMD5_9nWT8)07{$F_b0-0LuAwQ%Q? z1kaqY;^7yuGU0h}$HKd4a7Y!jhxt{k$aj&}>Q?B->W6v~hJ=$;hn31tq*-6W!pXk5 z{U{^A6P6_BiFbMQviYt({2#o*B4g8%=NF@FkEUPXs$GQtum=vDbKEDmRDQmt!}tvQ z38+%t1Ai~1mc`Z-r&wf>-UI!5E{3F|UEYoXIq*{E(s{>qj<6o-WJk398wV)}Nk}KI3mFxDcCU zqe^Kl&>T-2h=XlhMxv2)F$Ba-G^z@IZ8rx1Q=pV7aTP#P%2nmu0;djq8b; zEsO7DJxl3TLM+2Ou7gnyR%9Lwm|5^K|FcI5k)oQ8K(jBK3J z66qCp#13__j5(waL{5482c*5W6NtVvpInW@C4kS4&|p3WSCT_)=2E8=WYeaLfRmy|*d$A3!5>={KQO z*+x(_b4AKoa6I#E?4J;{11Xh0AQ@g1?>&V?W4|6~8}!?sVJv}hm;uwN4y(h%guD?? zY;xMaf6Q*^?0|TnZ5_t`@HU>W{>Y)u-EB#FQsjoQ$HSDs_bXR zdJmHD=q!gYkuXsK=;MCHMXf`Fh>4&HtjFK~T;^t0g#Ci%o1C?SeeM z!f^mcE#iB50C+OoD&WtT14@&p&e%$$tmkNhq?Pz4c4EK#OP0(Z%$Y5g$SrrxxZ7{7 ztzK0N&}fg&+o|JIg&^c>t!EwgSl_9-&e4I*6wN!$ zYwrjC^Q7~-nq4401o`q2)(atvZFw?!mav04Ak!?#8e#35#^sT!k9ZE|UYW&BIlM6_ z2D}nkd4A=}UMmqoVAVO&To>si8G`iVb@}8nt>T&9iTW}xxmAgRpQ*rh48Mm{Cu~pG z42UVXZxWqK0&i{=F(YemCx%5NH;N)fdY;@UBn75fbx?j)OEXlhdIG^}hIy-5Cu4mv zCT)n>gU5jtXhdV#J-!lK?i2Jc0yH>@A2l3SR1URm>jC&Oeg0nC{u8#th)u;U)M0E6 zp4q}^z&}C1n1C;_tnAhc=#N29!BM6QARed`vnTo;_#K>jHoQy5K&3>K5O1xZHU~8a z^SG@u$xav8H_J1G2q!0+I?m^zmF^kp^CXX>58wK=n?NfvGjxWy;=zP5qA@x9zDD@r zv0P?Em!Eb2@>Wj#=d^OH%eDi=X*)Oj@`7j5Og9lZ3g$FEST#OzwOGJ$tXk_6X!q;p z@P42bJQskcntUj@eyx--&M=~_UJg;l!cw@Mx?6~lMMm7{JqqH#ZuW`5R@_p7_PRU@ z#&lK7045NbrP~Gee2wOv^b6#l#$lPI*s=C=czKz_99Ej@$-XbBtO zpK{|d(!6ys-hakv;Ma}nQqp9pz@|f+a)6i!8mn(ev;OKeU7YWtCjrsvy4tRyw2}5? z`i&lf7PI~VGnmd$o?Qqg^FS5WHs`)VP1m>9lxdPs04)eY6QWbZG9y!&%E$TVM~CUh zcYAZv7&;kN0&#Cu&}$%qJu#uvf!E_XcT74Qrk|(k1KsT~@&FiCvg>;;PRLs~)d9B)CoV8j zfLCrpwLhrc+qNqe zrN$AW-KH;S_4{e#c3~%24x>$Hkt*hSg7O)glYhT;$aE7)APliL_J&t0z*AfqJOjY8 z^EP?>Q|VzkX$tda`dex}Ct)nM;ZwS)oKzqXuE`(*kRnDCLt-HIoW(fE!lnV$_9i(?zqtDI> zPPTsLRVcVSspzG1Pc1-&JE6Z2v3Hu{@ekq`Fv;=GoYX7VZOOo16PO6NDl)(Kn#9DV zS?s0Ki^N$nyRF@nsobBBxfN2;t1{7ZSP}dMLEXbTS>QDPxS*&ZAZQ*E!zQV-hu8mfuBQ65N;OuIL{J#N%T0(D!?QMYx^X+(|JHqsO4D zPCjT0BpPt|{^QPJ8}yN`AI`>i#i{T0(pNhg-y;2zs&;(czpO3#_2OcK8SveK>shp~{DrwM`|r;VGQOwok~M*8_)F@sTI{pm)k;q~!RxTozkUtoUiHJ_~y zX;!nG;hEgGsoZ?+szeh8uQFc0ZfAKlXoFPioSku**faI+4N1Gha*_S!QEeX`BaHiJ zzmXVrl4YIe8AB}+Qb^fqoUU7TVC-A^>A|{eKhZO_Eac&I)fS zT47Uaja_^mESD)QFZ%}Mgem}zTP%&9TD_XC$W}@jm#A5FddnMntqnw0dezn?<7@2Y zzk=%YuZSmpWXy@f;qT=<%jjH_&6SsD!ANn155&Jmo?%FJdXxTcYPVk2)egi3p7|*+ zPhFHR9gw@_SbG*KO@1;n@KDxp_KNJtAG4#Fq-LB0SE=XJOoKQN_(Pv-oa%1@b}ALi0Tb7`FO`^N}Yfr2O{*TE6a+)83(v1X^HxZulbPl_2r= zhz4~l;t|Pola&4y+Lkx2eRkkK%(X)y?G6V`YD_5OA~ku+U|-4^KEr-&ku?qpvW@?$ zFyv(0u_mUGTDyKq&2G+C40jA1SASHS z1zIIrTC|iTeu_fYiNd?apvo*l^(9oE7xHivK26#Q`?ew4mJ& z$?{nhpmTMgoZxIN?!S%{T}DXK7-l6l3JZ?^EFHjjq~gz^oVn-k!5nmKb2>cqfFp0x z&zEBr*;xm8yWSc90mIdEOJW|G<=j04P0Yfsvlv%ADXDBJI^z6rnLfHI9tziFzXfMA zOCp*FSn2^P9UEZaTFJl1bSl9LqF}P{xWrgo$fMFe%>m+W{SUYgpi4>neG+=Kvkt7M zTkB=LUO~Xpp+MjyMkS_c^>CL;EC2>fX!~DYs{Lb)unmeNMu<720Dt!F%Bd}_!?nNhx7vJi*nkG8TfN>YRJ|a;bZ`kH9oj3%fy=!k zNC@=`y(we!mA4~1=%NNE2VR^tmc`Qgh4raSziAz;aiyAc<&z&!*BUD*lp5v?-1|ht zRy^3^n~8s5%%ojw0o-@5Y}~ZCf^}+dWg}IEh8Hl#pJ0NxhhI>CR6ndW)L**|d=U!e zd{VzMz7o><7gi8HdcX{Bz?J&NV9UZe$_Xa6Z#Rk)G*^%zmwUe(X=!W<8tEcY@eVf9{(Qn!B?JaNRAfy0arEQJX_|!SlM~-_rCsWnP?6+Osw#06L!|I zgQqpMG_u<|?iJi=+g#-A)k$Nj)2ss^s>7BNBJi_5ePk&TPvghcOzQ6m%%@$!wx{vV zW!nuWhbd*ZBnm$_**>Mt#|OKU5v7~@Lb;a#2F;_je2ABD3OF`3rp&9455~lS4HQ74 za+h_St>|OJ$!bStCD`orUvvIX;#{q=%l&?YO!Rit?z28T{(b$95gx$-(3u(=S2PJv zk)udPFGY!h!6586LQG);q_-sA`8_E@iKs|j&BxOsfz1{n1*aK`L?L(_0CmV74pu;^ z_LC032-se`!U#1^Hwj{GPdtccRWxzXcUl*Jo-`hLy0{g0|NYB>6=$aAkAjW6mOly* z)oObR5w%}8X0$AiU2Ds8sH&z2+Y2N%olXKypwUV9SBFcRa()6&J7?s@A_%(8?v)hE z?Ueuc*EabR_d&i+ET@^VP;W1-BVEQANgU|sTx~P%1OIp}@(xdb*o5WYxgU#lwt%z{ z_H&Q6kaS*Pi3@V*e4?$K(Hw(lJC+%BeiQZ7Uk~Do&<=G;mTSPr=F!kuDO$a20PAs> z8qMM=;@EDI@}Euo&Ks1RnK!_z(e&BEOvbdgO-2aH*Pe`K5^K>wBV=}{v9jRL0zp!kL$$7SZh**_h> zoJsPelNWfE%*UWtuY z6kB4_HYtVK!j!75cw_W z<9`^~*>N}d3Lh1Y&=Lbn#1o;wcY%bELdD@Y#cuRW6Y1Nhu4e2X*~D*aw-c8(?4rfm zCiu{{i-3rKkB)2wSctiYZg^yDWz8)7uL(i`oxb%Md*!d$4aB=!AoEW=6RgcvV@Bj( zTGFZ%0mM+TRLW6YmdRX{9Kjd6f96}rS+%*psS8z%hkWg?Ui;c(F-lO6{%DR2Cuigz z@;}v$)9Brow@Fpb+{k?hOxUzYNHeby^{FM^;&G;OEA1vL#ryJA;@VUldmKEw_ahvw z2PE=O4V!8Fj16tkn4k7`$-mhW@!AA|s{3rn7mHp?mml?Bkza*N7n;l&2q^%&`hVhl zJ%#7LMf5zG|F`u&DJF^LA@oHbtIsiHE09U6BaX3?kX5O!Cd}|w{8;+?`t{)5E$a=D zI@id9VD*xJb6Y$$JrCgQXrwm&rFVdeNi31Ds`wY{Qngl8UU1jo%$ksY4&prP5fUVU zdmLh|WGP(JwUla{W1}DSM`R!xX*uxyU;7Var=6uF_X@Bp#XYb>~uO0OIJ-NSojFo~WG%&w>t@$^AI{ZQ~ORbRj-U zpD#L^wW?9mwXn!NY|r_TFFI1eQ2#q!bZ;HG>k7%KE3fl|YyXyioAwI&rq@eC`A9@- zV$cC4l+vB^AK>Rv>b(Sm6o0hGSW2T?&=OwqCF{Vn-adhn-`Sbm6ch9M!ssJgV4;e- zlws3KZQOQN=E-Uv)>ili?|oGkUx8iLN0KSr`qbpN4I>N0c{Yob1cE>B!!Su0JQ^FD zlF}7=8;r&+avKOA7=N}V+kS-DWZy}PZ_qf+^u21V#f{G#*+HUk^RCRM#PS1BZ?=>} zP4i84&Nd!dg>J=gv$=@J{N%rw#1_d&L7P)HTnC+j^Ta{crfdB*D*MowhL;8o%~&$& zp&Jn8C&uwW+9ON0>+}*4EUa#c3yC2xxYlOYvTC@gcMYt?d6~EWbAyHm$g0WEeR6+9 z_AljZwEP-yz$axp>q!fVFCD%1rR3(fkk~QN_3+k?^I*TM&__H4(gCz`NS?zmZx+^x zeoT=C>^UplQDN{ho@x@Qf+tZ_CMeswq(s}|d>#K}o4H(fvYG^S`;NAJXPnAA{-yc# zVF~$>@93@AA0S2VH67+UnwvKHDu$p54u7MRb0rDw_WvGO@my8nlM_` zT0%`2W`r_JY@C_Q4ql4>hx`VuF$)sqC0V?4kGGb2A?DUcb1nbFOxM(X2-V75hH9UU zIWp@ob)6bOJp{HJXz40cYoiobUEh&%^Z7xF0U?mZzOVJ9&$kyct7pb4NP)baGg@V7 zP6Lc6?C!Jhi=0Y=CiDRM40{3G7h)MOHM8j+f-^=VwgoOoWa#7t`7Xx*4d`Q#D(g^&XrNJYx%VqBE5PZADc z?30g!8~c>t7L0u|w}oYm962gt%CC8ni7tI;@wS){Kz!QzGbxe!^D`!in*Ldka%VTT zfrP)i%A-Nn8nz*8%5`dV1+wmE_^-QNO^|C>`V#dy4;_t8sVQx4@?ZW@)Z7+nVLo^% z?twD7*|w*T57-5Stn_Tm{%6-D#jH&O!o-aQqgks#7(b&VSXq-aw6(Pu8jA5@AL<_& z<}+@0{l(;V}*Y?!gu-mQYGQI3wI}2`a^YHrpa$r|H{Zpxy19&!Knkg zZQ_;^=G9N51m~H1Q8GvD`^txCrqlQA2*h+d1y5i>_XTY6HDRw=h#Al2zlMUR;!Tz1 zm?Mj03Mj`jSj(IJ%ZyL8yIlS7IsDfzgW;R*Z>MMf6<|-gL z?wYpIPos-w7@`0dT%=+6b1=fTut8psh{YSrnuS!#Ey%=f&-&g4C;I!#8VF^>LW49o zO!E`>;42aaHa2mkoYf!k4}8)^mSXclDVDxjSaKYl-4dfRuEZZ)$cSQ8QV3XZ+iwlc z+N_|AVNY^%`v7f5=gUTlzGo$mQ2i=n>}bY_h9Yi{ks3I8X#cJzQf$u4XLV}s)+O7) zhWpGy-hp-}Z#-SZbz&D;+s+t8180fmvdh(HQigtMkuM(24zMGXET(&~pV;MIW-J&e znuVL8^t+y8(%{;Q>h7Ci&+OpGZ{AwsUk`eCPcgsw^l(y0Gdo}Wn{ivn?W;3YE zkM%OGNR&PDu=D9ULx+9$zaf8uJuitp|6E;3D*~hUtY$_s&e5+U0dpB1-#h-&}-blj1HGDZ?bz_^86O77# ziI)fN_F4JuIBv^*yU(oto=pmM#g2gcu$65x1PE~+yu@pZCirp4Qsk$Lm=MgX1MFb; zJGkyItlhp?!7Jm+k+NP9o(i=y>Uz~8x>c26DdV+}b=_~#uT_=AQmp+AElwa7+s3Z2 zHWoZnmfN0}+$OCIl|@yTsK;$rPrh%@rsq#GL>>}-%miNyYW1vf!B46G`u{4XR3DZ^ z9H(RErqcy?%rd+9m($zuBS*t8KBc1IMtiEcQ8%DILE@Be$n(rsV+X-YNMpqL=>4=x3v*W7m>Oy6=@)bD472-@qubiC zW7ha<3c;OD&eK2fI!KoQ=9GA1q# z=i@Q9L!DVnYkljZ327e9#1B+TXhHqm_r)xqn3=ii+bZk}fo-JJ-j$wbO8CSAmB3jW zo=$sp^VQD$4W7D!Mni9+@lR6&ZoY)$x>v|$W}HLDugf(#)041cw1trpMPfsixH~80 zI+IXv#v3b&9iROg6nU&)W2I0bWCj{-+t1by8R83S81ppfCCWGxhPNgJ9wi)b(7*6D zkHJyXayZl@`%M0kp5l{#j%KO2xm3HRB`F~=6w=g0r9@D+wa<(C^r{0U>Rq3lUju@#zwXJ-C%_8Rbp>ECnEFW5C-2ET07v{#Ww^po6ZH0fPvGl?uBJfBpqQ1BLvM%F+s)NGkn`_h(PNd&ZGv2xhjR~L|- z+bMyvtLI@^Ks2N;9M?a2;(hY6ZHNG)>FG3*WeU?w}A8Nhreg6?E&M4cM zJyBOvSK}pJa8~B}Q=7gqe`D{;(Hs>IAFpAc`nw+En{Pl_fLDcUI1tG!=&rhbOF%Qm zMvZKJf*v$yrgX1geMdSv=4-_X#Zg`lt$+6)e>ZwYX z!5ReinMR!cNC&VqK0h`PxKVfZ9=q`_eOD!Ru$|WM>kj*V?cC#0t*%113k(?Z?v2$e z#o}(ZZxIWmB9)?;tzDJ53BX>;y(h6u>g&2nF%cU4cw0ih%DmT z@bbeWd~GV?K9KHZu|py+$b6IhRY z?5FG-jE6kL@orAQac7&)oYSbfxLs^lvi8q zTUxgN%(-Fl1mE?|`roTTZk|Q3y56PPPm?Z_rnStu{PnTM>x46v?-dz`BiS)=GY8gH z)Z}7DY>I$E^vKe`-JAk2M~T(|oiyd+KOI{i17fE4Rlc`JTwT3)mq>F6lYHhGS*+^) z4(hjXFOqJLI9}{?E-pv4ObIeN)mf#QdHYUNEUDYUP4{P&-(qLy2UBQM%^#DkI}!8R zDRJ&s7w-{zYWXsV?mNJElW+2XGskeb{7c4~fIE02%9o)yM!q*xm2^C0#ZMe8*JSH{FQt3M0ieW&KE zinwN=B5u(ATjikrfY5TK(Pjfd)(Wi*@ZTNSH z`XP3-AZvyU&6ED?#rjF3-6!QoZjCITYab%OtiOc&G;i?i#t7&avLv#|mT}inBV4He zB?#o~=ZGyCp^{^FP9iD4?^fB&A!PcohmRTYH(K9S{eok>e|*s*I1NoAf*QX(dLPVf z81fl&s*=J)-Cf^PWn=1jF>>Tm|GG|F}VxzwBMxEd7-cIO92}H?zFZQXg8H>BV^)SOB*) zhpk6bzx}+M6*)3Q!yj4y3w$s$_d`VLwbve;*);!y=0EMOE52+y9&$U->LVn&nzU%u zISF4eSWe#3-CCHP3oQ2YB3%eJ?*zYy_xAH6>t1#Dmg|PxeZSxW1Xm#RzaJ4X8Qb22 zuNCoa$Gv;^s#5Mo_WdTrWn|c1v1)DKmz6IDJYuas-BKh$f_Yc)S zE4;7kr}MMl?FVcc@uw=NaHhyVGcegwW8Zw?twPGacC~S-4b=7ju8`(Z8$9wz0wdEn zD|o_$GQoznBcUqu%xi@dn4rPrvPm%|0B0<@F$V1oCQa?Ph~0ty4aR-5i+a5+g)N*od~VKrD4GfLR5x(@lfH>fc1n|~&DP)HRkwPAC! zkYd-4M9^buET8z}bgt-furt<}0>;C@qZIw|?jujx-P?CEzsLPrnPZ-vtdJzRHY+z9 zztFvt`EP_I%=ppm%$|kc^Co!>EMcri(E>H5p-~DORWv|XX^1h#?*T6w>!S|fl`0~B zx6(R@MQYGn{MKO7yiBw5Etv(&LFa(qZ{L`H$c-=|!s}BgVeOyW8OWIUx|V^?u>0ut zvrv`bb^)@=U_6R9+n0V@INlXcd2AC7YYkdndprmGI?>(B39QbISzm5( zn@5h@tVdQefJ9qxq)5sI^79BvY|U;q!ErLaCVI!u7A z$qyB7zW00VO3`n-asC^W(dAG6ef2IS77NQY$1y)^@I&3(SBkv>;zAGqepr@)OAP1Z zjjXi@;LA;dA0{J&bof?A$cj^YJ^J&PQh#sN=eO~nK9=3SeRFg;`9}MZTPruc1NYS* zs~G!Nay)iy_#K!o_piB1d%aQpv1)(sjpu7gqr<=Rj;Kof{JZZ(0=4wQE z-COx0!}R0V>b(N$(r8V+C7rRoZa=q+G765~5S{;0)RH;6+Pw;`vs5UO%0}I+w+pEA ztrNJGjLwdw+(^GcdX6e$Ox~J03*}hOg~SENrG6}KR{FaUW7rY9#&vAPY1iXk`FUY# z1#91g2R;&F0H$FABWHB|SY#_M?Ocj0G}RUQX5*aY}9z|9@ID%iNXO04;Hzk1AkKq@n^!c=YLY(ZhzamQPPqmiS35hFpQ>)s^G z-_w!f!yUv)vmf}BJs%^P?*e85z7&am4d#5T5pg=miT3(oSaZX7Czt#wIKcI)$mriY zYlAxos!vtoqBkyj%G3-|CM|y92W)*;mX`$NgN$#N-XkKmHc_+?Paq@ru+`$zni~HN z;fdOg<57lC#>9NTt)5BeknQ~*P7VC`t|fJnAEoMb;IKbP%Yyy09_5-m0u!{CR^8V9 zEfWrW2^`8EElscZwhg&$G5IAo@~Z78n_)yA1a_l5w*fs9>1A72{Q;7?7NsA!=5KS~ z_XE882Rq~F{jBJgVclk<6-|I!?mEaDNtSh+)zjkwrK+@YunCug$=F_lT{9EZ0c-&&;zCTUgk!$uE`DlO8_2 zc7|(IL{{g>c2tB+J$_yT4CLRBcw7^;86NT2W`o^i>0I_y=9{JXO3m>)>~r$+b=42Q zg{>;T)sA5bmwPS{(JLiY1Cxl4zP5&)JdawDzT&uH)8AgRXaBuy8T!j~W~`ao8-2g) z988yfSDau(Z_FuhigwE(q&FkmBGQrQ7j-kw&RD5>jY<%%J*O1Es`vDY4lh3s1M(WU z^4T=T-f>*u;1Wfp9`(Jx!82O!EwKN(gfsd`9*x1({`i<$Td%CtY>loipY@EFjBzN> z@jUq)2v(f?>4H}5$}X^b4mc^+a$Ek**4J%TLrP_j$U+>3?(n}R-?7Q{kwV8CDPd1t z@<3PDE3GRu0H9A2Rzo8{`iA z^6@EIczR#?u{=}ch+Ss_kP?~%mzg*bts z6Uw~Z+8}|@VtvdW@rjOjTdmmh2^l(DV-t0v;u-Zu_6DOj088<0qqJF`A>ohpca1+I z*;pCq!3-s%WQlHctG|tQd0K$zQJhR@-rC{jmcfx9+zVyWbhkHnhI2;kWFkp-Ys_y^ z<4pn=JvhTjbQ}{+jLK)nKEs|Iv?JPYUt>6q!P?@^pisXka?6?+*)1mQ<@tInm3RS; z*${eoybE&D21n4yQ`h7AzoncnKO#6XI08Y+_OsJvo(btKa4b&jW94Q;cER?B%-U-T zb}`R^buL6$->2HM9r2g6ZWr@(<6ZB-o~y(Q~pPLNIXR%d`Y) z%#G7J5MkE&slXgZm^7V`kmba`LKV-B@%wF-Rls%b!tQ{ngec6O-H5i_uvQG29niE@ zK^~`9_B>k%d15Pk)MKu9<8z)V!8D1G%$1~Cp4P!i#FRX!5U9}$G;KwZ8vXNKD$9-J zzy-zf9AFPCW~y2%gB#hkA-RPF8-!RRt;(7h81rP82}bUEq2M50x#!uMNVX3Ap;^ha z`B+0Dpg&ijMY%og;(%@}UO7=b>oP0JJd=lVVjg{)72M}327eHX#1`p&b7Y=*i!kJ> zwis}I2WP%x`~TGkq@!(6`(AOcPE*neK&~ZK>5kmNr^5K!R1*+S>nlAZ*60M>g~Y4 zKdY!jyf9m&Q=La0cOY_AZykZhO^wGlNRSS*AkVPMd0M2MDkRZ^J?ru~*X8ls3-RYg zS<-{{SgFhRvDD%VB>a6h*~n~)os9-E)N728NXch!k6UUF+VRDgX#};>)rB_Od^YY= zL_a7+JCr31Nr9%8H&uP(>ekTy0rpR zxW6mQj&D^$bKJ)Y?-K0bEA)4{pWr)Dv7j(W%wl#5!1dJC5|}de%X0*~S@7=|r+uuD zE-YCElq7)=i}YP^Y9Gt13oG=W*lc7A6u8FaJpIn>I=zK~)7g$18N2A1KhpBz{atk@ zVQr>@9L)@CtJ%8vg?L*S{Y5rmcZq>~dCo#IQkrW0-#z2mhzASlyFzAJT3FHM6Z=o= z7>luxn@1GD5hUz!JEC*IQT_g*C$*+KJT#+|vyFH9X@esaBqEPcFLW6T`R!Y9eTK2y zpY4xUnJrL)AcC~)!_wP`1_sR^n8-J~Ab01IRIAj)QT(?u&4=`1 z)OX*5;X%{MOA58Sx%rnA{f^1A3!BAil_jbV&V_yt_I8~<_CxgIZDwB673L4>%>20L zl){GmbU|uXX;XHKPxNhlj0k;M%oCFA*;@H)jx21Va9{qf$I&@du}sXfT8;Xn1rmtW zB$(iNe1j4vdG44}iTg5?lrR$OkM=94^?nU+cij)94PuqId=0o)jWx+ddiA7?w{zNIHoIqA({;~S_ety(0N@6o7u|b*TtvT)$9iflW=`mL# zIxnw0}FCaJC)Hba*`VNmhk9xy~G zInA8P}Y*k&s(%G$WOfw^NT)4GSz z%F{5Ipju2P;}eRE++6)s0jl!%1&4=6^DrufuzheLj0$(CgEXRTXGxC%tI^~) zA40-F(i=o8rsvdj@6DuG9hr`)F{NRYnPF2lZBeKB#10Zl&mQLy@UIEF6E>a9c!+t_WGj#J zMib^2u+Ea1?AFJBY9L1}uJCuvuB2ye2EYwmpMV0%n!D2OFmYrvS%?M-OBAxl6AkS;q1TKRT0mcLl@39uVa=5}nfK zo-Q+=lsbL)DsyKV?e0PO&uMEcVE|8CbpK4*&;0+L9m(#qmcc$dEKnu_fXlh02yKDJ z^^tDQ{qy^g0>@W&#UG6KN&UU!82$9-Vwq{EnO>b==f+mf9qW3=deH?;{ms6L)j!$T zTq#$}>;jKy^Bh7FDQgcQ!;FMelIr=y{dSXZH3qBVrvuh&>@qKb?(&S$L}b{nUz{8W@`WaStgZvMpdF?`5<*p}{S zkDd9^2mP@$AjkLJ5NqHDv~8TmJU!_bKAr560FP&%>8sR61F2MroO#aaL}0AH%@BA@ z?FXkHl?KfH(7oMwv)29Zp041>jgS6-Pq;jH`tm=14#?SlNSNaEP=`|$ZTYlLwcZvO zJUB3YEN6b4a|a_KX1qh?Zu_xT<7BSGCQH-}LN16OSU{}Ze2IOLHP$?U9QIX`icwFW zIWU3TGa`q6##Hl5YP{_`J)irvo*GN8i&nh8B3^B{79+a#@d@iaE$TX&Ti;vhS>7>q z6z4-P(7K_F+V*|Kf9XE^q)+s3(V3kCuz;pXuT`Cxm+rj{HRU?DOlD(Vl{RO%s&^3c zrDkO2e%cGF6wx0?fp>P$ed37y+cpE=Ryv3mjy+$k!yUSpL$7G?{o&^!@_&@Q2UHW! z_ctu^6;wbJM4EttfJzBXiZm4v6$LvWkcfbYbP)(7BqB|kND)*ZQBhGr5Kw9gy+ag~ zB9IU%k(!V|3Te;!{r&&X`JeN=&-d<<;lMH+U94Y`cdLOITpB)Mc$@`NvfwqripYzO}A@>}i$pH|y!UU9dR zJkDh{y2WO~9@;n-8tskfqr(osYG_`U1seT+&xMNfs85M?IZK>f417}(NsmdeYYt9C zYIDT1qf2Ra>c}lIpAyyfazbw^&ry-vJp3)mE55i*&7kM3op{&zHpiP>j0-!?NXQrA zIQrUfl!DY}yPkA%X3BnFVIG>#sqBRh(uunfmuG{C#*k&5PSS2znmBSnH9!l2^xC4XSeWdW0EobxOxzNBz^VWrvAV#+qWu zZw>JVG<$N=A*AhcmYuJ4Ed*#FT7W?sPvvvzF4?~$@us&taJgJc&t{lHP{l0ZJj8~s zv{UFdD?GtvNvIuW{)9szwz@p;D%S}NV^5VorDKw@=Q)xk4~x9se~sG*7Z{G!_i$6O zmJb_3Y~5X~jxxPxv>5Nd2r;viF3*=uwAEXcUmNVzswj}h4ci+AEMp&GYj@FOx8pr$ zgF_6#%h*W6Xm3vJvk3#?&grVwrL(xNapiEA_n8fnb07yUD3{{^;iz5`jliZP0(eKU zBEmT9fp!uwI^IfG`hJl(ADMqTrf}3+pCo_xAT^vUpKdi{Yjto1c?##~nFig{4@zNP z&*9v6N#(dpG8p1XwuhPb3n{F$L__4cn{mzX!UC6Ovx9UQATI<}B=v*mu85f4iBMKP z)v;DpL4%altB%hr2cZh6;(iAp*GKG1=3sVvx(l*5^5!D2bc-NEsdk&;Eu<57vSRj; zPITKAz-z8#4!6QrC+XlGGtfwjcGQI^RZV*zxhhCW_7BHLdsup|*e^gU= zG&OtZpP~)YlQVcjrB1iT9)w!J?1d+%QOPFvakr{cqDr+C>kHwNGS?QkmZbv1qfdX}6u#WA-p+#D5+pK z=XJM}EZB24{b1z>+H3VtLe9$5dB(UZ;V8?6lQs}7Ga3x*PzP zb%v>^8+xXwpSEJ4PYGmOQw|Q0K%#;?8u<)^g+GA$ev_Q+_`p_KYADaPfNgu3z5NY` z>vd5$+^XjI0x#SK&!b(grwS0y?p&mt0fwdzvN8d+o_T%p1%1sFz0XE0K!A99=Se5; zY;$gsOCE3j&dgr&l|!AmYae84K3EKzX6y@z$@t)F_*pM=^7p|DIV7}5xna(Wk|I1r z>&1S%08`q2TEi3nj5qQF#B8>$3w!^YY(hRARKoM5xxS8b-Aoj3_?i{Fbt0&jpA*JwSXm#0j zp6tun5D|{ww9Y~9V_Mx?-qG$#V3mM72kc^$S+3eNC35oUPBR`VtZgY#84P^Ai;EiDYAj5giF9+y#4m|nCmVtM%E@2_gQuoL`7=<=wc9RXh94PItfTz zL;Mllm_z(c1WmhB*tD&SGn`)4Z)%IK(ti_k*UBR>&oTf?#>qd*8*3;3CQ6?azDLU% z?CX~gfdV)?U4pIcL%Q@1lI|wosx!@@Rf@q|icnBCM_Gx-ph{I9^C*cEW6f*6hs_D1 z(n%Hfc+jmyluYyk=PPKnq`^>GphSh@>S)Sat~Z9v7?S2#Wlf3CNOzUmJfUz_#0^x# zF|k|dR%%2kf^1i12$0BF*}=Q?Tln}+w-ogslAP2?UsH=7c%FFY^E)P9%^|_6qSE$s z+ypR%1boe-)dz$)S*gXF9DZ}t6XXFUo)(gN)8w#SOgfgcZE+pXIuMF9>950NwMg5c z3@z~)Vv*H0eZrka0>s-p-^2t0vu@iAUMSEy=^_s)<-NjmFs;;imhIA-brISmZMO9H zCu-?{Qrn(RFhRLkpqg#Z3R3SJXoCmNg!c$7l)9gIsPT2_c>9E?Y!9pN5PQL)iszhU zd^S9gd$z|`)6gZ;1Ji${6`7T6XaY*Ho_{hs@s+R7y9eU1@VSB}QPu-K@_0PqkN}wV zuq`q1m9Lxilg|0OpQ(x^E-@}rTb@x5;`q<%sfiQ_gC)W&K|o}iBUAY z_{%mlIrB?Z9{#w}rlmzFDW#+3@}V`e7i=`3S8uXmXEba!Tz-a6%{^Xz` zA$Q|Jc$*bEh5n0$pHA2>e#mK>G++h4B)aK`46sTaMT^q=-Yi0jRZZ(4N5J(;wjKXUy zrHlSemiBh;=X@?+Qqg55*c~P?e&>hASmC+H<|m6nk(ryjP7((dvv$K;(C^Wdl$HIA zh+81G3LPjG<&9$+cG|U@!DF~|3$L*is>FF)1{uFPyZSasgV`=mHUxWS8E|%8x2-z7 zx}1gohY}NIscm~@go4&UQ%EcO1^eBzkYX{YN>U0Xb!jOMcmep6W0l=herIVP=f!0A z4CjUJ*o657W}9;^!=kh1jG(f+P@PxaElkApv?Ap=YT+o#HgYa7v6h=>yK`Kz6`4ne z_#hdQY!a0U z^xJo5k=vD3d>+~+Z|IITslDbM2LUgSW3%ziniBr%*|F{QHiIYlYO&t9IqOb_+~xo6iy>AY0~->jRyAs5(+H=!;Lu zK{L!=j?S8uwHhG3U$<}@B{jx|BR}2Qs@xZodfDtC=jq^R#53+;Zx&G&X>E5XWaGg25`N)VO-X^SnsgHvV zcyRpC8!x|&FKjj;zvCV{PRmr^xOu*BlvYxZ#jNU4Fn!L;6@8vY*u|=Pt86o_)f{ol zg*)aeNkRdxNk48FsChJ!7bM`xwuu6kSOGILefnID2n|Cv?A31e1PjnyAg8(r4fNDVgsi9FW#QTlEhPjACA z_*w83;ZSmn-lD`WgGw*{DdpS3H=XxyT5U@=d*$Y*Kx!E}HX`bC!maUErq0Qr1tp({ zV?)5Nm?|~lsoxh43rgLjhew3DV+GVBI%7JV~_t^MZ5#q5x-{lFS2#(X-J%&jT zv7zxFjTJz|#!%7ky6#%Z2Uc4*CwOFqvA-T8bO383PV+`HGQL_EbdcSWJ`0Zfm)4W~ zly9(Lolo^RYsOV2RG09`YGAD)&iV53!YiJz)B1(Kf7t~E-{xP}u4K7&_VnM({# z=ache;d~03T5qK3*a(=z9wRi7zSeJn+ul~Q=*8MO`aX`L9w#`oV%McfsUwI%sdB0PPKrnh={Nn(vTEi+Nfp9GY&UR@gjHsaw010+@;5jTC_&6^hD}yj}zD3MXo5%Cpaa`zf|A zG6b+}0qh=2Sd%~sHFR8_7!je@_Cq$848$Yb7H5G2#dSn%G1+^tvV7o&T3Zoh{Mcod zWCX&G-^`Ko5m&BtQ^4fEnyNEbsjZjEvp61@UYOwSZUf5D@gBQnM~kVdSAc_c5&xj& zb4x=!_{*|w^(b<>q(k|~y^O{N|gnMHiZ=uHUU)VR$Wv@b9r z&T{(1yFl%kjL+6T47pz5lAk@MW5+I6mLr&{KMAC2!K=sPp;f`ZT%+`Um^JOo40vsL z(FBp!>G9oMS4rDp26bn0cc%91HAfTu9(;#B*|OV!bkc(mH%+v}HUXiE1s+MlUI|fM z!@;7L)38+HHt`B52`iynOqIx`G&L`hEn62U+zvzm^}u2+Ilbm~J!$H*Z!UK#);9QF zaL6~B-RS%WOPl+_HY9j1*Q+h4@TuQKxiestTy1?_o5VG(oNgi-P_|?!I`TpdPnus> zo}bL{c{wm{ZfbOWJ0%i$zAlLowvVwH4y~M5nLl}Y>40%|b;EvSdPFTU9o9N_I7pOo zF9Y3b8Ybve&;cT$8EvgG@>QLq+`4D68KhD}u8FEz*I8J;MgA}2zO@n5g~x47$$RCs zhG{bmnJN1jdd1XjKw;Vz$=r@bie)##)o1mNu4?A@l5n^QE~`^+2x_O4a%N^TP2D?S?r z%*@WA?`~G>GuOcEBw#)*MlPv9Hl~yOLDw@b<=RQ`HS$x;?3n4bL-^xiQske9(1-?o z8L-!^VoGT~?S(orwP0CiSq3y-F!r{)={#Fg9U>kRnFKjXzukNla-{&)gDd;PO2c^! z5Uz=W){{EwP4oOG6*oJL@T(aRyFs=oO1`tY;WYag_>VFXw*;Xk;ULN)!_j4&YuN7+ zKBES;QY^7Ioz($b`)kA(rq|{A%uO?s%<}1mH&MZNUfj!n9nkBZc6+QWCY|Ont7|W@ zj*K8Hc_fD?-#Eklv{Lu54*2&Me5Vk|L6cRdYEE?xT&9wVsh05#b@Tc+HwUrGM$z5G z^roabQJmANqfQTAq`r8Pa2@*|aGJA`fT6A~o}<{sL`zpIW(E!bc9 z9yN*V)ViyMdH!cO82G-AjY4GB{!eIfS@ANX5&P{leJZ6I39Hb{w|}ylsT~0 z8af^=N;)z#v)`gAnDMZIE&zVAti@RMCxKh{r(zQ2QB&0ouRF$L+~>0@q29~Ip3N4% zh|Owwgfbz`D!(#=RC$zl3^XYb8sU^VWrweLdq^k;${27Ji(&ZL@IUt39(^t7%|T!L z<@(*}G2bV`wNspKK+w_HpxA*`d+Mw@nMblVkM4xbCXobvCH<$|C7?q@dbh_Rn8ZG) zcX?mm#dj6`b)-CAM>ho?xPz|f^v={*KbOOn>4Bud2Pwo;Ha_D&9-a?=UWwP_Wcamn zeou6R)IEKCz=?d#zC=(i9rWtFA-TgI68Mtm&`OCV6Z7Pt!YL3Bp$M@&h)i1kWKdr9 z^mt59Ro?MlE>zBdWr|IYj&b~}Pt^XqAd8WyyEi*;+(=--VB{5SSm@QgGu$wD@m&RL z8R6Q`3H5pXgk4tGp{6~Ag`~BC?yhcjpW7#0!dQ7fLBh%b8q!0cYIbS$Nh|is+Y^1s z90!~M{hb8pFx?^B>;l_Fk(BjpV+j*nC2 z;zxEsC`nbHiCuzfsa7-KNt9)dQJL{!orG#+p#h0~k(~lo;NIOrKXyHz!y3~qT6s-Qi9cqZVkN?bfgX6Lk#FFp}*uR4%zhC zu4s0ljz7IDFaxbSgo{NM?dEgaB;p{;qC^c?lQGs{*=sW3 zLz+=;KhOMGdcX5l7GUMzek=Q$h`x5!Xj%`yau?_5k*cw0kbU9pcOQXJi}&~$9q+2f z&-L(iGp#nfu3W9CJAba+xYPRzXK_dek z19>v9^VnZ{QFPeG9)E8`v(_bUjX$v)M|nmtzv(K0zX5kKeF*W$l#426GyQ@-FC~># z5<6+!*pjd*iC`NawcMp9#qg2E9hKVr$cS^g4TV>3^%&}p``o+U&OT6O_5wWtz6DyI z1JJEaTUmQy-fBHmk;!YzDbi;JTR;~3er=iEc*1F%lYYX%u3e~BHNagOk?tfFY$UI3 zRNEL1ZX|6)+6K5B-{fkMNBj6^y7(9{`{zCUFu>-mV=FsEz)Cx#pjI>)CfXBv0GBvZ z?|Lk0G|%m!nFbn{!6m-{3@mt`$MCCbtz+%M@sw`(WT)@uEy1|N%s{qUKD>}SrS5+a zkVn!qyO_e1!19JrVD7UJ_H{4h2jpZj z-4s+~GVgc*)sRsIuqMOt}CR^Ux|&E zM|Btq8s$5gAriLVbwdH~E9BcR8HtrpU0~LZtBD|)x(e!y)!JG1w47GxdpM07nfj%E0kOp}Q?Qt`7IrCB585t4sAVQX$Qsqe1;rhVU{8xf zjFxxLEPp<6OFQN(h>+lQ8sin|AGcSkGw`<+`aU`Zb=@^mn{BALD`Q#nv0vQdrf%8M zDx__0XvNOuMd* zR}AO}Z7Wob6ArR+e9jK0NHXNrGdbx%E1a7SOjgz~0+)NtfQQN*{N@3-#EU8RPDDSk z`R&AU0N(DPiMWnvx+ie9Oq5OyU7maL3Nt>Uwhuz=18%9A3JmId3naxUe{(BHKR5%A zhn+;#|62D`{qB}Z2i$1eb8P%EZ^k@eEtSR$wSQDK;d$`NH>5kg!$6$7C2OC}4IG5o zf-S*pEM1|;Jw-Ge3FU8oflK>My7YSBcjZ#ErDuqjh?|jb;937kv(YB`FQgRH*C%XF z;iNNwwi$n^o6U);r43jKfpF)bng@@6=hbLMdl4IDJILlbQWuVE;CO$if^nI5$^an8 zH`6(twYijshvbeipW^6iZ`c%9)cIDeTyCYsn%z?Z*S|>8^|%@;aLCx%N_;~wX|a}D zDxifYSx5ZtlNKz@{MM$lXQ8c>r*}pCPVo50D5%uCcK9=@=9cBkWC3bph;g$pq;RiV z)Wlig>GA+W6zjxGS={jz<%IBu^YE{u@v~Cr$vuD zGZTvCZ;_O4LlkeT{To6QMCdYUKd~RTU9`!9OXwcJ><%O6Vc*5fPTar5iSj(`R~c|{TAjY)!b;0OH}0{C zuZh0OO1mvSc+hjEJ>P|6IvDqQ&M!1DrU!J8>(Ws7C2_XkpUOipy^m**u402Am>s>3 z|8eJYUbXx&^fG@AHw*{PDwj2A)3F=5f#2q;T&B>93EM8>SIg>9N(UFZ#VdWGliUmG-~n=oO!IU@978Wj9=*UNHjp z3KsXr#R4?hTLuER|%IM>p$5xVZpJ zTdvIf9&w%_;ld(JlU-^I!6?`2o$xd_yZY4J)O*GIwO1McDmO z-6-JZFFit-<#F9znA*9Jqnv`$Wv_W~P%k7NqnrfMr@Nk0<;dmid+Hw#>pRy+95)}T z$mi8B>kS;_R(2m7Wa%|uNTNJ}uUZddzq$5U>g&*7>OKSt?M%Q+@^MxGQDaYRPMYj;tO0>P;GtJR7V$?1vBZ7&y)KoH&PPJP-7kD6@$O zR=yaH4xA7`Y$Jm;YHO=h1C{%3Ot_VP&5ZL4_EDafCrxjT8*n+Y)VOE>riAl_2ysnW z$uVjy6JhgIbQ^}MhS`iCR&4w6T%c?l7I*I_@q%-wfnRdv*sSlz(cZ8P<=cEbwvhbG z=h?~!tHZ-zNd^<7>b~32*yI>&!e&r7YtVrEadBF&LaGZg`Fk}WWrs(x&EB4>p9{@T zEIf)s_Pf;$Ec{HXohZ_G_!tz;empbbW$mg;TYmN0rxsJ@n{N~R9jW9T=~tE`Sd?|G%x#`fkha&`n8?USl=^U zn=#Z7%+_~<_5X6*c3$y6>>jw|l`9{Ns{*t&e1KqnqY=0vZtmY={NLn@B3b+^>v=Qt ze~-)VGyj(1)CAP!uOyemC;x_(f5SaMH2`&M27VR1tn*(y#|eKq#f8tv8Bj|A_A#U> z=(h94K)myC?wS~6Dskqi_hVpE61>NQ|8EGBjKHYZGL`3{4nd=V&t~MRHvWr3aUKc) z@BTj{Rl!j%00c+8cHsVlVB@Kq6Xz?(OougVGl9G&I;#N)oGDYTO9#NhJsKwfK@7wk zyoX_P52HRGM}az=FDCzGBWLJm4hA?n^lt*P)mZ~I<3mctV#Atxm4?x%Um%yK^xVQap4cf|FasiY`gu8O~KZpOsMhgM$+REhq|4_95 zp@%wO2JoeK3M-|7T@=`rf!!6@o$e@C{Z+U8$Qij`ow$25e|2T&GyZa?&P}5HU(K`m zt4ORVK=Xe5x2_$T`On*7uoMkE`iU8UwwCl)HNk(?4^Wr?mlvUT)w1jFtMzn2>_12A z!2SQeEO(TtAO1?R_~73VQ2%eHxBjY|?oy}Dm(2fCWjO=x_+L(-e>Ly^U(IU*H1C6P z2qp(t{gvF0RqH4aDonqSj@yfmU2MUBYWf=bRp>rq(5Dm-6iRs$ZSnJ74akF*tRNh>L~Ei^hJEkk2>M zm+Zb~{)srL*haEd{&o3B#cRS|KR4z?2v>NUbP+&BPK=PT1i@|A#o|)Q$~gZL{KVNd}O5S6nC-d%i!6=ZMBz3Kfs?Nk8mXY z#_HhUA0wX_`+I4`OW+mqarxJhkqIl8EE@*158F-6Y<$%7qFl;*MXUz=lT zIm*;i1JbS>54ePicB2LIGOJ;~W5*4{OXOpBGia{Z_$f)EJye#{+OHzEj%%M1Hzco{ zcYXx#FrN^|s1v-6?W(eWfbUI-{-`83sMC9#fiiV9{uAnEYHYxCcU z64no5e(y*mp8B&RgXqw2yw@5U1O79fo*mw#o{3R5cPWWv=tCe8()$$(8e2o=j>ufUOd7rg~b9k9btn)fGi4|4veEvMOrbug(MD zGt#1zkbA3#wACJ)(EXbiru^*F%oJi->XgAX|G8L{tj+d-S&i(|&Y_Um60C11c=D`^ zO{Wu6^|Xu8>#wx+E!Oehxe{2|_d-eQmM8cv&Q#F) zq=SuY5wYR+!OS95!=Hh`T|?cJhm0==t%I}ihqO(tif$F^ls19IC;?wxF|)%VR*GH2 zcPnFhh_zq<+5-Ea$grc zE-^cDy81@43B3;cEn%-qrEczUxXu$m{tL6z2gAz4N8fyies`_aH36?PT62S~{x|B- zI;y_nWs%v`DS;LF#5k38!V2q@b&{EdLX7kTKw>4Uk?ZR8o4cneE zGUvhcfZqA$BIK7X5H0xge%l+psoL~8Bee!8coI#{NG)Ja6DA(Gt)Fu?kOs)v!+Rse zzDq9i!wv0)SJ66-Fur!sF&*)dIMzEW^g{D-ThGIUXr<4CAo*_S#l2K#uS%&Wtl&L2 zy{OjeRLZI5Mw?}AD(hi$Bkn4-h!Y=a{gHT_Ap$wD)L=um!EIrm8uz{+{bJV6H_mm$ ziCN*kuO749z5i$_wpY~kiORrYX3f?x&GA>lFGYhN|M7H>nk{1u_BLPhbHv3`%XfO- zh3Xdj#hrm>RnAjaCRY2~EQJPuTwcA?emZ9mDZhdr^! zjUrqe_+wKLHyT4X6U;1i~Db<4=cXcHZQQE?lM(3y*a z>4X`(3$c1s>h0!61o$W;ArQEO|GK|G32-?V_qe}KY0J_k1X~8)R?bXNG$NIWd%7-5 z4g2BTc&t_{mD5U*(qTRLU^sTjBE4<}dy~#L>V{jxpm3 zF|;1M7C4Hab>J0aIu+tbcXr<`^c_jT3)*PA>UVo*6WHegslD8*XK5!}#Z$2#mDp#< z8Xe$kqVO-Y@3$%&x5G1NhPNs|ZnJS_n^(F1WaeO{N5$S@7ma9VTeaVg)oJx?&R)Lx zHS0p&M!#nBU5GMh=~a6CPaCuABUg^a|HQE{?h!l-*V)uK4a2dkO1`+~~6w(cc|_wZ6mlRdLJAe(5%k&$jpQ!GENzmBV&fhzt)% zV8!RQ3~FklVxh01*FBqKW)tT`!GBb&rNcxl!Z|PHV{JiO&U53uX@XX6Iu@s3jxBi? ztNfPLq1P%Ex((1&*59{;n z%rL-0uGH}|(2}F~%T*B1W^Ea6>SKYc&45MnvUZe;|Gko+Dv$82pg2z3wMq#OO&VaQ zih$NR3AN>&SvRB^DF<{5{>~54G8M#ANJb9!nqWRj^|Uqbm~&{x{M*x5m|#H@R>P5H zTd`wk_(b8Hru5BDjaH4{pR{(O9L%lZn==QYrsVPI@L@HVmWT(GErcB?S*rq?C++1z z7G*l7nel)khmuz{T>AttLUEBt-y^1q7?@) z521Y@wu8^s$CkV)MICJ|dsO%G;}PPcKhLWhp#|ky#Ed^@tKUI=$`2A1K=InQS`Xm$puKB;AbONJ?;wl?+ti0)#(&&z|7Uefk z$RWH|$Amf-G~}UStq0a1%2&!!;Q$-VaTHLatJg>*diUP*R{SaqIB(g-ci$ zaFPj$xc4kGN+F>XZ?d*3FH78Oh5Eg66!m-Hs6Mgmhq4;>+A*g!=bz^>mp(*e3pHM) z90dypT0`45h%bI;E?!@=c}ryc30{m^3n?Y8{lPxwInzw1*PR`KX2)xK-PDn|3!`U_ zZJ81!im<_9jLDIcK!fvmdYyQhsK~Pki}lyQt6?OtKBrG*1qoP=w2C9dAB|~dUqfgw z=aIk~SOE-6=x())L$IYqDQD`9b)r4d45TVAZlBK{T|g6YsorV{{Y7iR_l?(ufex?0c~fQe+nUo78lTFbQE z-;*oAHMj!%%0270#EGv`y9Fi{1#l>U(?g2E&DoCt1fW2dy`4t+o6i{4)yzV zNi#YN$jhf0UBEd>%H!BWzNf&OkE<{L6-$fZxWB}(UV&RwF3w2Hs!9~J9nT>r<70?X=VxNmo(r0{1s`rFGHeJOrc<`1IF zD@K(7z?Lnsr;*s?OeCOx7gsE`1P)xKZ!F`mId(?1!?I`zOU3wxHj>E2gBwKY>2(BGl(^t2 zQ~}=9In_2x)DnJXdOZZTp9-xI$Nz)3kh#~^sETu+H%>96eBbyITPoNZq2+}vt6L-( zb`5QCrHn{NAF#wJq@)(E1QqC>9qXzQq<3fe605?9 zlqS;`i%;(#wYvFLZBmwE4U7UTSN|;r()hLcs;DN7|Q<_V! za^37c#8qULmm*q}&ac2e`B_J84K)9%O+@_;=8v4Ij-y|9w?$+fd;iO_uqSqX`^Xna zdYp;=(nMv|?d#loFUrxZ=H!>mfXt}R5~ka~h6b)DsC@Q*ALm(eFepXJeq|}LUA0=y zH1B*>7vv~&@66ZsLhfyvQ+rc2S+a@+QD-X6BnMDQTfrW$2Nd36k;-g8nYd1a6~0>h z=+isKf3NL8B-s}lo`(rTXgZpk8Q#Abwqp1julp3<@dd`TK+V|xuQDrt4w#o{XB=~B zPZiE2DWeWd((J?9auYqqdoCla*n4TIe^CuNyd8%vuho+ST1#JL;E_ga(T%jV_vv$` z5Aj=Uc0ki;3put@e*W9dtgf)n1D-J;T7p3t8@b3Tz-7Vs^l&_6w~Z6s|Ml{I0BXAv zoo*x$478KvlL#lgbZx}}tgd@=O%nbvC*o2R06+j1q*CKstXa$u_zUY{2UaLEF=$lFK*Tmq*sJ0h) zUWa(cfJ`KsNpI?+rp*#TIlQF9O#n7Rv$f!52HzNSmAw_Xp58)w&5E8jO9DORX&!Dm z4`3&f@R@+1qwS=*R{0YBe25tCA#psOBm=++NvFr30%B6B zmnt-gb}dJ^tG8lb2sD#+3=pFd5JLy9xp<57bDA1oxfS8czR?3osQwpf0k`gDb0cJt zX4@f|jcy1PHg`HOo+OJqNgpj)76*nKdvSY!>cFPr)pkNs8r=k0z;0~|S;V{7zTfpgxJ#v~0)h5;yU z$}_z)>|H=*!J2L7dAp%?w749+ykFN2Gpp-tw>&c3_chJ>ePB_)qfI`i(`GvBFC50D z-}E*^8$k3*n86<~O$wcM)K#OMID}^W%eYPiBB4M35YHIk zk%pM#R_Ryz`9dY$_7#t2$PVFkI{xH%Nvjl6 zn`fD~wh~#pPeyPIsO*wy+iy18;r47+j!>mnRW^j}NVa{Qfmb#5K+{S9_05VGwr?oX zq+7F`1X+h+r|QY*Bw>b;AokbDi`FcFhpmV}XC|HHrT`VL zLx2mTWrQ_5&Hnm+;k^sZI>#H(pS1JRMax-c2?{AH8Lg?oW=uC#$kU1ASg{lSYLI~6usP32+i3b$1K@BVXEX8j8VXKt9 z40yXAkLr+$PfDTySwMDUwnGuqTU#ZZ5C`-0j!uRFHbg)c!~(X5C-fwcg+q(e19>rh zbxi%Nyxn+Ct5ksucqdTOsNbOhWCuX63jV=w!I+2bAiveb@9oXs6T&`4mIpM~+HkF| zoR$MTkiG{6q97@FJgqthd9W9uw4;ISlBle&EJe`}Pb@g;h3Tu%>Hiub3gE()S#HYqJ!>!X=ONk zB=lKR!7*ZbtR{K&&W24Z)WE{trYz4tNa2%qN?5FZYWM0wQ0u~!eet-zJnGu7->hKD zVWc@N1(M>wbEm*Ai&+UhgsVO?_ikRI>e6G-%tY+<`_C4%+U~b`=v<99N>Tf?XfS*s zd7(l8%FUvKR)p7MPb!fuO_H-FCWbF%2apX=RNX1liB@P8D6VI^cCQI(r61csDL zP)0Prq*_>hT@R;kQ{#3a<#~wF`BIE^S)TUo<8wlE910`^2$`0qov#N(E@&IiO)dV*es$5s3RZ!*`L1a*o*#Q)W>mEQzN=7ZMG*4QluhA640z<` zQ&>nT^~OBPEeBWn1OQtZ(`;7 zh(IHFh}7Sb{!dn%$;N-nC`3~@_&&zuK7W>ka3u!UZyU+KX)-zZK^Ucb^ab&~Kc)W* ze8Y#h`C?%uY~yW}Y#VmGiB95QCO)lw1YIz5^ z$OdGgADfn*V>H%8<|Fj}rs?^clczR8XeSP{ZGnzh!Hd{Gy7F>wHVK*f5%WX;7+aeJ~~y74mHU>8GY0 z<{I(*gCs=VrTiN>&%yQQ3wr0IHkO|Mx_hdT&$8`fJ1W!XP5T3saY+ zXM2z`V}IlLged2J_Su5!g&|aPUq92sNX*~;Ownnp`hdDGEfOvvIh)3Bkw#&90jYtP ziaJT^&OdTnV!xpkhtP`ejT0h&Q4ehv1P|sN*R#GdWca4o6L!soDLs4;l&qhOz_v4OX{m|NO>i#>4!QIc#UobmAW&Gb8bMDnd@&{q^C!4Y^L^{Eh zt1B`5Y**1~#amyxMiq0zk0&UVXQ|4XE%b@ z2U|OYncc74cmd&R&}h&~>8`$w+rKvGiuRDVI|g4$Ry}=-azgv}V!QKTc}G}-U8#n{ z*g%>}aGCVzdOf2Sq?5bz_~ z8R9aM1x(dyIKAuk-Qq8!O&om=ryiK9%nhcI_M{${iEOYjvA{%3!Dj7m7x#~*?P5lT z+N1r4q%YJTkPYtkRhFTyOFs9hXU!Bn4|r~=8v6~@#4f9So+?~`RyJ6q{tU*)`|Djn zS&q)PPc~y`WH$V?7Nt;0_8v09z4n&FvXOqjqlYi-3Lf+=)FaK#Hm=7S+iP6`3SW^; zg_w=D9=m;RVhk<7W(N}N3x~&Vf6-I%8-5#x)~V)*L-c@qmBS99 z8+E1&HO*@+=3TOF0^`Tkh~tavU21=nbG(U;c-3{eE?;hN8(d843W*oK zg`hOwOvdcmOm6s6s8$_ns7;uC)`r;4xo{bHfTT?9h~v=w`2c@0(#cM#i1H^(19^z< zJV8$$qAyR-pNAOC6AMNh(C2ow2V1hqgXBa@Y!X=PoTqpM!0kHc8qmQmRw_`pob} zxdzO)Yabgrea&~$FN6Qwtug7%lR@=Kcm?F2R`m)6KY%xG>WVs#mP%f^&vAwlkfVbJNYd6D zVDtMp*(~U3MA5dA|SmN=_J%pLkJ}y z{mbwBBe}V|x!o&sd-LqhKBID4#Sr(0&(U1H?@q&xzly){>=<7gXc8EK_{`_CeKj)g zGbFcUS-7isbB!Zk^@+@l{O8SdzA}9hJId!+h&vwA0B{vO*^p_@PyBu34B}JJ?(K;( zYKZgU$=x%F_$jk9uEWOt5mG#mv0i{T4OT?|OB z$C~N8Mn3q{9((-huk4E_ncv^E`G@PDq~Dq7CSC&BMEaL73*PV_PY}ERA=hG!_rRhH zcZqrGI`Ej6lziB`Ssw-?d3h$l<66}A@8nv>?>BSPyftf8(Jckdq{zt?Y?G}x4lm4f;WJ2}s=#Z$3G3?)MZO1e`pM_2J z=@iv_hs}w=7PB+Wsz(CKp{EVhZR;XN)|Rg}0=AD`B-9$?G!_tdFo-mX(0s`kMcs$5 zLsU-s$n8=u`DE`j8pBR>2sD@!iND&N>Ox*x@>5XpPtoT-g*nxWYJJF4G%ktOU<$Q8 znrkpAxhmU<)IqcB4n~(IgTLhhV$_*DH2o0isk+=;(Gy4T%1iwv*O#IrPSgt?o(kcp zhMlB&aP4^xXCS8AS{HF+SSOMXHWBkmZ62Y7Sl#AQ~KN#eX4gTm+|}|y`S(h zyJ^mf3t?H#^EWX!o=DJyL}hfasP|2mT2+KYB82i34m9t|xLwmrl@1S!IR7+SV^{u~ z5sms4G(kJ<_vhi!l!p7?+mWREb!)rqa|@YC~kDC+uPhAnvFjt=`b~am2>!Oz%SAd77lt+QtX( z{LNl^P;@Cc$c4YcbeH?0lte$77?K512bUpDLjjY3F7Kp+Ihcw+%lDrHzvgBM7e2>G zi9gk0$}2%#^zCnHTe=Lsss;6h2!Z#~Cek}}>?f~p*^_){?m`qf3gyyav75ynl|D^F z2G#H0Dj8xdVgbeicH z{0Tv@bA`o85^1QUU|kn8d+)JTe{kfwMh^N0U#ZV9_~`MJWH1?$jr44n@G9LY&%?_- zqTF7<-i5xLcsMcE0jJ)!xfSr0lJ&-K!q4Q;$7yZ4bDZdJV-6eVa|AkmpsNVwEQF)N zM;>a)Zo(UCi=c&ZOm@h=DkIGsg%t@2@N%TW&ry`$Xj%C%cQT=8&+i#sa4vXjrkv}0 zulU8l)aOUZ7i8bA-oXJYH2-6ZkLBz)m>V~2l&Bt7;EK?#uhF*|4Y};4Dk(q7sbXK(2KwEl z%60jE&#oMEoA*|EyV$~>h_@{95Y8RuKou-diN5{CKOj-r&n*%EqqSrl74E4mCh&8} z>b_4NFtr4${2utC`7v0sA*Mqx)@Fz?Za3MJd#q%{%8|BakC7=|f9Fy7w>t9RdBpz6Z^W)21$L_WVRb7)X>4d_VZD!`r7Mu(cMI<^r<8T z8t@1=+ZpQ}+GOJJcEguPE*LS#rRX(zlUS9a5-YxENt2aF2R9O%#h(NVIjc-wp}c6J zD1CBylEeQs?O;UilFV-NB^f4azLzm;Efm4A{N?hI*NEhJ6w^fVYEy5qInv9(1?meb zI)7S$lCGD!1znmoPT@D0N*HfLp6JiLrtWS4<#`n%t-rSs!os!N^lwrd3I3Wz9cd$0 zX<~bS_r$;^Hu>(e=_u3~$xmthwMMM{u$7zGp4GmXc7Dk~PIzqpNe{>Kyyg6;sM&kL z#dM&NOHbItw1bdVB6)i>j=q;>B`UV*BNS12fmy+eHep((@VnCFUR}g;9y-^VwV+3W z>1p!f8@nn(5!ega1+-7wS=1kI^mV`YM6~LEZ+(;gf%=F8F8H4yFvR3`x4FVtnmC`w zpDZ=tV@vz6Q0b9646jkWyTkWZvg7Txv|_RarzmukiIs9RplcmYX-K0%tcA|6@GJuM zV12_bML6Q)SqCJ+?A(4V|Jv)mh%qpiXu^g^tDr=)q#%6Z(lPBkb~$gb8cfQR^E4ba z()gJ^Nd28g&FAD|n?9q?U_PS=jPuZycK?ItvIj`;<>tOYy?30e{hXT@B0B=sUbjd; znR+M%yu}8G!haas_`=VGWPpTADsqj!TvFL%35o&-3rmi2e}?$ZbjKuA9O|BpfRv@H zQJTcZrY4}Z1z%g%NtDGNx>6N+x45K#bbVv1($J=;#HeKC?^?hcepC~9{0Q_DPNnn5 zFKprsq}&f6;2!heu9F;@QUt1)^{sp#(0FE_rXgK#lhT|SVz6!>uYXLtMKj40B-qeE zzDDn>J;{B337lwlWyi`&l(AodrC=$!o1i5>10q*Nw`8m zO0zCoah}&-NFy@Bcck@=>IZZIwOwOJvY{spT{Ceg-wBI z^k^_Ykz_n_uiT5}{X{!8ZAL5a5Ld z7^&V%RKi19(yM)aiTfLOgZcmCm|5dRY_KBj=ZjV1J#-VWnyH7C7W&1re7=9*nkqJI zHU;lPfjQr?mr{d&!1R}*GJLBWtsWGLwI@lg{;@iksK}G_m|6vH58P)y=>))kxjg9i zIjh3ucF|9$l}Sy9<>aR5T`FR}CCsMiYN`qwXn#vniIp?Kikekzh{hLLcL+`xNLh-j zZ|&U|$ZFd6v!Wh6-KQ!nUd$Rl?hYTkKg+ULT*CDSo+>8WsLJG1$Iy%k0CoqjSiRHv zv?}3+FtkDYT;QlP_BJO*bBr(aH)z!%3z zvSnnWP~X&=&Z>)}=f-|%)siHl1M78BusU@V<~p*FRTOx-Hh>2%%ln~5o>(@FdYb1B zuNwS!)5x)7yS6AC0dzC>^iK zRNH7Wne&|a1;cGV=}Y#VZYq6&-t?Lx!Q@hBhdb!S(O<64N_);^0rZ8--Zi1b1*4^O z_yQ#LrEQNBbK#2RO$|zDZ^(C3O|$kfc4B%t@ar(_hU-Lt5^*nSqVl|{_wDAG_^Z7s zwE&0o&sR$XObjfl4umE%zB3&aRWHvF3gMN8^)U~IwDK8#e`ggi(rs8SH5ItmZKoV7Ct~Z$$DC;#CY@6});zcON zlv;ROL{iOvF}|#Pts*}dpr0B{`&6i+uaH{4#AjyO=_Z7xPmP2mHAG2yWvyvfO$rl) z@|&I~+r;dCdE}(pqfoRbuOu>1+(WY2x5QBN=#P*cf?$*yNE=%%H{c=7(z zcy`Uuer=74yrQJ#ZeYRw%{bp1t{sLmoMM0M7ue0KtY78)(3dx)3ipFQk*~UTi0Ew> z^wqgAekX4qRoyP$uZ#CpccmN51Qq(@!`a+QwPWV48wBPHJXi;uU4rz)kOJcpMgWFj z#0XTg<3sXAK2PcN5vXKG_-%FN$?}Sa@hRz$3z_wik|4`aX6vkM;i{Hsnx&dD56dk# z)ewtF3_VRab=?5;TQp(Bu8p$}SaW{oT^Bb)%`*A5K?4=E#cR6+n}>eU#@UfC%v{{zv;M($4~z= zUm@`OgV8tS6vv2ydy&aGz-M9C$CmgA$m<52KMq$5SLM^y3-+^*xIA=T7v1mP3=eJM zMx%cv1c!&lMf#Qv#d!RshU9@q#|Q@QdxlO@)n1_Kc$jj4*kOMXMewjk5S+2lyGr5sj-eWl0dHCSyXiVJ0&t>Gtv59F250ODCpD>7WkV);CW~*SQ}|>%U+Hbyk)fZr%)yW(`Tuw$UMgx@NMF1Mcb%5%P_Z-}8C+A#gR5(O!b0Oa{sndXYabsd^=dZ}b_-~V_ul`; zQB`xsFWv*X=eXp!zuJ#{OiI@dE%Y;HI^Dn?yvX^F@@#t}Wx(ap#J+xq2B9{m@8YM9 z?D3=^iQMiJA+@{rS7*itL|LgW>G)7J8xb)-9VDR&(C^Z=YAtJR(lMZ8km(nyvAX|i zV0}1yG+(D!&d*}_BdrV`;gxOkW%vFgr|Ufm#vz5*&=&}`fc^}FOdEy;URdzJE;>>OB+?iw z*2b)0nfvI0)+n^7cZa!lQdIjO2Da4SPhG}AL)0F-_i~#zMA84dDHW)2vPJ~A4iaH)^!fib zXoZs%B50Lzn>OjS=|S-Q0D_|w3x3+q5j1XaLw5Q=T2DD$^K4A736KC(&ERy|@prJ& z$I?oJoE?67NCsM*S3o2^D-&?}Vk>Tlcd`q#)oX3)I^=QrWP8+*BhjWmo^+rbQ&!=$ z+--M^;Qq4ztjky1l0S9VJq&Y7=bUlR#}{u%_sS#Uow;R1+KRU@TS}vxVWMq%X*LZ- zuRDD!wZiM~|Nl++bK`_-N}S=-!4~}+CH_*MH6O%yyqt@u8SHf^5P8HQiR^U?`Medj zL;06Hc#686RN2h|yQOh_+)_$LZCAv8Zn?rVZ}r+P_~q_N=z2ILZ0U&T>%=>XyRUdw zWE%#41~0`_cBQPBl8^i2p1wIs*Qz-4qC^mj;T?QAaRe>4VD|zYwhFzpz_+gW_5?=H z`!0UB*EOQm=T1O~YSh!0y_(INre=?Ff)WBKl`*;(Q!5+|n1^CY4W%@X~ zLVem;Ve+jiS-lHe_H4A?U$}r<$J^QnuYk3g=KyiIj(-k_Df|MR-S2%beef+ft}1rj zvm3rPQ>5^0sr}OmGjd*5Uf&FN1|R}=Yqh2cSIhK_B_Dcy*MDo#cx2&(f8aO4HNrj- zVmcC3C=VHL=JWJ4#7}ElFH9YN=N*Li)e; zW**T?)=Lcq4x28L^SLECNx9FA)-KL{XRhStOOk2I?>4_}+AY>TTA2GMpe2co5$PEU z$ISIzhW`y8@K~SOP?l$=*7LqVUx8^0d{_9!t`3Q{4h?6nR zc+GxM+!=`HKU?hMI{02?#eVkwFHMu1MXik|y+5ID7NTz-_zL>>*1}Q}YLv-71nQM-D4`Wf;2k=w9Oj07M^H1y1wXJofU$$H5GvGo&B{L8J)d(Lj5j-U62ci@a&wk@1hsg) z;3()v_B@05i!k4P8~^8uu9-e^=d=}N`}4(ba>G;O;r^5W)f}?zWCYi&^ab}%zm6Y0 z1!`3%fQokGjw`XdjcCiL7~jJjkL%7D`{xqNH1E&8SFjSn7ZJxVn&Ml#=N>&qT0WU- z%q#ll<8`M_@1WN5hV-Vzp;#u~{5>k;1xa(v$t0ij)DZur?BPP~^SANs4z2n3VAb*v zk?z-BpP6kxw;W{!j7*j%-f740v|ZtR<{kXV=VY`S|8u9Qe%|yhTUCggFPwR;8*Q~f z<4%fAU@pn)`zQq~b+3M$*omohk6xeIjM&H2o$)tor6seicc#xfneJ|qQB?~ul{R6* zo<|X0(;sSTlMl1jOGkvWjTS3SCD)*ydTR$)u*n0;UY+%MXFeedDosE})H93dVkX~? zBct-lV35&;`RoDpKlt3%O8v%1f%W3Iw?pcp4?$nyPQNGhvUe&qq_Cg$1J7aKZ9z`0 zBvd|Dks;Zf#NKv`cKR?_a}G(W2o?&tdP;8HerDoX+ndF`+FHhrvLF9~$9H&$Bx#Wm zh0UhtPqgUWI()}VdOXErtHWpWxuUnW^?GvkyF--(_~UDPe)~jUh@JG#Ev&`iDIpwj zA-@munWH-ubT$CWvtaOq6Zy>O$ilz$8XEs3^D;CGn>FxOG6GIL$8pu&^cTg1MC|}} zC(ezLN1 zp}HPlA1~N`jJ?)Y@&_Kh3m0)O#Ndo@k|(j|6bVzv&NY^lu1BCm)13df90G@r|45Z3 z^H~L3FG3Fsz7CvM$|ci}t=0S2#FFxYr9&jI(yTPth+ETE{=!Sfx-)y1)?y1dXAua! zsOtBWE1VP6ok>5p=7i-gL9%zU{H@7ChufkEqK+X2^RKjYLFHTHF?NpOwBBbY z!BNT1wXN~;VP(MN5{b zbV@S+GpB}ku*2&%1e!L`Dr_0DEOnh`;29As{gru2*X%&CNB_gX8M5OQdsUcnZly2D z5;Di@q)Ns=T(Ct9e%o}>)eCqW?p6rsBpD6V5I@CACxn^n_8#c>uz9=T1+A4j;LB*x zJ(wWP3@vn!e~^c`n^mxnd<+eXQv1vjzk&UJudax9FwpDP)C)i*U&xgx&hZq^y+iu} zJA=rIZl>Y(+tOmR)ODZPu(f^;#KrxnyViz2P^W5hk>Z zmlT==Ssx!^a-0`ezwcl`A^4|1S}U*TU()-$^ZGvUn69^sBGu!Rl=*t(kBXqEGe_Yk z%h0oBt&Kw_ix-!M<(oXrw+9j`e}k8p3*3}VToY*{y|{ z)NNrICfu^J?pX+Mp=u*EM-RDQELPb&h~*zAXom&T2z|%R7hb%J4EL+H`phZj9jrlw zR~4VMxyR)Kv1!pUYq5HS(`dz)>?k^G&hqbxI2#8IKQXqu?xQ0H9xSTFi_A-j>db(p zLy85lC+37KrB_E3lEQQmnm+I736--KZ`R_zzH!v;#r?B7Ss3;f9hH5&`D8-@M&%e< zzT2j-@~6lLl*KxnYj+3Hz9R1@A*TisC$1>2_V%;&wuR0@&7YxX9si>SYsmGvWo6w8 z@*3$364Hp+-n+{_Ur~H~02+H{rJ?&Pc+X^v+SAF-Q>r5EaJTOLPW zgKch6Om+Df(hZH51Xm|jWNCo~9Gm2FsfAE~>$;;OAqJYw5x`k#9Frt@A3`h;NNo7gGIenD-~AQwQQaz$`;I zo0-Q@hbTWn+9Md(igM7D_H3*DYB>%(S~sP#*YV96gQP?J_g_tp4{;X$6TQ;%o_L#F zfbNi^BmU<@4)SYr_Okj9Hv0Co!aAx#Rs#nMSG!Nk`|5RfSF)S))`E5aKK{%0{W`Ig z_1o(*{#xJx<)ETQVX>jPBQ`Q#vgF=T()#Ni)MXe%cZMS#c7?tErNY6;Z3_Jj53+Fp_7A&IrBCI+>5+`VbBJ2$$ezCitFF6m9sBACZXr8RTgypE@E@B~_5VUybu z?|A>0ZN3X7H^1LuyvHQG0Wab&Fp1JkY{t$%`s$3oEqMEnoTFTa<1BYZnr!L1L~AA{ zcE_s#esUlGuf9e{`Mnp7Zb=U#9eyF899=w0J9e#J|E@{xsXTT~9-;ar<< z{DJZ5P~XF(zeLU%v!&j-eb6)zJItB)@y;yM{xO&vT*Qergz{pv`-{%e%H1g$^SEsgOzrxTIKajZ{niA>L(4#6DbUBBOYkvpD=NIoZ_R;x9Z z#ga}k+iqv$Y>wIP-VRDrI@oY0$ax2Tjx55%**iJdsh$ANBRL&$im0iV2tMAS8-g4S zz8VWx_?=~XQ$UT5mxrRiU?AaKrr8`#dQR#*C;tlCRr;t?bcMch(2q3;z&&h~dHf0P zK-3I!4wl?8!9T=0wqTWvH(5S7xg&e{T$4PJXpo7GVOHz(6Ry*I44pvdVdq`Xmad1* zmwk^v{s(`H;%%k?30k&pYE-!d^VK_F{Z=wA4H+3LDGBim%|glZDpt{Grja zN|`Uc&NC?jT%aQ=PmT-Q~f*pm{BcUChXwd%-d5 zD!H`KoXqJR;{3a#@CpbLgo(Lcph@0!q3n&8a)Hcwl2#fwA{wB9Kl)5j%4j`cdi5?$ zfF^T_L(JWGdBvQGto|7K3493xHpMlbBAFl+cMrar{IX!^?{GQ$o#u~r*>_B|YHTKn z+;!^3+}Y)l)G!`dyTh;d8Oxr}xw|JM(7-smZNzfptw0}PypmS=SNc<#_IXaoYjkLK z2!iQ*vPQdLpXYm1CKlOKd(xeoJMsuJorE9p%y}Na?IDn85ZwY1I&@B6`DfwiT^CHy zyV5F=x!T}m0VU*Rc+-(7)^DGpDXptSUmZH0=QCCiaE^U+$Q=`Z3o>IGEM1+ZJ0%Rf8ZZ`^rZKW*n%O)La?{O zkOXNlX<5i>epBRV>%PkG)t5j4mjlB^pv4O0U;T?ddtWEG&S7|eA}*i&LNiQdFXgJ} z;0x9Z%?|nnGW?FgNf?4l7bfNZiCIGPc??B=QZhZcngHD#3iSDpd8K;wc$deeej7KJ zGuJm2{MJ#;-t+xe^`n=IodNnuJO27f2kEv?lM-mGCw(oh&91U9j=4GWo9rlZcck7N zcQ^*hXEuI}8)bBV40ii^kbZ0hf0UR-8~yb%pM=YL7kkL*or4fQ_xq(J)9;_@9L8qD zl4hH#1Lk53;hpwnl1ndV@i_A*+(v}6tE|mf)FOl|cIwS;d6mu13a@*c_~&Jf*2d-T z&47aZYV{(74cceK8d#9QH=|V3(+D!fLA!n*QC9>4A&D=Uk6ZeI)6+`c4MY9#gF6nR zm(hFYFM73wGzxmR44sG&4lx(eH|R8P;?gm#W_dPrS^1Qz)8+Il{`3dK@`ta}UL#gn z)xXW-xcN)a$mphV+ht{6K?85CP4PfF%}AHx?bIdy$)8K zI}eH-S-bbORachMEwVy_Gjyc#kv=q?yEBa72b;FdVLw7p?)ORp?%S2^jeWH;F&WJ> z?d|d_1K!;2HuCaAD76rA*KQ1<5+G8=1D-Y-N)2;|7~1a^Hb+??to=8t z48;QVh{UH1pzN@yOE*5!?InYnqXHzh2Ru*1%f352IM~j))_6k7Y8lV64pXmk+yMMFF zFe8j*|JU8P*g`?q90T1vY#`kT#7L3-KH!_WscF3buasw5EQF9H26p1}7-ERPbv;~2 zi;sOV|HhCy>qE^&?tw$@(=%B<5c?18)_t4E@erpShBgg=9UkRoRTS0@up9m{N{H#D zs(rv16+YImCTo*v5!41I{JOV-}uiV|bS*&Eu* z2MW3iGj)er-|=;0K0_xQUfZCm6o#Ydv1Y6j#GaHup(=y4=}HBnt$&_l{RrvCp1Qr@ZpN3hYm_;A(2n8&d1xdkU)+Rzf;L+SQB{Nop0xM#zg*1_Z zM|XY0zbV9jEti6(DL~WKOz|uC;pq$uR2Juv9(FaZx3PFoeB&h+QVnO!5gS%9H~ac$ z{{97^ZSX47y6yUdqO;Q~@|aOD%ZjnRE>d&wcXpT%lJ^ZIZEmhHs7{$(O?ANa>4Svv z>)d1@^pNiCVegXvVnf)YqO~uqTuN3`Ltz&AJYE>!7}*RJ_8Z_6h_v4^@xs>Gy`(1g zBIi(J%|3ysg3`CcS_pw_qwKa3P%Jx|R2OD8pLrBE3c-2&Ef7_JS-^qV6?Q`NF{ z?IcZY*X~mz$Jb-^nM*!8(+v>VSCC01BL;TZsW0H^EBM}gIwzYCPF4#wS9Mp{(%7ji zk&PL+GmrhFS07;lbRYSdN^NX!mKUS_A^aw|^<0DuNsDEybsn%}4N7yiOavOHMLGs+ z@ak&ql_}_vVzHTB6k^K+sXH@NhDl%knPf;i%Bn}3zxA`guDY{^$KjzmIVl4EjZ=nF zMO$SuFlOO;k)jaTyw2F{r9x99Kdp=5>CgtX?r zf^MP)_MzqhNpcpM70G?y=i^INXSzhFO1tuL8LnGV4E4F$-?I7Ys%`!CWJ?fGrA}K^ zCC)ZvpJok@{STcX)aUot1(_BWP&1sbjNB$1a~%pP!vXsHeaN54_5&R*IPw|4SQfeD z1DmjAnd3ePVGe|GiyM@6(p_R+b`hxm(CDK-;}KhBf9JT zRUw7o%JyRW+a(DN!~eSw_$Sg;B={MWF{W<=rIxw%c&v8hxC4EF1oKJ2;G~29W|%f@ z4`Sk0F>*=;KJl+TYM^p{`Q&n= zEBm(gQd0o;6qiqch>ow|46I_HIsoU|^C1L72IaMzsQ50Nw?r+WPpElli6VwctB|P8 z)Jgns!td3D+#R!srAE*&dj%0qfdm&_&oLA`lA$D-uQI=(CZtsdK^(144E7bW6mMS_nx$mszxwaqY*m{~ zK$CTr^;6CyEruK)M15`(d#LLQ`)C(fY@YS1`f6&L8|!OAEteV)*4K4KD=fW7|247C zE5Qwq^`Gvu;k5y0yD@${zn6Y~_4-~GqH)Yz1CAe}K)ZS_XjhXQ2sC#5W1ZoYj+$9t zg+9MB>@&zb@-4792AH*_py*xKm)y)5UP0L%=0Z_>KCh8-8z=k<4Y5U4QcatMeLj?m zqv2CQ=wB|+HG?}L?AgNZ&$ti@4cCh4;0}fitt#P%7H6Jk~vFA3HG*8qW-wP&cQvuD#V z%CC^B?np!FMKkI1&CPDJjB&~%AhTi5=8 zQBa0XWM@yo7Ko4)6Sy_2$`iJ(18di6xB`$`# zyL22lNxmkk7j{vP*G`!n-3hq#{{`Pzjq1%djn^r3>0B@(H<@kiJ#$*9Jt^$67zHi3fu{~ZeL1-f>1M{WHV|~e( zyfsty;KrE_SBcXEQB0re2igM%f_kU+AbGDd`^MnM`cEo;QLpxb7TeS8GM=H%r`6wY zsq9a+s6!omBW@)ULJM_=_0OhY$+~f{t;q+~JgnY0QHgrU$NZUxIFB$Tg~gtS<`C z){PXNhE7EVQ(l(HrRUStOxyLo9dHifAk5)Ul1BEX4jFP(AHDuT52x;dQy=Sp^#T2Q z(t?s~txd3?F2>!KqFmV9p^y%_7Uon6%`dR{A}kPH={0Sl=@`Ouea*V9pY2zdAV4U= z^x5paMy}*+yNsS78Dg4vgxWnCr)={dOzT*Fr2P8vC80Ak8S0ktsD)e1c9b4-HbZ1m zXFt^mNzB(jQ_>9m}*eks{SlSgtIC_XDS8q?@u1cfIrE#{vXnJErjjfdGdP zuvw|pYB9GP{#zbGhAh*q1qb*AUq2fheKJCEHYH<_dHSJExL2n_ihc;DG2 zUp;v6?TP`Phc~4e9S8@Cd3i8uk1EYxE;FO5x9FjoYKy=Dxmnt5!w{_B3JdjW{}vE# zQ^Z1adSD-o!e?9GCpJUTbK0qifr6y*k;n4W_M5dZ>iuht$ z-?k!Yf*WwjLt4i)6_>2oH0U<}7!|Z>SQqfGbRXPYm1}TvSzYyc*${%qyR+1T(vj+H zc}64q+OH#|pR`eLir<{#%n5n_06)N*_vZIaO>f_Cy~!(WC>TtL;c(UTup4JH!wxex zt^K=_?>_v2BIqygM;3ESN*2HTY@%OaSDiH(X~6n`(f;h?NcO^Qd1`Z_ z#wpM{j1wz8-qSPvka=0X&hLrDl1?8Df2TkJZD3bhvcgX6r10Um5dLS25;NPpCN`z2 zakw8jh8tS9LQ@5gvxu2djvm!evm}6biLrJx+JS6!i~bz`Py{t*Jj8~&bB2G^)?MWI zSM5#qm$6=SJhaDhujmW%Xcn~G7Ll|>Kx{qVKSrENqew7MIMVoqs~h^w*|rlk889L< z(M9G@E$UDUeXj_d2uWjN9B9x&~pkpzua#6O!BA7AUMduQ;k zO#Fead2eWDk*mtB(TbWPciUC%C9(0*Ta4Sip<*NSL~9E6Ynn<(H(O+j+%7fM_JM_& zRAE@|L@59gs(lYT1vy=znqiw!K4uf2^i10VUYd2@cem~3UmJnuy;Gh8@~(|&&Ts_* zu5d8P6-I}5E5^l!3K^P592?@e0z}o$Y5d9227lz$Z)Oufu7JP76>cjL`5YT~ULVvI zbcz@hLXx$>;9aG;{Hj3ubGLOszEYaXiu{~W70j>Qrx0>>JW`o9Bq*J_E%K=f#5fm` z8X&%PR4m8VtTQyNXhjm=<-&S6TJbW^-4;>+wO5D_Ff;EJlO)<-v>P|>Z&0O&RTjkt zJQ>0ajZ9oBQ*n27xaEXdzUrdjx!10hk@QUwlWa`zxz?!Snx=D!m{By}R(JRiXF9){ zerStJh?QzYuDPHcNCNb#+BFxr14&NIE+>n1ywP;M{4`OAJ}IaT$c2Ig7}KFXV{JK& z!$uH<6y=S%_>Islm`6rc6?$VBfF6!&c8sS48cfd|{1QM>6D%i5AI+~kHJ`|jn*5I_4CzN59>f0=JP8hLAG~}NT)(Ig<}&XLno6N3 zR=rf|hH>UcsR97#{}!hKlxRnHfl0pvt@-=nU-5jD&j&#w0OEmY$UQT>=V29gX_OrY zV%!H%!egbT&34@ddb>XB6QyZYHY=mBjD)nR$vsW1>9owAyU#$EnccL=o;z@$7<$V? zU}Qup8w7y^h&py51%)gCl5!C`J*u&rm`V}m3j6LVe>*W{_skgS0AdEc%4c&l=LZN< z1R(yUSE+3E0?-y_kO}~ik5MJ9M7JyeTK&Xt>oKaR#8FHoh%o>l1~IAzmD%JjV9p^A zWD`JKkLDQcV&&MK01OB(aF<1Yg2jxXWAye}??8B^yWGwTrS9N6c=^M9$4^yO;AweG z_|CfcX?G5w8V;TYVybu6Ap*$%E$sP_81gk45Z*`hVpDPBWd4}PzsiJe*bR`De_+`u z7#Y&s>ehVSY#|9|3_4W1sBdLap7#&i>>-WmHMWP+;V`+ zZVyZCdsdW;?pO-^`d5_HBt_xY7F>L)j2v}u~o%&-1052ut$#Kq5-Nd~oM+sYDCoh(_)QAr)J zQjv^Ro%kjRuz_zxG|Rjh;4&gBsLsq52gZs6Cj)>pur0f<2`vqI!?tgHhTu|_?lwM1 z!fI`B>){oc)eQk%#*^7G$9O1txumj8s`13DnHWbijS$!U>oK6G`h)r;;4>6*ayMXh zEX|P=P>#I_#Q7IpR~Z*tsPsuQYcWKADCoURmQMw`qd9rE?dpjy@ zDO^g*sCX7Tymk+xVSu5}OUzK{(qGb^fM2{=e| zrD3sXFL8!zIg(6P_P{z0YKJ&`P0`0uqnQ;iBu+6eUVOb34+8>o>b#>^&6Cxx`Et7d z8NkA}!(7BE=N2c^_60WqaqfEM1Rr>%%`xcSlFZU%ehd;$!Sd z+{INNgMgGNS1Sq0eZJ)?KPD)STV@;05jQDUS+BS$;kL{=nx)g8if`e*DmBi5Z>Z@+ zrqZ|=tK)yVJ6?!s=&?QhVG=X=vR{3-0(~Y7SWev&rCdJ1eT{Cu+w3D$$(qEK{+%i9 z@0JNzEYm8xq1)Uj!g&2>LUr2BzkD#gr?+yY6=QXp5fcjUTrN=qciTaIbE2D#!R_~- zSJ?>VHyfu>JRV?<&wMPeogGx&y7W>=+kx<0;1S8H{guFQyHp-hbl;?Wn1td)DaYpiR3aAhz$DAp2$>+oz`w~hrTCngl>3-xo5vY7l=?Zn zz;f#9PY9*`7dp*OvOMrPdYryDfN~1VVe!ktpKkwT2#A6g8vhkx_~SyrAnld*oYI6A zsd8d17ux)Me|@ud8)BK^vcS_Q;E^MOMy$%l-RUP?8@{@YVE3{uxFd4W26{Fy4;{9@ zww#Bt1SHVg-?sMVhQZYXspjV5Rj3F2<0Q2ftI2Tue@!pHrO8Uam7rvY>6u=y`o4Bt z_QZ<@BE+mg(Jv_yl8HYL>WA!$i%U3YGZSWa%811(FQj`FzjJRTO9b~L}+)K zCtlC(;I_8T6`%z^;7_^q>OD@_M(j5wXa#_K6ndU#rgPCg?k3dZMUVZ^+bDZ|O4Lot zToV_8_=VYDW)&;2+{i-*PX7ZP5e;e)gcbcY0u}IL;{sk}s{HMqhBk+FStdVDBxI^~ zX7#W}F0NS%M1OP8{lLZ;7weLJ@FKfC2oN~yF4dIf^cpFR*YE6?_PgEj5Y+K7Y(}t? z*`GwSUmV6aSs(4ppqmH3N5&&#Tz~^9al8eaW?J`=90!8jH`-{VDZHc7d(EIM30aF_E+Txk9CQR1kA1 zUe=RQj(^uJ(U+$4)PlAPQ|ldJ%~<&DW!k(gFDCRzoWf^K(Gpo5gY7w)SrYy^eJ;?9 zPGSF&1vie)tp4D(MqB@OKn-HzFE`cE98c($_OlK`Ua%KX&m-9kpFTzV$r>1%j3@oW zZ{YU&AvWu0-K43XpPSRO5#c$fVPN&kR7Beh=_qm1CKrW#r7_-)NmtnmtY%BqK6@3x zW#qCU^j$@4FhbHSxUCSOh~&LILj7uT0&+x|()vM%W*&(1p4fBT`cYpmXxES~-l(QM z0M}{*aiIe1#`6zZ@cyf*?Egm!n?{W_KAk5SN_oUlT<~ut`mb_CKDRYs*w<~`2Kq2R zTEmHKZ;k2k8U+TTxEd(jWacIMd}d_ry*C^6z-VdakqE>YmWMx?hT+q!S;%@kBRvh} zeo0<3A{ay2o)(jN+Wf79fLQra7Qhj3#4!uX?=KLb- zb(YW-YC;Wk9clksT_Pr?n~!0tMf?&6E9o_z(%Nyh(Z+sBQMoC#7Y*3(f~$0&^RA%& zRVH4Y3i&bDSnkC}OToy6P@-sq!glJD8uxPT7oGl%_|@m&K68m*UjINoD^u#3OgX!( z)ydBCgF|Of?Kcwt_^LUC5h5_VJd%@8-M>wpqE|pZk4MN)p+cD^GuAV6YpbBwK6t*& zeX_k$gKf{s{rX?XSDUVH__W=Uyj-|`eh}BsFEg<8A*-|3uetgc#!PA_Ymx3}*{m)f zhR8Ke!UFs}v@=x4+F_|GMC|v!Ua;N4hMKKFj>UAD0#TR|Q6s%JF`%ULa>j|?lnbLY z+B8B48x&N*4R0jnox@|f3q|3HBhsaM=~Kn-$WIQWqih9sYHLE3fzW|}E_aJT866~o}M|DT-04N1z(^xA?8c}*{A zt5$f=Y_WZGyAra-)6;k{-(-gL1&`h)79K@DKSO5fJexFxW6XO%4^l-NLhGd&;=2oJC?{2-BR%bUyIYq%D zVBzu9(z0M$*vjMPx+h>|+IS)TEqB-7XtRTr$Kr2(SUCRlD6t$r+V(%kGbe1iWz z3W#AVMf9UpaaM*g=^%!y6fvJxg(Zw)vOo-90C9>|<+eI1g#lC80C6y&imXZ$|qAbHqWnZ#y*~V6qErbd)_FY6_$c#1HFk>+L@=Txa_xF09 z=l_3RuX)|MbMHO(oO|wlzvtX@?>UDYHKlJKmi@g=O z<{%gGIC%=Mz+{T9WUXX!KW_WDB))=IO?H138;xEMrW2C&+fZz4A@9w`D1>Ouefu@6(@~$-~nVU0Qbv?j#rLEVe40 z54^(;eBUhw^Dk|aTFS`+f;axT`Q_9m2x>lBtX86y8Sr4T9vhDR&@EOfb+uLYcdUm= zaQCHt|9fI9O+uj=P;cBtE?;L4m95zLdjeP7;r3ntw4E@~v3`xmmDoQs))wzjy=^>7T{0>)TwZ>&^orOThfQ z*J;L!Hz70Cjaru#Ieb9f9rwgcn>33b3GJ44i{(UiWzwj!^%7jfQX1$r93D-rzVLX( z`lFxKj{?~dtxMDo7tGg>tUl*if@CpkRg>q>g_dx8x}mt;fZdU-o`U!{SU0m-qg*{( zAwce0TreS>PIL;8SQa>`5TVw0;fr-l;6)J+@slND+@`W>WHhfE?~-Jq``Nv7as2Q% zcnRKcl_go>Aa{k(C@#MHk33y?D-S{zkvq{KW$^BiNM)RB{LqEh7X~)I@f_S(wEO6n zY?V-{mEm#YhNM+j$j1x)t4}IAGI1)Cl`G09o`U0OYb}HR4~<%S1Fxm6Lr?Avyvnr< zJwIeg8v}Et+PRO8Qtyh*{P->YvHME#Ypgt(OEuZ@Txg-HM0rpKw6;&Wqa(vYtd&A#Jx1+mD<~r zMf1Ko;MINUo|tD4N2sJ{rsuQo$5@rD9+JnzvmhY=Ee;f zskU3oPxB3~-9zRToB>o0_s{+eL=gB<)vQ&me}5^7HS`gdWql8x9d{-6kD6+7gNl}> zBFBR9YI77RpQyj54Fc>bK7EJNu1~`~Z3M8-zYu~XU=AOq_Fg$yDu{~KR@XZAJfcOH zwaUjVoI(Vq8wGpzPLNpVYbRPT@(iBUdb!yz1tjMgyKdu6C{Ifg02S*mc?tiL+w&y+ z4eKWF!0lq)6NvI|v1qIb^Fg!`eg>?PL}FgShrc3Szl$QeKS*3f%TZBrZ#tLMnj zBNFJdj0dX8>7=8fg7P@i*>0^fshN?=>E4L}w_>zt!4d7L_r#)h&Bg$2#x)%E}^BHIw|QL|J&zid3MdbmG;YLWfMov0a# z;AbLOC@c9hca*yUtX1UX?2OEd;PsfJo6>;y#L5S+CAXmCnY!8I*G|^dbNT9z1kOe@-y zYVwi;``(XXyJR@*-j$d$x>(yr4Ge>+-UxM@`p+Ree(5oC$A{uv!_hJ)$;uhPj&nFxYK9M==#D@sh%puNqIrp@lYFQM@CRr zrdVJzKeNto2`_9~sw0I+3K5X^&#e?h6&ywyh}kUu`ZDn{#Ug~s`e+FV<#L^16&(fVa)TO zqTM{$uh-+<~xnrf5 zk{+V%G2Lt=ujHz{-1<%|=*K0G?&|^w%qdMUf-EmvSK?q<@ARONj+_es=AsWiRe_)IAs6fc~UCAOnmEsDi$djC@ zj3IvD`Ceu~16`3fUpeLDE~(rEh;DqL7{T7>(#F-Uc7k}8`8&eg>T7|(r5eq?(Qg8Q zH3x`SIM>1eP5k=V-p||DH}zr{&f+-kjJ8OqJa*yrSUf!YJIW((ts*86t3V&~V)}pD zpdPzr z_7~oNdU6#j$GCtW7wc`4xTdxG^u1X0%3>QMIxZ71P!@@@qA`Sfwjrd)VtrW>SGBtP z<@<+@WFRtWdIF6sQNg?@kAAi{?eC3bVR=8nycum_sGX8MJ^zJDtsBvB&ne zbHH3^+chwM%fhu#IV6?e!^~R2P$2NMLVpk4yEhd4a`=+Sw}IQE@!)fReqOHV$X%6D z0KYHqc=JBbpU;kQ>8kC!Jby{gr%D^F3H9ggOD;(G>=_T`TXxQ)%j3KS|A?Iq5@33$ z_T9Ej1N?baY_4UcbbGXw{X=z3uZ*qMx6_>tM1f*+#)IQ%!>ghCWM3_OfvuK}lKsgN zLmVs3*c86xe~uK^3u7Jbv-+)?YuJhepIogR)nCB`^h%#cwlQGNo^3W?cEy|8wwvyRraORlLb^;PWq^x(O& z<#$5pv!ELcyTpWM39ZU$yX3Ds!cG3Vp%Mv*sNptIEo8CMsMaFkH6+F3=T2FkGq?+! z?(x0WmdBGHew@OUc#de;_XNzrV+K;O&xx2OA$8@v>AHaJIDy9+m&g+~Qs49oA0 zxyjPF`##|xj$9JnSHG$C)o{@GI*rW>eXUm%T+AA7iC6^a>I`oN^sPsol-XSFIVI;r zj6pKVx$Okvsuo&7I=5F$?HK*!lDCQy+I@p1DS)f!Qr8WeOuA!)r?%C5RfMSM*hs;B zj974ospGu;ahgW(jx3|Vi>WmTzkvr&c8fj3cA+^F5UF$H;KdI12uV1ei)D-jPi?G- zhvw11$G!p1l3PE}@}XI@efRw4CG};5C86jgrma(Xs>WuBDL)$`N%EY9WUbo!xR17^ z%BroY*)-|2Uni-rx)Wrk{GsEB}S;oyq zV$vcuSNPH{&jcuwru7e?@*(wR22|n^KSV1V3-xKSx>H>La67JdrhPn~$(6nCJ4H6rTW<~>)sqpJgfV1#FkruS^K^gSbne|SzJhT3#s{U|;w+Sw z_jrUPJ_NnKHbVmqp=7Qx%}AF9H=qD{I$tNE6E3(6wIwjQ=WUKMIgqLGOg1D_B9zH) ze2R>I37w&WaIbLCQW}&K3+~Qmh?8triE2x*DnqDjJyVdO8S#W5W0wOu0X03OrlLTm z1pxEh|BP=^g#BA7=U0{omHM~z1s4)@!7S+N?_(E=|DCya|2GI$Hcfw=>rq3zGv zMQN}<(Toqr^^Y--Da}aPu-aC9aw1%-q{z`|RSqdt=z&!J*`QlR35F`Hs^YUVl9dPZ0!*dg=ubgHB z;`CNiyU_An=wpJYUGYbo_^F}^#=ewqkal-|9hVDdOQAK%rLkUPt4Yw^+CkQ3ifbg~ zm8buQTVGUz^XcY4*Y%=(SxC3ajVE78l(aX$yd=53G90bFkcLC1X;EW7H47~5SJ9l| zyxGA0?K@P%^M?c>DPMc33`8F07wse-cxmwQ5#5lQQy%DdDa{SWd)wD488dPuu=tkM zYO|lv@{IZ0QHE@&2S{yz(k`$!9%UPY&KjQQK8WcwNcR@%&VS0~@>2f^_wO^`H02;c zspsgL`?f9MHA34oOCv@E3L3uh*pdQYn=P&X19@XnW(Ri@I`f z4NJ9dcGdIfZIbc+v&Hov@AKJOgZzqg6@KT__6&z7@<`72;q`u;$j6H^(c^OhsCOpJ z_GF!jSklf7^a#tos=UL~Ulh9Y%6g2;_uJJNe7$`b(ZpM#J3j~O$=7MI(*@<-v4Gb{ z@)`~?MIwB|#NGYtBQ&Ypq5efUFv>{vGxquhI0bif7|OYIdkZZ0J=WzY+_*AboTY8> z{U*PZkY;yfz6ADMp=Q%&5~$LKn0y=HDY84h(ZuCUxTW07S9PJoIIe2y#nEYRp3j(j zy`VA^I!~$T!DdjdzQ3>|jD5nVUJ0TmvIXRpDg(lbe)`lOokkP3Kf7{i-YbP$ZDi37 zS_#es=Z8V3FP5|kK(o0IUAd$(V2l*E$}u_G2kyhopk!x=;MhT=IPOF3x8==+Cs7u@|&uRQsMwP@HJp>cIn1ci3j7|OxdtLk8uGu^E0o$It> z)t?Sr`ex`iXUjJMNv561*3-3GCF2TiTU)pZWSsA7) z0Jo39f76^`NmS@^6LP|a+A0wZAc32Nir3F9&hFb^;v$B0@855|lEX4ZKBAn3_|@Ru zrzvkZ!8M-B_snmuFIsdeO!^Hd(1ac(RlWVJyH&rGAvy5g$tF~=c&SR}S@pxq*&9bQx{Esm;_-{s~R>oVu@QILvjprmtfS{oDSlr(^-arJH!A z6b_bBGl&kT6M8SRJ^T6jiPS)o$d$hoAW-X$Z}oc-GhByg&f?#kfe25S*7WD!#0#i~ zZ)=9z#|MTlKnsQb0Dd$y5(TBP(VH>>=dqA(p`zPvMD~2$1RR@<3R)&I=72L(l3JS* z0j%8fQl>%HEFK(uM8h-Xv9Z0|M4waNC5P49V$u|v~VnO z7TreQ9oWj)=Q;yejiyxU>FmIwg={{6zOlFwCiSLLzZ5Q>Vog1_QwcXSl$1 zIL4YFlkQ7}x6yv1F^`Pv_N?+{#smH4Sms-LrSPwLuo3E>;lMCPncN@B%so&K@XI%kmiR%%n^a^U-hZ>63BR63Prx0!g_v#dc?6K+C?5HD8#}^I_}Jlw3WXT8ynmh~Jz;0-~4e(3f#X`6r^g;bN*FB#W@^ zpnrcxC_2}mlyNV``ce|^JcZ%a>^XIV(w{b@SZIlMFgl5hiFUB3Xs4_#SdiS6v!J~V z?TqM|E2ZtbJd`P7#2LVHG(MH%z%%^hbCa6Q0j_mZbLIn1lt*{cQqUztEUi3RcLUE4 zId<_6_~^z13zFS1R4CN)gyuD=d@NfD)X2REBEO`briJD#!RAmSb>wSj+eFCza_#Au z`9HIlCAdIcm%8#>vvDs5^H>02@uk`CT7b2ORYprLYCp zo~@a$_-$LUr>fjOz9BwX_nOvpgL%^3+LGd(PPFfxG5m^tQt8RE^SV48BDEve&ZEPl zarI1>{!UYL^RDGhW|K`GkZ0pGBS;J(9cMKlDt$RhMQayuu9-HTD{4BK;cp(q`W%>hB^ysBVOC zgmWy3iv=Ab=!2R!9jB--`Oea}qlxJZ6C6v_j?tQrVDi%r)8ZalW0l)sc*|GDM=+*P z*(Elw@oTHvsR6QU(7^_MK7I(B4j199yyFO^6ZBex^_q@~=1Zr!4;UNVAe}{qh#eeT zlS>N zNmE`_S8f*!QtBGnvtm*&lc?f;!Y(I^UTf2Vi{sazW{y)Zen!?R;s{84Y5XRG2Pe(J zxJUwX>u@nn>a#<+rT$R4CxHBn3=;4f@k}@HHU!8CMO-U>ZF`NyKqepQ0jqZUz@ZZ@ zTW@g!dYufFp{cW~wdvYR_2&@SYfv5<+eST$9D_xfYnBYaCLOwZ&T$GY#3(*s9;a|F z0!y$K-GJK=#ByY~;F1N-3YY3N4hjc}>2OUS*hWLkXizpf4-Q)bWlaI_6*B;HsUMLM z36-N`qoMNjGfZ{~c35mO8FkEud6uTUN#$(68C|(3<%UyWv7K=p0u`JVZKPdy+-Gpu zBstQV{EPxjpd0}Sh-Q}3F{Gq_$=TfoC0FFq*AEPY;&BKasSn+*W;|`&pX}7 zJF3p?i=5XeQEc%ZOJg(Sz-Ei7;s{p?2!F|BlQ<4zlX|V~D)L4D;GVooHojh<;hVRC zY~5+D{ptkTq`a(+GF|(c1E;ZQ@LxIasEeA%jKd!T+2S|aqFvf@rAEzc6vNrGj#JuP zGZi%7C}UAl#76aXmLynd(>vEV!4+70;|Xx#CH#oaiRobf?&fodZzbcLb)4T$yIap3 zo%UtR&!KH|2DAO0isxK2iuA*4Gi=k_+=n-qo)ene0%vBF$pdyToS>nS+aeye#?zu_ z%uH&g0Ok>6)qD_hT&p{dX|ibEg-&|S6cw8Oj2U+ooOlz(w2sG4GL{qkG6Q3nJ^UZqO1mQg{!0UG1wFH?`TE0;nS>L$@gA_;KkR?ew>RM0^6Q@ zP*GBuz}|cYv@X$6CXrdDVrjYT>t?YWQi69oHGf8E_Xfd@jjXa{;{|e9{go4tg-4vG z)G0-XAg4}+0ZmB%G%Blk>}SzDyUKm=wDwL$MDj42({OM6PzB0|1I0T^^fDx_0&n6Y)6Gc>LqOe^yX?RD z9*xNTE*J)T_EIjGJ5C`xbxUg&UQsP-P8r3slo1rJI8=&P#>e4+fo&y^w2MwXEBp2kuBbd}2ghBK|>46&3VaeP6S zAEE3u3ei2_I|e`1a_We*V8f#?=_IxxM(GFaHWx7U;th&KdK?mM?&dN6DZcsUaF9Xh zWN~Z{qBV_nq(UG<0%>rJ0^*eBdcYybd@)&1HXT9!%67=;CdNV0uLUaL-h0A4txK)`06J1Y7sX= zC=#oCiXyaV8yCrU-Gm{`VzF{2;PF+W)!IDP|*!_d?@o zrR1qW)Yn0P8SrVH@!7p9(m3CJa7miAz5E&Pfs!A>V0C<#C{ zkgfcUc%x;xtjK>9dYgu1oFPZo5GNY%K$GO}zvo$EXYCMMOF;rlVXH93Coub$xn+JV zI-s8cU0MvnOPNrc)$YNOwF+T{pWeKc85Ty#D+FYkhrqMdtkJ#gR5XzEE!8RKn?Jxsm0t3V<|4IC7Ap3Z`~HD zMqgQkyvN9=x1Zj(vWZ?r+egE?E;Y%d;{D{?vxnP+d=#19EXB(_SMhJn7M`%A$hNDX zBM@H7i(}YWn#QtdT1P%h+qECjJB(3?P+S1EaEAH6i4GNAV;W8-c7RKa0m9 zkKY9})AT+bEO5{qUH^{S;r1FXDklpOA0K7t9dw+asbUsPLv_g(BUnXnra(b%#CT1^ z`!(viLU58%eV6XIxe4w3uXW==R`Jq7Qfv)4rVTln||%!JvL|3rWIP!jRwWtobq z(&#hQ$HJp!XMMeRg<{9!!xN7R2_Cl-W_;XjedFcIrty{S7NckAlvwstqG-Zqf_ z`j^B|u!d79@&muXULA{o_xx?K3#htek{g1ozQ5-Z*N>dE( zeg@VS2eAmHB8KZtr5Fr-%noNaRCXK*dsg_P~WPB6^~%|h*H0Xj$(!GmX9BZX`+ zZGJu)2W@iNC6+xDiq(C1l14vN8Eos>&9%6us{>DDo{hY2m*%bPZv6n9Xfe6(=gc?} zF74Z@vhh#m0w^wmaMbA?$OJ~C2T$k-qT;o57*Z8X)ihlp#Zb{r%Z5p-V$~b-`|kJ3 z&t?wUt8?pLq~B%t=POh5*InGQOY=7%`I^0YOs`65RALs}edrmUNj8zV&nzzab@toj zM>ecTOberhy0b_x`b0o*?>VFjlC$8-zkocCLSDH&2#}JH?~vgG-xR7#GVJj=7#bFR zYjel|3sY_veR@wkR>v3i&rvK}{-JHdTpn`9xa9gG=tvlW110+0i78={^U=&9{|(f1 z;vc~dmvoPz_#&(Mej9T8Used0-+~5BKPsJN27pLx~P};i4H1ffkdtwg zD;dONwGsiK&&_}UnTf;%RMhGwo3rI2TiNZ(Uo*Pg{w;FfCMop>Y3TzxP?MZEi}5%0VgL9#N6Z zs^AN~;I(}!B0#u*w4eC!pxNLD)sER50o_8Uv05oF6{mF#Tq;3u9$hcH9oLM#x@~oU z`Y^Roq!nunk>$Slwmp&4jv4D7K@oxiva}*pj6eWG?u+>m@?|AG!|T-YiAuN`mPcBx z{*e?;Htq1pa>xPWwP~j>T|5EKD_dC3P-6ysWZqsheQ8lz&pHk(XUK3kaR?YkuS%#R zJWDQ>%iKClzgbhq52|A74uUiI%^5iJok_Fb$KJ9e1}gkvS62oCxDmqWYD;9qr3`w3s6W2IXNeNGgNXY=sblLS}-uJ4~4!U z%k7^mPf7oY;3|cSEozYd06VXkRw*=SOs^xs-A7 z(e`q#)Y$Kl5wB^*DOwi|PekDf3(ndFyPz zBS>YTX=5j-Ml{Bo-#8BiDi4I&f1vYpfiL{9eKiUJWN;n2-uU96^dr^dofG}cdf3sS zO2;YtmzCY9?+Ou+tOH=6@)i~n-)vZf+q4sunU~pnYwr(zGkZT1=m~7D4LadFw`@CK zhIxC}ZD6#&O=L?yb(mO5m@|c)ww;%5sGCOXEP^ceI>t)nd-7XIvo994$?vZ(fnO0K zb^2oN;*GBLQQ&pQmgY8Bsnv;x^k{;yUf*_N22oTM5`{ukk(|N-HOp9Vj_B&vJ^$Tl6h+W;X(^pWmN(my>Y4hYAbPRtIfn) zuvmoM4=Y+E6=T>#LG>e}HQyX-A?j_l?P(;Lz?Uo&jFq{A!H8nGuitkBZq06RpOV08 zkln#*A5{KwhuYv^E<28crhAhNe^J({`z~W2*8ZEE{rxI7Kn_Ok~sS^^;kiRC{5JLGsKPUtJHAK zrD+wMIQ%UMlw=~lf-vHyy?~l{hGnnwP8|A?UzDN6+5OhXL#~%5?`b9I#IDp&Ge8zX5$^|&$H?z<8msMKv0}uEW zDOWi3_tvk)x9XA)9QI5*`HrGR6e*ildy_kXk%z2s(Iof9xK}bqA;&{miaN9fT}DW8 zy!?C$u10#vqI{LyQ56b{?MPi@dFWjzhT6AZxizeraIC(g{-KX>Xf=PNY6tr2X6p5u zk*OA?H64Jfdl@QK*aQ{Ue{|b9w=;@|0P&bcLOXnUpu7TJS$2E6*ukD=mi3buEId57 zf0zhM&Y%=0m^gtMmV5SgchF6CD!$`AY7qTfTVM_DM>}NozHzggkt2U0VGcAu7G%U< zNJmYxSKg<7z>+d3z$0VD4nS!Z8d}!!Itz`6or)(-Ev;pJ447kM9`dj+0 z{d7#@b^_yB*3bF_hq4OBOnGNh9?l~iHuO>D=i#NL8CKa9?ngO-ZuvH-)H~8K7w@~F zcPb5S1t5tiV(Xc9Ld56gXR1td;U@?IHz`FL$oy4H5l+IcyFRFk5PVTa1#;;YsnQcf zyq|>;)yD3qIE_E2hbiA86x@1XO7d7n9Bs#%4?zy)SUK>~YHT=0G#NNkMO{Yke3ADoaVV5(=xRAT74g5gDoH3jIrpPDZvbwA)>Yr z9N>CBpN=m{!@xK6xq;7cL$d>LIz!m*!( zc6N{DS(kl>FN>&F24opRr_x{k3K1WMScmfdYCS>as>a@Nv5l~%O1!I;Z;vN=ugtCb zvQB7~ZV@a)?8#1F;N)1sgIm;`0P(%?-or^C zr7lbfeX$0scA~!XjL$aqSxr|9gQZoTfMJ*ERmxM04JXVs8d(c99)7X5lD(#?MH(Kh z{bOUetq}JttKl#}e8?f?K-B;`K=rZoL68&(E-i3)qV^079W}Emk$O;V2FTx%;B%H# z-1gR+zCACa*(E)Nw(X=w3`{Y|ff?&66E$$I8!`npxQ0;9`q}~8ObFVH3gUN*HAJ{A zN0wRq2&Z43_A8gUzGG_|{@Mr-ON7}p?>kgjGxpPTs774aZKGEt)|Os*DYA25>aeH$ z#aJ546R1%tZONtG_PMiumwlRdsIz`L(WS!nnDMDi`x7wBgQh)*lP{Lb1$thQrh=!D z^-vDrr}|y%%S9awnhbWp=na8r>&`NroT+o2-j%MpDP%4M^;mZ^zHyz+{|=J~+}>|F ziT+*x#7q^f88V7Q^P$5Sz#esf@~|ga8)E(D6D=L~w03mn^O{=fn!_|g>DHFT9A0fZ zH~0}fqpn8AXQaLcI62Knk+xb(iaWCxo&0qW{ zx|%+s@iE=_&JFJm9jZ^{Mf~bUE*8ebkDW56)(m;u>ibM)UGs)rsSR>qI`3vyE9@Pi zIRs)s8sOcRSAM+*YJgKJ5Zf}9?+M?t-3V|VKG^ZZGA^_PGowJa{^UcAfZ zM6Jdz`_TI*$M3nc4n0DPOIAv!(Z~fZr7n|vse>YQs6}qv!sz8+U+&WczC3 z*rO5MFLx17W$8VSmvY0E4o9+2A-A{}6zI!17s&S)KHD#^Xgh7e7@3yV7>P;(sBpv* zd2BeRL-DZvm$Hr2j6!ZCPT3)EQq#uuw}QjmZPLui1p6eu!R%j*u17$zGnFn_MTpetcl1I~zu8`EHV4ouuvu3|=1 zt+yQgI$6{`)$CCCapsDHKGDG;)O?O!7FKt@^~a+EOX$FdlZY>vG0uUiEzZ?M@QrWv zgZq(8m!->9>vE!%&Qkf+q(5MXjRk|xhg99V0N{<>n~)ao3>Z*lCDeJv1(^=`@-wO< z0V-V@OII`UDYw+l-TPK)Uw2;qo00w8H}fr*uc$}fiN-U{r|^7f@YJo0>MstM zRh_E+I-Re6$j7;qTa+&qVRc`ISq3-`tAJ+fx`UZFbr}`t82|vqx$zUoiI@G8siCZ9VT0Y>lO<9dQYD z=Ig_MXd>R;Sgik-$mibu?M;`jR&I1TPav zDEM2BofG$7d5>c7fU$`@D^nun71FB?7=rhpD0Tck)ks6~x5@#X z23YC7=ifokjcn8Yo)dh5nmWcvf|2FF&!A`Kp_@uR#8uV+c=W1*Cg3QBFmSR%-f*S(v;KxYIr+3QBK)JV!6`G+pO|JwMSx-pBHg8i_Ld!*BqqD%+p}bZEAyOA$D^% z7{cp1$eY>Fe?IY>5X?P zN$Em>XImD_1~w4`RoEMd!h;bXM6XN{soWkaj0jj3{a$}Agt61BTSR$J$`XP-+p?bw zQH~6m3)z!WhOaFCh3g6_B&FCU0S)$iD8EcEci=fsZoMyVk*399f&l^j#9K4WKFG(rd;JY+U1G^z zntSJzjn{rwvY<%m_5eY2AdAVYOL2-nH5qcocb2EN8Sy%CuB2(h{YoUU=4 zJ`b#{v1q8VfJ-9_5`cUcV2MMO9{cBz1$~XWL9_om-Dk*A8ypFqC{Zu0@Ca&%T7qfz zK>F(aPwK_HeHydWtv)$@HI5a5jH>%TX~9puS!z}IJbUNMfJXI_1ziHm+JyS`7X9H%S9XqHmJ)*xGX+d~=k?#}%F8?on-hb1SX{CQ5 z8Ws(#-+fQe!x}W|COrcE`J|iKTo3C(ozLlb`=693g^cQJA$UT(dwzaUXTIY=3yh`J!-8g***&eqL-9<4p6uBs_~m^h-E^R+Sc z&RP|bFFr|EGbpCHao|enbr(|DJGC7--`(f65y)=An~15|%6+L2aa_Xd^zbUBcuv%a%yuXMYMMyy3%Z#V(S*r$G$l-EFIVvHsYEq zkurY?tZ;`ZQ-hg&5ro+2LRJO|YTdq>LU7-248h zj%0_-eJUpDfZ1zTgIf`tiLEL75@vDly7#?cU%n*%L|S@q8{k@&yhVFa66~GxS&vtHuzm5ttwvv4wxN^Wkp| zjWLZ7x;V)S&$@>-^8+X*~uN9AFKpZK*S{z&qx39BglW#`vK`s;m zHR?wQ$;cDats>`vzmRu(c!6V0CW2 z#~no&cFXh~_wVU=BLbBtx2E7)90K3D#4((f{omIxb#k{1yXW29+cCNtfS>bjoAS?G zp-6W(Sl>AJxG_uXy@t(r9@Z0p1y)fSPouB=p7;KzB#ZvIqIKL4>=S~#4T6ctuj%hu ztovUCzpp7J3xYCZVj3&w41ZJ0XDcsJ&)2FpF6b%DuDeZ68~3zFo*vKa=tU~B=$sis zdA>+!9sgwS_OxAXnI@@cQTVvNF=m;gaPh7%f>4z4o_+A{@ zl8;DmiTJ~j3)JtQZ~9aDRBFe+F<{3$7y9UP>-uD0S!OlwKEdUQ2EP66eoOutxktH@ ze|Gc`&IEv3&|}zlOw;F7++DrV`6ih*HNHbap$HQHKz9BiGR`G$pYYbmg>pEo0&1;# zQ1N|N4^&($K%knmnW)aG#(SeZfO!K;Q&QpPx;|%_PJdvYzMoG~WPeTL$ zpP(mUIWnjTD9b*i{B^=%qTb>$?<8PyB?*>_jlgHKntJ=%NX;Sb=e}|OcX{?8WQdxJi7CXy zv_pqbtnO@h!Igr)*a$X?jUjl3B2`YATDAzZT+On4&^V5sQ4t5bNWPSoK1z(r?s>dTIV#_;00TtwC4n+r8LgezUZ##>vv=#g`o7y6a#_e(JU;3^+%fyMln^uWS0Zw_Gf8 z-WRPbdbfWMeq&O-uG-3yzIGq*9Vt1dt{Zlz8sw@-OW6t;9CtdiKD#uh`dK3M;7pkN z7jHX#`#+zlZE>I7GL0wH-uup{0UZ9Mv8#8#?R<(DYQA%&K=m$btFuDmTyN-?-@p1m zZM(wnBqVnr?ELp4l3Q%lNgJ<#w6O%gQb@;m;{}(Qo>W@#*tYxd=0(_8Ye%6e7kzpIGf zF?wF*n6*Q#u7ahpS9A9KBxCD*267W#~nEI1^j@0J_R_r`?3_fOzS z;^?n>FaPXOE?uyaH>)FXApI*XO=cOxr5LzXV)u2qdTnl}>V?fCHAX{t7zAdAy5A(U z=6qfd%#TzO{g^HK9nin7ne98@?Zj3%-12z*<64Y_4S~FmUg$7HJimi0dODdqw@y9y zAhb%^ZKyJK4ZT-K-8})n{URp$$0Mpiwz|Rnx+>Acq9i|&g+6S4qCY3{mRXBfV|Kis zmY13U(qr(xTw`Bat(jMn?1O~C)21zg>FTk5igFK5{->ed-=8+D+5(~fG!E++%KHd4 zNcKrcuIkCt7q^eoQcu@a;>Gv8p3ZXruk4nWl~n)Fp*;QMs!XlJ@Sf-P zvqHnoUeaJsmuia9kvapK^UH0g|HajNM>Ww!?V~CJqEu07LTG{oXE6t zh~#c+83Z4gygo%~-@mo-alxtO;vQ4z{w~9auQsncU->?l!M1wRvbW=V{Ygs<**C+z z?NPnN*Wilnj=b&IK>HJWUIgh846X%1V=CUaW_BE{WwNppeV^mJyMuEf=7IJbG@h1_ z-Oa}exhMCH-no07szW-w+GGa|Do!==Zp{T6$<=B+e0FtE=y~FQ2fcfPiy@c>LiW_C z4h9chVEiU#lK*ADJ1+uz0Mx*CQOI@MH}bev`+Rr0c_{*XABWn!hQlt+g11VRXPaJh z=x0G>)&&_&bESDdi;xoGu>2-Y#|fh!=)A=L*I6ej5n+E-k$m`;{O# zKIh@_p?W~K8L#mC*xuvI8b?DUhkmtpob391y)G?)Z*5!1J9@r1Ab-7&ch!v$@jSn@ z-nr+BN6VhzYV7=-z}M1#Wc90FkW%ma;ahl0wMHWQ{Lq6A*+s#@IfbErI%GGbypF>D zjA1Nwx7Y!EGPREU1Hl*e{;lNYYz+Y=+S+9o+qI`XE@vJKd1srsn%42`^LB9Hv-Ryd zd0*eB*IZnw)jH^o;{31g>zaS)iqX^H(9hejz@hbRQSb8ky#UT1|KqET^TL4+Yrvj( zgzy)7dGpoWzL?J!a>FBXdgw(ZyXIgbL2atm{`>Z<1;&6J;viEi#`>J$Ua}I%S3Bk8 znMU}faerw#D}|EMWJ?z^;xlYl$E8hx2?G~{wVNI<&;Et?w1YftyA8k z5%9NPuV~eJcuhZz&!a8g8!HG;fM=WtsI8icIG3Beq^}oK(|Tg)$=5r1d0I>Nl>V!I z#<(`#bNcC3Iq%sPha`^zhb^rbc*gR!`-}U`(ttZ^dw1V--PNl-<2C&-K5unNS~bQ# zW4eRqK8CJkem|4GYjQu9@%+Yp{g4dQNYMRl@EmsMqBjvhE$}A-k7uuXeSewwJwkn@YWX!*eZ{ zs=uKPhGt%}Q4Km!ulEGCGi41YptcdG-hQ1qH-vqu{_1(Ur0+Ao)!NHEl)Y%J;sA(z z?r1pk%ia4)I(khFPPx8cU7mXxXsDxhdmn(!E%YY0qR9`+oB3x!ed2 zd?YvZ^R2iVGOefKBX@X%12*`+7}wSDTU2j_=%keY9ncJ(TKQ#OIct^l$j|4W%KNB;MUJQBt zR$t8PddscaM~vn6JSAb>9=Cq#J#3@$ba-4mwW&t4BfO_V-r>@8KwLdV_rA1eOmtqX zizjrLo~GN{g-}44c-^7;C3}XNv#!QTP<4~uc|g14j!|{*AF2ODP&?Zb9wB382fZxu zL4(owE=_c5!(TFRU_NG7p;iZ|(;hfu{~@${MzmzpzvXg|E= zJv=a(Ny+sIa|L1k`m*_$hUV(fS5Fis57lGmpADF8RW&>IMD^4aOndr@WiEQDh_x*) zofnf?^3oA=A}movHy4-w5ffirk`zl@S~B}8=UE@?vVBnVyz%@;#U5Vz{>}Pi7eA#t zb0*cV(Xv0M)72Ie#G1vsA1@j%cG{Y^r=d@(32QniT-58)`C6CevenaPl>q4p?_oSm zN}eZ{xMYhCOD$%4PCNST^u`4yc!2A_o>b!eS1J!E#Uo*sbiD%Hqw-2}UDR=9DNGEu zSx}Ph+f$G-x$TD9}Q4OSNe_tfv>aly{32UWp}EtebJFB7xS%DtEkE zdonzyZ~6rec-q!a-xPFBP=9t>^M=CS<(@b6u%VBl-QrGyX!JSD+;lW^Fn0QbsFJKF zt9?i;XLZG5D_0}&vK|yFjX%5jvDv)Gh@r1DsfphA=(!k?GvQ*o?vxaazk6EEQzAOA zK#{71kgU&~f2L!6eKHU_TnSvAUvOi8fcG)zaGV=uFG=$2gR0+;G-_5Kdk)8KC)K|; zNKBlZo-p+E6w8tJk_|ltay`9xpuW0qT@22rsjDHliEN*wK56KjQ=^j7T29rA7YSr)k@Gm>C@a@Kix$?uj=1Ji^&6K z)sN$l!kX_1S+7JJq_=c?He+09qB86LCwH>u?}!acw`UIZ|=O8=3L2L z-cf>WRq1*l8q4`+=Ve-Iu}V_GlC|b&rJqxwCkUyRx|xc@IE-Xt+&>+)N!`Hr zQE>tr08;J*#R}z{(mq(Y8G+g~ea1yxBGpUG$d%|110Ik>z>%!#(63QX}Ac*qW) z>QtxZc`jQY zz<6fXBEVR|YrH42EM={r4(x5gd)CFxCV3oo;7F(@A!Gtydv-1(!21K{SeUDXMFVDdRe=t{41R@CDJsLA_v}jjgb6nNv85ZMHVF95P2Zy4%{!nJ?NT#`g0-`4k8GDnvRggRx!;0M;r4{jKy$XVA| zaa?5A52E--r0X?UP|+H-&n~4KLpY=hUbC7gpu+g)t)}6-4QI~iSudA? z*9VR7bNXKPk$gyW8V}%nP>niKXbTW~ch5%TOyuFwzLE|Al%_yOo3gD%jZcMh;B5;a z$Nhje#LJ~MVDZ9%dQ@L=5)yf6tWPZ8gtDa2Ervpy;8;wlf96$1jrk%u>{f;y)|kg` z|HLw#MtJ#nDNuSj&m`>ZOm}5P_lAM&N3?2nt5Gy5Y>bxW!?jpwklz(Rp-uA%;{Wi) zpn1_qV@Sb{bzY34DR94=*KE)I53cP6&7v!B zpiFtLKsw{I6xjvvBsEMUr0dLQ&Y{XpRF(>?7(?bUi2{%$T_;l2x;FTS#mrq4H##C2 ze*>nkF=$ng#6A8LdD=%8l3|i>7$D59r+OUulNN6QenZhY+$e?e9*Ow(+;ZO4%Z}`h z6WW{je@gv3E}!BcqzD5e*4+(HjOAjQc2OE^XLk7VOoZNXIE5HG7HYK)dw*p3C(T6+ zd(@D_zRM842zQhi#T-T>xtUmVJG_<^>pRS76lx*^$g?vX6yd|7qfkCH;j>R4DR`lt z+`I;R`vPhX`6JH0)968=SM-riZ*ct!2aCw(=e9dT3p->0Hj5z_dlp`vh4oITD;s!0 zv|>E%ayED5z#sY$-MgC85U17+`bJ_1Z6mLdV2OuX;UJUWQ{q^;f0?w{C@!K45WA5x zlL*Dy6j&Y6n7HS|qx0WYxx1p)xp zaQzW(bmzeJshh=MlO>uVV^^5~uw4uI0T}op#;!K$-%|VelOwB37Rac5=Lgk)RT$za z<2aBLJ}O@KW*BClCuMGJxX_^l?6AZ<{t%u;+EwP-uHkn(o6Yp}#N4eI5d!`>#u(GN zfhfoq7ekAE1&S6g&fS6C#``1(>ds4C0@TE4l^Q5x_rutO+Z~?7D!y&rE{zcuLz+Rl zL^!m*t5doS-*z_3caFkXyA8y1j#7ycBYvC+S^t?x%=3ZslrL+TR6|Tj&7mDkDV-QR z;?8r?9O=)=IhNOMMtN0=`CK>?5v27e%~}9_ZS(7GpYdg!2~1sF=x?X*GS`icMAwz!RXHNp%L)HZco5CG*EwKC##7Q7 zzK_g}XCbfcYtbRLVd}GW3}fp&EAEL$Nwxm)gRC52lE?Oj;r zUg&?Yzk7?!*~6?L^H@l8fUI~38B1wH;W!d(w>1FkZ;hN3=e(rQqgmWIT_KEl9)l+S zPz%mVs%IvUoY!JG>_eP_BhJ^kx`oM@bv9LI1t~s?vjQh!r3@L(yi1Sp&!-bUf{wHK zC%h<-N{)XD*LwkPioZtDc~~$vN+ZT2pPvse;Dk`9$GSdjf?sgoa%InYg=uYQa)?hN zIc6Y)5{ri{$c@p|Vkw1Dh|mdt_KX0VYqsw#jd4ps8W12pEXskW{L28ib_0KL;t5sa zB=0<4pgiFXdA+z0?{C4C{g=tqd#Tj;goRHvBHlT%jK9hx?bGU#S_z|c%_$CSd z)0!_#-S5j5(``-Ok|G3rtFATBo1fmOfTFff&T`5PWe_> zwt1krv-wFjpj&|GtO4fVT~r&6ZsAGs$sqBCrjbVmUBNcE?HiB_3&K8a!T_S)(VFrJ z$cekKLz_$aYto`LYA`_Lkny}N7iOC{!8|nvKp$e(@+u=m-V(31i23ydz&0R`^le@# zK_Xh8iqT_CiM60vaxX4fLCuza^Ec*q!izQ$sN0$T0-^HkJzl^yLEcy^p(0IgteL~R zwt>Dvi?)X>FlbGk`y!86?DLcw@pNL6Zt{E%qktF6-zB@oyv9>hU~ECOWrGgWg_VEB zQr?Hjr-KC9dn&(Tw&)M&vM+UoKraC9NOtk{GJtLXI$Vv_iCcd18cX9JG7Yh&@LUC7 znfMtWkip2|Q9t(U#7Ch+7o%#L6n^ntVlsCZKG7ez+*r_L1W>pS01C!g(vj&HdiQ+Y z`&J96#a@FRV?J-qZM1AOCk>G>+O*D0DIW2*rbKCTWe?2=D@KZb-=CT(uJJ%wUuO

4{`xTj(DGUN!s+-APlMI;9B6#^EF6wo!!HKSb5Vm$zJ8#}(g)~fwx zxiYFXMhxlo6vOAE6eW_5zd?aFjFN%GE6B1iH8P70rpu~wt&dMqZlKV`#7bFpTwh@l zaG|FA0i^xi$NiTwNJYx{z`|seNVOfu6#Pv(IG+>-FeQR3h%O7_CIu$@N8UhoMwN;2 zDKwvjv=rkg5@7wL{AI1f6h9#o05uG5`N4vVIPZRL7HZfmf5(@e7Nr_Bg%#10BInsq z#w)SkM)H!0R|)}?ojkQ_+kMQg7Z z_U%SNbdxtU@ zh84maSu4uK`;CtnhNpw)Sm7rr!BV4r*O|^ykMXgFg1cP1g>cKFmLu zrK^V^$sd8&*>XnHqQIJZ0h_QamH3(SZ!sk55(kls&=7-bM+%Vz3lj9AOTd9_B2{HU(_;g-UFu!rX;U%y*(MFeZ41bl~;qq^$)ql~O`+zM60F#dr7W6&67g;CF)GDzWv` z(Ul!PNBXKd8F?$WmGLq*IKfB>zg72QoE@X%SnEH`2yuT`F4W3Za};8c6EkpizWF+B z?iNDl8}k%ah<%iBo6@o7Ix?AOflQl)@iQ){a&oR>Lrq}f`zqD^7%_ykGcXPxufFglr zd+AxaF@^dL`s@G)!$O?pf(|0pa0UI`^3H;9#CvpZZe1A;;7e*mU7)Dl=ipS@g~K^4 zcLeSy>;MX9o)e?P)`a6DjJ``wQuI2({X{gSV+SNZfJT9p=!ip5UIM6sH4LN)M1fV{ zekO460q#-8FbbzYKZ$fCKSMp66nBTbjYPx5$8g8zZ7732OhB=L%*6%t8d`PjG%7u1yoZv~`v8p_Hg!xXs(HxADQYMfWF8FU*$* znar7sET!n*!cV!aeQ_?dRq<)RDTjtwl zW0L-l?b`yrvy&1l7;7pLMXhnyzf0VU5|W&3r719oXTA1Iic8_iLQmz_;R1Sgv4(74 zWnA(KP5>b1@lJZXWnXQ52T%i*+CdxtRIgig4z4s?>c{gxdmUsu;`+XuJw4g!|HAcP zGw(B=Ul(P`f}77l+vDGM1!Tt#&h5&Vq9i`|6VazLv zjjN_@!NGHQ1;T(>ae(tu&p*wh4 zJI(Xv|K_374 ze8*LIEU-OaiPAATv|?S>9bWJoBPqZ!HvylZq;{6bC+10<$3{^!k2ab|QD?1o1wk3Y z)3wMTVwfahbp3@tuF|*9r^^d?P!T1YKP0=TQU2^FN12AF!_>yCMW0=x1QyC(4O82h zqlKwsO?ECXf<&@^gXGY}C21VuSj)xVAY*AfQ3t_xfQBaYUFO4!=pxt|P>F=*Iw(^b zX&Xt*TvvYrH#qeKCihp8Bx5YS9xVVe4@##l+#9F;j~rVYD4 z(stNSm%zN*2H?xQ_~`%ou-6eJ7jz!0?#E*M#;dMH?rBFN=k}=vztCg!t@Zsobvwd9NG4BJ=qW-Q|jGU|A!s_9Noj&i4dx(f+cNJSKe#dtqB}41aDN1qlx2 zgCl=oc@cccB1p_HtOPX*$-hnWXOFQ z+d`1S_c;wajt2+-;_SZADv}|%M{d_><3oM_vz-pt{f)yOz~g|fKci*^Az5aTkh%RF z!rY|Ylp)NWWmdY)7M6H{C(&)3l_C$0-oC>u{RoJks6-<4&tc%s(nv1snmz%{kKfC; zVi=>bG4w)+}K|G zgda&J{}m+|z>%Qg-O49jyu z3O}7O%-hGL;6H0)oxc-rlfh`xPcl-7^r=O+)|NsCoNdWg1orqNjACm>hwwflXrX@Z zSqff;njN)v3|P#d1LUgjFfEdLh3^SMcb)1bLx7WJT_V&ym1fxdA_O4ckYPD2yu*IT z+6Z2Qhkd6@PiYwMXo@Eua*v}Vqjcar0aCqXV1R69zkgI32fNPALt)Oq@yG6BDWMbdXpe1jLItfaQRS@urOH47fJP@W@?zkO-lA_)m1~$UM9U(|#-p z)VrUo5Gg|CdX$0=BMv{Z$0d%=n_D=~DlS-$n?Bwg_8M`MBEYT|*p3y|GLL9Ds8Yc( zA4A32#*G9_=s)f>QN%k&^NB`)3D*5UmtrS{zBk{W(sRpAD(^r*VUI_R&iQoUXt zm01LKJdSw7XcG+1LgdG`492wU1j`zVAbcYF!vwWXEDa-c#@X3@xT|RA?fJapYvS4ZL2+#cL5sWsi+W z*)?Fj#R#|@K_=l1)rz=1q!jMn&4w&ZxkOdjAcvO_bvw*yA#!=S7=&~p&+)hY<`>T% zm?T%C1rl)$|Lp>aa;;nL zfKy0qL2QoZ2J;1JVBMmi;00Hy3!2JGz$=A=Up<>wWf_OD*b(>V=BV6zBgP7>b34e_ z4TlUI_YZwU*ieSo3<(24aW(b3JS*IH4BDAlu3*cdC5V{|9ajgeL=2aQfR9p7F{nj4;o$O3qrF#qbSEwOW!r8sI`n#Pp5#pf;Ed~G8=HMHXlzI_{ zlU5pOYCw5K=3!TZQV61o^-1e0Qo67sqLb-qxXqcxF5vkoF>Ax~oypgcJPW-eU)@og zDToua_kgCvr|*7%f`>rxPbE&rrEmM%uQBmXGjXz6+;*o6mkpb9{=C3uDo> zD6SGMm&Nn9>sFx&qj;+xoL=%OB5Oo%4oZw|^^45$Hk;w=!8G=wWW0~FwfUjqBd#V~ zp(s}~tY`6*G7Qi2sD@i}Jp|B=d}hTOtn8RfX}&^Ov>W5YrX>2&&&6kPZCa*;-1zS?b4o(q|YpY-Z6jV zb4*&*>xQb-wcg!&r zlj1odN1H~(Hdz* z2v_W8_}%8e8me5~D2%cem0 zV@>%$_}Gt=_`ocAbL%c(Qo@RLf?WgIQf0FQ{FCJk4*|0%L55aL!0WA0Lm#gwW{DrD z7-YGUj!^!Il>egzgLIEpaL*QB*p9O^b7pEN+&9}p9`GCe6U`%^xV|a5_JL;yWVTmD z2`mLneRE)^Q6WZ20F-*Q*OuOwX8d~auoPO6!vnmEuX+6q0~~*Ry~7R6y6(+i47$3z z8F&^ZNbst}UL3&;;@paGB?6%2OANh(Kpw}@W8^(~MxgTW;kQPw1Dro#G$uu4MBHLk zuCsr4f}Ive$5~n5K@wf(Se((oI^fViT5_XAnqA8q*%Q^eo4SsA+6`wIpb{z zwNfqZ#qeZ@+AJ{p8;=?u^|kCM18m?q)G$99-F$F6tSkE>FIIHhHS&|Ez2g~1DKL1R zRB%s^XuR|TI$=+CPpZ$d3%e91m^rp@&%dqsUkDF*NulZ2;-GgSQsM;y_;BirvrmsX z8jCXmggxwsGU-;HFd^&R8b$!aND?8tOKf!Kn{`Lr0ZJ|nmc+vv*VvB7z@rdzR zMLg`W*d%482Pr^je##o*-^5$=YiXp7XaJ2TQtmH&TlmEJVa>%TGES4ZnVHmuc z6NjkSE*jnoiMhlG4OO8`EgmF(LwQ5D=%?S~`Q*B3-?@riiJePJUoI(R1PK2OMXH47 zTd#{03YYl0irfrWXNr!3tYoc_M}qhF)fz)Vgr*b275m0diDIQhl}J4*QZtAapzJ)`K8Yr|SuD1^qcHbcC0SfVIVRRCP$`1*%-gtB)Gd2-W3qp%z2& zhuEw&%){gGwh2S@c0z^8~D(Lae2 zaa{7POE}}haAT9rIrT>O-!VvdFZBlkErwxat#DV7zmnXK{rQGdN+2KXR)RAzMdF33EeR%x8R;2)?xjyZ-ne9cu<+a;-g}C*{=QM zbA(|VEOBIV4u$7Kqn*tdt_#$Z=9i><8+ef{`R;pN+3t>Ehm4>!FBQY8`T524OA7u= zOs!?+#k3LR4`mkaVOR67t#Dd_Le4r-VuGtg;#*tv?ZUr7AWYd{F}Lvld~C|j1qxfp z!=4Msg--&C<1`7t#@H^{XPGeLNxgPmIH{!_BLdNOF!Gu^AnI_x_m)Pv+( zzQo|$AnLB|0s&WrVU=QxD(pHV!|o<4`2Z?H};UXWuv~va0VQ`R# z-5WB&rc5D9v-~iz)8HRDKv~3ECDohXXKo9jzKj=U32XpKw!{bZkVVz&n?$?)kQ_Mf zFOO%GKa1rIAzJ7Pa0_zALmsgzqT$AUQja2XmD z@6BjNs_~{Tet>zL^Jth`8|6nl&aJ+6351DymQZ}Syx0QbYcglKZ}f&}Px;x4QJtqf zz{}WLE3gGURx~42jy9&F#(@M>mQhU!0V>z_LlY0FtDLqJz!^7Jgj+#ksih}@uq*BJ z&mrv&Fd;Y#RU2{r9<<9<3s|qX`-De;_+6RRs(Zm-6sV2!+j7!q8F%gN!iWCd9T3^o zjpKWODD{dnvzw(;LgKuZTSs9H!UUZy^U*9kye=;+66;{?qRDxl*pM?x$>ty<)$&EY3z>-O$h5a1fW z#{}G-B%45`c(aqeFC?wr>beJcz6cdNL;du+t9fD@MynZhKSpYfy67u98KfEDO6kxf zJT65y6}}fBTC<_Cd#*gqv4|YeNn;n}Z1m(&itr7<*WOQWJ~!(6rXv)Er71-mBdtNo z&qfaX!fN2f;5F71;gmT%H_@zM3^o3)Tad^vheZB!^id7Ytq`wkLGv=BSUnteQ*g9i zc$U&E9-#jA6X*PV!Nz7nlOL&pJrnNUnFz-*h&iQPp8zi@<=(#T4CE@T z1mCWkbb;Nz!IcB1M4Soq)AI9>zSW&u5nL1hA9^)$;Jj;p`esK$W$zIc?_omv?n#a^ zrbOAB&AwB$$;tmb1Jp+N3gDB=4XSzCPres6IOa}%_7wp^Z@i5(NaK>#YoF84mG{vd zcHOYwB`#9CzoxH$k0ez7u-5;yyxiGPC1Ud^!E+l7jI>XnRf_!t0g}eTXCC96H#n4wiYJYDW~=bYg?kPQU(f069sZMOFDkc+|BH(-0Y3vV0Bc7 z{z`%v|MvV2J&UD<}&rquj?TrTbIF0hYK!lY3dCP zwW*La2Kwk44oCI1**2{=RWqy*?-9ywm7o>P|NevZPnCfN_1I@|>(=3R;5W4s=t(H! z24Wnoag2Qyy>7j!$*#yP1J#UEmNrocZ9Jvqkv;exP?}y;Fg8EcJJ~nZ>&s2m%{wbn zUPJuul$8-V9{tC;EFBa>d$3ho}`J>bDIKh$vMnjj>tOa z@3lJjv2l5B`iXJ5|7o~uZtrxsoNbld0?rsu!RXgVst?d54Imj~x_{l}Y%hpx^<;i( zBs$k!z<{P5Q?5)WVZ?Qp=pL#n4MVnAwLhl|dVf74yS9F;{{A>P!mUVMRwM1prqstL z*q@ju69xC+z7FKPKeiDk%ip`%u5$9MW^Ug^S5>QC#dylq-!5<37;pHVI~!g0l`nVp z#VXjV(#e3fp70e=JQ(*Bao9E;_vCT#@67y7Mmd4WbehrD#9q7Mu+etcK^&CN*+5p~r_8#lwf?u%+J8$6PXC{qjBlxk|8MXAyP0-+ z{k--6y*Hil1tPX>Pio16KOF~oY?Z+T7mQxi|FpS%^;M|GOk2i>O^zTvrb^TepLJK< zFvj=AFyulxhkkMBUMFnEU7+R8_dRVOt}@>l{9;ql4NaN{5FdsmM4tPgmV;x=1s&$mKjZ&(5Qs!=1WN$_%6y^!ClgyX#1oTRGW*_eBt z#viV>936D7Np()!>UezqbA~T}e)dD+C(TvKXVxrP(<<8*o*n0?$Uy-;$1_B%Z$4wS zjkL$}%wZR*vn(^Ok=|~L;r%nau}p-G0*Nx$Pc3s{@82{Kn%==^iuYsxEHxE=Dxwz( zlb!0A5!#?ov)Mn<#?pG`-Y4NHfBAnw3N#L(2|S&v7=J2Vkt8X1z?iEhHdG`6z+Cok zUXGTt^Zpr~GIXd)jgdd903>UR%$EBw%n~)04ClrjCjV>j7{WnEdGRjyhNhKEekFGjWq{J6WD0IMe8Nr;ly(`;Ibaymr#MWiKkH3?ZHYMADr?3d#hfeStcK34_qHL38;21b1;8d9Mx`Az&px;H?%Q@HPzq%h~NNzyRd2Fxl^lRO} zwp0?4bwsYaFAd>fGCzt^ePis{<05Oi?<0*9ztQ`>;IKO)lofxAb7EPOeGC5Q<;FN= z9p$LV5a`!pSd;>@*h8ae{%yN1@p#;c#)cyxN7nmyAV4-OFW8Fd8Ksfz59~$;MIiMy@IN%0n^d+cGzC;1Q>rCruBW^%w-&atwe3$gsAuv4M#9 zvk%;Z%j$~lah_R36x{t98wX_e8~JM2rL}(d0P{|-V3$@uuGXBP*mW!pVdMiKmz0og za*wK6>V<>Kkw!cC1j7D@IPAr|f6ju}4<6OJ4r-6k2x;DLOBv6P=EkUZme;ozA_5D+2UHtPx% z=lZ`x{z>V;TkTu@z>Etxmb(SE-7o7%AI%NyCQ?p;g$r`=zW+&|O_gmh2y-FZ zce9!zSL#___c)g#7k}s*|E`;L>_*!BthIB+l3h4OHM(~uok|!n-y^jDM2j%{BG{st;1c>i!97D(>LG#X(Mbip$hrU#?B6?T3lk1Bfq4!;&?^e8#20rh8deQGq zl6BZqJv-gi)$i}dB-qo^-}&X9Vq-2z-TW0svNQA&Jxs*Yke#Qt;HgdazYfpu4nRM9w|$Rj0<{l=$9{ONTRPvW zTAq1_zt#2RPkmz*Ik4+F!HH|5<@hLK%0J!kWPu~YIy+p=h`Wk7Q+;8mxp8B1?1QWA zri;tHzT!95y+dRAAsKhr&Kpj>vtwn*Pq)W$WyhY!-1-B>w80*6a$-f~?o8qqCWvZ- ztZY!tKy_2(g#q9)Lv;MN|3%=(A|G+c-41e(bsPSq+Q!VZ_|Epajq75wn|6LSCYO{A zW~ll5XXR$=&fSq~@VC$L_nq}~9oK!G-4saM?viUatOMESXoN}qb85CWIkjvM1aBi* z+t0l_k52wnHt3k%$C?-rn7c05AO$(qRQjYr(>`ZA+^ADU$3LX%NrQKR2y?2D{;F&c z9cj$69sh%NUnM!&=RjcLoW2Z|=pYN%m)h!2+D31_V@%!Y%ZSAC-{B3v%>~nv=yJBf zZ}HJ2xyEH89Rut7l+s6w+Z=i0F7ssm(oZ(X_3Q-*ky}TTyY75qaFX;x!G`aQP0DFy zRo+{I56r@Z6Kvkd^Zht#b>gJu*W9mhoV-gzCcRv2S~k|liG?Y8#&igOW5HWZwWrRsgB+NpD6J2(05Wbbz? z<~>syRdR}TvJUc`7@ic%b5t5#zaHxfY1#Od9WR&JUU?sLH1B6q*KKcGw!JOkLrKl~ zi2LNdVxHQBcK=t+;^DzBu(hpgrz@Lp%Ran4`XuB;p1Z`thNb@OMseCN)1ZXkFWSD# z`8t2YiI06q6n@}6^L*RAG;Nl*B_j28W$V`HUW(DZjgpXbqgl5z;9$FD*aKusd4Lh9 zULqiPv}pTGE~C5yMLaW{s9(|4HTQjY+o`mnTsT3$)sP~k{;K&c$AW$17(v~_8**~k zIs8Ipf&Riq7xUZk5F{n_!zEcf`4c!iVqiWuA2I>uq6oFI3cu}BCZd8BOn6;wmN z->UOBDpXwdq0++NuC~OX^3=66-)s~9V)Q$$EcLss!v1u;s(M{7#<-b^#!PFfe(Z5%7UKH6l zx!?G!cY@KKP%JL3Li4((rhDDoBGv`e9+l*6zJeIEaQs299yUvW z&TS)9FlMgsP485BJJ#1QstDx?ZNOS|>V$za;I};UX&5l7__{@@Bpii|3t< zyu6nw@`i&zt(gpbZ}8-T6n4LQEC^Y|>fZOGs3;}_`el#DILA;0=*Gun_OOHl+e0fA z|G8_}^qy8K_ez&cF*xr$>lQ_f>|_x;R%gRME4pt-@J?`e?~&@zs6e{gHT-5TH*Qb+ zgiN&fD^Qg7ijXBoDWyqhZ})>g7tIX!NSL|pS+!A6V;bGwSDOo(taQ%I1ADN8`eZ?y zbm?8uxz?IK@#dk`){wn&p4Cl6^k4RLb`CZ6)8!52CYYwk_+9YS-#c9Jw#ZEOJ8EpO z7O-1CEA}1rIWSq+G*0*%JJb4W4(c1!1iIV^3V-)^yD!_g5wiCnh&VX8Rt>IRx}jSC z^P6E$b-^a03POtw!Vm2UxFDysO!9g{H2!$#Z?4Kk|HQy-TdjdKven?Nyg~=hspyc!t6=sUD${-8u^Ec?pDRX>`i zTv-F+@9JH4E4qq_ZJJuyZZ@*{?~X`?$91r$8w9sAjh_6jYGUg`aofHh*_}n~{_Y?s zc+b?F8H~TT_u1d^H8r;5Hc(gaB@xZdRrhM(mXKQYpv;#*Z>NeKJliC8|H-31M^0@_ z!6SZ8HN!0?L3>I6dvjqw?%+10Zb3YlnZOC=CI5Q@es;sT1GS-fi*}Mk8D5>iwrpVE z{S7bl^=w@)yXE*bXh1yZe*dmxtHz(eq`e9`bohxX?CbxBxp$9;>U;Z#F&J_zg&by- zLI)9*GpX>YL^>gdAtaHroW_h}qJ&h)VML`OB;{-dIm;+HM9hesnPD1c%;~qLzTfYC zzn=S#=l6O&_aDz6d+%$neXZ+yU+;CTwYNQMFOl?Kw;DUYf(S$4SL$M7L4@F7Pc|x= zE~cHj0KY`&WPb9ATiC0Muhpn)UY#07d`k?z@rn zAMBjYrQ+tw(nKn#KL5#bwow=JZu4^Svj~Y9Poq){Md9qMVaI}d-K;6=jh~I8NKYkf z2oJnTX@eCBknIb$J2)fuQ|YS&cerU znpr&8KMc%Hm>k9nv$jxj`&H9d!beQZtY2*EJn{JJPW8Gzsf~Vru)OZz;P_#aMORkt zteyU>-WAmWBZ&pusHY3U_D}xh?mw~pxYW_f{8tb_Jh(OqFw=RZ@4y8CptVE+Aj=kYv#ty?lh+Y0{{w@*<)E4N|G;4MW}*6jVsN_L z(f2MdHRj~%=fVeg^XpDI_HJhYMF5x zi`u5wl!WnneNrnGNtC$y9eJctv*3>UyDO=6(|v(p{@aGy*I(;t+KK78>PxE{!L^ae zhiVfY3B_}U^3?c7v*B9nFZ8M=vsnR3U|tE3Z~(kS}w| zY3%ry56h_ykbA+NCle$N=$q(1pF}RH4z&sT%qcw_o`W?zPbg zu2|X&-#451AWhppJ$KN+u}?$MDY$9g?#m9v#Hy)Z%&)73^*aGy%d$l96`|Af9$oXW zRk}+4E&bYmHiBa3B7P$WMhY9*Qul&++h#FVncC+gn!Fn3VD0yenBNOYNv9&O9L z*;47ZFQk{v8cxo3(Nz`#Rkr6L>W;IvAJ%xHeQr9liw?QYxiuCN>Q2jFLp)(!6w*wPCOT0d$F(j$AQ_4E9u&1>l-{}=_W!} z=o=Ed&ecx7CJsF0BxZ0d;^kkGhURbJ6$7K{$UAQsj4{-{cEZoHJ$I)d1=qe4rUF&E z+4(%4OL3|(m~HHMM@$0g6Nz%X%r2A{g1fz^DkrG$;K!C8To7({ z_wo+1t<4?!?Bu57q{c4wQj3S^v0Qr|wm#XLD3Za^N%KYf{gjIm!zLJ(i=dslvB_GL z1iXcOI7eVD>bml+2j6sLHe499=Jrc3-X{Ba&&j{aFO~SX)yZJ_M3>B7&bRc5)^R@C=c6vMeav_>b*IYW z$qyfj@>FWu?tZX)=kTm)0eAm}v$EB|&Dh}+j`lMIxnXZ1!WJ)A6IFU?26I@T9O?)~ z=1jjw<-Sa0DL9shO=wzCzDYS-cRM)9{lmUW9GnKv`;1E`C)8gw$<;u|{2F%Ap4kx; z4}A1lAh>TIN-Xj)(mxYc^gO@43oZ3+czey^u=l#>yu~MWTlHviKGsZFhDkk7VD0&& z=O;EHnDq`nrh-}idBkW*b@J+2vUtGL;uP|+3lpOQ&TG{?zI!(O)Ct8~%XFS>KAnX5 zU{}Qhu8X{8AGsl~XEoHZfQb8;KCPG$p}&`tXG6G+%fnTt4pbc?I!#rHQbJp)%L$?8 zS4Z$?j6*Hip?oCq24z}b*X*Hf@=>;qW4y>}-OmF~VWIo{mcL(K3l&&V+aR27vbJy} z?V;XE1!>YAdQW@o)7ipa1kbG<8tK&9&5asKuW6%)5fLh!`l2SI=*U>o&SI~~7?NVK zM;2D5jI<9K3Zko;ejmCt|nr`vJ50v_w&Ww4X3&tBG(@?BOx1U zjE!{C0Ax7wOjP7gZhS0UdE4ewHe@bxTKYS@=4dxF^hflOHI#Igu4jLizeuCpk(d*BpvYa3rfcQ5}1TB_1YcSmTyF`D)n2 z9(NOP3lXkF6tfRl@fe#;*e+mxx)Y_`O(?Hk^%DjIDiPtb?GM4dVJ{<(RgtOhNb~=W zH#*)YKleQrRS9phenc->Kgi-g}HDA9%Jjfl9$mVK3I9kX?j@($G0a*JOk zvyoi3piU~ESVOI(Y)nlM>!>$c@-tREs3 zaO7ius_lT7+xG`rP0MOip`K)?1o@RMO;YU+4`%Z;^B;ybQ=Qz|{Z2C?zds*!UdIk% zzPuhOH?g4UJw!Y7hFtAp7C-JKJ&mrG@vRXE^X~1?C3xSbONR$J`l(WSj%i^G`RmfA z%uE6r=1$J#+`3Ob{1ENko3Pl)ta;GOspj)j`r)rmuFEP9GOE}+Gc|oQps}gcWT7j< z4L$e9{4V<+mc4jw-w$gV>LJIo^aXkcyJQKDgt9Zq*op_K6}LG~>r%&*QkWKw zoQvxks7zL}RX=rQHxexU@imj;+cJn)k{R)~S4O5RX+-fgInyGRD5plo=-_{sT-lYv z)OO@tU9WC>$SMUhU8|+a*p)jo-^P)}A99SA+8Q;OQQy%>d8YCt+!e0bGC>IZp6Yo2 z$XaLs>*RNi;~_?#L(7%ICVy(8v(&n@SV9Shl35|cd`Z@MC(+CLQSFWmgK2J*Bbrfb z@|7G`-BPFq&n#+P;d$f1+Xo%)8lB00)$ep(;Q4Dtf!03~>}vm4kJ;5NhOK$CMRBNYJo#9!}!va2OfQ+Hq&Ta zli~my(k`I%pb)JMe)!=T;PGWS3t2YoH}VTCvQzLJV$Z|qO5B(S28S6R`+AJkv$O)G?L=JB4^$WMd?;{-~bHPjKU4K?A ze?21Mo=gN6{IL3OF8Grg$N`F9NPAAcZx&r$VsT#-KIf15J9*N8u$R`b%1$nL*avXv zWtd+!J{0Z~l2XNHWj^Yyd;Zkzr3367)-CZZ#5Z{6Vtz-(OKt3=fYX~W`=8e}EGdR} z>{A;T%l!IrgcyqzJN)X>8!WJF@;p$D|kYTrA}{fB(xIMTG}xYQwoCi zCh5;qhbjTGvAOM+ccDro@2rgv ze=3f1EmidBg>&sTls7JB5hl2fxGgkdkhXEOmoaLP1~~O49UlU8=Qcp>0e{02A-#U2 z<1gi}qk38+mJ~a=+$}412De%QKwKuQ{_h~()>Gvg=E6~=0MLJ14;BesYvSUDYK?0S z0K1!F^|={b!vIeG1Nt9N+;&TCgoJ}uF8>qU{GVu@`ntHW&qNK2M~qPjgR{5(m2i%s z-D7{+tae9c7@(-y_roVH(v?bZC|#ap{20Y;d~|KXt4k0lLxK-P?&uw|lh5+anjaDb zp?5St7vqv1+5YjY5qdV_?7tFoz^DAhAG1#mOi)1l=$YY-22`uD_!FlYs{GLU`TQZl z?$4UPyu#Hyy&;%;uEsLn5YS}fqqt46NE1u$fzo7*L0r<$!9x<)b2wM~W~G)W;Y6iG zeg+bjHE)c8UN-`}nW!jZj0*-2(Z=HcXt+!a&r)!f8{nR~xC(ZpMGE~-75cvvxptw~ z>+rKNPJOv}2=~;w0-R+NW+}q!e`|!hyaZlGe)azU#XxuohVmEGyz4|hH(qaj3V`U5 z6lE;Y8-X-V4Rr~#=1bgAU5nq?KM^x&B&smc8U|8jmJ$Zi7=xbz2@?g>6uH&102!$u zPeA2e=Hq{?{;L6A1%} z4-A96CH==*nH#wLr(sq>H~iyq;Lm>XzpQ~y_%H6mKzjf22-+6-rT&*S(EmV__Wm&( zj`$Nw@P7rQ^v7BV_p-~(AHxmhe?kFG{I7uiSewY-_pb&93>Y{6D|aM%fhkCRt{w(D zv`&r!RJb(Z0mx(ij%2#wC=OgL0x3RAxd8!w8mNc=<{{TpL*p2z#ZAD!Mi{!Cbi;~| ziEF<>*8G~MgjdDj+qf0EK_9CCT>Q1fxz27Ff1yb*49B~PW~y_>%EA=L)QOR^fK zdG>4mx6EwV-VJ>14-5F>R`?c*^>k8l8h&?Kafd!$eV>-@{(bs9W7VC+dcRAuN*R6e4B^>bc1E~2&@(zAO1INw`9<$) z&Ay9kP85RghC0vtfR`9zSzSCitqF^~BU{Y`hm{LY%)V}eI)}S_py9j&qAm1IjJ7e= z^!oMBh*!bHP(c5Dc-SS`{?)8kn#bW1^d=f@Na>JL(I>VFE+mv5c~eO|$~>?p7Bd42~d#3C<$cNp5cYjR^riX z{tF^4RNRf#m~Op)BJD*julK~9hUFv8L@&%F^Y$FTQ9ecgx~xamwHCKG4-5;8AqxaX zKZG9g(xeD}o!GDMUkla-(d)0SnT!7Uvk;PGNUS+U+jf{1E`xkcexYeN`YpyBcE#}! zR3Wn~rsY>)=i!#wEr;zkC24MYX|!~O3WlBd)~`HgC4|cM>r2+iwcCPkXoqgfqUL!U zG!oGJ1h08dpGWLT6v6J-cd4eVQV-R%(b86Az%UvR{Zp)I|K&cfw)8Mu3Br3xr$F2#gL!~ zo-)f^#lk7x4_~k0Y6R}@>bYzB92Q+7>zOzg=2DicaJR%U_;}fwT*Wt2yw&?#N@8qx z#C^HhQl0$%q<4;f#TAkEqNB;;!Gn(=uI<%=v##&owz+)xDBIw>fV=9Xmv#j^7kxEO z*Wg<_0*Qc;wclV5L%<^cX+wNp)P#J<|a2GhB1Ez^rTet+s-i7qWX~;IiHl zZa+VoK|hUl@jm|;7+oSIejr2=vh*PExYtE!rM}Eg7e9@L17R|UX)F7Y#f6Y7<5Np% z(h}~=O3<>~`}Ctfc;_mP{^Wh*l(4}=I43#*)*UhG6F0lHaQxeZCW`QW4%hD-NbC&L zIE*7$gkf|Iwo|R4g`1r*#Z6|=g7uX5CodY}s>=OghZa|oEj!?;IZB$A zO`HOHOds+pah7W%ylb|$i^C5)&u=V)+)bksWw@mYMDF{$Vy|hLI0QfHbneS^#1@n= z&4X*hV=dfl4g9yE%Q#!|aXH#$!vZOwI2?yiGRXf;vPtXeK=vII_lgh>y(RMB+%$CK)C# znb8ct4@whpaDI#&@HGH}Gf@CSYP5-{u@P_zKWhv>$M%fI^P{#i1IXD#Yi<-7MC)ji z9YF6r4#S7m2YMJ@v>fw0aEjhVM;g=7;!HE*Y_n$^R>)WtTt@I=AnZT@4ljV-$$ZS! z+X4O=c{m87Nr{eBr(-1kzD#UJK+)ihQYV2Q4Pm|odI)~DH0>w1f;{pt&463s2py?I zNAR&>z=?wi#DXm@Pni%5^2uB*-k`3K%3Rk68}k2-3XCe$7~3f+VOwhygG1jDagO z4+qBV0D2r@rUeWh> z-pP^_#>>M`PMG*j=27n~ks82%6arQ`6ct)5uqxAy`ob3um(%HGJu@SUOx>3sg1C#U z_9=4<_7d;;M;T8{icIqiIW`n^i3OP~hJZ%n`WrC}$71gsHr*I-PG5C}wQnC!jkIsi zwAECZM@=Z~#5lKS9kW>HI6qqbTr-(DjeEK(^YgxZzB(gGqchCwhvtUFY%KnPwr>_A zu{;*L-SbaL9KMY@tJxlerU;Ndf%*(;_8t-6zEh`^@dDpX;~36}))6+Vdg1wPxhFTg zF%Rh-16l9qP$VfWboiE_d{uXJ*vnpYETmC)%mlTK`3^(~&t%PXxEp%_2brERCNQq2 zOpvZxeKoEt8YWOV4FcG@ z$RP{SPW}-zAxOD0Lflb4s`5q*VFv(1-MbM-0F7C(;IQ(9+S+Ib=GDzu*`t4?9KE*? z>6=OI$+M%pYPykJiuUbz>Xkf~>6=c?2x$FgGA?MW2mCphA&%M)xi!0b=gt?e@L-RE zz!r*E_^|4K1zs#<*sn$I;pY1;qRywCI+jtR>O>tbshc(O9#P@iL(kvf>z#*+b*`N& z*~Fc$Y-)sgUmH|)R$iPsZFdo&yxCFW9(4;K%>ZN3KJiddg!*Rh0gpysP?R|wg8<-x zpc9Rd|0~2G5*IVwQe!p;4>W6}07^H9N^lzYw0-TUA2Pextvg2EgSC+MR-yxTt{YxL zAk&x7j-ha$8p1R}3@t3B}0}uo3 zNguK{NXwV3R(|q(f7bRTo3F-h2Wh9d7oDe$kTZbqE0L)g9^hlBrSLb6ok^9PaIJOA z!3p>KOPKt-Mz$Yp^_0lA9He z$sy2yqaC^Y#`=E+K2)sk9?{5=Yu3SOOPTUImXU?6xcT#onoFr?Ya(D`tx}*EHNYo?`3wFA><;OYo=|qhkCi6VB@;6TmHtHA}>R3~adi zn}z8_JpoBfLJK!>qg&V*jzx3(CY7;>!+xSZ9*MgM)jCkoVeXr?E(C^b?tnU~jXcN* zDyb+gUYCS-vnM)6q%K7!|Ee^h?ONYH2%7?PcN`xWb#1hvri{L0j)0nq@MvxZhGmb$ z9em8P;x^_xKBPSuX{$IiA!Zzi0+eh+3MdMm=&)e4#})Q=!E0Sd4IbRrQoS+VJefUW z@#bXn*8ZJu8h^zUnkWe76^(j}OS7h8`t9E|&L01Q5WmwGR4|eVQ`)o!#!U3p_6PUt z3h962z2-NH`2D&)F5{#loX-lHa<|BKRmQ(IWd|o6yJdmxLEAZ!|fo zZC8csXe*4zD)BM&xN7No6(b21hMs#g2(wl6UxDUTjZ)sUes1dbDlzi+`{I{*Ty?@> zDKRn$^#de{%m#00VsQUElJa_IqC)uSvcnkz4MXF`Pa}DP#@`U6OlUa5Ocyg z&<`@U&=2*^*RRRE)38mfYL7c<|*UmVr-pyISm zB>T`c%vZ5v>Jcy(gLi)Od^xg4*8QiK+&;#gJE!VM;tmldZ6D28Hf#%~Y%jQ%!E)4$;-l%s28{T!^B z(fZN~uROSwQ5R9sypA3i?VqWIHKEXT}5HAtrFS4Tw1#+kvnkXuBtwE z;rZpeY0?4haZ=|UH6*MULu(aDgOqrWPsX=JM!qeCf4XoD;UIXdHX{G9G~>sGit)!` z5;2^8fNF~w9A}%ALegh4yhV({boX)wcaf}F)t=aaT{rDVBtem$KYza_=01yQlLD*l z$eOa2)!rn3DPA(Z{;g&`uP$8X?lJZlDR+(jVO)N;2v)r^&Z+uJ56R0hxL)_mRi6TH z7#pW#W3uLZ{jz@A;L~25DrIgOYIS#9*6)T@-#fmRss5(CimZ;K8aoITb9(Gxh@F%7 zIZxw!B=GMhz7c*sKo(yfi$9LZu~oqa<;=W>mzckxR4;uQIXs{)F(A|EFfm}_jp*aP zYh2SDU#t$Imcp~UIw^Md?CkT+ z$Scqn!B%guGDdJmX*;yv4k+miC*QRkl4>sVEY(Zvo&wiou^WQY~Z)frJ zm?e;u1-G(?v9pToK~n8c#Mq`^O?T=o1ulX-I$i!_@U@rP9L@pkta2cdf1Xr(u>(zw zgRO?hbGDk;zI?%bPyTW&HEDib*$up+1t*a#+SbHi7w++$*7zcLn>mc7Ls?iNl%;{f z8?bG$vl<%VHPiR=hMtW0g|KSs&-VG!^Zppp#x!|HIMeom&=lEX@8;$C)8e zI1dSwt(h{^+6tXu|Ft&#C!;lZb;I`oY}Or2=B3CIC%;zDl}deLh@0Fj{3gd9hn*PG zH3_|^!3PTrdNMIr+fILCUF_kl;hl>iyFT?SH$S)LFi6uPBAy=Y(rDb*rj7A^h^?G? z8ci}TKh56k+h@G7s6yYn@jUGF>vI%a!jqrx5|4bY=In2~Y<%M>0^=Z0zFmKeVz@!| zn+bowew#gv?kV})&=-*Rl+iem^XIC!# z%Am@>HXB(6qrL8VzHEf4vwV_EN$PRmn84In_T|@id#v3ozkDb|#-Thg+cN9JR}Za? zgvW<6q*dPrXDb{Ie$f*jZmH7irsc{~ks9*SnryUG@yY3mzongB0ZLFB8N%4|u9&Eo zQ~BA*QjHJg2or0jZO*N=C0m^z8P_r#2E4x-4wYy5Y9Tk~j*Pp@a?-D5xMJSQPw#8> zg1#Jaw_AC+Jx5dntI?*?`Wjw5;vUwO3<@%T$<6F*wZDA9N6Q_Sv5S%=YLD$o3wbIU zu8{%0B-U~tv%KR2N(epfog`mYGGToBG>Ees|7KQeCo{k(^K?!V)lmf#49>I3=bSQ6 zzqeSdvs|euDeIa3QN$IE%gTD(aT6gW)l*DqBMn#UKu!R?ECcR+Y)OHFM?`YWM;n21&{N|<<7dTl-$iJQ9Pw1KQ){M zMblml*M9EpU^@3$<;>qQ@cM1(=TID&8p+7{9rgn|EbM8xLSVfUfo+hQT-K)!>15zL zu?F>)FyD81fP_W;ddu6g!{0qBtGqokyLMuO1GAY`FEe_k8+Yb8s$lz;rnSQ7lC2J9 z2+ZCN%+^fp;-*3=!M#QQoJs>Agqs7m08OBTKzk!*DmyM=V5Q~kccoUP>s&=UpLWr1}~VBHm1Zw1!x0PCWyve2D(fOSz|y_0MG z&L8V(f2_N6t&7ru^;6iNp}@|X@Dv|FDFRR`1C-tX<K``w5<{>4-|#zxdhqWCxN4-pWxn9? zuRo3Omi6cKzqL~TXxG16%CuAUz6gM-0iZqrP)lPhTkIg&@c~-^R4D-UAb=VG6sCXz z;I?;)OY>$FU^PsG3;g3}E^q=DeoRz*hiOC6Qj{-4Kmpnc<8L=@Re*{GDTwlVYKqIv z=-$YhDsX)ecSnzVA{)EMMd3(qK)+_kztsMpCz||wak{d6BL7xvmiz(vW8hJ0ipZm+ z6dAB7gYD?Qwu|6+4s7;d3;5R-_ehxHukhT`&ZNV%JAUJ*?mr-v6`=dTfc7Bn5riSy zVY z0j#D`gA|^F;R@K>HP#-GrZo-RbfVfweF14}?*d}9-mS)Jy$gufdiU!H9^;Q1zo!pbnQE!Ym2sy@Pi>jL`xKOZCTK@H9^b{raZ=TPjl2Z{F_Zrug$o2=|B<-^LDhQD zzlZGpg}+zc9{fZ8jpf;YSNfxPTt@-=HctVnP6S;=q`&!peULlvek1a^$?d3y>D>8! zuz;4{hpVl}CW@|PFKS=2Z#^jQJ~H+0;me+SpDK7+RCKr~y2{1;^oKk0q!Mq$HCSuv z5|}8z=-jw&JtG{L!>OpY*x-D?Yo|_%>zoVHdj&H^8}z!-+S@KV-FcJRPf()BHZ8AN zqMy}?vRGOYJ+P6$`jqwc4<_0YW5w@^dFf57A9P6jQ;-EkjR{0 zOgL>R3lYMZ{7yD=t0^N*sg{>Q*5QEBdeu?2De*3Hk_sx;+hKrV)XbTRujaphKN#$dP*rQ()Holj}WAYGV3u1`f? zb5ktqbI3}pG@AdELao(LbcGok%-D{X^?7C`M#U}Lst`JfBE56wLD z!PfhJHotwa?zY<>H)FC+5?T@r!Lg$CV|DHBfW~gq<=eq;yA7Ad9z7f7%stHvr;R;3 zcXw2LJ|a8ZZk@@{`S{`sRT+elxm5iwC8g{@b|RrM5}R_%FSxPG@X_)!iq6N@FCSDX zEqtkQxkHSZEMqnQXzfkv4DoCr0H{%b=E@vmQo~&JxhdEViNuUjo<~K>ty^%BY z&|B=EyU(7zYA3CboW!1u4SozAI{D9zHkAt9yS95>jJ99iyGeqsj%s!Dg|4PupsE>s zYm0XN5brHn{op=|1pk?!3n( zS^iS9OJQp7&3==hyxw9H=DHB{YMOfvxajp8Z;I289^UG#y5I0piRq9&U+BY=wW6Z! zCmZvMmd=xJ+epjaPrO-w$}BOth=WS2SRopScoH=O#dd!@K=WWFua9HY45kS?9zZ`z74th4acY&^pwTkA zF?Y3!x3!se3dYFjzPQT{GVQz*mnzwZa|`Z1yn8=)*PSbra=#Mi9?Tb9(aDf>2}!=V zd(C7!jUaZdJ=$&I)LiGQ{`vlNo0&axbFVaSd;CVE=|rjy`d*?X?o*#h3X)L7N=Qj{7zkK0K9^O?PpRC)a7dPjlR^oCi2>EMcm935ig zdj6=OjWSxuYx-hQOM&-5nt5Nr&FR!r38urcmr{`Cmt=!KPcvV2ZX9;ePs&R=vev;> z6Rk97yFU`R_8wcDW^OE!YZZYJEFSpbS$I$~hh-%15i`=FXX>vne7*nZnoMC!fsY25 z>VNx^?4w)aG@pEjB8(yddqRC_6D=Dt>? zJ70ZfJEv}mt5H8CN0%oCce7M<^N`qtBWq^F;B9>cx2F9p5=_Tst5T4{UpomYmB)S8 ztB-W^)qW>L{^L++RbSY9T0gF)QPm17JC|bBYAo3l`=ITcFqo9V+EnZ2Yy9H%-J-?T zJi(M8`)%1R;LS&^?%d~%f*oEWZS!L-YC)ClN`9E+0bRk^qJdg`0{EdULH8Zw0&Vn_ zrrHl%KweFVjkHi--ke$XKn<0MxF^*_ZNa8&iEBA5q(Bd~kyh(t%Wi*QMMoc(qo@8k zMe%v2@dzd`Y^L9uPN7Uk@w+*fZD!&*w$E9+#bF22c;l3qJ8$XVRiG2htoHcqqI>=} zkv~<2^Agm}3x0I(JucAZk-(z^2TW&d{Aj>cpqp;>)hsNY-8DOezI0Jio&``!QW9nA&#wyt2Q(z_sIb zceXvZiu-yr-R&%~kll8;((uCo2xLqKQPeoY_4oxqVaR9tihx&r+)7W;d8RhHFSzMF0#s6yeCz1_KU?g z;UMLJ*bu$VyZW`hyRB-+O!i0_LY0sZJC5y%CzcwQE zCwS{%CA&#+7gw#mP;>Q7^#w>uA%Tvjxw0v32LI$Kc%SbXAX{Bf#XoLK8qjUX_|_G4 zIUq1taKdKclYO3LUP9<2{eX!xxh{DrguD7)<-4p#$~yeahY#GE-Uw1e1=US_QA*Ds z=L}LG>U-4-V#A#fw+>)AC94nmsrDk_2*;$*`(?97gl2Yxsm@27&#Q5|6Z*7FRlbL@ zysbehg!TRWM5@e`;+w@`!8PMXNs@~b>851A2)S>FTB(2908T5y2*i?J}p2ZvARDRB;26+Ym(qS}e>L|)rop&!6LmwQQ3xYR0_v)!!uFm7Rw zL!PB#qTU_-@6xIlV=@l~{(Nid)#1|j%nH|YH=|tY@a%cjF^9Vul^L2)8`ZI2pStY9 z8lEAX-$vP3(w0)jyR+^_{fc%QK{7p?*DPGdB~WLFRL7%3I5e?rbf~};)t4egz56Il zxP?!_A&>MzR-mO;?k1^P#h+O*gQr(AZDt-tC{^g!vi5i9UX$RxqFTLJbnwRDd6y8r zQqwF8o*?v^3mFs7xl{#bW|Z2Vi4HLde_ZMp0a;}K?f_qq$lGny+jd5HOSp_{pbT~VzOoj%950i&mFT*L-&SbLzT z_w{Xs1pvtosWR$m17xi@e-)x|+x+#74V1B>I3=*#eT z=0hC}NQv>3h&_S?xOi%kK@CT^gj`^}UMlwCl7qNcS>QGXDFI)TS0V;>+T~66rB)WW zJ4Fw6EiKwe2j7Cagsd^HKN7e+CTy1{sgYb+a1$&WmN8Xbbnw-WL!e3Nd1@kOs^vAQ zZbrDwEeP;>|FE;1ht>CzYvmWI0~_7!8+%;_LkW8sZ-2#HMxg4K2)?|fo9p{3ISzt$ zR7!Ox`?{A)$U}X-?%12RAf;9p-~bXrEc&&HFF*S^Sry!us;tfJ`zv4K7Th=H)kHQ2 z`RwxMjAcAbhp+OLWDsQv5597g2SFLCcE`4SfL@7WIDVHXgOqM=&R3!vj#eyi;7?ey za=4q;_eS3n%=F=`_FuPEB(^%~21n0DRdE0G#| zZ6kf8RJua{d!Dq1Y3of8_k=~^!5el?E+K(N%H6SBZu0?ehTl2MLcp7?2d4&7vA{s2 zvu1DOZoC#yRyEK z!&|~?(=L>_!B@I2_x=>7U)FBfD1RI4n9lA8A^tJ|9l*)MC8Q7;`bZ$8gs;@g03SFr1fOv8Oh{E+=euLeVZz)QHc>1Pf|A3 zjOa)(-5UYXzH5HkQT9?Hf0n84W_yCE(YgQue8R9T_&HoRE^A3*0uhE5jt%6Y@k~PY z-0j8zS6xcv<`(GL^AC3sMSr$LtDj8pmdtV`f+b+i#@dOcio~Hrq1V&i#7Xuio93AB zK0dIk<>=hNGot8;5LueqWYM0^9gwSvyBy=rD+;3?k&E`+9Z3&x?XPgdrGk~>_yr6E zvrKy*06VdY61_?{+j ze~_W%Hl@VSj>qgW{oQw8B(6J8xK{}|HPupp0y`ztY_#?qk)Irt;N9Os!R_Qv=ao?1 zf>ATwu5ni+ZksbtuhM;)wggjQ4MFTF+TLy3*Dm-A#<=4;dJ+(aOf}1SOwQ4~w((QW zkOvYlhfI%^n;*9l{LmoCtEnoC*<-3+4)K&cFUV{#tr6VXxRt3gsdHL#FsE5n1ar{T z&QI|A`EL%*#X^|frZzj39-F%OfdC69#Cw%0LjmnxBmlU7Lb$h}b|ac_z%g!R0@AD0 zv=L{b#N-v`W4eGg+R*2hyq@;$bsFo)E?mH~|GMCf z{C&um{2nNUT+`<}H8)RBTAz_zChuw2uh>at9S78&K^4bXHbLX>R<<{D}6qM=MD{xoGo za&+*t==lz%;2z2T2h1q`EQ(SHQ8c+)fp@0UHd_1DM2`^8f{x9ZaYf2ui(D7WI-BIT{li2mB5oe zy$E7XL&TN4Np^9kED0iwXw^hQwBOx&bN11hhv^(% zrY8~Jj7|cx!w}7AUXB>kb`*RDCP#-8v2h&mmD)5qh9k@l&3(z*=Uc~-hQ$RnXZO7D zntl=JB^T~RzCiTg3if2J`|asx2ReIxeLb?aM*M|4Fb#y{+9N3q+rrGq-CSWyn1_Ex z(4eCV;U?~KKva(-nB%pB_JlYX1T2V=7l=o>f;#yr(IIY_uRIT!11o6=mWwz;8=McF zQzi&Dz`|Id)&x(3ao9<+ATfpO+l_2aJcpBy)A{_uE5&T0JttNtt~4i^nW6*n%Lg_b zR4`*I9Ce%nub;?-e&);cYF_XWp>%^-SUuMktU)m>kt=L%fP@uu1wEkS2c6i7WN^>+ zg0oNo65oV65J)@|V#p3q+;kBDB8fLi(fUAW$V_h00ooyAJvV+Bu|6gzH!>L+3SALy zvfx6OLQ0Su0b2S5F*0VO8xY8d-rysNHA#eFKwW3P38Jv0UF0NE0%v znGv&r2Nj^v8&Eh8iid`Ce0n>&bBuPJY??+ro{n8LCB^~fYCm_pEuUjH-TMtDeuXsl z+i#WxwAM|`DX|DOu1@7u8H7}D-sGjsYOQhY!xqPo@_V=foR^@T8PJ-G#`6#ixPl*^ zpOnYFRF2`t&uaN*Q5Nlqj2W&l@7cV82S1L_;x(crIz7PLH(S9@QWvmKT2jH90KcrN zdrVY{{1A1-YRy>F*KRmye42I5TPG6h&$=x`6R!ocy&_h8$%;Wcb$Y2k8j0h7gz+e% z0oT=HJro!E8F(0$k%-v<9yEvLgK$uA$!_>S+^-Ec;4)OOi-ZR*HN+kf%DExwA4hS( zT(!+oY=Z`v*hY0U2`9+vlrA>2rdjTwf-0k%@flP=Kj~zA0Y~h5`o?Q6H{%u)9iU=F zZDs?Oi+SC7jjiJw_NElSk+#}eGwJPa@}l_uM!Q%L=hs#86M((x>bm#UZt#1D>&mbt zpWkCZ(+d6v&%`l6+z(8xa6{A~Fze1lduM|iS3m@bfSdyLvDdfIZgXR2f4)T=<3`HR z35^DkGV+ee46_CRK!evWi(AdwS$tv- z09yzDacbxQcZOe}hdq}q#=s7bD8SZAXl4c#OxdYJIGYdoebn(?)LBWz@Hqd8P{U*^ z^4_0#nC|4YKk?A_5qAV~ol@QrAO8`?2AWHzxe?ad#^``-saS#PWKxrWNz4z+Asw#I z;EVQf?$o>C6ptvb0$S%GHH+(W;`mSyS0OUWp2Jn3Qr%fMfC6baomw2w`Ud_=eep7w zl7u;bcBsBxti-tRWoc@P{FNy45PO8Yj-l0WxI_0QQekLC*$m;qw3swWMlJq%2ItR{ zp}LxMp+1}9z9lO1vEP$1W}Ks2nBX7GC9xNU$R_ceU7O`aU?KuLbFTG)Ajg45D3mae zHtYlZQQbOXW@YYvH6FcZbIO=_AfbFaD*(onn#9~~3Ns<&H=#B%s9F(G0{rS^Dm!X#VRYh?U5jmCQHPl zl{Qx!n{9;?WinycMkoy%LfUX`FeRGPf1jB z#CH;mA2?fd$0C)uv$Xay7NI;PMxW%qV+e4&W!0uM77K;DiC(RpgRBc&iA)(Rw4MVG zrZ7x0`x(F8ve}g+cA<{H#ybtV-EVkf^jMNne_~vGCWvT>=p z=5mUDGvWcmnvS(JT@;i>gNA&V&i#uBpTO;o`_N^47p8*>2du zALLyv5~kUj`Kp-2E%4+zJGKj$P;SAKx*he((S+Z_LRbe`LvFQEDJ_18SB{6@ud_pK zr==4U`QR!{p<0w~H*D_@@|TuW^K4B_#fL(&&8vIAQu$1znLY+czI)I z+Nzq=5d4_TR@C-|YxF5xhd*lzvXuNKkQMgG$h2lsDgkp>%eC>E_rA%FXNR7c@G{-Y zQlmSBOiq_!?p78H=^)>bF9H~|K5vzo{NLKvilZ^@R7G-EOGh{LqRo2n%7jrvTBM#F=l_7hz;L{eT&aWQ?8Y1viEmtEK@9@duBH%=Xsjwo!gW1RQsWpaq zr~)Tt4s+)=w67ik9BCh*@tn7Vv066)%Tu!3u*=-V&>W&^u_-lhs|+eQJ>f z{;enDB}{krS=ALW4z9caOrXBVVuIXxkF z07CJ6=qH<(iN*0I%EK7*@3R1=GmQdF+ePSa|BQ}w6lRx;@y2ad}%u-%L^UgaBuuRd? zw#hqS>+JC zRVx%T32KE;m*6Y!n^|^@oCv6R#5JIG0rMDG7y^fai)@j+_=>M;y+8xX?rAmSt z>(do^hQSF`m>+?hv11EV2;(?i<XZ#n2dCh< zpqs5a-mY}`xML!E>iwpYQGLBnSKzCuTUmCIu!u=+8$gvJJa@u=);(|Fu`#Qhx;5kZ zO0ZJ46$G@dgXP+&omrsm0QSTw8{S6P4zphys9*VlSL2tR9v}})3hK(YhFjLsm{YBi zAxuAGzUA~D^hluf8y8o<wi9Yo^!@qY$~VFLvJw#*!1Cd z>jIHIuC?+5Pc{9gXNTo6Z>iQgEAQwU&uBp}@m67=N3bN!*o5c-1@-Jyf8N0Cb*Z(@ z$~(5k9l$C_MLu0PJ?Fi5f#1*tl}ZYt^2229aJvQ6p&C3nfI-D0HanHHSDx!OIN`5!fwvQ?=J zcl&J6r`yg*OH$R=LGZ@onE@Nk@|r0!-8!w!lM1t%LHl%PrM0p7xA*%LnWpXWn(6K4 z3|yrKHxMz6ft(DRSfROTbR>n+vp~mV+_rF{^9^4b7=65g;ncVaS~+qSRWk{le1Aj3;5}ca3+=8-JmD31H|@x`FcYB*{lWVz42vw|wp)GHRP&_$8RKj% zjI+HgJ^9IX;+n{^+~>eamJ3^ui=7KB&$V(m|KvQAW3IX z>^Ke-E8x!KI3Pe6N*E_j1U)C#mXnTug%kEcZ|(3*r-^@v7?^VNMH|O4#bnZPyU8UW z`T6wp0oy?Hv2y|F9T2y1D}BX}ywqG2VqO^mo%tlW;A%sTXlQke0Y8eTDKLAYibF~=aPHdjj+w#SwhP#AICm&Q8P_{dy*2S~=a> z)&VUcMZDa#we~$#F_Jf8dr?*9YTm(d*3>?b-K~(B|5WFHRZV7SE61_e`peVQV?KvA z|1Ld1>^gy$r}Vla^>;Ox@7NNf{t6eZ4j>+9ogDzuiu&)gj(M^YbaJ|Cwb0-8Zlk~X z-$CCNy$Mhq^y@Z`d{603$T82t@>Y(2fK238wjej#-z2gcCRXNxcbB;knm76)2YQyO zpuuSz0|G7H?EVXX|3}2{I zyc!xF04;#Tgx;20k-FL>6yQ}zO9aM0fa~86JY2gs>z#$%!4%dur3@E-^;YB<*fw%q zQcWOguG*u$=Bsz-w5k69Kl&SNYj%%xsMq!$*7FX|huD0iW&Ih)ux2p320XNvxKY(K zI?uoU^RHR|8PNdz=U;QAr~`v5jFB$>dU^gE;m_e-lahjj;{!5CAmj_rk3$;W^kPp%;kTR513NcQ zyYAd2Fmi4t9280)I=nJmN{m)X$4{MV%-(S$Km?DMEp=oYt(MlDu2x&UzM$V|A87T| zN;pse^Z3R~mG=y@D4`+wOD~mTqFqh+df!Fy_o-_~M+vHnCAKR5=xyi7b4=^De&?`SgKl1QK7H@ zKj_+ZYT#=How4vc7IHmyr-0jhFBdg_^pb!X>59bo8oPwW{Nq1*!*!yg_^E$*8iB=O zB24%)eR)5oz19G>gk*ZQ40#9q15ORFYLx|IGL}pkzTU2FGAI7HFE|OZwtG?zvd+Sg=D>t zmnT`N>qUM#3D9uuEXTdsj*U|pof>_lgfqfX+x*T+W1GjzF4;4a{=su|t6kXUc21fR zJXTith?)8io|9WmZK4C77&T$!1?m?9d!H;{>Xso;(HG2-Ie9CjC*0=9lDuV-%}H}) zgYXLNAwQleaKA|l7)(&gT%HuxqLa0R&FfeGUnRVfa@)msjBSW z0FMXhO-;u!^og=dz_j7n3+BRDk#o*bOi!3LL*yPpZ7ZG!M(|%mAbC2}L~ybQ{A!09 z>>!17%h*nsgOoKZh=UGIiPghs8;-M$d5C!ga9Nt?z3)S;#ym4;(!#6f} zyT6tSUnw45BS&%rJBj@t(C`!TmW=jXoxMiX>2ET4@S=(v*sG<08p>B#TnJKOWlojxz^f&U;~Y%Iu5{*bsR z@4l*A0^~X)`~124M)r1dn;rZT8(|-TslLNEO;lctjgpE_01G+;Vg(!xU1VNvc;WsN zEqNES)?X@jZaY=N|1T&oZUo5|bK8hVNQLi$PIMB2e?L7p%BK&Xct#kaxPDEQY4JTT z%eOYAt7l)S^FI@i2=)WUvGi;5)J%|&Yy^#@S1!fSjJK?_>LCWL4i)*M2R2Uq|$iE zkObz*-JdRGh%iU_Qk>c^(HK%1^Q`@j7vW98x0@h=#_)gSkW(*#-e`dZNaDjlf%Fcr zyMjRJR=fnO#*H)PO!79|&QZ7|=E<8*Q+F-$Un~IPkM-P?LP0tON9JzZ46k4{wkQ z{qmxQM0qQtkR?otKCz49(cl-&=CE6X{P&iPerA1B@=;}iqb_(IK3hENC34r|+@AOf z)bM^Nv%GzN>Yp_v6Rcd{?ytRa|G8HZ#c$rd!}`q?fV8gX0-3`?nGY=%1#aX;O}VnF zXz1K{S*ByebBA`a3G?O=RQU$eOzW|uf}Mw81W!i+%kOYh7Mt!q62@{Wq0wg$${>Fw7J4%#b zwQ@Opuy|Ithj3OJbu*Fmxh+t*CH_?3cRp-F3}!i|9DbFj+1aoLI~ zOWud}FO$tH^`y4rx!Q&ms6Znu3di5O(Lm?+;r(|_XB(}*Eq7MT7e_e{(d{N*O?p{YZ{jNEhY2e^o^vrj2eB3N zpy$&b4(5oN?6PNkFE)6j8*7E7x8Q97iGBiMTd z$9QHW<;^&qTt^^Q;YRw=hdZ)4q&0aJO)oSzm+qe7~m_w_@_l$#x%WU?HxVQwE^VX<*Vtmg%?{&@uJViz?GG z%&JVW%3Ux8jZ4!O%;YYEROdF1j$s82ooS2TJOev(_OAE0Ajg8ze?z;VbdMa;@#(l4 zwgnbDaRJJ)tvlrTHjba+(XO$?*tKZDy(Y#2I6HPNiO3l)dXs7~Nj)}e7#b$}Jn!i` z)1=EEY!)$GFUa6+- ztiuyb{`rg8<w8K7u>lf^1IkwiqXFd^luPd&FKvNV^17I zKP(OxeeU`6si4nOK@Y8$xlvuD7eme=+ST1>39)%k4`l!kinTry_{77bxPN@wA!d!; zQr`j3RNd`l@#l&y!+5tURj&+T#k6w!g-0S*i&~tz$)t?8d6>a{zTD2`gfvh9| zlzl9yz@s+lg9}Fk)Xu$uvkiLmACUcn9o7FMrfU3Jg^IwK>F}VIVCORqPYsokwQh~C zx16APX6v;sBC|JYG}XYPpe~KCA3pvYSU)Yi&%YsbA3(|@%&Gp|c{MGW~?W$^w3gMBJuv}VlbSt+_NW&YZ%m;S>49`|Do#H=LCLit}%vbuy)2Epf+!v zk(gIHJ6bxw?xH?A6jZ>-*}6lzR>N5|zuumMyQ6}R^Qz~Z_YiOX!~OK#0{!L}M}DI0 z)*YSKo)S27_6zFi@BYO|=Rn7O&g<)TP^TCM6}Xvc<&5aP*}5b9zhnQ-f>E6ZkbXvj zaM7@e4Ca+^#ju&o{43xpSSEeZ44E)xemb#LHOLd&M>k1w;i-!xkyFJPUf$AnG3?v|S+~8s-TXDT1?sUT^ z7`X9vwheA)gKUKQc(@Cj*rQsdtv0PRZ;*@Ci?Lm@C<20Z=iq3>+gQWt$-&WfY;nkB z!3H^$^O04dOJW4(kua0UzUx5**8O3HDWz6VGb`IJ zbghprn>T8H@AIl*XhY&s{gSc9R@`SYl%qIgfn>Ueg1lRtKz?joS$2bY1qH*}YqF>I zkV6xDMh*H`jME!Pcqq{kXMIIS*&Xk982BhWqf64VK3G*F7#g0z^rbJ#`2oAMyPqBH zO6;N*xxi8xW~GB`q_y-#}$>-a%5_XQ;#`aSWd=^z|K2e zfL&TX_uEm90aShYCZH;Qc7U3_)mmqI%Y^<3IhKi<0#X6PZ8al(QMeZsKTmR)py0&2 zEJzxq7#ookLl$CV7&XUatoUD#c(^A(b~8dgC+lYotC1tv_Q(ROdrE_Af?IOCzprYb zDcqZpU$w)%ImRS`i4IP^;aPts?g7)puIuw($T`bq9MdVoMT7foj>!x;B7`UV+HZvt z+S3_(U}N;S3j7l+@|mw-h9deI#(j9wlgTT>tLYwCbdM=c6j z{TfET`{2=0N7@0Qs?rehaa-<-4U{m*rLt)zYfGY?ooZL;9wU9qK=6mMtGC+FYi$+g zf&=2wwhv`(S2~Jq80%xk8q2USGB?e5Fql<-r6-tmrE6_~6laf5d86z4d+!7IU*T~5 zYEs|-A=lAz#QPs>4e%*I-7AoT>noBZ^iMOkRKkpGvZ>d^$)()?*jBlWTx7t`zA9oXR z=;gWhTQOHovHfjy{u~pt{_9B|d3$Y>zXnemsjfbM9sl~wYr8uq@0cjOKK1%}yoBoO z<9A>DeevS`?=7wq*?Ur!!%b^63}gwW(xd8_yEu0jQa4p;-Qs3C@!6JCo+}hU#?Vq4 zJ-_2(5z(vOkR#XF{yxrN#{60wT5Rto-pfQ)^;aB%YT%1@5n1mdnm(dW$;Smed@C2&ps(p(yqzCFUCo7+vEGm+^+vNz?*cQ)PixkkZ{CIQFLtann zymf}exjoZ@n+fJ|jGvh^{psnP)@xj^?a5~HwWhe{rvcVqZzkxEo{)FGTS%#NX$}dn z)`*ucdwj8{{t1`aKxU1Ak-o)Hq+*XUxOrIioN+2c*1>5rGs!WNeZernqkCN~X|ckU z!YJdL?JB(Sq$jmUUSsH5#WOBNbU7eG?e9!ES--c+#}HpdD!LG>Psk^iJeid=I*YS6 z(&t@zhrV+V{xkrRT~sG|&Jlej{)?xewIYnTe?q>#gptCBR%HD?T`zU6HYnX1$Ykb* z_O?(9Nc}VZhIYDqtM6IQGDZjA><#S-GSp%G7azKq8uum9(VPQgc-CErDP$JvaBPWh zvYzphZ}Nt={ET6OgHTuKD%9b|5?@~}k@FHiGNc}3nBXd;6+X=1aD2MNH}ROk>tM39 z`)iB#J-=tku!Z(Lvu7y-ZI}?CVFPQ2^KFGhc-F%C#zP`NfnfQC-9uVh|4EzlCdReG=Gm0l-6=Ef*Q1SB<0Us8d|l=XGHYc{Iw&{ak@rf- zXp?Dfue^B{8EB->wd7otR9Tg@)v~akIC_wH(xJdB!QrddjN#zcHKViWijxjb-Zaej z-Ua)qVC^a2ge_qsD-R(>^tI+~p6;E4gkLWFg+XRqjuW*v&w3h;k^b<|PCD3$R)38x z*o-a6%#X!2y9UfF##@Aauf)Fr4hNV>A4RIHIyfrRyk`I;Vhy&r*t5ASab-h!%=hfV zNu#qM*^@j|{{dJrvuOA8HdhE7&8OwW2UB(6NOi^_b`GXf$- zO2iP0B$CqQYqVIu_p&ECNZTg?gx2zyc`=JhW(el0|r8X)9I4dZeQtHm}VA{E^tRkD(h87c+Dur_Q+YuGgks8U`S zX^xa%w|;<>uawosZOV)R539v!aACf9i4IDVJcQV>A z@3x?>Q}H%Iv|9nRTjOxBKsR`BzF{gZJKQF-BHS>r+?ts2Wxu)9uMr-pP~M^>@0 zewPD1RZFsm2|*%BIjbS0x7LPnl_gxS#o!kpD9s1RC0e)@L4lD*^(KOvt4(I+MKEb$vLM$p%hOGsRpOMqtW%>=^W zQ;oKc0HMM;6`&eM0MC)hbx^RJF!CWdD^0b_Ck`l8OC%RlWE0>Czj<9G`0E!HB78}a zDBR{<3Q_}Qzp zU5|Om{l1x=rt0WhhYg{hhksf3P=g`9yGmDH7e)pDQsglMI=(rUyY$&|37HH)lRP{5 zW>k&lq#Qk#GG|}N*ChBRI@*Ba=#V6ui%ozqa%5PZb{|k|!!zI4>9v382$X=~n`QKj z&{blH2>GuJd-<>ELicq{!6v34(_&qi8uwuZ-+(?CmT(Dj1>y>iA{Z`+8E$JWd{SjF z+Pg*{A6MC6X>ml8X`#K&YNV)O^AS-HA(~Ea2netq z@Bf9@n+@b|k@0H26JV`IAw42m!uYS6O88gC0?e$=NAH?O1Mf?1F7=9bD$x>u6o-PX zP(|Pud<5r2)}FW2iq7}Zih%-*s$X?!@5`E}NWQ{wn}?EF6m4rP=WNVAl4toJ+d)rh zh&DE#MStKvtntb^Rd@Lc?X&W3^Kf?VM{4moTWd=1+;aIXF_dfU>QzP@@9LGd;WOm5 z`hf>tx#xdyG+k4fA$pE*JQ#ei-K?-oJ}jF1h~=T;c=>6*2Ha_TID8gH#I`KHKjN!9 z_e?#h_i9av>E_iM*Hy8VlwAK!T@=Pxd}p6s8tzfS`@`MZ7=)#JjDTU5AZ#6ISu!y4 z3PTc=W+p7MZ$Nf>@G{?$z4Ra2#xLFbYg$_KHX5~$ejHA}h2p+6-CsJM6-Hgo?D-6T z$E|Qc9MnoQF=O#||JWQxUe*3wc7RcNWNlPfd1yJ#9r>o&fm~X)kRtf0@@bc*R#_?A z&04m(Bd=oiT`OEmw5w6e#+=+(r9L$%&8<#qtbNd=%)00a?&^e_*{8=Xx^=UrpC>9G zRs6nN_ODxK5VXGw|2s@9Cig%53OMxXkZzCvSJZ!}S`)U1AKySCg3DAe%H@?2=;~$y zu79Jy;c}T2AVirI{qdhmz&D#8$X3Rcme3rTnyB^l82PpF`?tJ#buJ7f*NEa%y?8aAeuzQZH2u_axThZq>E{2e}dA z?mgn+J+dkL>HT0>)jPsolR0XhFjmxlUrq)&pQW*cG>ca zZXCt5+L9+Yu?fHjX#;Bax9`*A@OyQ$TAwFG9#s(Ey4A6ylJ8!z{&OoGT0c`oe12$N zA8S&kdC>*-p9s}Q5i)fwW96K6Ea5f`nR1bc@anY#`~YkUF$Qo>*HV@3Pt-h?%kVLsdt? z2nny0!7f+)*F8M_(VSOSY@oXDJcd@KCF z{1ZdHNNu=LTytli?v^9NZJiPCAnnfkdbd)zJ5aH>#(>M%f`m!fr3X7U0_&@DStI4= z67XIZtX1L`Y#qna3O03(1}&D#5q>EgQs?#{AzUnQ?(Q+=HxA8~+VW3zxL@zO=m!r- zXdh-uT)|DB0H)V-zdo(GP|5EY_QF~ez|5^nnYVjHd#sjI3fy~SVM5&jaFdJ0>Pb=m zFsUZ>$@FS^Szf%No;2!o6nLTAsYN1&R1V~(lY>66FiHpl<|glwaD|yTm(hdKAV?5b zm$1JPs!qdI2ajKuxRNeUTGN)F^BvqG8(FE49-@*fWve&YM@62RSB*D5#b z-*%(9{d&CCvdCu9XdqHz`)zoQul}!R7X0br7}B%RKyhH#(~DQWI7VfDmnxuu#N#DZ zJ7ymPyJPd!Aw9-?BSn#o=}N-M97r7;A^`v(w8r&t$!BUw@4#2$qhy@blEl2ZyXDq$ zk{nY}ZyfS}TM50WWa2W1vM};3Qr6EZjSAS@WJ~^J=8=D(RXNCcgJ=Q!*$0ICUU~b7;zn%QRrsmFTVAZ z0zRB>@l2$s+f-h`rhyS-{_9PBPh&vZNat}Fha!M|%30E{~Ed zQ2`oI8@>aUKmg|i#+HIVd8&ypmJ~0uWPvmU5W`9Bs4f775zU;Phi{B42vbGZ?$Dec zjD2DJ0Bt0@XC~3$wFUInZ0xkHnxX&)0RTtD``4k%*#JIpWDny8fLp}iA_@R>hYg9t zd?rf5a9`h1{^*V3B|dVHMV6v+G!TU_RIA_`a7IT>iXfSNcWUU&_YReT{@mk|_JCCd zRwKy9XD6W!zYg~2o|kk{OX>tG5NzW!lTgRH<@dV*@eXwW@fuTs>isF2lcvgKG#n72 zz4EGjkpGOrhn73?ka@tM2;COw?g)@N*9Fb9W+)CTF3or+IM`Imo~sRkMDZav3o|ow zfVA$I>B!4BWVRo`zc(`QH%8`hnD9IDcjpT;8_>1%{-}1vcz0C%ulaC#j{H_II#6gV z#Eh#e#BdU^s$tsz&m?XZP#|*g?rVWUOTY(p+a}cVZAL90Q3ntKa)p=jCGx_OflRne^_GagZHXAxNTG zM5wz$Q5*6witpf-k^baZ&=6nchjitC;>D6wzsWwC9f>@@M0en-?Fk`f6!4LFS-&?T zat|0uOv1=&4%u`58s92ob>t_ibma5A@A~2sd`0=Y_vJwWc2SDQd=sc>28Y8OiMLAx zS)L*&fUHJZjh;5LQirP~orgW0im>Tv;7HzZe-xlOv;Rth85+V>OKk_hG6kMdOCOGc zUTcO{+)M}@3~e6>5MrW*acPBD0Z29kFnmH00NCf}Zj<#(UZP(G)%ql355tpD8gri6 zm`&p#8Z>|gjlxrDrBF(C67{8|5d`#1Z9CGT(p_}Sm!TvUhG~0%q}fOGES?9HCJ0D9 z9~+_}BwUBz1lmt2Qz5-12hbQWNXtL*H%(f+Owvd)f?SC|f5l7_#3Xky{&?F$fY3`d ziTLB~vw$r^4d5!A>jpr$fd8aApsF3zyRN6almHDy@O6(60aShp=^Ely+b&1s_{Fzi zsgI<0kCcM1G-wcY0Q(x4X%3j(3D=rdcKMUmfaa?aQhX_CS5)XAm;+GneN2)=rl^82 zTo3<8pXL28aWjeyh|puN3U*lE#hu0(N$ zoG{gJmp>f_;Cm^$`pIBGqrN*PQE(R2wNn41e^OLeMUX-(FNBskY8BQJYPK5WRhllc zgf?R{-8C*zNE|qo+Jeo@l%o$=extKvTkF|EtC2nTVebyi3<^)p`&PkMkFKguVfMAW(b8F~D}HgtzN@sq zQ+e9wNRYVoiEYS>4O_ifoFxYKSU>7@NmHd}y%kkH8dpuBkFPCS3;CPATc+1_*0W`B z-+wG~#`$*D5IgF%1~8aC@L=-N-S=qozXg#m#2?C}CWqzJtM0Y; zh~!p~LQsiWBqb+1)wZfx&VH=5hw61pd>OE;yUo$}G&jK^FUwEL{y%=Ex#`^#9T(G> zI&NEOqAtDPrCZlVZ-^+W4-4+D8V8Y=Y%qD5Dad_RtkkZ3sDkeau@!LTb_b9Xzx-VOaO+ z+6ZsWh1t^&)D3Buq(0;YGg8w=3_gwxzp=KT8KG6)Zk{6Kuu2MthS+{IUgH0>Yc(E% z*c#h`&Xj!6tTyawalyO}9-^PaXG0_xl&C+#5p-P|-*xI2;T*&x1j`V#s_&JlZmbI> zVYKf3@vhI*;I<%W#d4fqctlvTQQiAV>)>$6;@2mA7TsE~SmjAww*~W|&EPi^1~Nhy z2pEVH&S_;s0}k_d!7Z0OLQwamV#W=W15RU+?N;hpQ!*dnDLHViYeGM4^DNbyumx|~ zA>)c42Je@-i>J9V3qCRF%>WhJw-cl_WWfAKx>xd6^qb|tS>dgDP7?rq?UAoBpH>f^Y#2QkE+FzxX0!=XGk@A0RO)YUDM zmM34Jv9qS199qUJUGf@?ai51yiqVR__fl%T(bwjKbb1xtAnmiquA@6DN~RvGM$TDS zu3Q(jvLxjN`Fqw)NYdN}Vp@0WoW)^pa32G)v(0AnD(+aD5q%wzVvO~tdXJdmq3T2o z`_>}qq&iu+Qv~W>9gA^UNVWG``|MyJp%I=rAo56JCqFrS)U=GJCvRAV&A(-U+aMDG zZOEru6BEK^5U-{j4c775sH-xN!Qo&1wGj_Tl3NeTEh)(telQuH!XhE$Ty%ZKs{oX0 zCrrJV!^idDs-*Sa>$eM3LR5|CR0WfDUi;lPo4xs)4Uo|DRjjRr_$Ck{cVHasI#<{VKytbvn;M6o|NotS#ArjFJ$uc&nSs6 z={Z#mAM!EPyGC$)%)olLBae44H*A$Y(r@qI&5Q4A;75PWJj$xj;ZBi_4?k!{Ma)j{ zM_wTHH*2IAAh@#IC9Xq^rhRsH7aOV<8)ko>Gox>H#oV`j_2snk2(Ksg-tO|8!YX|5 zsx+IZA2r{PAXw%lEpEHpzB)tTK-=V8gZmITX9z>);CVf6W6DpxH_ikOsbW8ng@yi# z=$?-JJZbk^_ln`|G5D)u4C{PJ#K?p=mm#IW4Yt$NuBNeGTlFb3Aawm)6(SR!H!fvq zn2puZv^Bzxm|2Fkb#kZR)|~e99kpP=hO#Lhxg!_X9sB>`ZRpFed5ri#$W@d4$bo3n zSCD#k5uydXfl@uBDfGRy-P8jI8{UIw87uRXA49M@;4@h8ysa|7zbynyRf*ldY&o`{ zv#Ez^ko{3Y(zY4E}7o;;?9adwbHt zz*o+_qNRP*6Vc^^545XS_8S_ko*3zq!^F+>Vbj7tRBX-UeTl)WlN{xlbM?yWuJva6 z>~4aD@}p)4!ne3Z?}yx==0}9(!dn=~gCZw=uimkpI^FwKU&Lrr!1pIDz3XEb&oC#K zd-&O=8UkactcK8FYh*$COmcTl18+AnIY+iE-<;XG1!r<*#L+lXhuFl0GOa?LpROVG z)gPh)BeEAJek7a2M|C1$WVAsbxGZ(6`D5J1&bL@W-3-rZbILf|A}yWv)j`1}bR-;F znmN}dzTWysweRgqfz6p@&5}4+!vyz({e){UkAk(&4W)6gqWKSt_`d><_HO2Jbk^=y zBTRiLltD$FPvOru*gT(Ux4d2J=BPFG4sS4fNa?x7QcADtm8=T>x|K!Hh1=A;=r0e~ zI+-@+q8&+x!2_9PThaZeD9WdR+oC@pw0@hk7o|lolgk166|d313VBb$IfYFAUEJi0X#}sJWTPIIkV|kX~gNbYpWUY z&-9~KGhgh!*%TSEB6XPe1YUSrk@9g#V9GSVsq%$<(x%*qRcvPn@<8ZmCEAYmj}7{R z=Dm`hCuiU%vr#Vsxs#~oW*@wt2Xa%60Ur2okD$5U2g4U(t7?1;C#U)!u31@X<@sx} z1rFEU7+0P8^$=ynh+3s^Y-BB|Uq_OX+Wb;l+D`?x+edgQbRWTArmtM#&=mcl)1H?z z=Wly2a%peQsaNb4FD5%@IrU7l_m``E&uF*l_DW^{NCl-Cg)LpVr2@L9qDq~Ai#W>8 zb-L4%;G#y5YqO-zEq8e#eW4V)9NiRP?ctut8~Rp?9rg zkbz%p9(l`0-+=Jr(}yb9q@)g{8%tXI$KOU-1c_ALu=FBd70+r_{+OY8#SAid84U#|MO?)v%?3bO50Yu4=0>{`MGyth4MV@pxJO58kwRX5IU_KZgYs!rf0odQ_&s%j(J!=2qS@fx{c%+SJ78)JcY0)}6}p8sK6 zc@&NQD*e&hix^GyaJ`53>C5mkBE5yu#+|*afL`-x#;&P_LC!~VSyvq;W4;VpkIhgf z7Fg#LNl_rAAkMwJhG{xOc%CoveKBb5g2sk3z^;OV-`9QYbt)Q`0a)0!r76QXU5Zw?QbJ5#|V>v?Y9P^H|z48tDg9e3d6lw7?!b2xgi-Cr(;$vs#JQ>lxPaCMnv zo~m-YCo1RsQqV{5o_EL)GwDa17_DAeeO~fGmk_yg7u>{4jnze_0aJ;Xso%}aq zcPxH}@9-~r@60T|S!lhn&!Ne~mBB`ulomrnL#kg<7DCnaN~=J-#P=I0aj$Ei_A^@2 zAJGf;bU)?#nd+4t!AepegXdHxB9fE$d)L>(od{f!N_&=vgPv6t*T7Aa$Lm(aMJe~M zk$ZH`R$Pv3bjCa(L}h`Rf}1{4O7o?LB{CucEJr+{QW**Ux6GcV=k2@k1hk-QQij;v z`fOL`IJ2=0*UD0*aUztXB`Gt5_yab|WPMsnKj#bR&(;3>X!r~0+L!+OMOr7&r4JbW zzl5xt#KcvbZ1`+>()%8`$((@>yiM^-iA!d&ZZ!0&!M5gaM&?oO4)ym&=A)RvQ6P@% zv;r|hQzJS*#>_}H_Imkef}p6;HS*D9^_AAk!dlOmdUR)FQu%$DZGz-#O6hHbD*@K~tukq{+n$A6vLiTZ#!1&)O-U7jfG zcYRrmQeOW#c*s8Fdz2;Um(q+^8E-Ks;>5yu_t|!29xGif3HBv;uI$V7CrOKAiqYY0 zig;%mRkE^miApM7hrtFlC`kmux(Q2d)%u4TYuDXB27jl1Tf>r_?jh9+Ja)^BH|`@`2_IEvY)r{g zW#Zl9uQ0Hn#|KUm;~Tp8qkzO}_8l*_`LY9*iNLC?32!K9A`H)FAxtk1CnD8M!_>5{lH8){hJCHwbx2V6o*Hlfoy2zRu42lCd>DsOgA* z&tp9vmspM9;j;979OsW@&DJo#)pmifAQ10$xNu;%tEgggbHAiUesjMCqM~{G;C7xs z&DyT9TQ979L1|xl3S_QDY!EflLYeyAXPfBS#O=M$%IgwXnqDJ}lVmC%8e_F|&5RjV zAA*$*(8)YymHRp2k5Na;5S=3zgqMjHhQQA|KBBT9Ke1JYij*#_3YAWA#WoIlBP30X zondoDtF~Jat938CC>>EsD~eiU88I&4m%%h*{^zi%B}`>;uqLD2Eo_PtTK+kB{t%_n zw&|n|TL{d{1$>n+_x39>>Od|b~Ap7h5NyJ znOWrLx7!Dc4bd0U85_NSpN3E~+_(%vs+Q1P_tzQV2;Ie3Bu$6l#aI5Xn*7Je{nE9e zkL zU}G+|+Exu3BJ`;K-LEmkYvhxT=~X^9->w&L@^CWay)uf(OpduX{UKU@;xB6t$w z^pTmpM|_+XS9Uy-%!)C5Vq#yweDI_`2#|_V_(w`-SU04`$B-of3PG7cphW ze;VJ}U?2H_ZCYIXb9+Gv}|g_Ro@RLj#;~ z2a#yRd*Uw)t+{|mG5jRFZ!rY{(QrA$^GvyB*XH-Xt!*+(UOPJ1KT&#tvpkkQM z&{~@7@+Z`0!@bBAQa=6=xz~(Wg21QRh$f=a=*ftk)~zN#I)I-1pa`6AQG4>>%{N?Gd5 z>e^T~^KS3u1x46b179uh(NqP9O%ZagW|;dM{b%ul7w%0_(G2X}TCU!=qktbw$xVy+ z)C_2TM5dX@d_i(}i&H4JMLcF7y#d-D-u8XIPZ%4(3VMH$wWKug*9Xh(+;8wSuMZe- zyM-5=nqq5~DujEbTtjcyOq)y(h6sLCWM>J2jebnM?igq%?iilWk7iQmXZ>r){Ni-q zwAj-g_D+MIi?uLYRhT^7Tr`- zm?srEJ8S`(RmHyvG6>IB=EJJ3#Rekwk_3MRZJ)v{rM1K~`YOFJwDIqGNb>K>HyajQ z%qBfMKY14;vZ(xowj6om2b-vHe-?Dk(rW>Ki}A%h7q&S&hLl3J8X_ePiQTnAQzD2@ zkEHDBdI(`zbkEo9d@3|}_pf;p#T1ThAX(K9vN06acX=Zhd29vu3o7>J+sj_aK$j!T zR&LbpHKFE5fvNqhE0AsG1oq~Y*3j*F;x!Y{QU*moXRX+j1KaHe{Y3Ds5;2V4AKPYp zyUg^W-P26FDtuXQW`xmSR5`q#kIZYlN!%hsqqef3YZp`&KfMJtE#01}-^=Uv+P^PG zTQp*Ib{&&sbwHST|ZJi~9dKGoxJGtD-CW$fd}GTDdXRZ%jT&s}Uz{nfBLWNom{lXsxi} zg|uz$v2Jl_(a~LXNYQ@JCl@-0%@Zkf7@q!E+3Kh(xEcS=9(=WJxOAe~dy?v&T5>lB zA6Rv%fu651qlK7ids3XOJl?XyvQlNa&Qc@}#ILgSe(%}EQkBA{DQZ(i_0l}xErLg^ zGS4?m773=UwFU|XRI$Ry7NP8#bn*Ezt9xnHL2ISR34e0dPsOro2TnhU#?SDuk@Rn2C}CSx%&FB`5#uB9|wrNx;j zf{98`(G*j4r>@i)^+4OLmvX{u7ej2f(&RXZkPz9efq&D35#}wd9GD2nOoE86B0;S9 zHxQl$R;skLDBxJA(npi$RC+;YfW2Y0w}Pwnw_XA+xmy1y2(@|bYwS0|`HYbMw>bi;#rNC2X4tC{ADDxFz0PC_myi~fzdQJn#x==AG~Ul^&+bcZ<1TjejwYX1|4wx< zc%c4=LWeY73;%-1Pq~PEXWzBS3|8cDhz*hb&OXXK*qJ5jdq-bq3wX1DhN%uR`e-?o zHHf^5tH|I`sO{iT7K^|C0;|9OYUf-o>D!zY;){a?ggxNYUGi=Y2+!}!G@1AOB98HAY?=?se3NH-rftyjXt1}S+dujc}bCDb*q(k zb$sxpsyaSewT054ly#JeP!#qLT16gZlez)-?I?Rih5osiU{{eDDu;I=n;W`72dgYV zlSQGn0T7WmB*^QNaDf9Pi6KE0vB~pP}QZ;kr}h8GeRrf!zmZ z#>J+HADW7z)>bIs>r19C-G zOWYq!aFZH=Tg!O&&oF%0rNb{bYK<9Rt9hdQ)#|7$iHbM+_VW?yZC*7i4f(#4tFf{# zM5bE3-fOO1Y?Gbj-YSPt&V5ZeIIS*@I<)y;Y<&kmpo!D#!kQk4o7+dk-RB0Lez z`I)5oF7)c)r(?vJC7YKIM&xPzk5YA7;<5>M@=w?+l+T+UOX%gB`KA!;e(4N_c6ied3s;i7Vd4`v2I!bUT^eT zFX=*vL%pkAjQHM_hAkpxs{3zoE?Ki=NBP@-WLkOe(*AT_-(XaMtIr-dqA_~RK%w+0 z_f}ciN=k(H(cV93G!m-COHORyL`<4kzyikd{#Z!d7DwW9SAEXYgpdXCr-Ui-plxNJ zw{iMO z^3CVx`YOh+l)Gbh(M~#djhtkwj^vqDDXEEmOWtpO@pW)IG3{r1)zV#@ldcmvex)wI zc#P7;c%Cd{>qW;+NC?fj9~@dK!+V9J5(Fz=mk-fab@U8jc_f-h{S$jJhEjGMd!A$A z@VfH#d&0G*rP)XoNG4TUF$3b*a}}x!FTqG@tH}t=DYSMw-%Izk;hI_Ac3{aa-B42**IyCM}mg3YP=Zx zwt>RJ%`U7HtjZ|?emcl+`X+BcsPpdwVw8jRHwpEAUuxe<6DaRyKRUYTOk4A832{}k z?^g2(BFp>hZ&5$%Pg{3i_?r868+5@hW}1alKQAqt-RqZF-tQGg{Vd>j+1IZpJmKD6 z?TS%d%xpl4e^bv$eaTfvEuBw82Fk7X96Bp-h1@JqBS?hSf-MbKiTjrB~$)-{z3H!XFl*h`06zf{#Zn6+N6bw=Xp zQ?bxb`#(|wq;j`n&Wzxg@b6JN$>K3WJ!_xq&9(LrF!K(MDiZPR{g1a{&s$%xz*Tw} z$(2rsq;iSHCwWf|7gIiCP}uCxavd(&o>IJNo9=0=@~E8dec~vTQ%d=bzp594_|?gU zud_Ozjyeaq<<%9cxKAvc*D7!Gt9SPbUk>aXX#5-&Aj|J%QTtw~=QSA<1j7#0amq#J zbE@!qb#~5)%(phoE7IFLF_Pr4LYZ+{x_7{^_~RB`QI509U6(+1Wyi3i>}9Oq6=#HS)(!I1sdS&iXn??M1)2m-@EJSB` z&%ODg=tKCjp6+WkO{QlpzI#I3!VgcDD{;12-s>oAia>p0SC*`Z&SHJC1Yt`9QN_1- zpGJq|xubV4i-z{AiQX!$Q_4sAiCw!hcQ(AqFCV{oH=a#0{aC!P@VeByGvW$k1KuZZ zJ>^NRVB}5iaIN})Eal+f^w;%=4dw9agA3)8q|7o_k|1K7vy^D)n@IVQAJ0IwU?({P z={Z9xM!CU5hb!AQTdF?wO36)NzCC$+E}XVxhq>GS*~DuE20<9bV=;395iw%dU_oHD&z8ZPRtIwtCp8f+A+0nJNjB_ z-)0L3=nlScj;`y&`cZo&;|tj?wE9#KZIh9zjDfn4a!k%|R#CqH8CIQ`v@H@h+WN*S{~h@Rj#Wk4@T( z>qyMEzpe6qIh;UbEiC`s$rzD2RNL|TmxVc15~`NfzoRub)H50#6nx6@{Iwjx%;>Yk z=!8s$*5Wl1rIC+imi7*8pT96%L9_SsYZg$1eI534{Di>uBjq0*RkGPnT?Tq5#EL78 zf>k*&!uIU)y3V-~{P^}o<J0jiLA6X+`>O-D8CTOGr!^(&yc}myCtqr zDTKt^-VEd6mqC5j{6A7xB*r*UKNB$h#xz-H$l!~2{%UNiU{MY2X zwpX*+%=-RXZ7a`r6Rvl36A0|zgJ#CQ7BfXdd+qa74~Zx=?qb>Ccil*Q!7h86CQ?~4 zk3EB$jZ^!KV&&!SXATQ$>SU{aY2H}1>HBZzb+#<)jkzGSuu|(OGc!s}#w*3XKeRB) zl#-EM)Ux!v$3w~`b7McZh}YxKzCIkvN|#S&ZSZ;$u%)r=MENir?v)>v8qvEwQm&W& zF|^Xkje^dy^)vX%S&nx2SHqiXo09#-KNZzfi+{RSwf_rSpnm6h^R~v9dPQD23;OfP zWgaxE^p5kM>k0RxcI)upH9hLIcOO)fyIwz7IydrOZ3kDdr>r9E;_)EKYo#u?h{j57bh2p7LxtfHJIRqM_xJ`g33vJ>09R?%eG;) z$gX2b#HTlq@=Z98lduH3ekw-?Tdg#&OljJ7*v_iWOoFb_@r{^fW7qcQeKgU-*IXrr zD?F!?I1N36`>m5Rk!SMT@(+9;fIux#E&X4RJ;q4;Tzc|fnqjv;>He~7_q8xrxA<+O z(koiQagV#d@T8z3=wbq?A1VUFQw8~%-&aOlu=}xokS7Vn_5!B+OB=w7M12UDm}4DG z01HhPPZnwPe71%P4A_#XO7S2_D%SgaDuHSWLI-XaNMlG7WX0JY{&66|vM}8yc7*wpvP}-&FlC(7U7$l)WVz4>~aK{RbEii{P z9H9j|oP_pZJ)r%blTm2g8Bvnfx&4yQH=+%eqilutX@^|-Z0K3EHA%^X^_g=j+a4o} zh^{7U*YiH7C4A)%IHgtUv=^YPE@PH1g#kT0ddTLdKnT)=m+q_;aY%7`-KT#v zXos^{Y1)D^p0I)O^BPMiKb59|C|Mm~)b36NksV5io!M8Vd1B>_!65c7`d*Mpj#ACP z{SdMFM-u~8X+Pzwk6GRWKFyiJQq3Lzw6n^8&-vW2k*0lEO24ha^O@@Y9HpN1rD-F^ zA(U6VD3YEBu$J=&ReNVrWVfiJ(1f~j@gC2j( zf2K`KIGB?$mZ@To=oR|j@&h|7H$Tv=oQ&ZaPueQJ9MoAwMCd1*SBw58Ynq`{-E|xh zjx}y4IQ~aATP!|l-ew8_Ww`L5%cyz>;Ix8NdFG42k3h~;dWM`f}ww` z-@UvDJ1Z~9KQ)4q3_|tKnnwDnuW}HL>-aLEM&xKn$kT-TqZAqp>-2i`Pk*J*t^Zls395Nc#=Izr<&OK?^(LsM)r6S7RXcwj zO$LG3DH?2nh(aO$oxk}^<0G_(@LwDdKKNIuCFt!GT+f~yrOwbbk?RzlzEq`IU2+lu z7#au`BRM1|BPz^J>Sua;jd@PgU9^X@9Q}NiW?^0oTKyaFPI;AgMCW@T1f^4Zfp6Kd z56~XOiT%(zq8o`+d&}o!WM?+Z`kH&G+@}4C6t4Hd*W`c}G>iWT7{Uz>&d*$}W{rI+{f8;v9nh+8QPTpu z*mL-8!!_D=O+5q0_DQbvS@0((!NDkKVrz(m-&bK(>#>M+u)$ zFk5_LS4lpjyvl7v=&k1J{)h83@J}FR&8)FSt#-}YeV{4Qcc2Z|21G`zJ?ApNKl4Bc zx1Y#SYOT|(mNWvTJMh|nk@fPn&u|@efoKruIW^c(vm;OPgE@W-aPn-ujvob_X6-hx@f4$ zi~Ns*<%t{RWFW7AfcwZ|fut`D5npV3uu1|o5k=rwfHSN6NYVC5%n`}^b(*(@&@Q?r zs!nErHcq)TZF&N%mG8 zeaQ-6o33S~Zq>6Pp~Y9IyB7#V~sV2Nig#a`;REQi;Ri8N!X1t1OYM1Uv5Zx^0~$e_&? z2@-03k>DXXC!=x;eX%^m~tyJm$3*;ex zO$<~-*#{6=_bJdC#E{Yq*eyLVt~Z^gfc*T^e&&rqv(jg)+`o$qcTExVuARuqFwi5L zg5@}1SYDFmCIwp1AF)c4%>*#kbG=YOhN-h;KycK+n`NDN0E>CNMz&Q^1F=G4uO)cS z*nZFd4x;7=!ZI-(<5B>gy1T{&e_$0YFff_hCf0*DOH+lIwh~SIcVQ5VM_$M=kZ2z$ zWZvy5UyweFrIR#0*gg5DS@u|2q?2YLynvtz{T-JtfM=j1aTJzbu$qR7BShzvf1G@eJ@l0+100sTF{yDg#l&$&{vvBX1KxERVcQ0PZhWfxaVe z!g zAM-m9vh~1g06;#$4;8u49`p|M&&w-Z3#!mZU{}-L>5BAiAwyUT7ypg`$>%xj0+!51 zB!Ka8z+qY)BGrTPUZ5H^#|`h7q-iOrLnNxDFiTkr2~SYLjz%RGTmnTa??xgo$~J*9 zK&|v@m@VZXL3&2>T$jrVzhQ2K^E2>@e06y4Ffen zmW0Ik@pRz&yvG^`DIi5H%V4SbFA{_=DCa0SB_WG0P3t1> z18<1Rygd&F*j$irzYrzJzYM|ip#~xJWznLqs5}O$EoUWk2R^M%188HBA3-kQio6P7 zbwT`LepnprdRwH-FGzLNYV~iv=6TEDP`ewJk3(D>B?L1%Y6`YUi>>pbvk3x+o>FEs z5?3|kLhS-uC)IOBPo1GjHTN~oPCkGtP3vsJfXw7+LG;iGJGyEvWR}1@<<%hm!g7sN ze1f0(&(7c)mah7lpCtn|yuqc_$Urw&^Bg4-kY@2;P;0*ySR;-vPXyT6$p?*19wL5V zAld?&b^&g$*Q|Md*+9e~-Q9+C0fLVj!x%3Z;|i_=*)vQhz_PI5@Px3p zi<_dYdrt)yiU)W736ynU3-nk4e@=jfBZgtd;gjZx1aOUreO%nOhQLS@td4QZ&ZEb(m2> zb`yYkXc)k*1Yb6H7G{Nou7=+$U|X=RfCeJPl$p!~P}Ug(m=6gVB((vh5P*op6=*b! zcl^uF3JJJAXd`6U2xLeBG$Qw{c4>#3=0vdBUxA0XpVA-##_oe{bOx*b5HP%mZY%{c zC{7M(5Gb$O2HFS2+~CCVXs{ZTjpVa-R=pxuzzFvE7=TUr<07RbO}zM{I%0r+iBkel ziEl!|nuy*WMt~?~i9msIi-)xD1nbd0(vIv*6CDr3gj#Tg49x?L`Vi(${^a!&y&W#1 zVawE5i^!4}T%>Hk1I!B7#vryMBMsm%8XI9>WRNW&W3K*WY7=C8sHO+uEaqlfGYIB29HQhtcoW21)H z$%#5-x@=Ppn6{qXng9>kR7eUC;{z(s4+P=U298vMjc;Ls6O{t(4zQT=f*2yu4+rXP zyJeUHf&GHAoj)MiXXeRN60a$5QFMTj^yTR%xPCyuuA3G1M=pIAL^t}+c zB?7ZX_P`cYcmx7O!w>mL1QS~25BYDUX{{NUJ^@E=XZK3$8^0{Yu5o{MC^N7_24Y zoqOR<6ha@-26(SDgI9(GP#kCEglHu9EntFy>rjwlxS{;7wD%3ttPUp=q|n^I_9Q_H4sB zPOW}^dy^`n(}5NV7;sfmAm`3t%iqBHk15yAs_FkmW3U!%eIO=?5U{AQ3P zQN%ifnZ5!Wm{+j(YoR|xkJIL}o&bTJl)))@C4xUI1cuG;<99)*R}0ZwXW*z0pgW;I zR}3pdZYY5px}riaup7zYzDJIh!3@AD zWk$037axR4n@BE*zP8)}mxG6+n>RPtb_xM-K!nhGGYNv#%aO2m6FzYbuyGvPMe3Bm zjHC|(o91@HQDDHSLE;BCES~>6O}&tE8#$%1)lY2ai_ugIm%$iii(Ucw=?tGnbkXrE z#1x`n`m%TClR<{~rwvnJZwJ?S5OJ(rwTJB#Z#(Srv7mzkBJ>Sl>MMU)I05`|_(gCL zxW&GM#F!W5!EO2?n0h0cxdYi_^jcmaD}zF%zsZ47!W}(pg_xb7aaQq&LRntH0|dC0 z181}FN3iN@0r6J4B-2;5TZTvraRyvYcLQ*<3K%} zlb8>CB$+y?P=(Kk@}T#P4zgTj1)C-Twa*mj;pt5HHAkt*1yo7% zSKu>jFFmliNKijfz8DF_rW~T`fl#Qfo--X%iE(wd;l*?rf_TB1>wpHUJ29RNV^|4l z{{p5i{pEVk#uE~R8`WJ%u(TiIB0Z2h4#+rig0R^U!v9FvS=lJBTa5@dxP>7n*9O$~ z9ukviBjt?9h?YJa=-+{2?=(0IAgWW}Z}j%oZVM!wErW$?Fm8ji@TQP*5U?Q%rw`}g zs|Q;xOz@a_n@Q##YFiw%jx-EH68@%^Hc06iAmmCRSEAx1665(+M>|@eN6iFo?4Q zR*1RBB<@b%p-jmV*d~Md&};*X0sJLK8o8-&%t(M&UO9(p*>wlJ-NN7#1iUXlxW5z) z#V69Ql8?pWHk&UfX>_MI|5L~)ZtO}otL-_mR(bAl@}!m9Tg#01TVFPQIo)b;NYNeD z^{7B>>2%K~hkdMdwT}Y-_SqCAOe;gF%oEkH&3#xW-EX29KR^Ak(Ll*<>a>x+t$+ObjD*fc9er0!3Wcf>n#R9AB#P(#XKjAkY4j-o`$x&@0%MF-T^N~c8Zn>Oil!- zs#m#5NjkNEdDDWQ?hZ9*sB?S#arXJ8%yYFHYVv7?VBF$ zy7n&1IdR=!6ZdRQ%RD35_r~+O78hN~EzLut$6`~qm`CRjf@)fBE0{cWd26Xq{zU5y zk`Cvi6e0Cj-c$aBC_L1i-9A}d=bd^@w>!J}YVony{&B%U=e6e*=i-pw$o|ddfd@4H zX+;W}C0P`P)<2be->R-`GgqCf#e7}ue<}eE^voojTm|(V0;PX<`A*{G1ys(i@{X0x zuI%>9*WOyZGaSzUOX&>u-5D3%_@shuThH}uv{3R|@BgIeCi+b8JCjte%P(5B-q=1z zmI>3GYm)r)SlH9y1hkayRA^(A-GlJ zJ?x*C{9u&~pg!L70dCO0$1Lyw>nryJk`|u~JRnrdGC4b#^ds(YmJ9L}YGmQgIGy*R^{Bb0g7YChQ*)Gyds zb2waqmb6=KYx7WoAjnJKKW)%cRRcblnx#$BfoH=bt9j$o%2wJu$0D>d9$Rg{k82Gd6ZY)TFfY{mkD-r z!)iBn58u(3oqOF;-bZRQVhBEX2VE{#c)ya7R~t3{(+$Q=Y~Sa^zXxWRvc*>}H`B6u znF@yZ_^HBFlQ-Ll0rmcj0`fuyc8EO16#eK^Z!btse536)8@g2DtS<-8XLaLT&Ti)( zV}F(ee|qu;%|uQfVx ze<&=PYVX)RaZmcJP1!_C$73ezfH5CiSX*|#S9)|FlO7eY55LuU_^FuU?>K(Gvwaxt zSje!7v;A;_(aQCfBV!}(_QDe=8!P@L4)>4nhA`c$39pO?B<4>F&iWMWS}2f7n$X1D z83@-V?bX2CX&%~jEY@`tcX@CZUsr?lJlA$`m%5B6Aini^-QkzlbXU8a3yU&N1Y4Z^ zWpgWjdcC`%WLSZi*|DC(og)%MyZHEW`;!2q7LAP6mtFxF{N?80I~20o>Lhr5P119A zZKTL3bt3QlBLz<4DQ^BUdFkkiaQES#hz&@-B)?dErYArFtzHyOFxN&b2Qi70M&nkG)8f3KT26{8a?@@y3PIfnu6o zd-7XiE(MOX2wq&0?;n->xcGK7=jWXB9fwX{m)k%T$T#2TRt$fpi!SeUKD!ijRc$|h z^3BB^s3~c6hhcx(4@7~wax8Agjg0x7skx&&HJt6cMBcJ1U%30TA z5_K;mw(;p|+r6$8?HH0L-_P1ljdKE^ zc=Xlt7;@vq^X)9<o4roym-Dq1e)Hwc3Thim(RCseDnI%``5FErFpL}8piL( zZ-4s+NWJq6SYf0)z)8!r4DO*pjV}62+1Csf0`SsD* zvtN3jt8IQ(_xm*GM`!4Nm`>@p^uPJcJQS$8Q!y_ePBGA__uk^ea9{8 zQ#Vx^B_hk^ho{zQmh5Z3`ebqbz+lp%!TYFP<`#eZ6xW=d9+pysze*eY?PzT57iMYA z@UxA%VS{>-KS*=m|Ng~r@WcJ0aGfk+zqH$Owlu@KVb_R9|1OQ?G_&3lMqH)&JE0Lf z9jRY!l6KFH?(!)cVg4YTp7{90V&QKeW{t!2az{S9T#I^3ONTp9=Y6p})IE(!TYT5w z@>{|A8k_6V)P)k_?pk!fc7C^BZCUaD@XDABlSuzW)z`V$>alIEnva*KK5lF^3E0Y~ zm5I&w=69}~=M=+BSQ><0Lidj0aQI+)Nobn!;bgVn%$Svumj7-H{)J(oOsW#p)FeNn za&e7sVsuJ+e`LuIRw^&4HO%N)hMJ5`@AT1C9P$wk9ha+}5Z-$o8ycERW_!lJ)L-1!v-)LLfG({UJ)KtCJJJE)@XM1sGPxhua(hX0$FXVZ@TZ-3f zi>cOK&$%qTId;+VS#q&v(r>~R)!5}nO}uiNGl!e58lR<)t}%-k;gm>4r;rog4m8 zw6l!w#SqcggP$}UCN?gY{@Td&C_>+xpyYUrlqy>ef3@nn>wyV58Hbu#&{(;R2^rYf zHak~g>e$rAp>RV_I?kPI&Q4d26Po^GesHJ6A9LGG92mEIsL z9Oy4+j|3Y`+}TN}`>6gL>h;`9I|&N7GCTC~<|O)2e}};~uYm$#>65A9fv*lMiO@`} zLEt;AuTtSD_@&77xo9Wexm8@)?m6d7i2dSo7&mivO{Kt`@HMgpXHj)i?scn zLl+*P3(A{Ug804>y)Haz-<#uTmjFxq*P3~bCa!Z4#RmnMMTLfLhI$(0$`7y2mNR4Q za%LqAE9^LW?TSp?D}vz`4YCB0W}Ermrucf$CsawTO;F8)XV${9PL{7xkS*mB?UQ6M zThXqp2e;__%0H<#!9ZtJts8CM7XAKORV8iLu2x^IaCikdoa)k0>KM+ZHrXf1O!YDw z=DqJ4_#`H6%c=kTtX8FOKTa5B+t>WV`ywN%r*GlFR(`gOZQozk_kUm60-`E>Lk@ku zq&^?J`hldBy>F^2$aJETyl6AlfGrLhXJB8J#!WCXQU{Y~ zi-Xgx4aDb$%OyT-tQs>g{B1NFb?`dNVGD64bzr3+{v4{)RyuYO3fE0%ATOa1#kEHKV!Pf9KLQ>C?Q?L+=N#pLZqp$a*gcviL3ZlSi* z%)RDF)2jx1mLCM1XuNowZPLw{ou2n3P(KQOTi_lEHRxgtPEX*G>|}z_V7uG0!S)q{ z9>$l;GUr5faZv{t1+OWNN!gtFHoqvn1=_QTCpNkI`u@ybQgSH=9TYgylpEEXpvSi6 zI!v4_Jecdp&l2^2U?1+eXv)8@r_SvOJ=&~_DtccT>=f^MUT0KMC_d)X>+`TlUv4=2 zx~VO_A(TB5UU4@sEmR?y@;;}qzW?id<`|`2zGnqK$TTAS(j)!LT&pX+Wc{qie!@fI zbJQhArzA!*{FNi9Z%`Lk=^{Bw<_Z@w1oWgj$xTBp90Z#TdY%l$o?$t3MY z8BR>3p(pOu3faWMKT3Rq@OW{;ela3vw_6kXnU11O$EZAfctVsIs=weoN%&OD@&9RX zkXQQG%uEH!Csdy*aXC~!E=Cd?S4WAK)^~f$4z=GUXewUk%-{v6KqA;J*iM|(qq<(1 z)ML~{;+PPf^yjI%pezSuG%!JwTBJg9``FG0lz^)=>Z5UYB|Y1 zy)}g#b_NPTh4#BGGQ9eJz#Avkh(4lsR^EcjdUwkmE zP=Um4gYJU|A)(4Zy_OGjwcRa7BMjzVn~jYSF$b_xFpB#H0ecX-7#Kpr^)}OINbC}$ zah+?bILl#bGfUkfP%r!gk|LPYO?_r*;Jtgo($#M~-rs67p=3{3rL{VMI{=Wl?*ZnZ zJtR~#j9|CK2M@53MndG;oGZ{oe-RZ?YvA2;QbCscS(73u79$vIFjgQrax@fVH4=iG zuYNOHT_RHGvt;7xss{18Y*VB=#!-Ey#JUOlFrv27Z{WU}{uDtC1-;~*@z79Q4Gkcj z&fk13?_oYw4N`V;Vk2sWssm4<=WVs*H3UlBVa<5JGG+^4DSQoBI^+W`axP~2K7jK@ zpGf09v1IJq%iX?m;?nw4DL0?j233{(IGNlLs%FA|thTdDRm$HudOVJo=h!*)R=VRb z`@Vtth$53LFj6Kr5T-<0WZw!e(IN?Z+G4OLL&epFiw7?%z~5e5I~hC}tJQiZ`~#{e zC9Y@Ec53nXP< zGI3iPc||sAtX9(VkTBHoiW#b>uI$&gn83G&b#p1nm-#IghlE`UIs*^Km|n}?MdgBu zpCm%O?sw~2pXdM8J@qF1Zw1#F|DQ&51b213t6o$S1u>aB2ji#yBJsp%LyF5~@)iGT3OBxJQWpYEKRGC8U!Fpb$ zOh-zphtJZei7%;&Rik+o3bpjeb9`W!S zmozq&`jp|Utl_mMJ=*tEgQbOx^OFQ}l5UOGVNsocNJg61P`lcN1g!^FwIwbCPm^>R z*CMSLOYKH;8o~H0w@MjP>+UsUX&G6_^Y7&)UsY# z-tpF%=QgvII*f2?KlQvn@9X489@l`^E3hy)9x~k3M)$`+wwy7s0 z^%bf}AB-bXGfNp7X-OZh{M49YS&w~~XhM$T)gk#MsEkXCpOW95s5*1 z0%?#wH~cs|%3Zkov}2Zc)+<7v?VJaRCe*tKgxqSuBgo$$130Qq$xy!%j`U={dDocY z_&FQ`xjMk}G zD>v&CC2pkGN|f0rdbr1IGTVx(DRdaRz{*H9kUylcR2YM6wV3guh zJWN-LMhOoC#QzA~X-mi5`VFW0+mUsDD;WLzeSd$sZxHgI;)bB0O$XnHm2Z%pve;9y zR5;#Hh^4aGYE32RDO>Ih8CAW)v>1l&l#cN@$LX_Tip=>QR!*yT(38OOiF-ZG&5r+`>@d`bMb;tO@nL?Job~bydHTmwI!t{a#9~hQlL>) zxMs}3UQPZI+Hg#tSyB2TitZ9XbNL!*-x!1>5lHeJN%FrgD{(QH9MRhTm0_MiU(Q6? zUrg@x@|=~Y%p6~M&y^3Tr z*DB{$OBU?X3h1F9EUQx7#wTDX%Eh%I1|<18QCeAp{qG zcMci?Jd$EK&t~*x6Q8Rg$x;c*X3$ldzPKwLez_*jHk4;5{!$~Gy%g{Vr&q_MpP@78 z6h*-gis;H+%<+i~DCJ}rs>Rh{GTG7(nS9dEHqMtR`VV>1lu9O{wS;W%?2bUowHmzQ zZI@vgN%loiYG@?{0#T71Q{kQzS!~}^`^kSp$3o2khr1fYHU<7fIQ1vt{CMmvZfy32 zpt8F?MNm0=s!ERW?Q4@fiXH9Pky)BMu+S_2v*XC1iEc5WB16?tckFJ{{b=-@vPjgZ zKK{?xk>_3~Z%n`NlDGH&!NmIf)ok5*i z=@l~0bT{q9h;UMEzljfg+O%SlnT(o}5tOdPMv+Dn1-f+Ep2X!&fgZX4Sqq2cOJGXW zYK3&&^~MR?<@HubCA;WfdHW~wm%~N$tXBqeM=sI&p3LjJPJK?Z^uNlCcGjli79t-e z+u}Q`!b5GRK1yg#$hnSkk}XNChv$A>a->;bnxL=f%VDN4!&@F|)0{8Wmu;c$nCa|P zJt>Q)u2g^O_3@!f^5{p58#}CM364|jq+8rZO^34_UU0>W5#CJjvBn?%j8XO9+<}h5 z-16v-#M~O^z3VfYA6Tq4O}@|du8|9wdZt@+uQY6Y#%bzVi1#7#xk~0?<|A(Qh|{bg zUD~`b>r;|xVdw{a)A`WLq3JU1CxxS6 zmJO)%6dv~*sjhUqbkU>qDW-MFFuL{;rl~+z_Ai|_kM4L#EjrW>rvge&+G=p+#WzhrnF$N1I7orRnE<%E5Wt>DC*hYH}a2fvHdb-qj-h?E3 zyrf{zl^Sf#d>BMHH^08PzXQ|t*GaOjaJtEs=`$i7KMsEaCqWp>k3U@NKPf%eI_)Oc zCao7OSNy3vS%N(6;ucfbS%R+Bq*@K-k48!G)7l0DWUL2rQVq;8{#fGdh*sHI=Q}3l zN#i*D$nu++^G;QcxO zlS@lYIw`2?35NfRP30H*13R0SS<5K%_5jxU#zju1z^re6;7Sw)JrGfzGvPV6KTHtB zD&;@>M58bpWrgZZ>Eqc4O${`quVt`pRmAv&=t4KF)yP&BD|x2&beV-tPDE~xru(FJ z2c}ZRG+D=e(zOGV%)Bi})QG-4P8~SdfytH#!M7fXel3AbPF&V=uZYPA@vUGVcAy3m z{QGYUs`W^(gRr(2bSoSyM9SzwVVOSauL6ctM_?oNvu9qVVQ1@voVIP&$~&t&Rl4+~ z@)pId5wq5E1iqA&hp@U|@`1$kR5j9H|&qnCO{$c#;tO{;K`p zK!+PfBzKzp{yEqF4bKrrlTqyXd-AD0`AK?oZ{h6c_W3EfVszQeE^2?SC4Evpan4a@ zARSG)zgx&3HMHlDdqz!)rle+Qj-ygzwPcryi!s8&{vvrxR#|SKTrRp=M&$TPS}${@ zNijY53re%k}T!pLX97W-id|C~QSzLSC%FV&r0J=}h%wSnQs$_1f zZHyfKS<{LNopg|o>GyGxyIyRB5r!0Vr;7PixObQ$ZgK7c5EYi`hw^EL_jP{N7YPtjO(;E>FSkcs3@7^p zuSWPpSCZwjiKvceTC<6H|7Z%H$I#efuIAifiRWXgQiZneD;IjksO3xd-M9||%WIX_ zQ^za(j;6?=xS35IuHJL^Qfh8ZVX9S=h3VgLQRW0zU$B|KH<}bBGDSK#(%gk9A9LCs zW!ckKExo(eLDS1ErtN}bSZ_l|5gUVQAAw{Cw{H)z{)2zaD^>UKY{Fg2OTAj28voID zxdrFBedc{?y8K7@DbG0#tH|h?0^*hy|L6?II`{V69aNz(`C>Z%$r80acSwI!zfO3D z;+Wy{iF;sv7q8-+<0BeoUX8~;$B50y;JB$@$h;iJVEphbzr%8fb4hrd zvav(^YBptW`q`C-gv@1yTr1qUWykSiKiPKLaK*L?mm5s%;F37b%p!k$5*0uxyd*~8 zkC64~OJBI7KC`+VwL>fOqg~FrqWzOGqt1T#nk;RF5!17Bv4V>ogrS)e2Dq$u)UeJ$iCApr%#9x^iDgOL1eqE!_lknS)?gg{g zY4;oFU+4#u>MDCHok;L$rqP`oZ4%WtH~zp|LIif;ggb4g5(^`dYQTQcIasxn)w!r! zte8n|VrKK%q28G>G$wWA=G;naUrbZjNbKCge%d8$Z)zp0b-=oHKy>Z@agiJNcG1z$ z*Hm_L=}5#|a((dr7+%6F-wXWq9Kpb=W`%=aH{yp zfcu!yj4hf~yoDew%}+AkSZ!FbeCPf17_8?XlOKCUrKI`OY!Rr$ao;}|6}bK}X`KEv zFob2C>)10vH@ty=nJmZ3tS!H`y|VtDQ67P^%g}#xcxsoVe=5K10-=)ZSawY=WKj@b z9zau~#PDq3Bdg_->%X|Z7;#I!I?i^A?kr{SwQ8IfF|V<2neFGv6hfvTn@NANAYD;L z2r(#g4H1rWgA4-*{&2Z)Dr^j`~g;}N1+O-_k!+7kxK8k((9=P5;;ZH{>(Gj zDLb#H%r8$C?8=FpPTs>nyaqFyqsm%BFWaK(HCD38LBy3#nr0(m!j(Kioj?31XRAOb zb8rHaSV%S~&R@u9{@saRSfcgNNP0GcZhsRrBZTDOPHW4=O)wu9kgbU1_x=)}7*(8O zZp-2LOwkCQ9DWfU7r*lLc+ZBRo8NTyX`nvdHFg~%k*^G%tY2U4|Hs@Y&Y?lA+*!J@huvwSn;nVPX=my`frTd1>2X%f+H7I`B8r*ccG3=|({!{~#)RC&`q_|d6 z+qv2%|I25v+s$O;X$eX!ox=fk`n72V%&r1*G-pIdhm}64LHgK+*X<;6R#W+QByY8v zhPBH=KL1Y+HaI6{;;EFl07DJCQ|;URwf%~(@^bw6(vd*2{t@M9dYtOk`~IiBs=dWJ zi-MOi!wmoS12j^(18**A;d3Ihj4my2$ari?2KT8r(I;;wPsIL~lYD>{Ghyloi-WH0uR7EJ?0XZfG_VsuE1tB080jv0Htb`oSMgMBuG||BMZm z=L`3&IAZtkllRoJZjJ{1y+mO7z(cxN7Mj=fPlz^{26U`~%Lj zpub<(1$`qYOF0_2R*3Czp}t5KsT8@I&HXFsBzrT)Af))y1YOr4=jdP*d91(v=T6+* zOcRadG5+t?DZORaX0c>+e}5IKcQRu9xfMB42p^%<&FLKp+L<4iY~2&^b$S~n!?oDw z$DWz#ZA!YK#`m@}9=!Ody@3_Hc;~@@`v>ipqtn~=ItW_6Hz39T>W3814opfNtBA%N zTpRvV!QfY^b2k?6JevreA1ZAkTN+MC3x=posgQxc49;(&S>nelgpgr6Lbn|Gf&8+sncsWZ-&co5!0GM4p_xvAeC zvSA`CKz#O(i6d3$%C!H%|EF(-xb^nE#?6HW8&)6N;BmCMaNF?}`Wi}@OqSIapk@cc;+>y@@E>4}`r)f9`#WbC)7oBU2B`j>6Ck(Xntk9o+CD;fY2w1D zO|eri+J3A3gcCv{%$x7rv7eAnLKVt9@=q%|?{~06>-7Jj>s})s)YL3lA!%(^>Q%$srh8&6xGgF)CJkx1r zn&bcXlzrcQzyJ5WzxRFSIoyZqzV7S#UDtg-&zp*rPa!XsdDbjDl=y&p?4F}~K&>S~ z7R-Ms&>>7dFn8V=(idWj6;^bQF~YGQr0NJ|+&IkaxBUTXN-{lQ8-aJ`1=2}@g`z$ zPF4!OSI0Hy$xW7f@kYqk^ws^kw86zSx z>!<#GSG6BE1`VztO=hy(kpex2=`i)%20DRcCgR%A`eOUop4a`Og<~uDtro=*&B4T} zi}ak#L`?2w8sj3bbz*V56&nb9&NOr-=19J5?0<$y z*g2u0IcA^iV>`Md#t%+B;Z1LxAHf78Fxu|Mwz+hdzY?=@WF}Y1o7zOpn+-GeZfa|9 z-W-^5c~hIRd2?yT%S|<3z0PruUbH3H<%g;zUzP36nKx`(&C~(i24DY%n&S>*Tm09S zV1wmVOU8C@s#*6s=T$7{{gO!sgLh2B;}P3xe#7G$Jf4cjVR-DS7zKq!1Y>&cdS-6j zKIq%q)TJjNmSvDSZfutJA}s4zTHl~)tZsBz{~wn;);d8B-`CE5{XX1a8^fLu<-Pl$ ztNo#6@$FYC<_;Pf(Zs#w>bUzXPKVf{Sl6pF8t5vP?w}v^=jJDSg=6b#ItC`{7I!x; z@K*8~!(TYoNzq|(tvhjWvb45?Eo!n_p=quOv?tZX4*1En#t;+^|F5gxuBsj|%P)L1 zwv;;6`k-aT-9?rA>)`tTSm&dx!79!5eFyR|ggR677n$@Q3tXwL9hkLat-L`cyguYS zzw%wU3C2rs;Xmzsxm>9TRL6M-t>4i5@w@^?#b`bhM;)nt)o%(}Jtcy7-$Tp`;=z%A zp|N9Sh4KM|I3~Xfx9}1i`_k@mN2@`Ld8%6UyQKBia_3BzVSkph<=+n@BYqdOYL_!R z|6q=T3sSQ_-G#;l1C!QR*1H80%iM+01b!J^#2#FfLZ@w?xYL^7KG73%;y0*GhnwjB zA-wZ=&A*2;_QIL}YI9%?;eUk4?JgvR%w#*Sf9go#SYk?U)uJo8N5=^pa9Fk6Vb)df z;P#rfi!(1wgf`W=gR|%4*xB*{2C%Si8Hqb>s;A%dFQI_JgpNK%pf#t55b?pS!Se5m z{;Q@>63BSyH5eB-70v8LaovtF0}^y5qOT_^7_5{hdy(tLR-e2cH07xq{CWnvcd7m;7~3M9aQD5 ziU4RTAps0BeWtU$NM!E>0;dSQt0Y@Md zW*@8BNJIvcX{PT7==d*}K5#qS<3)!>u_}{#to0kY$#yLY9@>OZMD%IiuQMBTi9-^H zoiVBdmW|6TpPV+m>btdI*)3x)!D+b8O3BqP1~eVH2jfX3>$R1+j0e_yrF+^wgxh*4Jo)F zmu3ov3A$RJ{SkR>P8k!ouXAj_-ljeRN*>I-goLZ`zlWjos#n zJL+hLOYh|egZ9(&5sw3*f~unomv{Hz-KYN)#1Hz_R!O=uW_(w&Dc`=NueR}N6(;6Z zPo(xs|Cb(6NA~%%qmV$W0Y6q-hj@S~sMCqy`6v&ule6sx z>@D|A8%!%VPZf8+04CFcjg{tBi)%f^%u+GZ;6Hn&{n0jcw)CUjwR5Qrp$3BtT5&aGp*rI`Yu+)Zr*vL~BhJVNx7L$f(cOeu)95@1{pC$-9 z6YLo_9?wExaXD@^_A3Jp;L5U|JIx^(B~_T7gVLPANh4%`=SLNet%MI%kc8G>67_v) zk{+S@3sszsx^k|h^vaGYn8Caz*iz{`7!zSyE1P~n(_7&TebXRPlLtbG4_fOp1{Vdx zMBWh0q{&rbJ|J6;5p+uUzlm1U^N?+r6Db}VHXv9H(|4N|^^jdW`BL+=ABk<_9m5NrxfYA|ZKGx@(ruUH0f5xzo7y zv*Y1;`;$!&-t|EU4STNVQjg`5?`_oo^-j02+Y5&2_e zc^gvRqEcxtb)-I16}RgOhC7f7_rM%>Nv6R%z=s`L#7GArC@V$ScN3M=7~nf5Y@~Jg zy*8Lt-;`<_M_o^UwGiIssy6s>@V@8l&*)rykCyt zKZVzCOoP%@!(f}Lwx~0A-YT9BIy#XVT?;LQs8z6QUDlvR`+Q&yl8YdV(U^0^&qB#y z4)jKcRtC7m654d&Vz#gmea+zybg(3M&_ctOKrQ5xm?+{=H(2^0=^^?~L`RVbq6aIW zJHajti2WD3bw#(G@8MkirD!n^RT{xWb#qa=I|iklFyIb0p4Wjt_ryO!|08f!a}&?z zLCU7dg9Dyox)b5g6V(<$?sugJBM8>q$R?Wq5fwgG!p3%d8pwU#eNPJ7PRUiuBa#i~TwyV|~v+n<`B6;tEJGrv}pZ9mEi)K1Mgs5$P|yMFGMu4;IiX zEkREM*-Ne~Mo2{5lTlszQNpp$t(2-!gFZ;`Ah8hJu&e|!1z`}1?I`R-5Jfx;R0xN& zG{zkg?#!_uObuS!oC33`6F@<2Z*ZFsxN$yu4kGjhhr9NG5aE-augye_F3L}O*FC551!ol0%C3hB|PabSr_F=gE6?i2yCbUwJ50$22f*r8P zJ}AV{o}c_^AM0?8(8(dagJ4>pqP1&z0XLHVlQ7GQ^vGaiqUk5Y+ogsbcp(w1;?}r8 zwGP}W1nPHP1r^Z6X+MPcMsRXpKg^-Y9_W)&~I3YoV}hYln0^yD5) zw=sHUY>|Zj>~{ksU=BelNO)EUcl$Kyi)&to<>tJB*-1bPz3afwX|pjaeMG!Vhj}-y zAk6m^>OV*QGQ^rcB?846!U*p@&TvFxacezNoGXaIZyZoG^d%Z!g-ij_j|I6O zkuk=0)ev!i!KRM`#pbDDSH~(qGCwipdSql}l@*xT=FNnld^FGa09q=~K^ds1c{7-< z61_Kliwg&EX8^TI0V_K2SSm($)HaP>vqQ$%rxg?zXND6jHed&vjf`n>bq)3n&QlBK z;UeV&k@}TABC_qDZuU8#{-V28u=4Y}84MUhz-B_|vPXpBpWl5Y4|BJ!jmW!FJ`e*~ zbeFJ!fXzgZ`R=U)BJ}y)13vcPcOotOaVdgNx`dC`y06xKCP0y%LZ`5AVMxB<0wR15tZ^BzmRFcK2Sn0q%%QLpBxtcqe3Rc}m|=CTP0RB``nvzv zmZu7TeQ%4CV>9~z8`>HhPU!44zP~}jiXT1Jq>tKE1oLz}CCuVAKEHv!UgNtP+zZb2 z4gA-IRVK9m=%WLXC+}?Qg+fyA_Fy0B5k9`btafA*^ZnXtU?!vP5UM7=y@9Qk^>jXj z-_=L#XCHtN3R(gd-dlfH9~%tH%ki;|GH$7fwgndE{Y@59Fw2F}4}G$ab$ zqFIWL>KjzF6;~t zd?P&FOr(TQ2`0HiB$C*+dJ}>D#ZMUtg9%9XW8AT;fJyvF*yuG?4j9sp$OG&kgAaml z4deVyf9K*qtz`D+hv#t#SS7+laR&`B!6TtqHH#Xvd_qxI@J zaBmuM8v{8gz~;F+HNP*&9HF^k#=FT?%GpO^T5X{&}(S>QZNEOQ9-Ex9DbY* z4Rk$4)EtRVQ#LE(-W{lt?MjBV-dUdVpwOP)%54>$5H{wh72IsDtm^-A!NWxcY zucF(#&pVc2q&-B6SA~Zi=|s_G7`Kkd6=y?>{Sn9;^tXFtZ*x5*;wmmCqk|H{1{r=j zR+|Pc##bK1270I?JVEy*2)tg>#7)FxYv2)&0-gwG&|P-L46vy>x@RhP+SZ4iLX7vG z5B4C$+`oy1f5&DbnOLE|NU-%I*Ja>~eI~@pyEx}F_CZHhogw(W>NF9$IaOP=&a~tw zs%Yi5&l1)1d@+-U?rHWPiQFap_W~V)1LH*mCR8=Db!tm%AcF5bOAy``jA#df>ZfnP zt3=*^1Lm$9sm306#*n9xqi*q9lJ)MMP9uq&@DZ{7vy0&UM>S4ZWduMmw=DV4RUlG@ zfSs^A!Kyx!?PE?s_fx09#+NMy*?($$1SxVE0yVOx5-0oB;J4(Bpi{TozE-_6e@Qe| zoxQCvWUP5_w(=16kr$X>lT0Ndhp>j z3EYJErUFsZd6ps@b+v1)!YAOlM+EZ%W~8IAbB*J{_(_X4+%Svex>Fdw6Aky*FaYC@5J6wG5svDC$T)LhR9PH7}_o= zc6_dqUiZTYRcg#x042E#>L9*;AlSeA$-Kqjm_!L)1}+#OXv&5&;e&^Iw54=_&2Ar^ zM%c#r4cM8E?P3x^@Tb#v(=5;L$jma_VNB#R#gCo!SXbkt1>%hyzG^^^+qbfN;4vrh zX#KVu-FIR$=c62p#kf9k$zw^!7lz$a}k+M%KkywP!}j(=Z;ml00*HN^D~ z_$BURvz2I|-G$($>i7yo)B9N%(NhEx*5K~~uiIIKqg}e|Yq9m=`MOxJyO9c(K!IV`);L+?b=f|u zf?f<$xW~2FV@ka8AvR)Or)6T)uNUTFJL`3tF_ty2(;NqmLBx>|?~f~br~=<1NTKn5 zsMb8v<#vub3M51c^=kT{iNF-LwhJ2^}{~1mY!L1 z7_BkmS{b7L$xA};TB@1Yru)yA&b#zptRp;jPtORV7*n6K>H^{Xzv zwebgzYU!<)a$iO51R`!Cu)lu4c>C{H zp~r~=JyUNCJPO+F4zww~}CWH7) z074KS2@LQrAqhSZ0Lv{<9LvH&X?qkS4drUuf{+qd`}(;Oay&t1w9C&J1C?NV>2(Mn zCXjO&tK7a>Ah%Okx$ns!k_O7){vnO>SHKO-zxEr6H3$}0X#-cKFc8JrtxGU<^%IYG z!)x)3Sj5t-|3V}dU-^bu*y4vM7=BtqtY{S%FB1vCwrK>T)*Br^a0Rujzbj)RE;@Zf z80fZXS?I+(qjVy6+T=XQ*Xalz9@vHpg-YH9_v9b<$*+J7{#miK=)}Xji{IZVc$!PQ z_r`err_8p`vsrgO^|`lfEq&SdlRh`sKvwf8Ci$d{O;6%+Tuk?{DcBU3kwmq+K$oNxmCL-$D z!UGm=5Q^zM=T%+!n6}!^Q>$3v?e{CX^t&Ii?^gClTw*`b1qW~WoY!ZS|M&fhn2f#5 zw!m;y3AWQCkC+^{csH5lh3f*_D<7`Zhq3~$ynV;Wc^z?vl>Ctxiqmhsud7YxONsls zOV)AEoe%mf#CV-~oqNji`Yt^c>#LTXV&%Uss%v}q&>2EUIPU1^)MUPdh8ly}%)`^N zJvPb-MR1*V-JF&!_+?TVF0w--ldqryddO1Bd}Fk(tnHCMJ$W9LdOoP%24vg`#otO) zD(^2{HQxiO`%Pe+?!#gq-o`pz)m&h2S)J2x^Hi>1+(G$Ye>qRl1$ z3p^~|+{pIB5KfiL*Hg3daI?ztGD)2b*&l~AXn&PHByKS{rX8tCkn`yU)t+q<6^|H8 z*2P;&+M<)X>NP`?Gs!9@#^KCY^j-gWpEX7k;itfww6EnRPYcc*?zgc<8NXF z_LoU{>49Ht^OO_ek#`jtHT5X8HLrW&0ZJ5Fft#HC;YqXXh_T^#Lu>eIMtzS%i#h zGfDJJ+FxF2XqD{k_t-SMYrI<`+dFa?Z5XY%q|&U&EIHupgLR`kR@@=gnx@%g_x>&W zTQ(sf;~PP})qZ_RrRS`)MZv=Jbjn2XMDq85yMN1WaZA~vKWq%dLrX>!86>!)y||J} zyJBEwlGSL_xIhAj5{{edFAwg6jEAZ z^)T5m*^z{F^CQ4|n}U&?k(^!rEzd-NnVaoU+o7iG$xAzUGhe8GmT5|o;*#T%*Vq); zaBMhR8=96H(wWDSJ!}eAG)%1Qe=tm#H4^v=xa|GZtaDEJoB*GRzDKL~$ZnTxLa`B? z5uBa=Ejc1Ue5mX}h|hQ!-`qC z!#PwR`P_1yj9D@!+BDj9oeg6weJp)nL(E$pd1L`(a2fAL8U-YItM)1PDUX#@x)!@$ zXli~i)qv#QUR_dIIy1@H3YeDNn;=V&tw~7thy&KxFy_$b(5C-H*b z{3SDzoXwrhtuA@1$VxKpYr1orTz=WTeVB5Xas_a$q|%&k&QC4`ih-F)+^N7Y?gJaI z3r%~JbNs6cz0C5LWcMCQNY9GT!q&76V~2lB>UcNdXyItTGs@$Sob0btA;w(#T>2LO zmKt%5*bz^SfD7J{OUYBYj@i9VvVwpoSvCs3VqDY^<`Cvs;JfTzzKk!Mo{;WZI9=pw zMk!m^+cl8_4Rn=Mddy&cYpD+sS(~|0h67i;BWIAuGiP<#wWz*MAjb2tq*71>SSK-u zGKX@>T}>_Y$ZQ+i3rzvanf_UYwq{Y^XZHprr2EDD#gjZVv`<3n`KDJ7IKz2s+JlwB zw2l5P;Ud6{=ayFB)S#c0#I)^-+O4i{R4c>^v8l*Z^maTusWXd|)O7s;eKc!jyP48V z>8X79fbN@QD-t9yj95mj3*M?AWsowpq*7Q6%uLc*0hp#lS)!~IgX3QpvqgZIEnb+A z&RS!molB1EB^B|ywNzZk>wmRm-R#qz>F)9J(akTX$b==jqxxx|k2g@7vqdVOB&&q< z(zw#NsN#aMK61dt;X^KDti5+~+>jW2hot&G#$@ ziU7VR|7{^q3=|oN4$J=NUdHg*8J#{cbzIuGwAtCcA~-t#;d#NdfRu?zoAxfDEuqOv zDnko_SxITe0H&TSBg;5&@)!UX-MwYfGmMU}^cO{u2RA;3uBE8wzsWO7MmKI+ZO?(IxSS40ErIDwzioL+C4 znN)9FpHJ`fOk!-`{Y)OCh*5ahFn;iFF)(u@o%dEjWASjw#o4{v6VgpR=u4|&eN@K| zGMd%X%}6Qt*w-I>S(&)a4I51#O}7EI`nNQS8^vZKz|4*P6>!;GH9bw}*?nSVHaV*Ui~ z1TJ{KN!BErn2@!)DYg6!EXgm$TQx^HN7-6ZSyfn7_;yy>k_(3S((iokPJQHGRRmZk zafbp6vwPiT?y^@2>D0r3yA8vFZb5c$*j*{F^>vnhow+;w1N)JGc(?Y7Y+FKlJfAPl zH*+&x)6vop^}KawOO%;gK11tUSzoG96oDN0Az3_31sVfeR@L;zei&XrFo0<4p)3=$6y zaD!&91~e)Z3&oW2Zh9kNIA8)m1YwE(=9s4JvcSX#Ct)Wa%sPz}Yi;T*I!(f7B!v{s zdkmhON}EcnEvaOPoc9S!DjSO$lLba)i>5&nD`hKXB?;-)hk>KkN7Y4I(TkrW(^Fvl z6J!(iu^v;%Gl74iy9wEZJdZrDUDw0>JJ^BC9%D7cG}^G(V7nr)&6Bga;r-8g`J;X2 zoGC4a+1%xKsFAct+6Z73FpD;;TI=b0pQ-S$G%}r~{k2js8W<)RW_mcj@L@4f1Xw4f z836yv1=iR&*^+I^B!EJufGmb^z5&Jp3jiV^_zw6QSPFav%m5|;i-FO=UjLS+@orQZ zJET6E`P;+Z?%4&sqhzCG#}m@MjsWXz>QcO)&du(fgBwQyHycK&cb!c^q{=t)R7qvf ztR!DN{RAp$d9#iCUcbdYyEhV7ps(frEhZq6^WKpJfy_v%U!47@W`}jGy_?Wu=_ZBp zxZ~>{>oh&3u1RsIx;_G8RH&B3J6Zi`)1kVk9N)T2SKz;;w|QsFJhX!N*j7?mgJfv_ zU6#YAjjt+e&N8>q3JF=ZK^ApMr6an4m#t4o4_|NNG$V(1JiO)2tAEqaYMX*U|CWOB zZqh5>s^;_T>z?ZS^5kxg$0uH;8Z2d--KzuFAZ~+pV~}QmKz;`e%}R2H=Zj@x*|?Ud zXAW=WhbrUtBsniiPj;S@-TNjXJrP6#RW^=y<6UmGZSbnpd$lXi`>J9~Dy>l&{Qm;M zbzK{4;rlF*(T(29jA9^NI?>T7yLU2}2x-nF`XqXoe@p0iFG#mlxwX2fDfErYTScV= z*N|^TVJwaSvTuZbQN^#~+ZO`G0E$iqW@h)^mEFDH zR;8Md&(zM>2sa8R2|rv57B%hOeM`>nx{Rm zyrj|(*@;7TuRZt(kGA=@NX^{zzk91(m9DhK~_=hkpyp%);Dr1ZEJOD)YeCd;p}2Y`68>9^obTE zD^eP)AyyVETM5F713(P3$+K%=&O{O;5WaX_pZ3DoV?&beM)IbY68(hc+5OD5v^l^Y z+Ma4X^-}TMqyPtQ@}|8*$d*Fn+)m$RKN2RVBnj6G6mR)v9K1Dx2 zExbJ>Da|(fQE8iCl`h=f#);A*i8qfnj}D)vz1Mzjct3ObhrFMV`-qQJ*%XjDWX>?)TVOnAYTK5{zLPuG z+0;Rz3ni7AU@j8?{x@ZxwVvuubEnM%I!Y?r3IRMe1t{6QBV;3FalopCbo)5qaMdhU zYB5j*@KgC)l&Zsd>ud@pawc*P`L_g%0CBLm1B5n^5K&*~h2!eS)f)kmf#JYJ;FW~J ziSlo85&;aS!l)v^I;q|eFb4=SlIdhaK}fN{5g-mY3>*bwfOymRM3B{Q{w>!*RwkKu z_P?xlclvWu_`5VuV)F}v6Xget;JE3snRFIh26W>$ z6c|W^TDv3MeeNAax-^D6hU=W&Ya%m|ol2n2z_Pf@9l6hXdgv!^YQJuha*}crkXurj z#}7X*a4bJyjz;$>=W}@jiy$n664IqHKs@O?wrNt+G;h^V`JW1j!EU|tN>w}-J7>Kk zSNgYLHFW8;5ML4D&IkZZlyKfRn^+BDz0p!qIUQ%n2Yi&vbjf<&BmV(bnUTaC2h8qr z+pXsv<05L6gP{)t@b)R1DVoTJs<(2^24|s7`4(u2%BS+7WS#+l1d%6Wi50js<(aZT z3NA_)<@J(E5}(9p!|f;N?$DVPOFneX+hLz=D*`|(!vPSxh0;Px09D1%278QZ zcd}r9QlHL$X0mM|&gF4;j|fhE_#YP~A$PL_3B+i=B^ zD1L!>%wq#2L)BG{ZFhuKjSu(b2im()&Ud;t>{t4-8}^I$i=Fq89#j2Wx!L-xRV+4@K%o46AR!1H-P67Tce~x$aK$>-_r1C9RIrFo7 zhtP(Q$EKatQ^35vvR>I};H2yuCdG_wMqZlT`%?B&W&tdx15_nqv-x`?oMefY|b*Rigc;aRnry)KF?FH6;xJMgm`vzKY_U zd!!Q<(OC=h`hO)aNK&E!7X};3T044wj{aemp zp>r63(@)h*)sTS|{w?NWb8)gLDbtxbqAoBI>AkvTsb#)^=4l0HQYoJLGy2!iP)O*f%P}*snFCSu`Rq#fAC@N zSq*ayZ8oqQm<;#;R~|9%hA!j!jqyd~8wGBO1+Yi5h_k2`%P8Z{BVJ&JJ^n54MSz)G z)|6@%9Zy`-dJ>LSIM61 z^!Fw1RwowvTaj`nMF?YiQwuG$8L8>^?m{TI|gNV}K<(ryWmo-PNuU^=En=iybv+EqtxeO?nxvZNrjj6p-W{ ziOe>t5CCBr1CGeyf;x`Y$4eE56-O0EotQ!73az%X@0$V&heH3K?Hns!4khwQuYTed z=ADov=U5?W7>U@(9RZ91hLVQbCV$8}WR;TZrTR|!o$?=&!V+o>0HqqqjARMe&s}T7 zSVUh$U+drE>8ZO=`W9O^V*sS?>y+!1cSN)G_#VdutTB3_AD4=VfG`op}}jrF6}xH&H}O> z*{)r3)H^b%x1g6uNzl%`CRcsv|ATM@$=;E=l1gJ_2V()`IK^NQxcn~v-9oDQN-QlS zv(NiR?x!VmKl#lk39+MGK{;;Uz5L^x4A;HBXQQ}{=~)d!2bHWM%Imq zTds!NyJZn?Xdr9A~KQ5R>vROY)5SBR=SZ!1H=CReorz2 zh65%flYIJ3kFJH#$)~359jjS3LXt7b5HKZ~vWEa80b+M|G%ySp1&jdxF9c91DU@J> zkpO(z-$fWag7-MZEgG_BzA(*=;5g?8dt3~Qx6BQpKADvc5g+J^yK>o7MMvJxY zzn3^}|9RJwltymyQ?22$#;46-=znuyOIJ~TRAq=V#2Ml;w%*z^xn2GZ6wEYt_;6UARY z(W%{Tlk_Xg!t8A-+lx1fDu1%yD)GSjPBqdlLcd2F(Anj}mdu858*G*fEpPVc;P zv@~e-+z;n^RTHq-DJl@x?=!3&I=Ht&UXKjse_sgUeJqUQiPLKGc2|41eC@8Y*R1E4 zucT9EM>dpHYDKflB!35_j81z%mrHlyZ$W%jM@qX%U%xHsPtoo-cms4bVKEoM`Q65i|vsk_C(LG$|XAkK2E3~Rxp_}GcuHx z37ynWsUKB;6SCzU%{v_a9lItuz>y~De&Xp978^d7ou3q7P7`!LarFs{SIlNdB?s8j z^xaSVeB?(>e~=>d{Gj~3J7S;Dm?NgP?Dz{!KPhi@NBrh)*AX*cr1vaO;+I?QW;`v=BE(;BD|u z42?aUZN#o4=BHfpBw(4LvngXf`3~e25EE%E>Jb}5>;2#2WpD$A!~Kf;HTMx7+s0sp z6K@-n6>S@z6`K{E)r#Vo{kpZvDZRhQa)>T0>GS9ebRit#$If-tH?C67>U}SJg%?8e zaJ)+tvA|1VM;r}t3?zyU7a9pYou%{3_bGjQ>tu}PD3O}z|1kQ-JK-VBTj-nAiN0JN zE>#=MW;M9tUD5^GSN-;sPZ&jFQDSjoIOf$%)+jrNF0ka8p*e`A6JyzNY+{xq<&w~V zh)K+$Sp9sf8KxPJ;{g=l4dadG5p84@WfePwWzA$-%DWiX(Vq|o*stWJDCa4Cl^ukk z4@Z9S7Dc7S(i?4!btO+Xg{;>2-6Qox5nVcKtTfAA&7y3tNE=Km`ws>-B$i8D1Nz76 zzS54<%vSACK13rr&h-SwWqF3O=Mhi1nn*ex*!UItT?dgI=Edq_^5%$PRUWwr=E`bluh@w#e@_h0iPI6|&9?gyr298f#U! z(pKrAloEXz>MV457>fSw9;IKE^%nP+wFdY0zb8)abc{#)3EwAHT_gm|`)Fa)?m_E;AtXC$Qdc(jC7# zI6o{jD+Z~Ee8kgadu4ZI?Kn=w@iLBEajeCWgO|(0nnHCCUK-jSOC$M?M213$dg2i} z@9KWy?KA0U@(p|=*Ix9bo!5Hs&1(WWE_8a6Lr zzfz>8w@KPdB)ONOJ};B~)Y~A7ko|;B6e~ItRc)gM@wTzH(YAZg#538CvYBXxI{}Py z2TdjOlZ(7CYyE4nSRsrFTPef+-lFdyLfUO;AS*sAhDuD;sk^hnwmI-h@M4D;*G}au z8iF`Eqw+eROnXbE*2+ zM(#LDQf^>H$(}&wwPw6{e&bQ-QRGqVfzlB(G>h-#cArUL@BY4B-W#~Z-6k)KlB!(B zWhDtIrj)AIkSueGDev_j|D8EaC;X!QU`-Fp>W>%vUe;)Pv%BAIA4}N;AqVLSL#PsY zc``&fCATel-82q;!+R{CH>MfWfSLKeq<(diPuG?fn&6D`O82tcHdMa!nro5%N1g$% z3Uw9God)l!HQOOSWj33X+%#S3iT6W+vJ9C7?dXQ-rf%}(t=7zJ@94k%zNA~uxS$N; z>PP8D=%(l<;dl?Kpd<-MW!+BXDOv-KnaZ`w3(b;8=qBsZ@erJJL-Hi8iC4tCuBGb@ zbe4EQWT1m^FIjw6k)D`TKPAcA;Emp$JgI$XtJ5dcUQ%n&`7y-*v+q6+ER>8pciArt zHSUbA=>Yp0hJcMyFFr9P&#%p^D|y*i#K2mqOJpR%im3*bH{>UzSkGghJ0IZxm=rml zw&*d59D#co(bnU=6loc)UkI=#<+DNhmc`n%zM?)N~aWp3f=I86T;x{}Wf6?9E zlx&Yz)gJlzlr3axem?6ba$u{l{@V3a`=gQrteI^!#o8Jf{SI{~jY(Th8%mo-D+&wO zpQl|Vj!GMa@T_jHLRf5kj!7gu3z7Eh$I%GKH8}nmW@cw=VmsXSEz~rS^gwSMIt2EL zPL9VWOf=qQ$9lzi9dQ(25YK;X<~tmFF-N@)d&S@w?-et^Rk2mkRY$5~tKx7xjN?%p zgX|YRR2{E!<4o6* zv0)xjflzK<2nsJD3g)6<4N*`XhEI#Qbysoih#8E?Kt*XS!(@I+eHz^!71U%GM4=6z9Udi7x%q87%4cnI zTDP#rw_}xB5k*Wgn`pcSjcd{P9o1WA!uzD#7bEnzEpUly!)qqU=6oNr7(%vw5$=;J zQQQRsxD)ol#fBOVg=cpYug4?@sH!fdiTX61VC5iVVl{ptG(_l}~{ zGhWiHM%1UTKoO6-fZ6oFLp$sbXy+|aXcY=;F zS4;zmJ}(nx3Hh%QO=O`7J~5EUvil|M!h5{SiE@QG(PlBq`MpEA6NKQZx6cxONmebm zt3ONJ|AhPHA~$jQ8=dYraf28{CNYTb=@aSh`3c)Dl<}%&a4|*q);0xn<;V`5PkvQJ z^dA?7FZ(WJP*>kM(0e0+x>BvLBYH_CBzGe!$}{92?{f85ZDXkM)EFsTwC9SJFVj4lQio6-U;Q(yz3Fa^>-ZWrt-VK zi(HxT{(9Hr?waf-;d4| z?w*;IMK%zWOz*lg<8n%1qmR66l;C;j*?l|HPDrZRu4Hq8M{!ET(6mJJS>l(Rk+vl# zy1pe3wVfXkHD46`w4=?1_O0)wSi7D@oOe1-Lx5cJy;0!jiL_504U14a}pz$5!D_*9e$NI~tLRquaj*7eeLdcVcJ~e)L zJh5`$&U+W*>_XEQUrw2uA%3}acpDvU?VHH4ym$QiVh-!ocl|w1*Z*wF^uFcQWW_EpF;0TLM47r)w73uf^m2Q!1t;X_)1w+?c$~q{qAa zgU@wS9YvNcvuM_w>GjJ@0zdDh1#;XV%B!yVv?_EL&d+a{w0o(YSJAw+Os8MgasvB1 zteS*j9$JCE^K!5{(wrrK71dZEbEZkpvOVez^K9^ku{AYZ8Y_}gdpsn;bTvQ4Coy^1 zA0>u2#ijR?DI-b8wlv165xiwqlGx~3@? ze3J7qLg#NG*YvJ&%J1kioE))jO`P48z59NhUi*0QWhc)AEN$c3 zJ8B`RxQ){xR6}rfbYkh#EG~VR^BF(=4moWc{af`5;{Fkj=NS#2vfae_X%BuN^meDz z;IBZD-N%kDgUHK;DKnktn&g(6UcM4%*RyQ5(kWLc4DDK`B-7_RQy`MDtY5i;K9oDs z@0ji9Qb$w2Beu_zZ;D^ieW1T&OgjBXoOm_NmHmP~{9XydjkqKHPGvo-61BlTxK@7n z&X=Fkzlv_aosITVyWEwN=yu%iab6?4s|@qy1$AgGgdtMBa!eGfIJ_ahYnzgVwuCYI zc&R(8I@4{rBw;*>XlA))2=f?QAEH^n97#Ds%2iM_BblQqd!(kyg_^IJQzsS%p96mYD?T3&m6})=~tX3O76;3PSi|cPUM~T<5NXd zU8(4scLB}R;G|9Xqh+Nm{B*FNV74^8Ql@AP)>F!>OzXvJUa4+==P@B)+IU(S10$l8 zkVGD3RLXq4d|c;B)=5e_rO5BRkm;-Iu+z-cF6%tWEAbOoD1$T;bt71(c+Z3)sVwiY zv2INGTps>kt{qVtgSv_O)!}?fI;`6X3S#dM*ARBfyC9T*r!V}cLs{4A~`93XKS=0n|w&Iy~KZQI*QEGtETK&v)e5|SYMq}vowP||1Xgfw^ zTFRFlgSf5@oyg%3(X`?U)NM0w}5cypK|XRPga{e3nzU1z&%o;3+4iPL-iIiqc#v0z)A zsrpl1M49nfg_*D>-&0=V@6lh@vmn`1jG?OW5X}YMst)a)qt6{jy=gCI$#!yPLM&F- zBo1L?dfBF}(~JW@ANQ8jaGlQ_wF?c{YUK5zIOWNldq?uhi&K_W6ic_qp0nv4uT~kX zueQ6~Ff~v)oq31cBd~wK(9KrruC%wAJr=3G_yM%2ttMWjHH}l~eo+yOy=Q`c({-)N zO?3VKp=?KWc~$ZE`-8X6?Mci!(D9POEHhZ^T(3Lx)KGj_-eNO+<9L(uRU zcGk3dBk8g5*}ULQy5PXt%OP>$&t7$fJnEPy3!#PA4wIfaO5*!6JvfH-b1~ooqLwvI z7{rM!PLh0<+DX~az+4W+IhxI~rT;pq;-#V3V1E#OYzV)c6kXG>Hu%XNViSu~& zD~)bdez!x2I&wJ*b#(P8hu2#1j`pAv8qo=_xqk2#sjQbVduGNks~1e1LE;3e8X^iFFaBU6n4Hg}RZfvzS+FjgjuW zpP)u*rkbw#d%<$c;2&ZXi;YsUbHPjOX1h;^U}DW zUrGZ>=7GZDr4%t6wxb)aKgoIphcVQ>*KtooiPG>;e>$qcm!qrON3Ath5Z+|l8KZ_q zYe|ZSJPHIPk2NifLGxB84aL)F_qAF_$a7U`N^>MvrmZy;14LO&TQOlN5X`0`A|j?P5vf9M>$P5Q2w_pen#dXjB-hub z2_+vT##&xg+Y zhC9$v(GXZ4=!4q0Ct?Ouv;>+jyBIX|yvfyOTpF>$UGQ-5krflM4S2l)GV#+_#vULe zs7lDY%ktb^09+Qje8n15$(0dRJ=tSo25n}2Db(>-<&k&9Uo0N%fK;#`u<@fwo;XC4 z(l1?CJ;)y$U1TLeq}sHK*8@D3#TP`YkC7L|7kSoJxf^|3dW!CzSz026AvU3)^#$Ze zg-84wn--CJ0T>~gR**mpHhfcuLhv;R@980{yON*k)2N7Ao+4#W`H?i5;Mag^76C@; zpBdfbv_unzyK+3BgO%Z)Tp!(XZ1TUgq6|jP8?LmYdbbb zmwZE@GUB4XPb!#yyuDEtuqdFb4E5m*Es~2*i-~n&u zo0Ox^rERxwQJtLKO8#;rJ_r~$K)cdz084bBTriP(ig+hKG~+(73>X1^`{CQeo^OB2 z51qW`pe`^R0RsI!s8a)VvY!KG4%BHJhRQhjunj6JB7t$FVVvx-K)(6{%doWnJ^fAK zAn*_u1M#6IgaW~D=R$4NJN#B3Ag8{MdY|75{1y<4`k^de$nWr&pP!+f%*bzT?^8Dk zm)lLNFZp%kzp6!C2X@zi9fAcPUV1)w8mP+IV|Vkj0h5YA9Oa|`>Jn*OrLR{l9!tl*W7^Bz}hv{rsm|$PbzL8(6XZ#5D9zs3pS@=Kz z%5u^9(yxbVBX;*tBL|kUOQ69R>zCBsC|`E2xN~GE!;l%PpNOT#2hz9NjbhP=$`=MG z*bd?-G~`)_U?j*EfAt|~OfVmR1t|s`a|OQSwMP$fJT-rjzMw}+J$>9Jm_7Pene?`` zA;OAvMZ~kAEwE?;cM%L#d6Co}2Gdh+&wL)H#(5~0DKBK6NwWPZ*CRIen{JZSnKe@P z@`~uQ0Rqo#gnR1TtSuG>`w>pX-Thz1Vr8ihI!TJ|$gWX(1lR0go3DT2bRD;_tS;yj z;;BXLW1MMLXPkNElOaS)LpMlqw98USyxXT%hxB`=SQp-w}%?GMl2C` z))??$Idk2u8OBu+e&UWvV}$*zC$JovMP3wt*L4sjN9#5Y=2JlGrEOmTHG() zL-P(87iGxZDrtQJ#hTr5J`wjh-ze?RPL5wt?Q z8lYP3`Tq^Hc2xeJ{yT_lkB~*J!oW59BpzugHTAi4rZ#H4G$)55xCJp{Jl$VDKTOm( z7?+mO6rfnff7+-TNb?2rwi?XaQ;I6ms5k(oE!Wa%AEFuPWW0Q_KHnnRmgYfN|Aa2i zgf61~4Ilo5dZTLU=wkk6aF*MMx&5lzJci)s{ysekq>#T9l>d9rhh^}AyoerRw=p+? zKY0cNW^REGe|tUvtxe|n5DXuz@B!ng)9(4u8Z>m%)7S%O>?nNrQ`CR-P&u=CUnm<3 z<9q|{vyag!r)>Ptd2UDcY(l@w*?x-c?%mwl*Lp+D9=T<0T1$0mW9^d%`%OhZx!IG2 zsfd4`!DD_EkJ#}ZSsj2tFb(=x%u>cfxU!hKm$q5(F8-R=ju}|iAF0a(zeDqRt5W=$pXL+$=(Rp^^+Cr%ijO0N?jy`scC0p1tTg!|#yO=3G300Xe`xFi zy0g>}WIZZ>PG^7wT&ozDgq{H$a?J9Efu3GwLeG>i?~XH`5AcoLBOATVC~S=b0gZd6 z%@3x{4YIEpADK!lU_fu{ms#?hbF-13^t&>EPH33QY7s66;`>0Xgto?GfKCr|mMyI@ z#W%!==7Z(p4gSS-VQhR4?MmvO4_;3mW-lI{>`C4*j;HtY95{T$Ij}`TGss^7$6Vu@ z2#{>Z=+S2xB}MMv7+b2&9(iuRsVE*E%6Z((cp;iJTmbGK zQ}s182|2JP&ysj>!0MK?=|)!{u-ePwl;2nqr8K#F*v{J|jElEAMbX8U|4fjA`=tNn z7>+m1=Cz$RP63;+K@)l18T;>^kLtr_%NzK>A7mJWFsxC!&V8GFdJ#3{xl_ZxZ56J) zw+-oVnY(?3j3(4>t>y72EAW1seVsKlLC3PbVD-VegE4^YI>4GGt9n+c#=0D12o`x+ z{Lu-$x~|9Vy!+oBO0);YmIE}MtWG@@l6tMX3#Rut(2fX_i)Qe6L_tzld{YB-us%i<7F^$^WYiLs?L9d>Gq5`2(-*>k?cf=e4aj z*-rhCGiLiQK`qI{Mb^Bwy^1cTx~@yij=wXE4XxbTktjAZY$-AG&EzA}CL47&cttwIg^b*MV1I zF$DItvB^^Sg2z4|y_9G|Z4hS*e|xR>tv*XKH&;c*AI9pR3xaAz{O8(%zHE`%x+iAf zLi4Ozk@UGXt}na8Opb_Y&RFIq_x=9bNKNEiw147marxBR4|QvQ)$KPv?%@XZqE?BY z$+chW?i+MaY(vc!KbLD?>h4z!2ys|u5~5(tHCTQ2J^P##OAuVoD9b4- z@02E+PMBL{<9es)7-xW;Bn!lU z$YCVAm-VYdlT3V_GJ!(PFCTAJ%(A?YYb$hdY3?4b>%7w^VtWRsu_jxze z7rriW5>lAa*CpsG_r)>ew(6-UGomUI^%*uhQGaR7_)+x~#jLN242;4uM6T7fqRD4k zl1$iQCa;NcF0x0-0x|13=#%dE+;{3F>}tl9Mgq|^qGPM^JNXTv6oLacjAguV?Q%tC zaD)l&dHw49Nv2{QK7kU!DtBFQ`lc{NHze#T2DF8%ZdgJIN@2QhNDwuQt7FE*>Z$!^ zzp6;rmsnx1YhSI1_gov+r)sempF_SK820dH5nZIDaH!My?P0+T6iTqnP>{u@lH@2 z56kHV&J8I{f0hJUExbHt{Jpv%l0r#gVptM!6*_;+$gQ4QVJ1{YqOe%>3)e@m9=o*p zeTYsoIX1>Q$G*-g>EY6EIlp#*hM_xMAJ9Q&>=TT4g(dY8Of|Yd*(KMC`VcU##2DxM z_WiOz-c}Bh(=Kfco&|DE&NN-2Iv*rdMxrm4E6Qk;6tO;-lbxWP%fB+9UEP=6Zg$jG zPwk6G4|G|Ah$fRxs`gpTpPFqBfOipav~~6(cpaN7C~$6cqz++~J@ioe`ZNydq;MAc zmpTc*T6qO=NUrUdk=mF*KBnWVgMfUYIoxm)$b;;q)<-~I2(MuN1mrL1Vf2k@9QKeU znh%>UIOlr%O<5V{C>GuA+DZ@0;`G<>MS2m@RH#D^`6cqFlFh|N5!Bma=hPk5d1u_U zHH)K6Vk}`SYLt+wgn7cN16qEcva=MbuQq2Jq)ZBh~Ce z9&}LBn4w4S*e&GspA+tEqmAt3RmhjImvu}yr zo5qn=^E&!B5KU*zraedG+9F**8q5{k462Su44qr0Ex-+&7b6?Ey%}|P zB>GBWt`O>H_bEHfRG;dz3+=0#cBgShs>E%hz#V0$Hhq}J@vlTa4S?c@_D`BNL$M0k zdKZd2>b}up#Tq@oVZcmX2;PHDLn(f)m-zPi4;=>Qb%(aY6_mj#t_B})ifB^m7;5)U z{@D%ogRz^lIS(r_Er+1E)1H(f75yx^DGNH;Sazwr>=|lNzbP!qL^c~`719qmqAF%v zR0@H~;tJDGzV>a_mpxoT5xjRx9>ywL=sxtF865p7VF3DOy~I+f z%w>1WweBjnU%!cyWQx;epKMgH$^|!_M^dESHzfQT<+ZV?9Mpxqt^kC*WeY{Q!SglN*RAmo+t8*ndTBO}1 zt0>;c;Ux=~_nRb1rd>MeiAL1ja={hnmK15mO-Xbm{`}b4)at37=I+Wk%n>ZUi@v#b z^yPEyt3He<%egOxw%i_L{iTPC%6G1!#tmcHB0Aipn!!OP3Ex+Onewl}UnPMfD3l?g zlc*Tl4Erou#YhlGOh6<0P46U|>UARtjr4z(qwYFWQlyAm5<)e*U~DR{dTPEov@*{9 z6&BG!Us^l5p-Y?C$Lts(5KTs%NbL&)`P96`*Z~8XXWwkChCUQIKcXIhK6KHy)Q*1K zrM=mQ>CAF|9z$Df|3X%Q-ps+AK+otmZAmtz=|mvj2j!?s&JRGmwTmSCiD%dmzxQOc#QJULl zpvxc7$6Q^|VBtLe6wXXa)37T-`V%k8@U3R@hcV8z_Cf$X>pA!nj2Zpv>q(guvl+bndJdbw z2<%svCYdsH;*%8Wt#bNpXG{w7;SGtn5}i9{jIN&g!Tb;~;vp>WQI~TUXLj^9xmKd% zK$CbZFTpcXd-d6E_Tx=)Dl9J%pMM{Kuvic%%EL9Er_DSvkAHTZ{j+<^iKdO_!+V0| z+84UJX>d9bC*u!R!}J$B@v+=g&JsG~CtQ(8epj-Baw)){nAuyVUOkWBaJ6}U7&Hj* z-53uXm)MWg9aCZTJ%UiwKT|n(tHRoRfOUwjaWEHZ@12D9YMXe%#z?KGTh zUJ?WGAAm3pHGkbIUqVzPzphtx)D}J)O=!8)A=b z3dx=}?-_5+dp5_v8rgmqo-VSlZQ7g7@l#na{D~i6$!xO!YW-g;m-s@lvR^%rY`Ufk z2f!vMCw3{8_M4U@WiByqlvVK8aI#M*L7P`3WhR;c6@d!bC>x?vZ$R~ z@jQNs{zjc7vu|{0c>%6D%&xE++PR8i8lIXogykoZ3Yg&eoP8FN2%OhTU6eXw34iJX zbD|*!V9dv}T+QEpX#M>eSMam*6KclmX%*d(&S7dsq+BX}2#XNYBLv&iIG7~#BK*B+ z9Y=m4_u9JRjYQLC-NV6dKt>;#U%>@DI9iCk-a6IJMKPUl4gAnserX)!3E?}+TcGmQ z_{${dk;guJ+-Zl-UyXwvEjAxAoB?t#a%kt$f98q*Hk)sZ%)Bn~t3;n0v+YmvfSW{$ zU{MSWVW-K;*q>sR-E?H_Na%G*7}n_aqX=HxzS2g|6-OQ`Y+hbF(so0VYqS2Ve|Q5k z`?e%}Vxpn+8|!5BbM4eI$4I~MwXI^~w{xZ6;a><=_M84p_M!?{R9;lkC<%~-ooG}v zl*fw%3;Rud$)@AxC$b8C2uE7UYsrcv$24D|Evp?Bb!(UDf-B>g@mM4Q4<6Ip-<#PS zW=@t>o%XH()pikFPtUA~vN@2RK0O4RGLV zmNPnHYdVK<%Duw9sNNgr_(Ty+emeBv`Rlj=R&($;qFxdwYaA3nTf6L1s|BbaGI5-S zwmRWFO_z3`F0(R{%_*;FiJ#d&DeThzqT6K* zDZ#~+Ht(w)xyzC~={v2C3+12vWSQHptBA<|qZW;4wPjdb?e-CjtPCB8b+@{F1Al3d zM9L_GsznLZl?BDpAAL} zh^KEyxNFKiULi#swvEHDB(<0we^gIL##$_+#Wl;dE0ZHUK|1yz;waw}Tsw|Jquw>0IW6~Z_?{d_L}(@_s*2fK zbCiE}zWsxUpiB;>+S0!6D1R!ow z{%Ay_#GU9y(04<)2M8g%U_g6Kx7wHu;hIMoD9({(>Kb-lcunojxFu3SHySZfG>X zPOLiv+)j|r_jeF8Gt9$vnL2D(BI%MJFu&i&>>PoSeXWa9Wx&WjH?K4HL1XXP7g@`p zF#xyJvp}6l%E!QncI(aF<%HT zoCF!|9GvY2bo9LQJ?hswEc+RKtzb_Uhe<#O;y-AVU<^}lu=G$!93(Lo3t4sEY>X1z zqj&1St3nFJ5DpD(wbxh&+PULBiWTnLbrO6vqksb5)2ll0IMQyZ!w-40SU&JIMu%3l zz}KO6v6b2Wb~&eU+$zXUq+f@KSr(?+n#KvMBt89NXd3uIMB65q9SspJ;KMW)6rT$g zM<0}HHM;J!ytnag(SUY??vUZOj2qt$xy)+=+B}`F@plOHbDawvNsy25fMpmTDM`2p zy|i%}Zo@Q>_VGl1uqdABq(gR?h<)Z!gA?X)fqj=%0pumlQ;yGpyp`@t{|LyFh0D;( z8zuZIxZh#0!A@2(aw*WsXqIzqo8_@mIoA4QGT-3#+g}-n z$9s)^?WnO^dyj|LW_|yBa`iLq)yTG@Q2xGTOxk_O7QPte;c~vzdi`!7tAW1@Y_(=3 zr271jJX}2_Vx#-;9i`9#Z&K*28RgQ9cwqQ48FqApUB1K{1Fw z$^4w0ro|#p;Ln9YF~QtnW&gpA?-DF^gRf)MxQpC}20Y*_wWEg{-yxV64FF-6?sO_7 z9^<LuNM#p-!byh>Z40QY%FRy?@v5w7_%ZIR+$!*u56 z5iYL8j{h55QQ9auCgTk5tH;H$nzvNkZItv^k@811#LV_U)f9YN)Vxx$Bb&n~Cb!zO1Yo4WuqAHzl`@Gg$oVv{oun6Jpn+{YAu>Xrc>DhJ4MwudargwdQ-xzL0=oQS(8kO zI(T!-g^F=*vfr1L>7h!iYfkNm&n<~x4f^Vs?Y(4=;e{$6$I#Grr>u&tBfObI zPbO>3wlvu^pv#6neiq}&&C1HeUt^WM^zhn|+*{sc?wD<6@7Q;_3{^M=py+NX{66OmJ4|p?* zO3>hNoqmu9pkpR%(H;YZdEweU4lBl+#RUTrCR09TgNeASBMl*8foGbfMgr*B8WLlm z3%P9kj9B~}-c@>>%2A$R%w#}>O{x(Vh5HjtK03sp9(oKr18Gu-xILx;B5p6}`KnIB zu4G(b03yAvTUQl{E-MdgLA~2Q`R2J+rE9B-bi)^&sQLYqrstlmo~lS8yWEu+?ml}d zMeMVO|BX%f@Wuoq%IKcSQ0)SDF`t3@DOh;3K{D3YueJajI$-uU=0iWdI0Ni~7iVNn zqpa(-J-a?$ow+?~2`%#_=`3 z8wSziPV-LrM`@f4^C~^K+0B$I0UL;!J%Q@k5W}vvXVt|IVWUs-E{v`xW^OPatiujr z-LPp@2H9TNd{VtBz(ro5y;oLJC%NAjr4}ycpIv3&6M;1WIH?TOsIx#+;KjFc-mzx(U!ZSGm)nV;m)-!45DKhg9F7c`29X)s#lWbHq05)-% z2b{Cu195|!x{;?ATh66p{&4eaAU0dVZ$MKR5s)j6*#Y7HG|Ekz2E9;RZ~r_ZIBgpA0xKViUj*dO83gxgCOCYE(hPqCXz+%4 zkaMr$iNMT~PAJda{DZ4#7tDo~+gw5m?LEpr>uX;gd%HnGli3HWAmv`%j0`NUlQj2H z)H`4z!Hg(SnVjGW*8^PrDeym{?on(7$c9DE8R&Wf7=9-uITl3W2{$s2@*xaKb^gKi zSh_WtkO-O@#kxG$XjqdOoc%et<)$X0<~hv$9oqIXNP5id^BMXAiiNc0@qnE|`v^lU zD3;Rp#RK>{+V^lM8CG?WolX8>2b(+0y00y5l;KAB5^!I58E}~Ndx#V zoCg?yQzPA`#NEnX9WPj@0622GM%vlf`PS6yu+k)6fd})i)a^>G0cdzZisw(nT*uM& z*j3h^XI#`3=O*fr*H}aweLe~anV4ksayA6*LDlTb$ZK+K!!m#Y{6Q)I0K?}G=lLAl zO~VGDe%C(N`WsM}Imy(MKrN!L60Aw*WS>&5K)hcs39r^)wlL+|Q@R%h$OJU|+C!}W ze8yFKloLs&+y zYp-hq08)(z^luyN-9V`5nJZrpGWiu&QfYH|Aj~kj+I`svaJM&q0aM%fo3L3UX`(gU z);qfg@{08r>>G)mP2eE~P%p5D)kOn$?+$F5cL&x2;61I$)xa9*Aeuff?;s!1VKFDz z=llUpt~Y-{2274Q#lGq~;LPQjyNEPwlq}ev`k-vArSZK&52%m11DQ z)-i@2RN*4?X!GI$VS0@b1Y+Ik9YT#*{5D1fvovCQ#cld9YZ?zFzJ*6w972`2l>_nHX9wJqYk4P>zsl{mEwI;4 zJ_t=EAub2OLi9pO9oBMEpDThj<}smFxYEj?x|2F=_9^{U2FRV)C+rkLKfH2+wVc=N zI}V$8aea+LE{M?fA7D_r?SH9xUBXhX5NWWDLHzd`%TFNXF^lBdKXqJV0pyNuH*Z5h za>(x#`UCdLdP#mY;tB>9)PO9z?F=M~Jn7qgu-?2ouyXD1y2EMRupEDJeorOBa*SzF zDkl1L%es{4)3=0ZdW&7}5BG;~U00oEKXE4v%LmHzsdep1gLO+ zrC$r9lW6+XTtEiFGI@WKNI3$UOIG2SJn*$^pV3_mE)?+3ZQ3?P1>j4_DMmxmDY}~1 z&VszI7lrQRPlcM{J~%ix;z`Kh>ZTJiP=tg`Jiv^beL?CDD0&vxH&B!XsSZH#Jnh|h z@bzk$NR^WZ`SsMW<+;e6);E;(o z=>lgY5n{{r8-z@Bz@`-7W*r@|`)+ zXoCd%J52U}xm3WT-X--yuI+GG8(41Wv^RWg<(AcyGMa8ltC{~f?$Q@DIn;YBeya)y znzx!XKCM`o}u#@gan^w=gw$^;dzr0uz%2|n9T-Ro$2czy6MYrSWOA19#mlw zJ@oA;m;nFD5jYxv2Fwh5-ikYok__3%;FEe>9p{@P@IZ3Nh;yRM5Gs(~rkWWI0M>sdn{ zCvyREt72537*efiI<=t*iruK?VhB5S=n@V0p!fo{(#>j=-2czih;L49r2Epi`lyTa z(&m`_9;E;;GASETnXcm^^Jxp?A%{IGld3jlO+y550!hltuOPkTfe2t$JaHjtkau?p zcJ$j^ej!i{wV%2Nrf8*kSKW^~EbkP)hyw<5i}_d`98chRcF#f0yqn=`-<}3|jYXcq zUv(F}T`kYv<{sqQSvp@sClp%+?~&kXvaZ|kCluizS2W~)Si0aeIQcN`dtje_i`9O! z>5}uXGvK!-Jb|&AvAq86DGRxFp>DMy8isX`wxRhQJ{Y6f`e!ZBCyC+c0=U z72{�ir2ihZw4W>^aJAuRHV_o1LV;EQHK_STLk5A(fuod`;uov$M86;}YS1T_N~x z&yg4<)Ojdlx00fWrdK+QdLcCEbtCoDnhr%4ZA(0K>s8-FwFZj0wAt~{9bTpI0vZNb z>}}wVbC(m5oFnXVZ5dx$FRAH+lW0)agMpUSPp={Ep;$(XD1&Y+ zkp&ITg5uA#HDy4XEAvr3hoT2gEv}!=Ykc-r$zEfH-L4Q9Km)I#Sq;MSge1^+I6*Wh zhV6hS^B^hey5&4dEBZv*O#oL1551o6HP$Z~apfV1>V5NvRxxZD+;AR}uLDUE+^gKs zQfXhfTDg`#6>R3EdLCbL2FQb9k0aT=+yV$kFB7)W;PERDnrf_ZKN8OTTfEMm)U*eH ziYHSG?#2sRq3FrIuYC(wVCTY6~tAIl3A4VcVTT3bnv?;0A_s6NCOYN=f&o^ z3OJh5Se4y26LL{-U@T22o8Afsgyc1(03&%aVQXX}e;*e-Mg8?S^ilk}P44DBSC#BG z!wP_F-tB!@AR@&=Hb~@*tbgz(40(+?*Dx0zzhj?at%EL}$Fqr=^U$gX5CPy2R=O|b zgNE>Q!l9F(WZ^t`o(u9gFbkacm<$u_&dO87d-mjjn>QN`+&0=vtlDQ>`W@#<$HCWF zbeC%reOo#QL13&B!UAiYaA!BL`XScxW@m@6`c{E23c?BR7VSo&saF@Sp1GJm_1H5Z zyh^t_M2UN2dnd=X+UNqXcB^?a5kfI{iH|0#z=^^hPXf{T!{mTQtvH?hV_c5+d z=Qf~KQ{SjM5~gkjWo8rMHCF#rFjE1Ol>MLAATd^?pwi)dSTT-lwM+HnZvo*X=?kJ@ zINE*9|{CGy4OBpEe0stu9)kFEUf2zAp=aJUmv}_yl?;9=LeU(eQwacTWVU`*Z~LX$UtNF6tXB3M|QVdj9Qs z6Bux$%Lkeb90Gh~T0M@o#(v&vm2*AkW~iTxPj7_uyxn|&++40_ zCDlOe1g8$0j=skBzuGZO&VR-oR$c3dv;wSfW^vU-J!tgg!^S|S# zb9YV$Pc=Qw+%Z>0-Di-6MY`Sp!POs!yrU{i-RK7EtbGI_A#SX$_ zH=WN6MsAa9n>|r`K73QAqYUlO;Cl`r8&v>k{Ol;}W%=7f2LQ)J0t9MH_Vm8e2+`!y z+0}`_cNry^ngY$KCWS2YtB7X2qqA4d<+$o#$hI*7qd&> zVzYyQ&HDUA1hA%Xa!VBowPgz-9xstpoi-aSAN zju#=r0g+N#HvD+o^tRjvqKT+$RMmng4Yn`%={I5R7Yp5gV+E*mjyMqwzmHlk8L9N_ zc*0!SYydeS-5phh$P+&w(5~xawi95Q7wMt~Yts2sspd9g324z)dzIAzoV-#Q$FiT& z-xX}i=3o-gZ`^eaewBAe-AqsF?pk7!obcmk?(cY2H)iDi-MkedhSjSGlq5 z9GX021+G41vY{?>XKi}u@QYL?5G?P(4aNh(wi14OGqivUB^B8>CI<7970WG{PAsZO zEPc5JfA2Ckwk#)ydU9=T`mEt)sgh4qG?OK4ChuT7Hn5dCr|iaMZo~!K9O|L9wG*3$ z?;Coc!j2x%U|)f(D=bvFLX2t0mbFsn34#~la<)u9B7Y1OA2u;QVQ-lP=BTDi-DxeP^%di-h<&50^kW zfxfsG(~c@Dar+g2*^YIMv|C5w>i0~3eD+$%)Y*u0xqeTVOeO^TC86HObQN-`dq;T3 z1gJ$g+s@%))f9A)RTAA99h4A^f9iNQ7CLBKJM6F82M>;wK-LbLK%Rtcw-9*n&2aJ1 zS$NP~M}ORPADCKBC}t{e`Qz%tCKco_<5M)K9!M1CRIw;K!I^71u;blQBzK|?MD2a@ z9B4}b(81hzYivji&Q4S;V1C|-9T&MyvqU36B5p#L{R}*jlLB%q@O0f1Vsk#(Sv&F0 zFl6q46}`u~*B(L})05_p%h@#fEBQxgqXq6JxC;Zqzfd3IP!nOE4-fB3y9v{%?cu0DgE2?% z6fO<}`Bro`!H+4!H2&8;#4DaiG7AeU_B$DC;FZ76fl+TyxcXOUNvv`_>5AT%5Dc&F zr%(^TbjS3FTO}}o!8>`Ek+2?6H*F=>YG~nT3Hu5XRuZbz_QrYxz6ia;K94-yj?F@# zQ{@jP6L7VR^e?2F8%YdN+(u+=wS6*PRLb_p_0g!xv|^Z3`FT+>Hs>o?*p%Th<5L)M zR!_fb28ig)9e#@wM1`rux zbbUf_bOI!4KL=S9+v@Ai!ZZ}SJMc)&Nwe$0-!sS`P324l2mTXo*)MFzD#TQ@>&fRS z8sr_uc}56m4|1~E`p~02+m*SDt)M*_!)*1s0|~*5PDd!U4yyj(SqOR1-pvwBXEw|Z zCIK~9d?030FG;hVb2)|&i8nd+OT@> zfMNonJrp*HVd$1bI3xw@Vp?jKx$@i`Kk88s0cp6|cn1gtJ@%nAAf(-~v?Kx{We4m% zLyMLq#S$j0pYh(N@W2uvWaUIhL@dJ9`%Z?CzXJw@;Zoy&fx(fUaMg#vVA~!3(`Fdc z^rA=z=ATr|wm_GO;-<*JJHX(2PE^DmU@&uXA^9s{5I#I+I0p=Bd-{i5z<^uA@1#Kw za63r_6zD-1L9xmLxKAXG9b8^vqZiN*2C=Ku)&2;A+tol|u58pI2C8cNzdV+?+Vf6=XXP+B^C5t(U znx$kx#Uk5BP1{%CY|DrFgN-+9&hAyaR z>lsn|Kwtc~m!Kl0L|KS92oLgYkz^V?_+;4E znEPDTmAymg%L6kfxM?dTAA<+0d-P9(fo1V_{Dm+W9x_?56nzi;A$rno90pd);9?UI zREXYz&trp)rJu9Sv_6LiyLzO958(kK$+boS<81oH_G8lq==Fw4memLqG(E-YC>U?? z4*Vqq3{Swc(a1-k&ExPI?knib=pA007>2^Hqb5b zdmYE2=FJ{ zfz}*BljyYTz*K*Sk?#g8VZ#k8hlE$aQBM8KYMW!*GI@^(Zc&Ku% zKbjM}cLi>5cSNBW&_nNb@!%v#`Bl%Wx^KXuo*d3g+YP-=8V*v&Lis|@yTz~qLRy>V zgcM)p-b*TL*T7)9cOnasFoY0M)2fOafL^@N1L}LB2MlG}KXhU%o;9r%L;%B-VS?JT z5Q2B`E}jO777v;p9M`-m1RlLjdn&&As5brU;RD7;2NHvW?gXXw{RX`cMP99e^2iQ& zuijJMfxP$%%KlrIq7|B3G|Y;tGJJ*Txbp#Eo}?!rIyusg6_(LVr~~`RX??H~UNcI*!5seRd!& z26=Ft*KB~_?w~F$D*@fPWcwf@90<2gR#|I-Fs(X&?mzkFacMqFQpyYt4a2|BJ@(t!C)BSW$FDkbtg5=Z!la(*7@Y#=_+wn&g;|nSf|6KS;f5Fll$rx3YOyw zM}ath^uTH7_l<$UoW_=z`Wb?YD#Mk9=SxkLFP5M#!Qsv*}a2G(^i&7SDPcXk7 zUh$XD<9D9U>3Gug!ei<4n;&-PT%n z#z+Oz8T9{ZkPOD1+a->!1?cFi=v?>_mp=NbmTU%mLuei+wD@}@~uZ`Zne ztf-;u){O+s*W{lbUn{7s`YvW*PsBoIHnwcAJmTeQ{J?sG=6P>dn7ZnodnrNlh`goj z(nHl7@;<>VXy5Lnc`tl}uPCcb*8$s|c?`g2{V8lR9L!&eL!061EwJU)pH#(H@-n4D0>RYWHJk5bpEiG2i(=pG9pVyc7gvDodHp>4fg7!~*B z)K8Bib6Jwe(Q?PVnu*;_3()#<$Gh|y!oSPmN~O6%UAbc(eU|VFzN6om1vk1a5RR8S zX46Y;3mvm3OMAOWLt#c7{8RId;nuh#{UOZi28#jS-*=!~Ph)cY6?t%l+Yl38;!h-K zFrL@<9WjsTfoB?_myzVK$>!cJ{GMQao83SsXpp5WVLBFd&TkM?iq0$^dB=8|pdlH; ztT=)u*Sf~l8)JJPby1j&MP2n%uj}nX%anwIKiU7Y#8p-|;0;J?w4Jiu8b;74$DD&! zKZ54Ib(8Cr4MW`DNYe=Kv6y><-D3`Zqti0TxW{sLxQE>Lm;}p=u!*_7U1qBlVcSN~ zEE!O-dS^BvVKI+%&U7BH4tN)Po0f=6;rW-Ah`r*5cqv64LCQlSL7?3(s{!aho>f@SAJpnsO7XwtCo@>TG2(?e$916DmH$s=`Z-zT0kMYtRFkp#E+IY zE#xu(T=3HTJ{HSg1c=}yLG%C9;11@2QT0pndswVxJ$*5$1!p+g+l4b?9gk}!Lai}G z-iUn6RNm+;OBB3_vBB!`zsJJ2BZrFNUltaW_d@YLWTu55{fxISm?Y|lTYq*r8t!r^ zZ816dH4{ggmI&XJJC@UZg=6K8g>VH2*n+Z}2|MWU3`K{aUvms=`Ox(~<8?V)iuM6x z$WhQJqQOU18u zN4ngimuIn$ON&^NKFj@@XPEF{wt69tT2Yg}fuNZLEzQPO=*p?*YtokyG`^)QWUIdl zRt*RAZK$03sAeL$x2rfj*yC+mV{8Wr8f|aauG9r^4NrTtier$B8}ExUxQmVI<~mA* zB!PaoK-Tr7lr=iI&w8AoY3S{eszy^I37V-o6spBW&cX^5F}B$R&1~!J;RR_khl}p9 z0>XpCS`MeeyagDG>Pl+TVd|FG%|i9rk}TvOKlWIe2Q}&7h4C6HtFajub^7l2rwc)I z+s0BU1P%Ob<2bnNx!J9yrL4xmkUCCHdYF8H^rwn9AsEZ|V~fs2R;6cWyY(NB=TTH1 z{mr$X2uH_RXtuIUhr9pK#gUDpMhCbE7bI~&k?$;Mp9xo^%<=2YHNGG5o?pj)wnJtON@4!p9sRvx&<2Me@C9f^J9Hjb!>`~_| zY}p0RMRunaq8DJ=UKxJ^g`Nf1;dF!==EJ2-?KN;WQ-6$YH$k(Pys)Cx8O3ShlT(r@ zv_JB!S=Sih`K5&;L*a(iWVjqk-=00>@!P)2JpaL2GCH08LKF9l`eFP<{k1OI*s-NSKJlLp&|r+$hK~Sv$w0;=F^~H>t7p1LSYXRN zmQtiw``u$@?+s>L1`iJZuA)2HdxHNjTW*Sp*iC9gIDt03*AlO{W>9ZI3G$w34duzu(D zc2NV4`Po4ig559L_h)JLRetV%)n2yK+d(O7sN4kSX1*|j@{`fO()&Ft^fz49Jx&ZM zba_tQ8qF7#r=Q(TFMs_lE^KM&$4WnRQGWItVe3-D;0B>QpA&;4492Jo!>#a0!_$AC z6EjOWM>XZX3y}cO9;OjzJV-Xb>6-|-68Z{f+&~!Q6l9C)7yHma;>5z6*$2&3vZxpg zDg++OI$TvcXFS!gd{VuVF!)~)@C9!X{)$Iqj-rjUjZ6=C6J{gC;N4}eL4&=P$IBVp zlBi(|o`mc@9>-#pTuCy&y9orm+B>&5c3B%zPe73DJ& zM+$>uJm-rWC!Qu-enveJ2lmYSwhEK;iq-ppSKU0)uHH|)8Zt?zdOrfeKss_xEX{oN zZo|9#ry}Au<^#Ioo3k<@JK|Y+dih%z9OvGaVtlTxH7o6-TJkm(s;wQSH54oTMImS`JsdAk7&N}UkuN<=7PTqXyf%2 z@W!sI*usQYv%RQa!_l6j=H(UVDTeO%-B9iwae1}f0WBIldowxt{s_;tvyLqH(^CCW z(o}VWeSS8gmd6D1oTaT*5WZ_}4Xy;1oZ2q_YZge=B@CR(x-Da* zwS<}WDDKF!fFI#$ZpqU=iYifUHh)H2j*Wt2*gMyolrsmm3C~gv*B27MRTSd8u8tWQ z+m_pA3)QoQ#M&gxu5zWv_V1E-r(D8Sg$}pW@gj$pL51M=%ixp+;4gU4(v3%!$D<|b z%$6VpK?8b$d3BD`$Glu}r9!4ej!Olt{#75XdMv!bLzYvJjVA@uK;hwX#u3@zhvv&z zh-jF!{IOWbFZxq0xF&51hz`18`ybsP0}f5~LGu}KG#9At4curCz2&$S)Xi1q1=cQ{ z(b2r6LR2Jd{XZhY7frv!uQTOm>lGHm0rMJbE6(@<<|4m^8I!=9)(kQnK{Jq}v_YWjE0|gjgR{GcEo|k>q#Ct>YzFP+E9xQ}s2NUHdsJ+& z)fqmEsJHdg3$ksEw(jfLXahP&`4Q;!rNLDnxL*v42?mKE-zkJ6LLHpqgFz%*cl5rL z;f;19Ep%#r=M`3XQrOx|B8AS#sVnkE=QOP$eL)y}UAfg=!OCaoNOOv!-{E{xJiRkA zNC`2*)(8?VbUx_pqy*}E%wp!1pvK9m@F!*T-bv5QH2sCPNz-NI?LeuM?*DK~(+2?zMf&Feu8 zzvxkSG zQJm>SM4ZSMjZI@l{ACSHnrS~BrCl=Gw@(`dnggI7Y(cC7e4MgK*L9;p5nt348^^9{ zL?gES70&p4!XRSV`=a@SEPqLXjZ%2T3(fD4Nn1Mmlt*4pCLHyxnXkLympn)=$d<+i z)4(8_Lrx5-6t&&X#`bGa-Ok&z|}_8*s1H2wBhDi)*0&9BKDhJhFY7)Jyw`1=)Yg2w|&Kq1J+#v`RI8 z21Sn!wl1(;MXZOVw(E2dC!K}TIzAZtH|PSoHyYI(sAURU=`y}%Gj(pr1!jm_k5X)T z!LxP9;CvepGhp#Bxn=?5`1*3h70_u&EIEp~WxTe${32(3pRjcnX-DV_T(^WCeluU- z@8Hyus(ooV9r`jEgP*Cl#*OhOed=Y7p?BLd1i|j|q1Jt5W9Qel|zg>O&YT6SfZKXSXTF z4c`z3-{fbb!PZx?zz;B!`F?14eYGxxe3x4@ECd;5$7~!8rMj0~M$2@X1Ot_dDH%PC zFG@h{jL_6>SjJ#xXqttsM@dJi@Lqci$A0H>#s{IB(c7qCon}Ybo-;Z@M)WUh{{f7V zRFD~dXmP`H%{E~xqEUcSh!_}^?mQu`s<4MXb}E@LI8u;Jtn=D*_M&tD6=7>;^eV)y zHyeBczUcpP>s4AhG3DU(8)Wsq!@+UHjjWAP89hGeivPL-qTPDCaa9>TsIgrk5EKg% zqaZs8+;~j^xf3zLsxj6%KI)Iv`V$g6eRDDi+v}hgShPn}e_U8Lv)A~A!-Zhi0hWIk zF5wf`W9w`FJ+@OnwLPx!-r4LlKQyCm)zezu>5rzJv1_T0Sm#}O~-nLfHr{fu_3H#yBF%TCo zWdu2nvZOGRpy<(@r_3)*AqpxKRTOvLOz9;h;`*by6*80xt|p9v`2OUnaP;eCKa$Z; zOV^S;`FX|wgDac?+oG2zX&2UfR1w2w^vJAqyppX8ZI$K7Zxn$yS=5o8Q)LMu^Eu-& zaEvzi4&JkB=CB(aK+?1nYnKrsOg2;JfL$*3s#yNK%ZkNUq)jFiaFg$d{m{fZXU#5Q ztFv~m`6*}oe{2i$I$Ar7pMeiw?JIOLVQyUm>Q82UugCm^3zKEWVZDgKE;x`B8zg4RK$R;cLDASflt-+o!m@I5H zX=&$}>Yt95i|FqJTK<3rFK25)4Dj@d0UIKdTT{)F%8A+?)K7a%M@|o_du5$24QZNb z7sLr_lPfWC?BE@GQ>&<2-1u{d{>aZ=e<~cHYsm3hBK&}La>-T~2$}^rFzjuq3>m*F zYHUh8HW_pWJc-fARiJ-3K;Nw)z92*lhGpm7e9=yIvowhOD9E<=K`Ukcp&$cK=U;uh z^3~m@*5P#d!^+Pa-PnEhA%$G(VW~+2p?vN|> z#o@ue)V;rcrBB!~?5;E%8~mYi*|dv-x~5#s47ojKD&pC!Dh&V2gd!6ywDy9*f32xz zZA9EQ@8l;jhX{kk`PuCF;F3YsIdvd=2k(k;8|WdKaPs3;>?p=#c$46HixK){(N6eCYP3%)gy~HB*IIap6oa7xJIrhJ}Z*-C_u`& zMBDY&RbAo+YdxWsgn_Lf4MBdD|yvKGVh># z>N@IwukCbBpsSqa{~Im=aa$^7s;T#a1jKcTm_x8PA-fb>_)6G%O7pFIaYE>`8;tVV zU`y@xUl7!gr8!L)%+q#Iz=A}qpxEF-crV!VwjCqv?l}mK&?SYb|3|;!tvaUM(^CKx zU`=ts;ORFmr>%f?N$DEy515%$1yRN5gFMPn_{3AagWFD1RF+AdZ?va-}Ag;w-ts6o?c~8hh|-tfal9 zNdz8>oYG|1(YAq*d!W5Ev*lwHKiH7Cf)~KS!Ww5vnuVH9mKPWf!2!ee{8VWRQ9;(g zt^}Mbe78+MS8PjaN04RoT06r`M9fT1y$l<0$faK$(_MMqI+=i|V|rs_S+Yd4*Sw%e z5C0H{=a1NWraVYXFnFG0imTJ!REW+dJM<`D(Jo?@24<`oe4m94HuWe++_OpQ`~<(d z2UCMR#=l<9ep=>hvdw-nehD7dF`L``XahT!o;j_{Xe$i=;*66GpX5pwGpplyo7~wzowDs0sEcg)T*Jf`rYOH zoNsgZ9T9X7t#8d7^oSuLKist_?MeO9T3S{_`b&N(qj8~2rnfi1g_<7JTqJuF zJqvUj?R&#q!k{PkNaX2;4b&wVaMESKc!^HX=1Y!)D6NVrIY(#9m&dFb%6?kwdbs!; zoA_ouQy>#5G)jez6cM`gZ|i6U?^FC`aH}dZwAfJ0ld|MwgHy<$=BQ7N#WF8Bpl0>3 zdqfFK$iobeSR*3j?4s5;2b!g*(}Qho5Ze^I);d+J^3zXzYn(F_vWcU1CxWAsOIRgKg4wFS z%q<0rx{CwW@ac;f$WDOdnv-!L(z_4X?^yjNdirDCkM?f)H^FuIdRV#;-SDM}+;*56N{dq`+w>EQ!!N3xGyQA-(fP;?nyb_0ELP zWwy}xza+*@>W{#ZPHb>(A5{}uTLXM*3oD&?Ieh**XZ?^NIU42vu7D{lhA^{y@&UqN zPp{N3drX}ttmpJf55UzUVT)(4^f+7<3qewb6@6ziu_{g`)%uf|00LxM$M*kY*av|IBh2!oqJ(iLP2e9(Vyzv2>ZbH))dSCEY;VsL`>R{wc_8*+rfrIe2g zuYvX@Y@PP>aK@MW+euX{0B~z2d!t2-It^GaIxUr&!x@L|Fi?OIJFbE=9spO`ljlSg z8`etC;<50NJZJUz>oZ&i_){NepJ}%&~K;tfiSp@GLQEE-DxEZ zrfGIj9&yGS4JT?|;*1N-pZq1=q$8|zVt$D_T{R(VJk+A9x$WAP(!Z6jMPR+f1=HT)j7!aP%lRJGxklKWCcsW4vr!~FPjRM6Iy!6n zS!U2u4;a>%%Q)j`0NDD4GagTfuuagpCM)(%uOu1!y^a_W&CwAdH%2@~W%VP^II<>3jx zn3C2EcNXLT_tSIHwy2d)?Ge9;au!LFk$e~5+n z%dKQMieaDHO*30dZhgg@jV^Xh4U|p0mIU7=(eH(OVYg#x*xd0Yu;pA<79e#;i`O~w zZ3hdICB-cN8#-q}JH~c2*i}8$>Nu`Y6z7de9K2RwF*RkrN%Y=<7g-O_uhiwe%*xL$ z>VN;r_mDJJvvJ^iVQYmP=gU8ncLGEMdJM%YpgI>GC`?hma41L!r~TeemM2hX@N54l zZpX8}RHs``{ao!zY7iu4Xal}ARd*S~&*c#I(SA1%9+%hLF)jq9EIkL}MJ&b#p6u&y z7r!cB&R)r`a~Mby*4&5f=9dly#(MLwx#A&6aK~N%5K0%xO_Z;07iFg89{e^!MPh@4 zB2crIYz};M-jjA6w6o>dD@4_QlL65ppMu>tm?kunpwrBoV+JO0ZpI-uS=c(RZWlq4LRQpL z9Kc1?Y|=QX%yES#ZO(wGcd*l%oa%5BOUen!(VjKW1Hlyb%=LOXQM+P%hdBUq*+H2m zq<(~I!NTB}SHWJ>9q7Nv;ATER`<)h}#~Pi;wxmvDg*kdDt(l+2Z>0B2wXc9ZTT@`E zs~_Fh21kj;ZNOfzYUA6D#38|`o{mJ34AOhY_+lgdXPZThwOG%K9Ddqqbzr^-P4lxR zKK$nQb~o9K%J0@+7}{C+ImYLhec*A|!#C{}E4?pe{rqcghWsZ#%R`|rd#AA3n;xr$ z@@t|=)csKYHfU4p7yHK2p547x{@Qzwd&(QA;0gaZ-YK#0(oyZ3o{q8R_Z)8xB*XXHxw7u6BMyW9(aOFxw`F<&f9?*RB{!q&}nB? zZYjAvr@*)~bQUO1O`teMcLEwLcJFI>f$QhOAuZGVU!I7dN&<& z-rX~=azWLH2zbm|kO}vJ)ZX4jUI!p|xmRQL*nPi>x_DFhLAZxupqnaUqB4tR+o31Z zV0u7&va%qF`i%Vc)Z^Q+cCOf=8<6KGyHOdt{(?)NB}_G{3OZWA-E&raX5>e17FX^% z5LHQldf`9+8W$@r>TL^?ZY(hEJbF*+TyM@PNci0K;&b-Q0=pAj|CA#S zbUDPQx=)8vwEy&PN>0vBt7fx{d`8HNEy68x9fDHLA4u_m{j&DJfA1vlW;2=|ef{81 z&@~u^Q`*n`-J$ms|M@{*rV7DytIL9HY@HgPrS16n=9r%Ig&}h22n=OV;}Pv2P^F^( zz2PnVdTO3fB7s*NWo=;r49#|bXVE^G+s`An_nyCGTXtLo3+sT%aVNBUls ze*$(##`_yK+Trl)>WsIKUzLC4vC5-aU$m1DUI^WqWyI8M0dCgUypHmyS-%)7U4gwA z;>nES2Prz+QB7wx#~=_TO)N*G#6__pP4jWh2iSoU>Ecjhp|eU|fq&v*;YvlRsc zUYb0hE?udvBSOz;ZqOqxlF+D@>!Bq&GJ_$|tOIg$8MdvVlyxv7rZeuzMMAP$L=pAtMh5D zIZFEbUyW@=Lh6jzH~}3caD#BO-PEsrFAUY3*@%R%oQPRL-Qwfm_WFURQ~m7xgK5Ih zMQ)^PXEwT?Z`OPP?>p8TD z&zfIQ6%Wn(=1Yzm-a%>{QX~gb!y$EQpjbOmiQ#>SXE+02QTHJID@bp7|7-4qYaspX(!k7}VTKPgm$;!dBN*LH{etIpCK>+29J(l`sR` z&hpvcRt)Y|<~@pwd3Gp9%2@lVTVG67enI7L2}0;@gr58X%~n8%dE4OTI^1|dOQQXd z>jw$v0cZ@y%{U1ev5+CX1*DPT@;bC-&GmZre1xAN52vPsAiFA;~C#dbHe4@y=k_AiA4ZC^?C)n%!W)*jSIh3hHvcA zjzHww$21p^AN>UsJDQ`qi74~Z_AGyU!!{o;AOl zGK=vukSO&iMUd9*Pbg3rh$wTFrKU-SZA{X-Li|gHUgn{p)i_Mc6HSic1M3`m0ZdLF z3~1t5mU$lUN8>^L)PK();uHLz=Wo3FeO$7 zb*|0B(N{P7TZ>ldxCP|Mi_1dl!tNXF-1$dtCaj3Lbg+j0uE;;s+i{#fY1(9>Z_({u zJHQ{)`{aLD*nU|Uy4BG)w)7y#jNNCiok8C?aQi_2*AOdLFuR~?u6w4Av^4)@WLl77 zk?{0Rf>1tJDBIwk2YJigGuj9Zm@XqTy-hLaRpPO=Jgntq^2pYqB2V^35yHh<%uMi7 z%Q?}_2hG$6)Zn!=+CMSh*=!;iztqNVBE%YEJ*Slwxegd-GJ$H$+6zPW(Gj6*pi8N_ zzvhCIN1lNcY6c8QD1>i)A5xzqJD?pjYzf^6g%*R0`gS88LQ>JBd7&=irfr&|m62;{ zn4_Wx;hAS6c4AK2YzXCepzI42*&WblFQ^%}oWETe0%I4O94ZR4P6@??ogtzy`uK$5 z;}YlCnPo1#6;T(RBX$y|^%tm`Ctqu5fsyI}M!Wb>dFY98w{Dp6~UGB(umg( z&BX=wz7+A5yCCZZWFZQRr|L4dUs#D&{Rjw%m42!#Nzqo9Xc17WjSlMd11^|woeW*o zHzt$ly$%lPZ!f*t{(-|5y%@S(=VaM)iI zW^?SbJVzxwB388*t_8Z#v1E4X#v=@asAKN!qV# zK9Z*8RGYX|W)k)Kh42>YYKXyUgwQ(G2m^M)(%)vkDxcx8lHKGG-Q8ZSok;;)+5hS> z)gwXSX{dCFsV#RUt|mqoRlG9pI9H_q@>x`Rd73tI9K0)mTE|yYlxG1~nCWjfzM5Q3 zTYHRoqx=cw_%n>td6C@d(M0N*Bv<~zCmw-42MkBY+rZg8ZPfe;o9QdLB!xh_`R26} zK=ZjQG;h~=K?wZ$zd`K4&#bXCB-hx}FILFI47<*Wm4Ugx28_+OZSB)arH>}E&X_)< z@3nqJhjC5tvMyKGbG6|$cJxbnd9uO21`A`E)2^4XVNszzR}1ipnUgx-?jdPp!-;dW zb;tM_M?m-)EM5M$0O?1;+}L17jmm?+n?w5`GJafS@G_&V0YDZ7 zQv~i~4HKf{?Lm0JzPQwI&tlDh&2TwgLpR{5JA?VFTLjowG21c8Mo>+jEqT#mI&w4g zV#12hPnEKrm79cZEjdB%`I%}wzG_6V&WH|O?HjuC-Qgk4zL*(K&HF;HpVP@Jzuj)N zgt-@HG9A1zq9#$uax6xuFs5HlqRB49!=F;v0|wE;eCh1?WK!aqGOf-jW`~}d7P`(6 zi(17ztq(jWO3Me|vu@WK&I6suDf@zZ_B?AxxccIOQY@nRFxvVT2?gH^ZHw~jzt3-8 zn%@X+W@U8MxypHClW0bp><9-$$lZAbRXev|7!?l(24LbAUUCOA#9(ep$YIN{vf2~Xc=xn=^&5$nVXh~@3w1Y{5}x}ovVl)TfR z3Z>`uJCly|Zh-XI-nkVot_XVSpcNOA9XODi z3Sb1t^#vp`B=tpy^acP0hh7)hdXHv9QZ31&H?8fBs~)NDpl`O2u>PMzU;Y6>eXUo7 zp!_uKf<_=}SF;IRz9LAP;UHL5<)5rM1pEd<;LaI{!mob>QM+rM`MeO2m1@Gvlv9B30Ofz!lcN8n#iX&WqN@Y!Cn zA>DAYI-=U(*9&vSh77ic)yNz|Bc|SUO=h~~AC&W21 zC_OD|aCMs4RO#&N)B%o<4NktXq|muJFTfPv@BXKgW=>9%@zt@l@AfMeRn0xD1Vw05 zknEiMg~)&qW}I;FM^uG4wtu-UrgDQjB8nhP5b@OXKN~ZsWA0kR%y2qsqW-eKY7?iCnFGbmP&_*p zWRdRadcP4)>2J9nz#mJ5y5;dyunR2K^;I{=G)_RBx6a8|*Ie~$ZZX`vRi=Iu$6F04 zkK11x%76$29YZvb4{t_DV~89bjfkoG@4Mem>rGIJErb!U$7ix%!ml$vWdueGcD3r` zplv)bQsoNLN(3VlV2aF9UIBvhH1jG?z%cEtToIKI1!jZm7hz+8S93?qpL$XT6x&F$ zXNewW9hblC!mvvgn<7opWfcwQp+p4?dhd;M0wNRou0Bsx_pWfF7A5mOQq|QQ0m4FH z3sk2ngGCvZ&jr$|D_ps%()lex{jx7sYZ3#PCC_!Vc+BQ6VM}M~+kqS!=8#zC!ViM_ zJh1Q(&gpRdVI|fTMnBX(@RFuNC02Y`l@SCs`GOtm748XkD&OBJIQ}YcM zEBoHC1frMIiS?e|8~rS~P?;dhrNl#-9?dy_n0?(CL>0lj8|V9rRcgprL#q(Ad`;b& zDy+Gf%(37RmH|*&4U+>lU5`qHlxoh<-iCoapj}AC1GNYwO#lefkcRH^>ak@*LJ05) z5~~4GoDM-DJMFTX?a<^j)HG0E0oT)xVrc%vWXB{K>1-hMoCr;s*GbM{gXDo@${wH@ z)GyFx0m%wj5wMF@e;if>wj-g(>YoLbyP<>#8k5|Gn}nKq{G0ZD+x4b;d!ffT_mXi9 z?CdY)U&hyaaHSptA)4al;={xwXiE%j@e83&CJ^9IHulV~@pLMy<&7Px$ub^?<|cd> z8aJAe;R0WBm0`kd+)t(P9pxHQ&Lm^sNgBB?)II8%lpG5t9sEEFhQC43)>(p({HXEx3Mb8Be(B?G|sN4Yhm%-V*ZCb2B zBoXY~!*>jgQpGOACaWu|K27Uj_yqRsFVY*Z?-V|c@DW3Ukds|_KjgBuD3oN(nl@UtYYId4wCJI)&nE>74zlb-V0@iFT0u2`VMKVxUCmZrc zcKdE((xxA7ce^`i8zy~7J=txr=>}&QekwbGADdkFEy(npAXJ5osopeM8R$CK?G?Mb z!Png1WFy5%wV1bbv!JJEj&d1ur25>lox$J#bMorK)KAk#YxS-xIIEL(?_c=%LD)C@ zC-!`K-Y?3}*!?~?_SL$8SYgI%Pl5-eB#&wpv!S%lPkj|4B)5qz zLSG69-!L%icscLut@ExH*PfjG%( zEVgoC$#oAhJseER#Ub^b(VZ`NlAR@2igjfw6BlWU-4xQl%&?!j81%Fo(9yHNGEPsv z&8~;9S$i#*1Y>dcS@_IiW2htE=`leF0o2iB>nuK8CebC-uZ$gZYoxy#;nZV)PqJyM z(lzQ+CXLsSFRhS?UmLeqZ;NsU8e`GNdof5!2(Cm@B0f z+V%fHFPQo0k9LrYSM3x#C}$>pSMTSSyiT?}PW;5Q2@oPEP@91)gj-1Q_0V`=Ak6Log5on4K znz=xe8g!>Hv%@%1?IxId?wqf{nG=0QFd>A#<6r6>*JtS_ei@GR(c8VQy)>j5Q||qq zYns*37~8E>Bp4*?0`hWn+9NzKr9!#K=WT8J1<}JY9~7h0Yp|ESPk*YKk-Xzhd;ppM zG04*s&@2|2iVS3`@eJNNK?cIk?C?uMU?=Mc{6zb)v%ZU%Y`UMaF7`6E_l!m$>4HYF6X?tCTiIPlZjCsQtkDm!+!cvak z^pXpZmX6#hH%;att<0|RQI2ta2y|F0+Xu{vFM{??PD~WXve?DqT-}oG`th^cC3=NY zEJ~P1Tdx$y9=gFC>Zw+%b78J%?n!;WRNOL6Jglh32buk83-}lD=`aO3+5?8?qZ6H@ zbawywKZ+?y&@;X(^pgmWt}d^}yj^dd$$wA7BDcr8EK~{duoM83=EHXi&vzu4YO)k$ zBd>3Sjy(LfG-)FjhBv_r%kIu8TcdHNZRz6xp~W=Mnq@hS6mo$=Hl*WxWTEcQFZ5w9DLsYLs5{yWh9gw2Tc;l%wd!yVxh3c~u@brJ`e%0eT zBsM^i(2ty2_K+6jr)8YPF8;8 ze&c|AVdWzD2wm}YCHU&vr(qnJvbZzS3e#2aph^>Q*lgz6*3FAiM_VC>P`;6s#` zdVGh)tj+e(KdQ}0dTrIKu{G3LWLrpRL5}!T;2^qJk1Ap?tKJ0^t{o{Zvvq#Q&aDm4 zv#9TPS#3?*@-2F`-8trf*>>%i5AR0p5~($j>Qa))7JxY%>IMB8DHYdOJJp6dh#4>{ zA6H_ct~&Q4s^yot&|OQX^upg?oTu(x-)^fIxfgJe(jjJkHbpHPXSAD|w{ z$AteoJE`X2+b3nVzE;WF!|EV)A!-LBguAhvT|_(}ZK)up^~fhHU3e}P0vF9#P9*)&Pdg5ulSLD#ZmJ*sxC}cprMhX7vfa2- z@w1vbmit5SQam2!QAvXp@lY1TYb%=YKQxO@!@*dJD*1l)mxr{RPcG zrj2Xx?=5nuZ`AyATJh9GBhI}?a(H}@{e&i1L0vFWu4w|fma_b6>K0G< zoX$~H_e9g)CBeRUq6w(nM$1)7D(ytVa6_37*Yw9@iE-`nEdkHP#$`BXG`>XNR; zJ0LGhXAK{d*o2HXoV`9M)PT_tj#=U@bt)q0VkJ_MC?Vne)b@#34CXgwyTvdxNcI2a zkf>2lVB4QGCF*Xn1Mqd$e@s?yI?N=G^XdGDPGugE^bb6)!Aw7<%nn}y4@H}HOU?SE zuv`mqR`?-s`n5pk??dOq4?r+H@+|qn=QG~0P*C*_ih125kGgGd6@uRbA@=<Mw%9G=6WsV=`Q0#xsNZ37TN@2HJdLvq+)TWOR?%lcp;7 z=;0OP)HM7R-<;0jm)X{iRPU0u@Y@PX+@dx<;Y|Vd>Knpf1^06Myu~sunkYUiC zQwX>V;3Ivo-u-AZA%wmOLg*o)b&2Gb&a{ta&(EyrFEEUCxnkF=o77Jk(F{WR8@}2$ zXiZ*!7)A8irqn)6JovkfVhkg_JJm&2gpDR4owUGUNt|IMP00G8L;vZBu(3n(8X?cR z4!VQA0Ye^yBq0KKEx{o2(zBkf|bS7ns8! z2h}WQk#d54YSIY9(0<` zC)iB$Y&&c!Ywd?%^f%DuSrFn%2CB9ca84q#{>8pwdY{zkHZ-u+EUmKg3V$L93H@)h zx%+_4B^XC$0VF8GU4j+!qp!p#-GKxWB)ECEGy}U;-tJcptbU)%k%)3$zz3OQ z`3xuDBtNBYaq^9_RZ2zMd||ILaEdyVna>C!Mh{`Iua&!dVllk)%Jy2zAKSlp$tYUn zB7Y5nJqsvDkaC+aOmyC<G`c^M+%8J3un7 z9^0mpnxYdX=RjfjP@paw8N`^-*&&DFCAl6#LGAh=SmFQ4Gw&*3k@r%2lmByTLq1xh`-ufV%M8AF@evJDjh(9Gs;Dc({ctmc z+;~RaINqN}I?y|#qBWe@VI|u~9g?Q^{Q5+59uT zvKx3|G_BJ72gtZ)2Ff-A8UH1WdIgY4@OMpfTm8PfG9T+OemS41?(iwRQ+xQ}Yvl@~ zTJ1r5=hzK+ISogUqU+%-gf-A2BH9aoVgx3vRBAUS9&DQ%AHcpkMbcBsRzFYT-AY2r z21A=7SOEk}qEJ|B9j$05B}q`;BcdNn%SAE~Th|NBz~_a$<-cTf`zuAY6IS|9b7jt84?%=V?2MYmX&IWm(ia%%9e_BwJHa5S|vN(mjVJ-|8)2-Uu0= z$`|XZ3sB7?+AEMqn+u;f!4qlJ!j0rIN|1-#%;pjGQ_O=fhZ~_a^Ec2vEFuy_2*VtN zfyLMn4E_KVP$K1Lfx5dHxW&ss8@3H1bk`ua$f6P>19TiH5QC6Ar1(5@waL5@3XluC0cJ07nz&wlT#g#lr*Xmc@*bpr{c1MPPZdyj9S!EPU07)uSa=> zUri$>*xK)P7I%fnvLJn%=?62pg@s@_+VVCRqfXL4VJ^$Mw6a$@f;Q$abwRl1+)zV z4z&Z`@KEjWsq2J51ytfKk&PR>;PWRKPpl5f?nk}SKAOd7Os z1lLzs8xXG#%VaM!#U(qN&Uf`Oj!vH>-e(Don0PW;agvOM?~QKPu8G%YWp~c& zc7}vwxW0R}n`xW278AeYf5@KKF%8#L{VOXIF%wMpf7i#m-N?>QvU|G6X!clxr(x@$OoV zQR!!}a~AK4W!b2T3^^zHbGW96w&Auek46=(2TuJ;TH_zEbs9d( z6Pj3`bkrZcb^7>u5p)ueury}q)osgupzK~;%n5<#QBj7#u8pcfAmM2Uv^`Wd6*JjZ z%EeZ*5a?&Fskm);4xkruv0RpWTlf;Lsj6)_W^_Mc!vIVXS2a{sl-Eb z?{mV$Kf=R9j0IgRcOml72pnGyFC1N?d2t;VcDr`9YxZUYtSrtYTW45>3%H*AnZzY; z`iSv>QXGO)N5gKP1{6v<#YtRbT36!%w*W<9f?L2JHt#qW%!oi`I5b60cu$fHja@7R zrG>sIZyK+I0j0K>PMdM(f`d*le{^VxM2<-}=(<>iLW~Q2Y2GyE2OCN)F>RoFZ!ZS3 zqh1Q7{3jC(XU$U>$LB3>SvzhB(5;+G{>F`#@1Osz_{jhGMr>m zZpKd-;LWR)*q{_dPDD<27=G+x(QaGzWOo~_>rCyoS4eoc0zqM#$r$-uq*8py!?~0O zQmzt%olbdNNi#*p&7NFH`H2{u6X}sDFhovl9Ifcj1PWQTYr}uf>m)ywUSjGyreTtU zr7T{7CEk3UIDJw&bG&1?r;FGaG!+?lcJeKS1IZ_dDNIeraPa68%~~lds!g(lsO=b@ z939iX;o%VcB-&fAV!u*ygUA^9CnRk$r`kEm%lr#*8rldCrKhC|Fh&4W89v<&xJ;NFr=&x23vFrPa9-!)E_DC*FnqUaSMqwiiqWMZ z4R4@}fVSuV#%ua%(ijGH&P zjKYKDX4+z&*sGWw$zLW_=5-!0m>4DF#0NM8EETihekZysq#wJBlepNlp1NggG3qq^ zQyWP7v)y9(ku8xEjiU~VH=dCblu51O5xf@!nE70#@>b`mZox@C6;p;h38RI!z-iF5 zKHaRB)0mb?ycM_r`A(DVi=@~>=I_sUzK_j}8nW@vwWy3i5fk57Y5y6S<)er5w}`s& zYFc5b5}n=2UR)*)S*tW2I<9=o_^_(8Pm1CSQeGg!^J$X*wP|6>6%@UgMw52DHZ7hF zFPr{cDEr!n<44CdN3KnaahmVuVj_X>g3Y?u>C){de*(!blP#V!_szxX(|kw%&3l~% zeLA~-Cr8fI{7Jv3Ni`WP1ihOpXnQg2J{qPu0Q8+qVTQq`X#jKn?R$T|Zyh<+eo18W zv6I32@6?wn)n64^)<(u1n7nH! zZDR3KElX-PZ~jvU0(RmGYq58|xPmuJ4x(lzZRVDs2K`-wgYm7jFADSTb>@`fuM|OT zmq}mB_a~%%alepD%rbg;Djq9!kiSfbYhm<1XG^Db0vIBuT z)w)Yrm=ruVEJ9DA;}8^;%2OwUnT@phyj7cvMG;shY3{vFg+cp%Jso7sDf@Rl$1!!7 z((k4W>e-`?8UZ|RAF}acMl8?uAHhr!4HJ(K`g|G>fy>6;?6hgrjOx}WF!8HR`#|5@ z6>Mv>dPHU2vz-m+mz+1;pGTPZezZsye+?H_Q0rR=OK4m7*^_$8d0euKDUR|Lj0d3p z=B$oHuy_rsCRRyZI4m4#+wl14U};hfyp5Uy@Xqiq%CVX5U;1&<6!EoC>~PTI9;Sth z@nDbS_%QT$JL9@XfG7!<9AKL03Xp_OztH;>JrNVxqai2t1_}F-s7>>S#YUm0er`1vlO z*y-i)sZl|6RujvbYavi~oeV}1us8Bx8L|P6$QcNFO-eO~U{U#E>0w0q*)92fgfcwc?B}_uF z=rj|wIQP?W`iGNKr^)o|MP+p9#{UR78q<*w<8O7WZ~<>VbIHBVk#4cV6V%?HcTP?X z{HQWM;g}L|Z22H4(mY)4{p4*{5S?BCkxsCSoKVafn|P@#4MOK*$nC{u!-ar5Irbr- z4;PzaRq9p6_zkDoL6d!oz>I(E%hz=p6P}9dR5Z7;si;XVXn^UgLV)Pznx4EE-Zz>B zYFP%W@C63+H2#a>2YbduZ`?pq=Z1S*?&rNyS>nQB^?8*cV600h zzx5MDgfOGE5>SvxLc$;dqNZvU5G7S>sSOea6=X<=1W-W&wMdX50g50*k_h|~2ua@l z1;4xQz3;8JvRZQHbN1P1&t~7VBx?KweVT9lDkF%1QVkIaM5JHPN8Ifv->5~xoN5PJ z5{tQoLfyQO_Di%MJp!98f1i)$ZwpW4I0hv9Qpw5XHJrDJ-hY$x?FM8vKBYC9hsErR zSWZbom0@AU?3eJ2>vqaP3lmzFb@}5*sDBZxzms&%LViX;AOA40y>)DZ_>hzf`_&?evSmyr9x5ZV7X+Z`G0*Z{S2LSS>D-B# zB@xqKB0mT`IjO~HfW|22xwm-w<%Ig5%$(ol ztLv^w2wm@X%I$BUDWE|!JshBN0%CQhD)X<3*;q4ja>AL3%D$rGNxpx*rDz_3QgWjh zO#q2EE9gw_R)Q|)7|>VrC*W}(J#MdhD)?IXjKa+d`@)6UTt;ueqF5p*3Qfd+AK+=v zLA!BIhg_YS@phLXAI>v!TG5<@rDV2MKwo~H3w6s@rX-AG#95W!86>C)kWwc9@sdDvPOoSgM6q}~8&YxGpuLhv`{?78d)-uVZ z^7@IH;D~wABf?J}CdnWGbVJ1r(uo(vc5Pm(B-yQFW@7tNvU+(yUqPKKT#LOn_1(nG z*$6aCsNxA~O6a$&8BxN*-O54Rs{wuVIxKb5R&6#uBHRkfo1$8TATFrVw{Rn=l`Umvo2*>+o-jF-5jHnt&b3YW$n-8u>Ycu%v zsbV1K`wWof33XKqkk1sy2BB|)%6^3UOSyZfue9`1K;7+1R!PI@Li%1m%-{%%IT!P@ zAM0PRfApy!sXZi}R76B*b5LsFxfph1d73>@XlhD@5RkluZN)Gz=){!a&--3}jb@IL zo+t~bD@^wEased?Wem+xXkIBrFK9z)m7J21_q~|^_z}Z|=lfK9BGD$$`k?|+XZNZ0 zM@}ap(}F(CVLyDUdNbHGZfNK3Qyqy!*VMjt7UaY1Q-wrMe~;V{^!fT}?K^#{2^>t43yT2qaYGJr|Nfsfknn*wD1fB&Y|FdXQm#tFu4=>A*m1uvhM-#2oj-bJhB7P<{U#<*$-Y z>h|JbKHH9wzlG^qPUMY5wT>MS7f5GTeCA^CcMH-i-3fLtJ>^2m*`{LZuc{v?e(?9a z%8arX>|iLbzxmk?c54f>tCYpnT!@{#FcVVJo&}ct153XIZB&txZQDz6jw3F$nHfL5o~ zQ{g(!AtQ0YO~w7M*p}8Wp}mZAKK)XFYOAuv4UClO3gz!5pK7uLRPHzyQ#>L6Qfqo` z1odzSa>@+`u*x_WhG4)(CDRS&M>C(gz^k#h+EP)Xy3lpjmnsi+OBqxF6@G zdc8BCNn)v_{sBxEC?*d44f{ETRL1249k`zC;0)$aA>>TXZOPN-Ovb_d_esjpjS{2Q zu@3QlnYz9hO_+$c&YQP40NP#=+sfY77u&t`GM5-@387S(`q_w?r%nFd2SrFC*Ke8E zxm%Da(ilWdLxOHa9SnNmWy-ODGsx8Y{C5IPIDD5iiAS*a~_BW_g`;0`fo?^n!e+wN9J0=}&v02)d)V5O>Ir@sfiZ z-Ixesq1GS;7OKYJCG;z=$Nm;SkmW(KIoO0we?68yrwZtjc{Jaxm_38=Wu0XKsujv; zfhWGWn4Jee^w_e4StFI733B+fD!omcB|4`t0L}T`53dBxPU---y94QwUWe*ib=&*J z`KWz!pvXgOrJj2n?I&!b?xHriFg5>vWRAP+mtG4QYu{?Lrt25v>qpOXC9HUq^-*2U;^Q3)8t zj#Ln>O^I3wtvDoDk-!JzERq4FDXMl8R**ts=$x!mOS*gdg#oUpwZ=}z`oy^XmWF~ux-J(l8GueZD6UAR0} z0|UeP4Jw#>5!tNQ0W7Ey98)>;NfR5y(P5tY;01|bpgz>?+jwes#q3hVMf&mXXRZ7A zXRUi1lOK)8CN6$GMiI}%c7aBeqSB@KLo;ePTy?8+q@0l>0c&kVH^1o)7})nCE^(Rd z#a?$*@x5N#n7-k7<4V{&K`|HX|199RpQcT{E5`1YHgj>{`KW1vm^OeK=CKGZcD#L# zFget9nC-NUsX=`nJ~*>+qN-jQJNJ((_7js=r);A({wR@ za4$@X=1l(@CTmvPmH=z>5zs~Mu!TI;<`Uamo!D|(785v`yXUfkcz#`wckVg&g58&C}y zC69rP9Q%GUF=+UWeMOS3(w%Y?1f@tqjxWfAT0seXQIKIQG^t5eOL;VqXyjs@;@B zirN>&)Jv)@l!Fo4RK;E(N;1M|ORO)ojumw?nljc_%&tJ9r5VuOQCU$H3$sKDFXq53 zT0R8T9?D5K+*T$bf@Y?KqPcRPTUINCs1WLdBm6k6>a8aB6|f0_I|`+#LpIRO0b#@r0i07& z0~u}`lMzj`8vzW`LJ+LFHVK-)wsar8?f%r--Qv*~MO5duu5I@Ze zwSCO8yiRueU#2i8Mx?Q;$B!$#pRodki_46&~|7~)53Q9G5`zRiHqbc^EGMJI>rtG z8`mWpcmP-5RPN79G>l4EhkQ>;0#RUO=z7Vg9>BfT%CF`QHUUSIgYps(;^!O2IFAQO zBwK7Da{y67%YrsDo6G5qhPo9=tCVhYp&@?sP;5FL00H{6%m+^Bs_awbfZbyh&F4Le<7Si>o*GVBQ#KrgH7`~{mTd$sPLoB32iX%51@uBQE-;Cf zqUc9W|AcfZB(PD`vIUc9RW88Ao5@aIC_&OXv%%BQ?LWwY{iDX4XqdZ6z1#~pl2#)F zRJ|{z4_16rk>sgNqC|m80m_ya_#Uy4M4AD9ik9x&Av}y;q1;MYyO~*3;oD4r3)TA6 z>Wd3sdRfo_)hYzh0}XJj^yG!=jhmU0P>vxDggMaJ2X;esM)DG`D|+sDh&GY1D~PXyE&~B(9~xlrGq$1+t!WAjA)% z`_KCW-iISi3NG|QeGot;PIj{zDSfJd&Cy<{*OWlagrNW<+6dJ;O2ewtP~EEDQUXRVEfHEx)6@lYHdjm-yal6Ct@|BNYb`$qa*VnNEb=>P6`IR|-tRTH znu%i@g3YBIi|4&WOdYk^b|x#RNEkdCtz+a z{)Xgo>)57l7H<+JT!L(p_QHNsK`H2McV%+IG)uaGuxrl+<^@-=P&5u^0}O(XH3Bok zb(L@L->ytd1-9u4RIgTkO}RnzqqV7bvfsHfB|}3wC7=W6o%m8;d^0e;NYAT zj11fd4^M8gv%1Z7o}11_P5+E^E5Iwv4`XCtz$Ix*)r@Y$!S0g8)6!2bic9#xSQaqy zg<@mrs~7Y5a`Cgz3V7Kq2BYNk-TLDG=WGLOpnuWbjK&PW3$0cf;zx`YUde%XgzB1r zH6sE>gE!EkO-jFGUu>S26##jbC^xym>oOw}f`->z4Y*V4KspjJ@2B>ON{B-SNqZvv zazk*bK6|4QzC*5&{sYA@T!s&{on{(%uL^ z|0vd_XxOeLvQbg^0u6SMie40(bno`~aw}60S%A6J`V+mcK?R%AiuW)tD&E6hpNli% zB(Mu!@FF>&omNeN2~b^NZNXT{*gp|2z|3>3Ze{JBu=Y`FY z{Q1`c=1)elml~8s&fv%U%wwB2GdWS3l>~sEmiU0ZLaU$vWz;GtAUB0;mUh8A@a@Jo z`U8(^Hu%WTfs7W9iua9Em!m;#s0js)b=%C$EyFc9fIJ6*Wpgz|KTRtO-22Axa8dCH zLJEkJs_~7v@N6oVyyN>jzotgLwJjH_QTjth{j92`6c`pQa3Pfv{W8UC>>xTphn!+K zJI`|<7~$8tFDD?bz*~?b@`8ESC^M=cX2d!Scb*I{UpO~Ay0H=n4M(7PUI`9eyjUZ8 z3z8&G$*H;wu_Y1sY$CX5#%E;X8*$*_eJ6e*GZz+@v;z;De053*Jd z1$wj%c@w)!I7g^pq@nkUdbfXq020(04ly7$6|PMf2pl= zfb*h}LBj=|jompzW)S@XbR>`H*DT&*2hfbRdMwX9ZHU|n$nAvGdXq)W-d0zpLz(Y$ z23Yg-k;RH|xcygNmb3}*VpIq(bEM#u6~B??0v4b$$txFTqSa#t>)2bBrnA`p!;F9T z_>d*6iZXFnpsS3KX${dEI*4u++{;KfKeGm)JR=?%at5-S&62!5tOlhO;$fQ@8Bx>A zkPV8EYspbV-Rg#%&*@q!t(JWsDRO6A=`J9;Zberdo$qZI++7ElpzG{2K5 z)esYI>;v8NEb_4mIEB^}3F@z;fliqeA>iN6^;@k!NLo=Aki1LzQIRhw zj^X#);UUaSYl91$$5Dv#DyVR69uKdWt-gmKH?5zI7`|qxNH-H-ZLpY;GqV-f!J4hL zYQX`}IJG;`eu+cV;~P0E3($DTLI1Fdq%Gj*`ouaHHN6(`R^-9}lq8VB8h$%@r`n!h z9L#0wYQXmF8^ySUZ*gHd3|B&Q#s=j-#rUo>{S{zn14`N{X3B&xht|geW3MHzQ*Yvb z4uOG1wFYDtttW{E=56hh0wXy}cM&i&ZlZ$0x9j`Q;?%mR=}@Gh3c_BrYFI&D=d@sa zV7M$GD7Vfz*s5S&WQAf*ofUQU4rbB&N+IskNNuuR3zg#LL&N?%)O=szC@k)O!8T(6 z4bplY;Hq~cn7G3r#N?^MkM+4S@sXNk1bE8ilfCjq<$cxuov z9!Nf_fIN3$`j@euJ9t*ievKH)@Bpa`$;Rp~7bZ4}wwwWaw(=sZQSxu0Wvyr6x$%2EK9Y90#R#P(+oIuGQ>tQK1`zZ3Be>Gv;|ms>zKDVM~Z{$^T~_V zufe?$O|!Lz2U#a3$3bjcKc9^yz*1U)7bvd2(!z~F^dm+IFX7-_GH{6ugb_VfAWvUc-^t6S!%j!vGW$g`!ffqMd2+Of8@1?R+ zKze{CqP}h5*jf?CB(f@nb66{*GkkYGxKPNtMbjvj5r7IYN@;1R#H2{%|E@bZ`RFsz?lAXCV9#mX-|gKyCouSMKcZQ$s)pcKBQ z?wA0LGP;bBu?u9Id~x)kNoqh}N}WzH7@Ve2b_hI#^^1x!JUk(@?5^}#;fZx2GAd&~ zyeRJHvh{L7WbNuEG&jP*w{ob}uNbiW9wb{~0q!?&N>J{@&HW3+F&Bi{N~0c-dWP8S z4N9bHH$SnV$DwJrUWI!EM)q5M@j-!whvQ~uPMLK>18Dbd!k~` z<QO*$QN!FG*bwR;1JGU2E(%f=5e>YDSqsWt8!^M5H48wD%VO8TOgQFy z@oU*EERM>AYxu=6FZ<2$H>0(Y{jMOXYc&p_Kf92#iifcE)0CY(mmsnawe0L~oww{j zJRoY>x$)VA1MW}Kclu*bN-ht|n9I5S37GCrX6{4LN{&P7n>Y z7G3b0uz8ggf>5;@EEG|Z35r^EH_XpLyx0yx%FM{;Ga*{B)o$o+cEFubzK9F+U#eSf z2dl3W>=Rvu;>EgUc6ahRBLyv@GALfDTV=-p*+((md6>O(3zHVDv32$RY@>zswPt8u zv0dXxX7wv2&^rhRtA#LQpHh0g1n6!oGC-me{VAI>8_E zI}-%sq6a|Mf2ms&443t2iD3M?YZ>QGvWBo%o+BD+Fgb=w%HT_XYq@dgQ%RW;{psFa91g4^;l2AmcB%r_6Z35GLoCDdarIg68&MPEd zQEguZ?)yz*mgo|M2%uUmT>DOBB=!dgD=1W*yA4=jpqTDBJOQG-_KpB4(K~|eYa`>K zc)o7Y#87@G3-wnyL${vEo}NJGCUw-?b<>Kk5ZBnn{9=Tps(z*NtZ=7$V&s5`s47l? zID%Z&F-j4f1*M0u=MmH%4I9!*`h@{1Yly@g4uma1kSc{4?WcLIc8vj0Y05P@J@8B( zLM-Er9#A?oByczEgN~kvT-pdDO_aN;z(dJtR9iWJ1VI-Ss!o50U@A&(eRM&!uteZt zZ@PV(KYC8mUQ?H_;nipcfL>Mt?boWDFl)0IJ2VE9fwQ^l0>mps;Imjj9kekiP_2zg z0djjyweJ}47kn!b80AJXSKL$N^K^0&X`$D^+tY+fJb!!e=dDWNiqmbas}8zku3o)! zr$DPq;>y}(xv}n=dbuj zu2jnd6Z>jPiW|p9x;mfm3k%2kYRG>vX{j8?44X`+9QG3B;n@47ksYo;0%EM5I?h^& zA<4+|o8H0;svU{}Xh{s==*3t*b#%A&VmM|f&pYKDG$3z`r9;z(5MP}M802mw4ydQY zbZx(OOb`dCr8WI?KmEWfC<;+en<^eh4Bknd|!Cp8Ss=(L`^h>6S9Qy#i_&%qaAKMAL z(;0=s%g;OJOfa}`#J*CT%HOJv85P}b5yvvS93cX21T0uJ4EzHU7!2EcK&v`d$76krvE zL6StS&{FgwMqU}~N@361;eL^4Hc+jOdBV9}N*Ox-`$`>Ww~33mhby-d&ypGaBlnxNheD1Z3@+E-fdMSRfmpODXn#JuKh)s*^AcqL` z+6qDfro065)X8;l%L@=akuF@NYi8X}(m8-aRH>^TF6W3uQ|&BH;1c1cOZ3RL(m8NC(=&{wXBMW2tnfsMV5hl{E!l^EcE0l=OW zRHhF>m;Qyy9kExS3;u#Cy!1M>mNqS{ICC%4ILU zjUr5uDFM)8CEWRPaYKD3010y;c{7Oy@J}tp=u3tM4*Lc!!ksg;NOw+v|1?*T z)ZCEtm}7T)C&22cpexM84=XL%((M3%)3TJcplC^;m1<|9B=^=cUKR4bnN4*4L)jwF(a*xiXE+qKbSS2t2*z#l5FW~`GW&(PO(JmlQ8LBUgWn6n^#{_6w{LnUW&jz+15xT*m#!i|w+SH*$u|1RQ|b&!XQ1Ovg|d7Z6;~A5 zacTgbPbXk(PXu5r$x?jX#XuMTt;*;z)F0mIloMl2J}G?#Q&wiwIgt_$w%pq{D0%s# zq7km9r-5+uIrjZy$7);g$9n9)@Wo7gx!&l^QL7+pq*~;98orn-eQrL-U2x2CHX+AJ zd2onzAvm4FWpIzD*TW%b^^)Af4}vfBVwzOkSE3bww#@oq0}mItt%g$kQY!xEfcSla zz%-#zpjDqPVkJrh6rX>3aBbQ*jkYX9{t!KY!3FjG`n6xcm~eqjx;3y4=QI_ZWig!5 zh#S0U?iif^Ua7SK9t&VxE^e&H!HaZWN)DAOU~dnvayIT8D7*sSLVOJ-2L4Mjq2gtz zugL^l*d2Z33(-NSuq>lRZt!q|rPc{Hr53?bB@4&~(tk=LJ5I>tksEq@fE3$`Kh!4! zg1o6OT-e(J6`tY`T)Nv$@96WM_KF_>%l4N>>&nkK=CtXOt)xRRZ+8fPp`8d2!U6@| z88~fMTAdXs7*0D@>Tk$53A75*Lsp7*qM+gi8+&X5Q0cjGT7D$`r#7J7)L;*2fr-H%TwT{tmmmll`dJu2QwxaC**lnbSfj8ol22VF6P? z0!doWUVzBunKH)=!WG!Y668lwE^w3F^L1Y+8iD7|Um);YH*q7^!v3bWb$Z=$MFzBZ zhvJq{y?}9;335^#fMYnP$oAcQ9u9PCB;6BBiU;5uhSE$ub^y`)T40pcoB;>Nkg3uN zxF4Di<>il6PvCLb3M46kJ8ybx7AlFNn*bBnP|o6*33x4=#2iTZ3N5-yoTv#}IQHs@ z4ZZH@))ny99>Hi&fh4sD9lcn|5FyZqRBo3&eW$WS|uC%sMG$S@-kV+GR0@%7T75 zt;dEwV(;}no!A&?<%vPgiELybTBIhMD3ahRD?%B@>UI6)qXDIST|!Q!W72xD3)g?p zDW_0Jxl}q#YPna`;AKnM09_uI`Wk3f5d)@}rJN;fQ}_}ga7d?RRXWbD6A*M6=xB5C z_4;TSP1QlH>xSLE=Ofur@76@yml)^e!Dj@H);|pmAq-MUELc%|KqY zq{=G#Gc|*n z0Ydd-l+;)?v?xP_hHchmj!8H%nTtVN^ptk7{m?SM1=#o@0p4H)Fu2YL2@)NHbrPSm zEpD4ai-iEM;{zxyNl7+zLj@#ysAjnsoy0_WHkJYvr%H)>BOo!=St5@_RWNH{h)~zW z2YTo$*T*7IVG}A`)Mf>f*$eQx(U+mC36db%56j@st9HlELYGY;1f7GH(8W_A)GI<~ zTZIgZBA`nym%a4%HaM5Az&b^OQqBeMUCWo*4IQzvH6*Vhp&TN;6u-!B{D_t3(h*v~ z5-j=@m#Tqo1O8TjDfZ^_ft^^V)-58Xg$Klk3XIa5(TcP>Q^igoD`}T^b660M8@IN$O-*lO+~j6El4NiPDD5w!sh<0YQv8o`^xrm5CQ1EFO)gk?y511&qmPq-}Dh*r8RfsG^x znCa2z&NAvYDz?K$7M8j$;Cuv`&J?*IN`y&l8v2*l3Sg{OA%J5RH1w~k?S%>hu~WSS zNC$qYvOy$=mOyU*l3L*J)$7DgTnQY{HN9>HDIb=x5EP{30z}{^97Nu*q01pe{a}FI zynqK4r$UH&!Em}hE99xD6Dn*&BnyJ!_WBkh2So``aVJ!=G*|)^mPm<+4jZfC_8Zp% z&8apL2i4m^#jfZ5X0>mj!c+W_i-nCu8SGzu!T0%jak7?5#N zKdA63mFo}_9doGqh)+Eh079&vzT=ot0efa;CVRS70RF5LbfvgJ1#N-SP!tbalGLkB z6fr0&_Zx?_uo zMXAuUf?H_pu^NW@2`bW*&|{wAL5oX6;flEV}6% z7H|yx0kUcnL{e{wjzTpv0~lpd%2<#K5cSeiu82i3tD=-);Ez^dl;>g(Km|5bV|EO9 z`mBS1rrVVOldM1(+-aB|$E7ZwL#4b(0WRGJKu$QXT3f}23IhQyWgIFr3zQhqQMiMV z5WHath!x2zkvF2hpu#_dqZ)I!S2|*dw*ffe#OJv70Kt*A7=H9~`^R2So7bFU z=!vnZ6{w(Yg**{m0y%k}J;A{KQu#t6sv8+0!JF{v0_r!wp9-ab-Uxv*#psXOd#kp2u0 zc&t~WX9wc$9Sh{P$N?s^FZHSSg*h->ISB81u(V-=*Ya9C5JxQ!0aZ@5SjcS*e6zLZXKC&<=yigo&5QeqfMED>Z2y4a|{_N>MM%Ca+;p-Iy9Ow z(&#kyjp$QZoV|f#G;_*c1}j}%sMyx+%auEpjh^9+h=%ARpGp=FUO&E1#ZRNPkI;VO zn=%}fI~D409cOiA1`5T9{W*UFS-|55YJ3{)t(@?c=Bqi2Zd|>5ZQ1BPUan|}L982& z9K?3qoF(WJI^@w`Y4%g{#gJm+#*wM*gD0gjeq#S8$Rz?xu+ms3RcA*x@i@PzR#Ir| ztdi3e3n_Dx4=QWFqgbALs9}i$MTFm27Q!!-#tQXb$JrgSQ?P}=hwHrOHof~%Bdq77 z6TcCzW$%W6NuWwUG8HsfBb80AsU7wl6t>@-)##`XjR$_MIY^<46FXgVBRjqh>yVe$ zjefzS9S;-)-+cZZSN_|yWN{AXor*K0^4;s`zBBIh+yOj;ANa>=li!@CeHR{Fd{Fn! zuWkn2*Be|d%SQjjrS6kDAFx5C`vi_-R%qFhXVyyj>IPoPDy2~uG+|j zga3guzDadSd-GM%y0)*7De3DyfH84V3dN)`F+ao27LKrAR4iKBz9PHg7f%;Tg;`G9 z!P~Z8YRb#N3t29Aou>HB#vXDS%C3NBy5264X?&hr zp?IgL;QEpH^KQD@R*S45*xQKyh;H-lUA)B+^m;i7Oa#qY-VXnkPhPd)?d*6PcZwIW0A%x^}fBMwSEsnfTP)uwT4 z6beq)xt8a=b8yMl`qnxlnbcpZHg_9wE59ro4dXS6hBUz+oN_Fz_XLg+mL1bQw!C^# zTwJ+zI`O-(jt5!$xXl{R*1((Voi9H9hx0|%(ki$3#e;uG;0%Q2yn8KXx#@Hbxv3!(WiFHtWDSJ%qdLs zoRYoAjJ?#7jQ(=>IB!7H!`$ulH|{b`{T;~L6>q<=3d*UnqRa_x>LO1K{sk9wGHpDC zxw~t1$pPf3^wB=YYP&d3IG{sP%Pem@9I(p(uU}#ulv(A~J_w;6ojR$)2j>KCGu9wPa#L1fnvTXo?h)ZJ@#^`@EcU?!eQ0#E9 z>PxFKfc5R`BKHk8!TJU1*oCecF?)NjiJe3}7mviB9DEDoF;h2BWfk0q@dhzQF^g53 z<7~<+FA#Tyb$rb3X#fDe4m`U$CIbLyTV-Em93MDn5<$cW5AyEqvPirD0K8u*{-)Oi z0O%0wA8R;zg%|Xqe+9cQ%RA9w!UO>L6|pk%EsrUSiY%X6zCMw>qvAR>>=1Ph8x<;?Ee)nqk<+_Ovq4IP zWZVfmt(Mzcsg{?GHgoSOEpj9aK1mGi7ExCvEr_F);};6Q=G`;2z+9lyIIV#uYbG+E z{zEfWERLm(rt)^b@LJB^o$ZaWw_AwCGg<<@zVlcFRN#N4heT`IeNFM-A)!*+gO0N& z28#ylHGAl*?EryjZi*Gs>+QZ~^wr8YQrqtwla|T8RJ_1<+|SMg@L?BItvqyRR}6MU zU=4&@c=wvk=^6An3(qU0FW_)nL?iY0?=sfe`5Qm~TPXQl zHFbu^zn-j1aWKy*+~cv>i|SQfNx4e$fZ^Gq+jbzhW9Sx|Pz`1e51xo%ED^5Y z-HSHopQmeT(<>>LNlRdb6`}yqiS{?y1bgLvMcaBS&rFgDWo~3=?eMX|6@Wg`=_9Fx z^g?fsT=5x^(!FeShBrAdgr^TW30D_he)^9lL0TYs);^gfT&<)ioL5_^tYm>eBM;XO z_wZP-1HuBT;oQQh0v_?Y%1Pn;g;iY^$&B(ZW3-WH1T+MvkJI58t4w5J<+wD-k6|4x zS-IS1ej>OmvaRpI@Fi61+T}@$;Wt2V=@K&Up3s4c_4?#HwPf%CY)`1i(#K^|b4do> z!c571-aVzcJcHimW9LA{obvpB^6HIk!Xr9$*A#K(tWP(YbsDT`j{27)Q!7hHpYR52 zuFT;VunbwL!9KM&#n|VGdS#>ZEPNWE_v6amZ|8IXK*pj2q9^U+*{;`A_KKMGR&^O9 zBg!0QCGpt}k{-0b7M&7ZZZF8Hyq0W4skF#Z=PAPB2Es`#w!8v(-$X;2ZvT?H%Ot~Y z`~}Iuu#TFnM3g|i4WxcwYYXUiP#PmO8THM=uTwfJCe~Qh<&to4197#(UW0ewi1HM9 zIzFTSKrLNN9w4V2nfiJ#T`FVve7c#LB?kh4U*NU0->{CMFzv=XmoF+Cz0dPOZ)n&F zZ|{`?H?&BB7wvA(%*NX*e^5{Xzl{cQBEWCjcNBeCe?-KpXMC;6RO~CK=?KGl_vjYb zOgfF$6G%NUw-ZhnE+Wh|*Vn=80xY1fAWOU2g{Cwg zgg8LHc4TV9;2|I}@M|AM*}muw7klZcO=ii1ZzAvp!V2C!z8M3h!L^khz7(LrngA(A z^rk&Ji+>$r(`a8J=2bS;Ilb3#ty=I@_DDmW>i=67gKV z!Uu@3HP^o$|MmYZ37|XRm=fTf&@3solohi}WDqF2P)Nx37OrON%ujG#u@TNl;8xai zz9KlVze8-KK?fX@EM*%Nqm&3^8SD7T?XP`eIw(Wyr|NmDM(AY_w-k3V<4jf}Fxove@*L_{w%JQNMME9_c57}=}O5GnA zwfZ1XYP_wRy_<3T(ZQt=z8K+t-aQwKXp~adRQ6iWBpHHo-lZQFSmZ{xPKP4~_Xw>^khdfDFUPP&_+_7);N;&uR#<3bEqrI}bXU-vYm zoH5V2V(J5o7s_&BqjS6& zU~|+7C*b`cFETK5tKD!@dOU*{g;=&hwzu_K=lLrR$aBNO4W)_JigepC=GN=UYZO-N ztb#68EuY_A++Z3!lbp1DDMq`k*EksFncVU>&l_+kS3g(BI@9^< zW4FW)M1ePt#P1wDJ&&Zr+52FFIHQsU&c;C(syw<|xRoGne$Trxf4)r?xxj}BX2%SU z*;VVtMV9-g5f6uTbY?NpcibQ7=TMRbd~##e!m6$DmV;vvtcAj!XP~`YJ`z9Od)Did zVcg-z2?g)%pSuhHGYf+vR{||D9gKYeT?z^_zP9& zTlW(^72RydSX8bdpHw`xx9Tgb@|=gV;h-NtxhHj3TF+ON>n6TJ5b4J~j@2%4(eqGt z=6wWmo~WB>keD*@ZEuG7&Oi?UAaQVF9?G6syFj3nESy+8q1$((%CNhpq0+i+w4Yap zN;?uKrD-DIxX@^BQI%o5@1R$N#8}AY-NUY}ELDx9bHq94mn&+^8sw_B<`;m-4lIDlY!y>E))SC}vC zzCpNB+wZ~IA=^BE0*7ov*dcZab%}@m?BYR(mtITR4cXrK19RKviP56Ly8wdBbcPOo zv1*xYQ90gNc$Ih0$Bd40jM~ao2Rv2*HTzatAu?;{o6^@Szf@dVW9501Uq;8`lS)du|E8ecP3c6mk9wee4 zb3rEf%X{*w^>Mb$W6Fq^&>1|;$7^c)HvaUj&GPmqCnR^DoP4se^T{Pz^!5|0W4A1? zk`OYt7xiNCi?+ALR~>2iI>5Ika9aX)Eh zUs2y;>-#;mZsU)8BrpH;q9KoaMCXGTl_!r9nu%T?`#0HkdY0db>l(f?CKO~>A@Y<+Ip*{~iH9z>{J}UmMmT%@5q-=dxK4a15c(7^ju{>WWk?b*&o=~*e9^&ZNb}>0gop}B2JX#dtr{p zzH(yQ|2*~S_a8jBNH$pD&58aMy!_?6gsa4+`CnYg*%$>6upicIdSH{MccPZVb1?qh4#pt ze#hQ9;c@E9uH$&S`9C+&Ki$FfUA_fFZExOJO+KFQ0L6pv{uw&>cKm;z_rJ^BB~n}O z^VPC6_Du7l+4tC8qXo3yyF_)_1@^-o&9<|Du-{kh7RD3uhYmirOKh)Z%@PF{Ryi)kE!a{ll!R^2YQ=EXCLrciR74^672Q(bQ_a@ zr>CQZ#M3or`NQK(VfT(mn^PmX+Y9=f_nprFNC?b(GunA(FuBjZJ1X(C=1;psN`>-M z<`2oy?K>*p&bn2wKe;@+^!6-O8D2o%=4(Re>aTfSSGT!3IkT<#Qk%zgUU$@)2gF{_ z;Rbe0;y~W64dL;srXXR}$Nq~YzB@kJB<^SbIq~E0f7U+g87192dc|HN30wMuQ}b`f zZGHEQlLjT&+nhb)g0)ARt!SE%pUobH=Nz{UoSR-A__?;j{b|>xbybN50SQKZvJG{$W3SyXAZ3A8hyF6M!EdNb8O^Z|baOB-EOpYGT^I z6q5`-VuuQM3|T&=9ec6EJ^0+aOaAR@+3*RM;B3|ve`vW;^qPbg(H6A$_~HLib%e!e zoNxHw`i*k%exfroLrZ5RbSEgh|BbIEW$*{-Ka6sIatXf6A3NE!Y3hKyXax(-Y5+I4 zg5`0lX_Ie(Y{@%pbm?XM|61>oq9@Xx9o>yKA5S{04tZz!%6adgUA&^2nPg zE{OmBKZ!FFmy{E;N>-zyVp9DBK~r;qMZ3iJ8fr>5V@qbQ$SY#(tB-$lnP`rda1Q<} z*;i@ishm4e;YkSpl=!G8i+b+Wi8olb-*8^XsXg)&@$bZj?6zUjn^Sur>%%+oZuZ{y zRh_5yu=YhuI;F`rS5EcqP3C-Q&6cP!&4n@dlQ-QQP?Nu2b-nsB75V7DTi%Bog#Piu z3%-3cZ1zweEM+eDOIod`~RunXKDWX#ZiyN}G3BcJqrf4t;yW zeepP9=D#yHV(!N=l`b8s?`|c2*l~~ZDpK)4Ka)9k9=jlSO;Rj+H@y7=un zki>5viC+@CB=-BTj)(Q|;XdS^sE1FscM&w&-8MN}tKUk%jc+y2X+uqbZZ2*{Wyg~q z-r#Gce5=d3S7wfiNiVN)mNo4QoO=*!64vqM#Zg?w^tz)aZVqL~mkmtjKL2vb5H914 zS@Re9v$r#68UBAgNtq10LoGBc1urGY>-UUOj8d>*;riuB{F>M`v7uod-dWz(2Jo?W z-peTZGTu3?qcPh%cL99#bFb}pkkD4do+#e5@7Rv_iR%VVgYnHGw`l00huE?nK3q%g zjVy2fh49gV4~X=}#~`yaeA17^ABa5=>lAxxRbY}wRDHF($X!&;yEmQ+AB(OcWc=$c zur!#KjV=@|6kQNC_0#;z&(t6IEeM2L5P^>r^{yKKH87RjPk>N2Pfzw_zMks=S>xoxChBdkao zh7SFL-Qt+@39tBR(~1@82^5dZYwV1a%cXA8BhoXXIFSsx>v-7Bd60A!2E~U87g2RQ z7JHb@t$n+Jqffnh#b;+z@Iv1UF@{tFj}>zp-)`{L;e7wmcTFM8d8q8*xs_03=zCw5 z^i8Y6D;4pLJnn_RRHO(>#2LA3em4L;;_{ha3Ry?r$b)Q-@_iGyEK|-mBSo{K z4ZK66l*2}I=CXZTM)`(9B)q*GT$nlC@Iw9q;;aFT|7tmbF{- z?fSkBg?28qf`jnG0LKe)2k*bVjTQK=BXF&ULE|i&*Y={_N2Nz zvtH1lg78tgiK{2R>Y@kK-^tq5F&(}m)_Tx6-ZM|H_j;8>kY-q4zGlMW+yCqljQC_@ zAB-~wMFYHs53@yIko09)dE*bvwh6z~dEFK5`)2OCE%^%n zRaZg!aW=AG8-XP+nhEhc&hD4&pB!p!|L{TmmCr3gQRaK4#i;^>&2y+mb5^8D=iJXZ_qp%;oaa3A+}k`8 z>jVe?8vOWbj4^ZvI24X>R5lz|Lds#|3~uo@Jm&Ei^lhgx@Xh!!+PGMtSO9(g^rn$> zpGN~YVvLJrkJL%yq;cUvJ3=$pdOKr`(HBn#%Lak}>h=|bPr4vxwSQy(#u;#I zx!opmCy3F;yeOMh@&vIF9){nBzI=L9$+@qs0UUtyUamNMZ|R%}AqUTo4ddvp1Wr&I zNfDL@L24#A_JYIc^ycY}(;JfD0EQu?0TzaS&xNmWc{}UF9&aL0O<%CU`vrVUyOFz* z?`&2NJNH>PS~m^?z864bbK~5G^(1_rZXab}d3qD9X4*s=h;ixCrt|bNcGoX(c+D)H z?uPU#WCB*YEWAmbmL6b#;QKov%WN^fDD??ki3qz@tH3c zI`_AV!`dJ>atkouDwG#LG|p%BhxH5QE+ndj^+%`)Yylu7RTk9QrOGl5a2*1nO#XCb zF^7V5eNag9JrInF=zHAZ*En}>Msh;i7YPUr?=~4!B=6K+MLas#`JnTnWFz^O#jdS3 zK7}xPaHrll@8^VI7Cnp}4%tQ)1|6bXy|7&&DBngP@1WM7Z6JZs>qWu6U+FFI8okhEf_JDG0HHyTy z3W1`(iln!I?M3^Fj&1>mw~D;!nY9&g7mMQHxwtrT6GMI1)qcq@his;Fxe>I zm@R^M*fy1;Y{Iw-1 zmnT>K2uNBdz44d59KdxHmK3xW0wNFYAccAC+#1BW>^ru_0SnuKI=Mv-PK=QF!+UYB zFY8ZF9sjae`RP#3Nf*7UeyUTiOW z$*PO`q?hxwNu4wru5*G^eDXZK-76)*JDVjT+{?acQ$Efc`m09*ten~ywEZgG;cj0r z`kt;fd}~!8wA~wxS#>CoBOh916RfEVp}PA%o$!l*{P6{j_ZB60jb8Y#83!37j(FhHS8S!LTJG zU$7I($1UxIdJdGIwxtvo?r0O-!u617(23Z>tz z9^YC5&}#Y)Sd~@{6_Ta7(O|8RU)(3g)#R{#z|Qd^!@B?58uhrn)dJ^7-bBFG#pg~w z@_oL=8Bdk50p(WCfZ%M?1@3PJMPhw~X%s%-_7oV4sMZ~>ZThdIHb7>S~>@GfJh7$KBLS!z_7+N=U~ z2t?_oa5D*n2q1tkKa5|RkF%4Sa1SCt`bEgW%A>>$P~7w?NkhFuz^UoGqBfzBjXf@H zxL)u}7sPl@PF@ED=(riT$zOnh=~FB}CJgmFNPXC}F>p`mTq(f?of}HzAqJfo1$uc6TT%>SQIC~WnA4}~&g#vh4OJAs4+VFeNJ za8y!|_;5i}Ab2*uBdGnF!b0n2JP1}`35eT>e3lWJ7Hsk12Tg&RrE@w2|A{H0=>HxG zg+sqq@KHU1W4Snjw38T_Y04HDCN~FyKz>y;31r0RPb-t;QCopNz7^eI4j)IJI(iQ+ zRG$%J9C&maG& z!T&oNiq@AKyh88*Yvi-d=i7qa+!{fmoqGVOB@#P+0ml#A^9O6JFW|NV0`*al>`Yui6BgRh3DH6)MHFv+mU7 z61Yl%PXiY?ivLGAl=b5g^i_}o*y;KcoM7IbU@fY_XG$bxyK|pljBryM9-_kdE9O7p z&`%7(Y=#KrILmNDTINV-;>JlNoAvHdamL0rKtOhaH^;d;*G$01b50^*K<(qFiUJYZ zI_iQaWq}AVL3AF2m(4R`%MIhhD5^k#i@|_NV4;lE7?>%DChlR!aZ%eihpB`2VEag0 z`kWm12nf^o(d-~pRd68`8b}KqpE;jsyez9~MIWevhp1c8DANv~>jVX`kl3BrJ`yAw zuV7%lZndI+_4KABRRxBEyD6u|w0<>zJLi!Weh3@q3ES2*!DtNfEfAd*5!Bpr_? zf_N400K1IK<>Tz2THeENBN-ENL=QrrfzbEcgS_a$Ctfn8mjO5H%v3`mS<_2&5C0Tpm z8}ZOj76GBZ0vWY%NlX#xXCR*CI{tUjxHq0!cqRm2`y;Lhk9dT)D}diD4q6SXB|G0t zEjR1e*_+qXB+x$ta# z&nWBpC>8VFq{{6^>nf~Gg;irwP{qNkL1X55CD$*T@rr-$PUTuJVhOA8idFb%JojTU zs1msg+(fPiWLzciD-xQs7Q)P0m#H$Ge{UjeFX6yr#X}Z1@4-^ns&qMX-a}G9DwIe8 zx`nZ*^-sICx(%40I?byPA|Kn*ExaZhDG`T0eIHsWkJ+oZ@ptL=CG-)?v_Gf+NA+5h zY~$tJ+%K=G_utCsuPYBdgGLC?3(P&wvr5CcERv8xGA|>C$7Mu=6X+(TO#pm$Y!;6Y z1U8H7WGy;?iI4A`+RJf2terZ@BCj!R)o9`0lHQ zFPhJYdMqUT3agzpy8%zGuOQWh%6@UIWU_+;IHPMzo2LVg6NjNnjR_bMnt*YOgMiZ<4HWzM%V-Gx ztE{slOP&*1SGwGIau(&pe>7aniN8Op=7tV%-MThdM^tld zolRB=ucFLIt3lSl@k}kkS~Fr|wkx9Et4_F!?8wwqJr)`Cdvr}+Age;^-}9E2>H_b> zQd`3c%=duh3tKgGY3P?101JEmuOat6mv|a~;1?$Df4UEy_$Kzc2_e2?E)7qd@%huZ zZF3O~pDW|(=U`ELvcP)3GWe*e8fNgZIA;6m9hQsp`SrrqZRI>pFra_v{CBai0WY&X z6ZF<)5&VV)BVu{&=k+>Vmtmk|1dBL`6Gp&37Q=t;t+TC>o76uxs%q()YiDfSyu+mN`1ept-bQG@3in&2fdT*hf#@t~wBUcLh}@ zjId}?Egp@w_}1K05j5UH%^&@nQe>I%Q;Ylyct^{9;x_9=>Y8jiSp6BJ5l(@ROwn>B2mUY&6H9j4rRsNt-6 zS44$7UyP7i9tLqnE3_-3a(=$iR{7g%VB|YzA!s`}KB{xAac%#=JXy%aLDElB-%Vm4 z+y7VIMwoKtd$wg{^6~91UjRCNpLue{_YI)wWK) z?JOr+L@zrFS(zdjSk@O&8JWei7SeLh&U0RM@+%DsJyUaN;BbMU)zxni1^4+X#S#o` zY@b)#AM^W_Pjd=gDd)2hx_guGg|?dI9vP-we*Net;r!dXhbFIX9(yZ!!R+6j}@{eGTzuOFAN$8&LNZAnq&$~~L_p&FD zwPDJ7*AAs(@awA#AwxQKzmIp)UIB!{L(1;Lk?>zn+h%OXoM+bkgIl zs2dbS&N8nUixaJk=A0WfkGD~U`ym{sGuOSGetzdO=HT+s7w zfgT|9-o4?-n|8i#dX0Dhw{uT7z43QIeb=sTdfPt%_1)XL>BLh3sDYdy+h}7Uvisfr z%8v&3eu|`)uf!i|S};6qD^%vzr>k84-Z-he#KNcK$iw*^%NM&MH#g6F{K_k*=KXxp&V9CSmt!a0@5(8DZi;+UzAN*HcVAPGQB2L5Z?Df! zUI?_^MNxF_YmTXTopI!ggyHGUqs}Ux1;!MU1DG75+S%9Dy`)QXec(R4C^Qwf{c4}O z;-~z`%jI83f+nfk?W$e(S1b5gj-V}f9u&R8{@4^K!dKZFbL4P;lNnU-py-#hJp)Y- zYzY>3V&&a`l_@%@*lX!H31RED4P3CaeP;PTUR{E#%Bs4EUc|xNn*AN0fLtnNjb$hM zLNuvA!3oqh<-W9jv?}IcZN;@tWbpoJ^U10bZv#1J=&m8btL6JU?GmFwE?!QUa!-!1 z^y%Y{Pag}-8-}-RXH7KPf3mxPMXONHf?D|CX<3w(Q*4#nB!>k$TdvG86sagVs*=+< zx_H0GU4oVy?%e@3$L=f&3+!87{&n1H_$>9&sTR18n>4&;#Tn{mkm;Dm)!(k4(ps!_ zQd+=hVM9axb#)2xnwu2ydAR6)Xcl!*ab=X?)4!pqx7Fe6CPgyY>8T2tF;*Yf7rA6V zM?UH%MKR&`^n=XgsdM-4B+6w*Lx-Wr?X{iyd>P>O@)- z_65|>Ha(ZhT0@Q<)r${0o&nPp@GQMHL!M_3i|SCN5~$=CyniPl2;MR!?0&WfyuqwSy>}dy&m(86>$W} zPS4W9ZEqKLtQ%JTH@(qQe!$tT!;WvgQA@e0BAz>*e|}QXGP0^K;?d|F#p@YQ^C3nk z&};Vzm7f*-wh-ix1!Ylf3jz1aQeE9(v`!$zN4ni3fTixF+M7Z@C z+HMzQ82fkV<*oi=cbQ0NHvTv_b+PT2|I-wqVyUQsrtLX+S%V{&?5oX%D%@q>7VoIk zPNN0h;~gyAX4bX!LOw z|AzgE*(QI{tcsFnM>1J4Txrpw+Fb(|)M1AH*|kGWk0X!i9#Kv}_5>XE}BF zQ^Do5i-9#Y>lXKdd*4y{_;cqp$EPgdOs|&X8i=IF16in#Ltw+z+)c z7uV(npQNnaXDpprcz~=PQxneQW&>7yVe=cTIx|-ejRZbKK=LtxuX%c|@VO zPo^fwy%G6;RPxZ5gFzANQ+qiKya!SRX3>j=0Sg1>3O?iD)7p#vArF8x4eE1XG^zg? z-n&_svNfoqUw&NAYqI-)smy^6own%zM^qzS6i%jf+W)e2eruXroEFcxCtB-AV7%Z* zs=Vz~H(Ez)(!BiNo;=XgC+>p+k`Dxl6#m;P+FH_e;Zg0 z)Q%R()%u{CNc?E{?*+0#vvokX$-mm>>i=pb&Z>Zj2SQVYbR8#Pe_X~TQV2KQxGxI$=>Z!od|ZJ_XpcRSt8U?4zZ zjpOe0nKc_EN&XVIUT6_L+&6Zy0DkmWZ<(!|K6jT!3LDb?zSdm!1OI?{XDW3&S9R z5RU>qNa!H1U+A__MC^XiY`vnU-t^?J2)uDNGt&Cbju?1}?aN1G^|q=Ls^qmJLPN<# z4>O_UVfUWfcRHqKM2j9u`_!PnPR-y{yQc~-A#m)cKOTk?pf?Nm6`3H4e#CePEMC2- zAzX28rnF_2IS|tx@lj}2kMxC*+HXhkp#^D}Cd1$@DSD15nTH}BOM9>N6kSDpF+WMX zN)Jf8k?HO4+`Ze&5b;Gh#_sxZ(d^8lOm9vK?q=wn)8wUry==PBO=jeWCB;B%wCOC) zwtI(%CBBwJsXw0tpZF2>sBJZ{QGl>X8}VMPoiZZmHvsXL?+xNUFDHuj#oEC0JMjMN z?{P2R3}wP6zQ@v3t{BpVa)PbKP27QT!0II_33NkW|F%Hm_o(B~FCN$&tK6xM(bAu% zi$=~;KT0f-ntJudsY2esrU+_>ZVTC;+BW*?5QLeHz|D%%47PQX1yP1J-fjk@@|-Cd zzHV~ykpN_ik-v0+)j7xJa6D@J1LMgTs)*jh?zlY{{H4|L4d*T&qjr9JY&M(hlpNO{ zp>h?`bvau{I2HTx(!Op)Z_-Ii^}Xt3L+b*)sny3IPPKla??D zK&Z;aCGqv9M-idhPVed_ZV$-8MI7%`y!&p51e-sE2hI{^%mt5O)2O7r8Qw~Z$togn&6`Uk=>ww>ZY3pon%5#Uj?(9H`$^{5FwZavsjivzfswrEIfyIRO1 zgqFBAQ?kQ__EyL81KMmH&I8u9j4C3+$eFe+>e@J|m-nXa6LeMDf^CWDBJMnhccM~L za8rFYS}Q)Z*K0GQE-`Jb(|6%NmI0bBtL2rY#f87tJ_(>kq+X9^>_(hI)4 zew4;j!Mvm2NWSJxhtH_uuhz70?=YMtY9-Uyw+Yj7#qWRK=QzBhCt3?0#9yODq>%D7 ze7p|NRQQdj&wf=b28k|fV3`u_#S;_?bSf845E{=-<`br92Na?|O|L}kw zm$cp8Z4h#udF1TWV~NmA#a<-NCy&TGrH&D`bK{vmpQXBrEb)@F5J*;ZJw66l)kV2M z@3wVMQKAl^r?Pa2frne@Wk6vM!M;jv%htgJtHdc_z@Dd{?yy=G1Ut9P9rs&^V`DbH zE;*?K?g{^s!qqT!@&RJ59#f{b*_k#=l0hlRTXLm3{2}`a$r#Z_iD<1}=G6TalgYRM zZV*52U68+7=9+6q^8n7Hr;IE*{p#tg9w*S99U@>$g!VU###Hq)U4zXs=dZo&)`R~d zU&{=eW%k&qbA>@hN?#f~CDq9>{^P4bZW$y!VMim}^I2W!HI;IjZ7Rj=MSDUfpyu~Uc!+$){ zxo;g+iayqG$3tmtAG!E&bOCORVj?g*g3y>1Dw9}`TaxC~!FI&>WC<+@O)eWQkVGslKwtNZK2?yl zFoFIpbU`6o6jg9+AUQ%ISM<3;o@k0(xW$z&D0?7zEbsWNC{iKH!VtR4(kOk8S6+_j zi-Px}@ALlsh3#gOU#Pd@<6Z;1_uw60bt?hFrS&i4;J&GE9sf=dIHz3Ki^ROcu)U-a zHRujmQh-bRD4XGy0q+z1$7C%zO0?#vBjz_lN%@J;5!1ry<=8QG(H-?YR!>q{v>G?% zF%5-rUt*}#kF=?RqYmhG^(xd4_4=L?_tX$>+}}Oxi)qVDX?Js7jZx#Z+eGWZSPH$d zJYP68)`XtcJSuOM_eRQ^xUdM!-qj#EM&v`%C%@wrZ!|1`etGes zoJTrv^8V4N#_s-6v;Lz;8S0|8dUhi@+J+GJ|7cfRo%0c`G2gv`UNq7su5g28Gj;K| z6i~V9raW!~B~5&*ad4~gtVj9;Ws?+Np6mA%zkn{-sO1JKYb0w}^a=t+SnvnXz94Hr z$NSTywG{EM`nK6Au3!W7v;hyj6m3J#ufh0Ml}SQzX{{^#O`CEEx$MK{Hj#c{C|^-VEypw=?h`j&&iacpVoX2nHHn$sTrLOsrK|$@-tcjDoo)I!HuVtR}H`jC2g3(pbhg(13 z1@oiKzMOqXL6Ail?`YTSD9Z}V4dT~Bvz9E%3{bx;%0lNpX1GGeS$+j+W$*xqCMUFD zlpOr1%#l&>i88AA#eCkZ_9sNz?5=YcM(YC^X!mPKjq&%H#jO(Mc=Y?_lGe2E8UsNI zwyokmH#%*m%pV^0z+F~$iPQRU{}WZ-%du>PkT&i75O>+Z=|64ET!4zcGxZ-+W3R1$ zhB@w+Khy6i_fOD7HG<0m1`12{IrpO`0Duo)YZcBY_+tzKOXbQVUyc9ORC#Y6r`3Mz z$N$(*&A~w99>2$P!}SGD4@Pj^KBS?2ZbH%SA3|0huK195my&8XH`kv0S{VFYSoOUy z{TH`JunprqMdrZoOlHRXg!%l^{_e%LZSG%M*CYQD8vt%^0XfT4gU;i%LyJb4WmM|lqZ<{OS|c@*#D$HNA70-X17R$(D-t)SIa1{+%uh)x zqx!uE>BBIGIW9s9;_)SJdGrdkkp=FgJ-;_Zxc@w`}nl;MrKe;18gv4Hu!B`Nztj$O!36zk2;U@6frn?Kd&Jj49>(% z8W9Jcd*b1QwH%LY&Zv%WpK-#3TS z$-}8MPbuI6mH0+IAlywBLRrWPs$=2OIaAPmsYKKCf_Dd|gvdJn`b@LlbaFc}&yC~I zV^w5`=(UBV(-TLpNh9MM;DfS0SAS~CWAMr|mx01h-nCH^>kRNo@vpE==!B@T7uC1A zn6K%Jkg!?05_y>Xd{!^Crwqe3&kS{+{HBUn&znacem1MeI+z%k@hl*$C#EGPwyg{E zqMs?Ns7}OR>0`<_lcw(^%c)2tJm@Cg$pgr!qT~$8R64G+w`_+kI*p8(nP;b-TNzyI z0WUm=X*VJV6Kx^s^w-RqqJUm@I>_;OE09XhQo12sYp~-zF(cqr`xFH@kSBf=o{4Ljz01h`>CsIOPNelp{|lwlo(Twe z#<_9y(yjG(E(CMUGuK46E;@D>8=vdAx@~fMIn3lnQ6&xbBlcByzqF9_MZJ^qKEBt? zGW)YqaQTLbQ5w?0e5!-7(vXBUeFJ$+h~A91lE3~uRTVKZrKpuguT-$g9J`wMfbqyI zvvPo&aRK3NbrO1W!Pqhn*T=gJOMk@UuCcQgL@9U7>!hKc5Jzk;oY6y_{z6Lae$;;MTta721Xtbr% z%SG9wulm1YMYjM7_J>7v|& z>f}D}T)h?REFH@mS_Ot7MM4I+iqEFh#lS)RxiH>E}IIiyzx70QA zubcdknEaDJb>RR=GXEl?K6o|r0;1C)o2hfJs9;Pgb)k{?UXNjbP9Pg#gHUFfY-EQT z8f>!HqSvHX+}wJMX7wgid(#!_p3^)94gE9ME_C!uZA~QB4G96(;{luzQN|3|bu*Zg z7!Ja%$7+^r;utnd7OUp^!P9Gl>c3L12JK8Gr_txwLlUXv0{=Poh*0W+1KnRhAIPZ% zQ}`j0ij_?Z_E`0KA10FC=upduzzTb+#XmuBs9L+uNr z4`IW>ji-$XJ)}Iju{(nHq>_1T$@4HbU?-Bdal2)CS{OD- zkA|jy<^8`-c*&;RCm%tCo#BIqT>TvvO<2%-q)XcX#?1z&cA6XyfIW+WZ| zQcs#OTE;!TZRsO2HcR^$HTFR?ccD#PXYt8N(I1!pkfNqbTcvPe3raQV!cLgve*Hw9W)Rm=W>S+#$Pk*%qgd1_d{!LGkE zLsm;d&UyvYk0zY9c(A(mfSyY1w5@V4=S8RK8x%7a&JlIvS7q=Rd#d3{(j1H(k!qJ zw^*?Hs(1cfbU#V5q)UF+l^Z9V@m7~l#WW?T3yc4K;&SGV%W~?M|GpT3=+KModU5FR z?%gtq)3ua3%3vLwVy@r3#&j5@VA>wn^ej}2dlc5?*A3JS)Kfw(kEsgmblG!B*Y{nY z_YK$bvc#iHr|+AtHE&9mXAh{l85LTe(L5v= zn*DfB>ze^pF*RG$_Z5sw3t}&g0KNB*_lzHCX{^m%yZ=&qUD|ytqP|~q_onrz%pBZH za5c8hG$$FuxTLx{I4&D{q{E#OZy@xzig5`WS^1f9X;jk7nG#=l_YAk9@TqFC*I}H{ zIq9dMT_Gs2+&pYa|J$SEg>|O3nyVS041Bpg1XC_m-Q}hQ>MpkjphWkXjy>vL8_<6( z{`(Up#U*(9sY2!MX1N{(pJ%^B&Jou-_E>2ATo^usY#68+Z&AD(lq5P}liqBVTb>*I zsZ?8x7!G|RRn_p#G@SQXs`+V~q~jFl(E~BTsXJ#{)h4spYgdXZ$j<3Pt=huKDpu%V zrCAEB6|wTO?fA>mLqlS7Vj?g74$m;OlM|ad746Tk^-y}LnrPk{HeuYEd)DRU zZf`uga4^f_MUqwP;SQ*a@O=~QR*8<6$TQ>DT+4M@?VO<5Q+vfipHZLFvNG~W;q*#_ znZ4eQum)vXI&Hw-u5IO3@?aGznIUd7?$MZ1r7CdGd*@r`_9?^JTdR-PJU$od-{%s7 z&Kn$jurU-MAmzfA{gu;uerbyVeKgWOICEC)X#?VHo!ycomQ{>S!*ZBoWe6cStQEo46h|w zI&8%2LZhdL(leJHQ#%<*7f&o|4&KGv)h5 zrenTZsal}8Z`_KSjM3?C(=2G$-vO?hWiFLh~5mnVjvZURH4gl5(IC~fKTnkQ2Fk)D4L6SPzM z%h`>RIroKTj{-9JGka!_|EE?_MxQBge|Ny!KlSZV=1_Y6eUmi6NK*&MnTzqX=m(eV zUseW{I_7==7cV$v<#)y)6wrPZ?xd%*uNC(y%E_X?e&4LR7tyJxml}oyilEy^NY4kO+G@QUn|^Sjp=qjx33QmSZTM0b-TY%bp;ZA&Mrof2CIJrQ^GGsQ%;qQE0J{9Uh2!@%h-;x zUQRCg?)>n|yBUnG*bfgDFC$RrB^%8l4&)zbfEB7vREw6~sOvh3Li)Vgh!*+z;Pa!x zq$tLQ-k^+yZ$WoM#lSwKK?D87ShW?sm)eaRo`*AFD|dDhe?&)=7YY}o zmuis_2mP*9R^865c|fi?zRllY(#bPR4{7n$ zLvYe*FfDWf_6u)*dsb3P>}3`%xw37Odj*%6%Id0m!+~X+9yW`EPM3e zlNx+r4x?}b`kohq`v83v@s!Y3glw^5bVR)od*j`SN!fki&TA$o-~?p$wMzf)B)`R3 z07!WxfvASyT#&@+&dD0E?jPOe#|@;I-}9jcGR7w?l5P;Lwk*Q92_ZfmzbT&h8}hD1 zD|uI}jRB}L7X!~auSXxf7qKfOqbsG(LVg&2FJbTTMgLQ8LM`&p{nDjke)ZM`FDCJy zO<$5i67n=pYqV!ZE-89Ev{9a{NWX_?B8$zJQaA#Oq6;^8-(^|R!Q#)k{}kWd8(mgs z9IC*S7Wf&_pQ26j??35E+-27$PZ;*$GGC;<37z7Ds9=_?PHtFfJlhqbG z&zTAFN!4v<=>5t}zZwm{u#4k=tZdv>|aCs1R$yj6W!*F_S4hGu z%qNUfE(VI6$5K&~!mqpcjJB=HbBrso;re?RgK_UkLt3sddi3+PnBlfn8P3H@?0msp zOzR?CS}xSK5);npoO+J|sqYFI(;<7Lzm;si$%~2>{$8^EJxurY#xcNY$4|Qkioe~r z0?vajgW02dB_zuNkD5&-ExCO07%DpfE621;cowJUq|79JbVGeDPMMLY#Pk%TEHOv= zkcpRuC`?Dc7}m{ju_p)Glg^QYKx~Zd(XV6^|h|`6eQ(l zzH=oRtnG^z!{f5#7L*Vt+@BeYGOs-E@G>=tuMZBUMR{AGprqRQltNbZt#sCi6-|AZL@g$|>r%?9R z#>^%MzmOrRM-P)VuI)h--0gBK&UXH)8|Shf9Cz4=t7D0PO>!=A-4B)#J#xfoz5J>n zbwY=Xq`&lDuD71K(1I);Nq7%;v{vnm67FN$o2qsu3x7j8+Nq9OG4j{4@}1wdQF7Pv zvN{Akp{NRx;Ska5UF#E4mwC8U=gPMF*hSfYlw1*MOCrSUT{O;Exxwx0U91RQH~pgb zDGbr7zTnKll%*d&d28j*oh!BQ$%`Hj6=y@{mlasy{)dg~z4DRAsNp9_j*BNqx&Ecj zZ=(eJf&=26-{P@3Yac&2zaxi`8v#0-AWci!1Ma zf?4v+dEL5koh^5`48ObHy13eTJ<3mi7?O0Oi+gZmyyfhRVMn~saB?CT7r9(+0RN|& ze+inIw^kSFY=9LrqZz5Rcv47j*F}n)D;aGLuP2gQR{5d1oENz%OB_3$c-V{d7sJx{ zI1#4OS1_M3eFa*<_4BHuqwx8Q+_S!dBBWaN6Rsq!XN%2_zHgQgcNaPtjwN+sok=?Z{Kjfotp8alqW9c-A;%*v>0cgz{;(-H#Plw>Dy+C{b7Np+v zw?_+UKTqBj-@JZa>3hDb-0`*k&Hp*vIh4wA&meC~$4!+#EBMlN1`aw8Nimv(3fT~ha#r`4;L zMbn}2XG>SP*Y>dzMeZ5#g}j8#1rEJRKf#KHeXXBXAAVNC5f}~8zDJ2~Hm?+J|4=FB z-NkK^W9_aae$Ab~i;uTPNPm9d`_++e{Q#mJ6~3f)Be7Zf_^lT{9iIj9dkL?YZMEIVyu6n1<$i77Mv|)Sb;Mzw&wUbEgJXKs&ok|n;787u^LhPNX*kV^nv+W>02E@;8HCrR3X4ce0y=K;u2Cc@= zBSL5Pjsc{2+Vc(xC7<_fJ-`G8XCgY%s_%+z@Pi@aH<|n$(3|5o5o+e7i%jE=G)4T- z-sXn1EjjPcbSG8ya{2HV5kfObiSQg;-n#Ne-qx^=z0E4w>pq2{`xg%%s=7Vi3dW3n zxhqy(fGeaulXxBuFVf4#Wo!YUqA39}*r#T!Px(;5LRoJS7o4%S;sqR2;XIO|dXyJ8 z=z`H36@WG>gXZy}{>I?K*rm*bb>8#EKqYrbn9#VzdbM(eWdpyF^iVb~Ny4x3v`={s zmu=g&t5YGlH)uHD<;6_e5%v1|Z>sII8~);0_-`@NCE6`Daf(Dmobc;9cM&fu-$omv z@F~iiiTw)n9{LpfoYv%11PA|WbL#c_(N4(V4c^kAYBR0thdOHgx7aFr=q0por_y^AMt?CrSLufq0v-#pqEZvuar9z1z=kQlIU zmSZTDibr}q1xS^*6U4o8()Boxb zz-?KdE}oYrKR)N<9I`g}m>5CN7fuxQ2Qw#IiX@2!{sADTpz}c59<0G_#}Oc9I?VjG zK7G#@SvbTyX@mTeORuJzNgScpoyfI{;<- zbiJ&Je~P_kKC?2olE3_piPO^iUbB z*(JbnH61)@zjAM6T6b}Gq4VekGB22p!RyIqZ>o|;IcXwH3B+a9ddru-$04#41@j>- zmlTF!UoW+6WUf>`+8_qm5yMtEPM<`W)vwVRY`oS6Pgg_~DeKqhkSMf##s1s)#d%#N z{2hd7i`D_k6+G#0cd$o)W&{PAi_8%>&>{ONpAa&kS~I+B7E+()a_nLcTrY@0jjV(M`^^KyhvE)VICt0wc04fDcH02m7b~bXgN)d0x zEPN4i03U(EJM@nm+pmlfC5{tJrScp3^1?>D$)zhXpyd{Ymvf5&6oon!zqyeyhQM~D(C zY@>OVWt3V8^=riJM_&X22XaZKF|fbEoZvGUMYN3{WD@g@f^i!`5%^&iY(F3{g^6Z~ zP(A__*o@^#^i8S@fz?mJc#LcZD3{rn0Sb?a7CcBPK*(^m%~&c@iZ^yo?wDsNXe=F@ ze2SIlmgmQ#p9+dVvH-%d8Qx8UYg8+OU_ZsuW8^`!5bEtl8JG}smA6mE;1d19=7U67 z0kUKgeGqa15BunjRZ!XBpM<)lI_agFYmFFu`TBf5p=qZHA`%xf*sgXniC^yU72fXJ=M;)ki{9cjE*#|+E>pI;rOr_gt( zN(9qhO7X*y>jZwh30uQlWU=5L)EHR}*yJYSvysmx;|cHr61>0M=b$M22(=2ZAtlru zr(RDL{f7U*_FAMI!W$yhIo!ATb>Y<$76e^)@vpKD(fALDvGcUAqbGb`-ezl3RaRMI z!>nlJMf(-)$){~D_!A*AlW*4bufT3ISwm<=6lSA#m8EU23up*OqqE$fa!M8>V=zB( zuTf8Fmxr*5DD1|?P0kK;mW*E`9%(i+(j2}h)i0|GZa&wobzi`izfD}H=-QYzYr8W952Bfn5WZ) zPiC4Rj>9lpHT1cXR4( z`c-6Af^?`esq)&wNoCh2W7VPW;rVQ}^kOB)D@cA$y?uYt36-G3)LQ_fIH}BWvU3aL z1KU5Hc#8XSZ$Ijb>v>FKw z^A-IoJy&9i`+%eov~F#lH7;{Qels*TpYybO0vdz<;Qo|ypH>*QAprIe{#yNEa@7kh z5z+-b=)oUX36h|CrOI!NE0F$*L1%*nvF^Y(GK5;}V$kMzpZ@aE7@=`PWK=#d0y?Tr zPr|q6>%a`$Kz-Pdm?V9p=&CO<2>g^2_2A2b)IV*vow@`z5xSTyh=g0QrKk?8EDQ76 zwCV{+4DW9sN+hi?e1ic{D7WiHNzg;Q^GIP1H#a{ts(M0|(B=mA*;EW=05>j!xCd>Q z2suQNGZ;sSqVtCT5yws!t6vj^{Wc-rWK&9)jOxf4D=Je7`ldnrpDlvJrI`KKHxjQy zgFV(z)1L&IaU)|!KOYj#_z*wsw@g#*Qo5%1AS~*p*o;O7$u;qt(n=aH2UiyIB&S2IW2qN$W~E;miYMx zYw}sr-upq^-!h+1md_*L%k`^?U#0E<~9kQ&t58WDAI(jEab; z2q?-Pl`XPCMxnGSvO$(CSt3hi$(Gg1o>Bp2OQDPc1qv;zbnv_S`nf)Z*p>S za&nS;Nphbj@lRNL1c}XSFDdZGyMe4Al!?Qsp0RPQdL$1fa^){27NWCLXCIq@+^gEH zODL}lbq|$;3l5KC7tV!lIN;sxsf)G$%kY2cMe_f$xlO(f7^`LoEp%c&)E(g2Nl%ko zag($9iL$)*6z?V{Fk%S-Sde4Y`7C4OF=78nk2J~QF62hIUPjC{8xDXD+(-9#b-DBAQTlhItTEjyYv&KvMw`yuu{nVWni_h|Oly*D$+Cq#*tA~W zKu9#$9b6OyyEs1#eEPY0F1&KE7FM`9Qu3)X?s#q3j>4LZ!?E4es#k~o-)@CE$>t-! zs{{<~A?2Y{Yq7O_W}n1zf7jxyy?)1v+(9tF*CQ&n4q+)WI~?X7je*jdh?kZ4)|rsP zM^WnK7Mp)UfxDTN-8^S-<=2A+jE&vK9<_{nc9Cw^>;b83SI-1Dgcq=iQ_+<6EnQ5- zmarR-eH^IP?k5C0eriFF`o@kLg^-N{fu;{Qz;=9KESMdjhCij=)lwF9U(kcu+fffD zx)Tm`I}Wz1;z8Rw5!(w60$?l};8UcwP98iG+zC(c_{TJ+$_Jie)6RPy8ipJ@Jne83 zFAxVR_qyU-i~N2KUW>fzwxEZPa+&;3QbEMF*v89$(tJxax)T5)QJ~v#AXmmXP#u0{el6;XDv=89Y3(~vi5b7>6WIH zUrYK3UBf{Lw|6`H`_X9aWj3xlLN{c6#&mNud{_fwRNY%d7l$`0SS7(Tmw(2L!xXW#jsE!%VY#5v{QR>ne{p} zVz7gB4EtddW8+_J-RZ}G{ooNfrVfp0>GV5;{XjUE=Omr$a*omA+N$+jUz)57ks6_PRE`oKkA}&xa53!cUWs_G z77sFWLYP}C;~}^zItL1E8l^xA(6Jp zD-)>+^#hXf1?d`{M}X(a;aH$3LOA_KA3fE3Ttf{e`KsgEg%kq;Niv*r#EiJVo>v$i zVPm-KrA=jGJsIgG?tNg~m^`~*Tt&{8+SOC+(m-v|u)16%U`O3u@Fp{kysp8oz`#wS zjz@J{eX-wb7*0HtF;JvXzI8^gPmglfXi|#|9gS>l6)6s`OSiABaC14p`<~231PMq^ zf=*6nxyU#pw3QA7qbzC=G#E6&J@2MUKy_o}+qY>=uc~=_j_ZS&K;d3~k5k5>H@(+aU zk9@Z@84-83^v09aDCzhQeDst#nblzIy4U6n$w|l=>ZrfO5FO|FaB!cOnQ%Xw#u=?3 zwjFp1aSi7*P| z>NrA=8ZJ7>|3r;k**f}_H**fKh#<9GL;tWJ&4FmUw})1G(vd4kTd*sHXj=O>K_qBf z>GzI8UPiP6a)RHvMQcGLz9B!{8mgFQSkNTfU zl95=ue!UbpuqlhfJCwnO@?iA3)2vT2K^0-!5s|F5tNtr@;VNCdFi#6eQRsG?P^&KC zGZLg*bSG){hIC3k0|@DvH(?(m;>AMVM0bK;B-0vUi_xz3bM_4715%zvHu2W2P&uJ2%1oyfg7*7ifp>Pyt@Sr z#&|s(#LG}hn+$yzEfW|=VZXE$E4|hgYFh1)N1?}lFdjXO+a>WVbwslVCKDn-h9m>_ zF4z%uz|avj@>mfArb|y6&3xg*47r9@p)E&);nHFq57&_Ffi>(HDRUV zz&TmL_9J=Mxy$@W_=#5TL69Vw4n6Qbff&DsMC8)cHOs!Sw^qVXG@Bc$)f(FpKS~0n zouP}Y?-5>RgTw*1s|ZZ-H{L$=f@erV5wOm!(w`?vf5%DYZMGz*bmmrt7!x7Wh}u^#Qy z@+wYoH|nF;7po_s<+d*DP_7y%XC1gpR-?0ugHBK4e~4?DknBTl&woYb=KpU{ubiMp zp}a5P+w*+QdoFL|wpP2KBvGy|aeaYjgtUAkiCu9~(v^pUwU!;*3*xyOcL(SMthBrUS00#56FCzZdU&G?AMN!KGmnU;Rh^|LAEX;PqS+Ac zSu4=29LEso{8r`Hd)v-fAB1P}vJCch0|#dLHeK)(!hp(*Tc^*>VVq*I<(;TvOoQwD zjm}BT^tG-noaliS76Lqm*m{}Bqc@e@HHb#9)qSD&%OTix1VB*5 z0hny6NGWju-UNCLS!$H5>Cb$0!8tEaUQGfc@D2#`KJc0>I$*@ESF+L9_c&Y-{$S|{ z@R@^(X&v-5{t_h&ums!R(L6E_esphC@Zu1C9d68mP}%Zm$jjZYNm)12Q==}d1FImr zY{LXbl^=H4*9qsq*xU3Ma{`2Ongm{;n0W6Ab&xTY*{42I>!a&iV3I7bjRD?Iu%2iT zFju2z_)f%vOsF#33p?sCvVjO2D1R;`r&kMB-G8oU6^c^tqo06FLKnVaG0{d17+pw! z11s#aNa$o!+kR$>qdEHMwl?vJ<@U|tI)}G*v*ValCT~g5KG=M)J@SFP+q}S4!(CB@ zAktJ3!#CPI;BLV$ALKc7rKKRj?D@B+i_o=0-u1>*VAt^RdGZxF%~+?^nKxpdQ7hH=2g}NyZg)!BGN-cqDmi_r@i4oU}l_b$C@*bBX>zo zvlTx?=pVOyD`))ds5z49(Cdbg^A7Sho2>Gnh*;vI{9%z<`m(Q=Yxy~Zk97NVWZ73( zj7@Xpx)X+}nbFRx>!<8{mlp$q4`%fO*N3`N%&~gwlk$v0$9|szRLjqq3nY*(gry zkLwQ6Vh7Qc>8E{8IQ?!;WAJB8b2)p5!h8pH<__ZQ9n`7*mMMjY4^!c1x%BHGuQiNx z`Dmj5{?1?Scn&cA{kzHWZLx{T)X)|5&S2`CkN2b6%WsgxhfPuwv;HPcsgNm9e|;o> zi50mB^{_IfZnRwf46pe8PCf7~5nghEQGRx;Qq+0z{sg-2pJCn=x2HQ|hy3IZZ^sC} z!?K5edd3JJ9b@2Tf*J!rP^%ukU$xtuP>#_(%S)?>Dbhy8-nx8fL)755!v}(_P{4%G z=AHTQ{}`pWPHzAJktu@#p4yu3Hm9aB!WTY)o!B(+ih@Zp>*1pT&`#x;%t~N6b9*_a zPQJJ2&;}n)G)I*ZW&6Eo75;h-uqDb(>yubz7m_ehxo^rLhLdioBhB<&h4| z61wLUqt#wFFIswTd?%hwaOvcr_VW&uv04nx@1O8Fh4?0$9BY0D8_4LBSbr0v?8GgM zjtZ;x_sWAtuyi;G0~iH}K(-WaD??AP*5jk^@&zJ0iuo@@0hX3@AfzoA$NDbPNfI6i zOcvO8oyaj5sm``)_-A`XhGKig@KXE24<;jI3bWC`Wd;2f z_XpY)?houftz#}vq?rvd-Cac#Jk9#75xdsIR5w|8n}wml-8k{f-TQTHQq%NOW}~A& z%m(Oasf#%ammuDUX1wp6InW;u$DdedsmYwv7HMFUny5Zua z-9Bb>KNCoLZT)zu?B)PdHf#3Eh;ih*eg4E-9w!f5D~Pdo+iEX#d2L>TJe_*|&Qr() z>8>rv)WCZb|5{GQz20;-hRc0{H;ovs{V>fxTE9e=(xxR9XW6lCpAbJ?dK9;KTOlB6JfCdR;^ zzx-KC>cc^%mULr;lZ-Qi5%Ot$vc2hCYlPN>sp%k7q0l|M{4e&VH(TEVgvW!tLpDZC z9KX3q;a;jg8K?PU$nC1gD`jc+rVlr;mmuFJw5}bI!gDfXptLz=b!9G6a0hQdn%N+p z8#0kuK>*1-gBUV>F=iUWbX!@;QlAfbcVl_v8cW2uk%8Ep{2 zK^R?o*jJLl9fdC0y`ErideQl0MoWx^b|&jZU%)JfcM6~8eav9J{66_LT)WHt!|-4< z%dwct&I}<)@0L&Y*N(M`FU$d0iPNXj6JG~Q0USTybIlA$JD-fNFTBX^v?yHo@K-!n zMN<#gJ1>zUM{m=+Nb%ytIOZaYS0yeF=1Xu#j7+^{iN2~*U+0wEOg}Xza4iOZ9{D3z z_;MT%es~dXeqH9aCfDPquqZAbN;g+j{*^(d&V(*5K9E>=CtQ&MOYhISIK*qd@ER`} zU2{T_>usKBxTR@OuypaI`O(OgUzi6Y0ycU7~Z3|7cvzGW$}%7X~J|&rGtjHB*@hVXCKSBifQjvY+yKwL&27BbiZBAq9JCtpP#D}x=H(C=&LqSj= zScE|ydGS2&1H%Hc%WZcgzxKksVV4G`>K0`q1`2l!KbYpKIUx->1}(KWed)+BY#U>7 zd`H~)d&omYnU`-R7?6=%HLrK43qMe!>`lFe^_U71q?{R^BhT&lbd`OlYDsy6^Z7`> zQ~D)2@@|txFD`*NkJO5f(G;cl_Dl!y$7MdvR%VQInm%j=`Y5>ULvVt=t4CaZFwj znIaYp&NUgt4_pmKFaq=JXzndWU^?O<`h%CoO*&M2wVVZyfrf@AESKs5agE&NW@HRh z6Qoaa0(G^}Q92}iM~p=qg5^gK`(NPE*Oh}^MJ zPk=91;RzjxCn8>P4TeZNGaT^VJAT9lJSX66uG)NWiWx7~FhT0)kZ6&)X~q(>w)ra_ zrmtn^)Fa`MM1lsk?5Vo`c6P?=4Z+}9jMT(XG;opgUT++6xgV80rGOcxkEAB(Ms0ft zruyQi6h@ym$tV)TgV#p6x@|nGKF~cW<4>C0kH2c(L*@OvsvK2weE4jam?E7!&qm?Z=9 zzSte~4|HrfQ81<{|&C4BE=n8&%K@KGmKFAh?`}sTBalai}#gF2y5UB@0%?ZOz zjAa_ybb7Os6R9foM~~^XVX51bFn1?T#=^^43FYou_0>{$1ZA@97hRnw3PNX>jfV)q zn<(fwNg7v`8#x;fi(x*eaE{{n#UqoqfKe!4!E1w@(U#)#cdOqZ7lQR|5 zSV%)+>^Jk2p5(z|8o^Ncfzpf~y|d5J)-h0d>HD;>#%P>qz^TlzuR0DNp1ONt8xwb@ zuBa}*{gKmkW&BCYIq=Nyx&`qzTpRcGkFntgm==;tP=d<_)2v%b?*p%i1m(JgEYR|nQK#ewgYciZ@^#@GIXo;bL(GBeJ8AR+`%fiE&ysztcxHr^tzd+LbWKlI zaP7mFfr~T1B5)Sko5o;wP;SK*95(8ATFoEp>Gey%^JRMFQGdH0H+`~w-y`bl8!y;^ z;*5CYjnTdB$P}FtjEOOuB{krJK#PZ!4BxD;UlgIQrfvH0PSkY3^xO}_-%T$j=D5{R zukBWl=w_#|)iIn+Ra@30E2q*Vfd{-`%qDAbC1eg8KYJjN8Ig~{lyyre{AMLpYJ`?_ z-4m)C9toIg9VV`u2c&44VZ}Bgz=6T~dya3QJQGW-q4z0EOE$A<<#q?f*P2^Y3O;V7 zIoxV-Vho4uhwcCVVRvC~@sF1);mcOo68Ui!=p%f8p`bFdVbaAlodtu_{3Fwu9=cmP zpFF<4e>#+RdGZTw_>#4xI%?ieZ%M_v6)KP4ADTkF2KjVod1URsY!FppL3sZ>?lt^F z1b#3F>|F?M-&WrEDMDDzzkZ7n8S)ld8OSss=A-oMEf$%Ef`+l1T!8_2Y9V$Y+--7& z+S7Kq#W3Alqr`|hT)Gc`_o-nEY3a5I zKRM$&B1{-}7V$KB?)6JTYjaY9#fx-c8%wgQ3muCvbDwl0m&qd0v)a*N`<{=N*jwlW zI@h(m^TuzH=g}>o4C>cn0^@9&Vp=kUjkX9r39 z9b2D`4C=Pn)Jx0{27O0m^K1%=Cu{byvlm)XZbmCV=_~F8N<1bUI4oy5SRe!enj30> zuL&I}b+QM($H}SlVY!!Z0%=>}e>xgH&E^?+Q2k$uW|jTnOt_f0%yQ_@M)K7zt>kt4 zEOvn%b9<6w>Wsbzz2#u6=oEX!dev?VUI@7>E>pXjJ@T+e42kub+Q34Y90VtWL?5V;T- z>a^XkdClKh-Wgf9yyM1Gvs~hxN0^ocyb^z+ZC! zRr$-gD9YaZm;6szjP}10N7xcUT#WyWcrHuvKc&`1M8MAkTLLA(m)ZWaB@XfbxE>1r z$K-QS^8YOTKPBQcd)a+O&H&Ype*;uI6)-F4zv{8Fj|ugGh+%_g6G4s@FR2%o0EYC3 zH~(pn%=7=6(Acn-T`BD%xHlVU2HdNg@Wg!~AXi5ssFRJA7}g1xf{*mI?_bq$#)GdU zz|VrdZpt7ZD7;f7Ys;_vZL$9v^8fmT641_n>u`Yt=)a(;0!Rh=Fpw?pBj~?g!~a%g zXpvFqWZP6Z-@F8PC78bq)ueSAUtN&^knj#)i}4vOW5GfxuUI}fC?&G~?Imf9PFKj< zJ;FenesEw%E0MLQPr0@BvEKkXXbR{m{34i|9uR#!TUmkLdqF*+|AIQE?;cK@?11z6 zTt%w?_UCEU1o^_yG`({Dgud(H)#}ox&8Qcw0~d2SYHE6;CPN)N*KaFjqmbrep8IC^ zpj7*KR5hjaOZEo+OZU1gaM^!J7GiNfJ?UA%pA-4}$zXsY!z%1+8g{DlXlRq&umgYI zr5WXy;|Tn4t6t1HQ(yY2@*9UwJ#(kH5RL*XcX!(vrf0vP17SA0+F9Tg}2xv#(UwWH|?RPm5z9BixKWe}w*qF$M1NYoXS z%W+h1143P_Uq#&Xvo}uJ>77x(G;ylE;l+vl7Vcg8d7ZK9pAYJG2=V}E9Pgmjs4 zx~RA9#Y`qWW2{yV`!QM9Ik`<$i5bp2`Yd+n%pb9RJWG2bsjcFxj8FZ^7AfaI{}j&a z1(CvYKMGy=8h|Y)>o3l^)G*JJJnA|7F4X*Yea=Adhji_H1g=jZ!}}4_+%>}XuQF@{ zj*oP-rnu{UNVmFJ+++1}2Tl-~=2%&p6&MvjsusJzydDrpvl+sBt%|Mqkb4O`wxL@1 z9G(vZg;1`2@u9b?l+N}0hk)|`1rp`X9$+R@cZRQwO>YPi)PoY}Mva#OHXKuk1gco!)~m~8Tlj&@uDSK@leIq)$lLs8hJZGyeYHWBN?+qr4d$V zO-xZ?6ErRZ(F-nhy9?k(SBGvHrS5vG z%3!!g{hV6O$HM-66b!Dlx;M@pTmVV7UAs0C>VLO~dlfAH$3$=U9$1_$XW#3t!VCFr zp~5UC&4*)tG{cU7&Yin~ojbP!6NPbxSa9c#X+C3v@vheC`hON|&T42}C z)xacSaeOqr39o&n&+xq48~B`APL*2n|Mpr2Q^sD~k1OAG*- zTB8dG4$+G5s(WO z(=AohQcGu3FIW0YA7kw({t2^93wkf$JJI#-aqjY+fGh0-QbvJ*2E_i+RF}&Nl`XFU zp)PBL3;i|kT%^$fKvGP9O{$r(?IWlYfVDPzWNQI6Su%NN_Sn{heEpCrt6IH~Sw7ze z4F@ugdjtIM{}wg?XzT{SsSg_e#(IDlUb?cNCD)#63xR5?T0-!{1lGSm@q8d#hy15k z#5(}v>|cmCcof4g4MqbYJ2SsrfgkAuQ96-ARG4b#T}&rHRq*ck8u3I+>ha?xUTM#= zmP{gZDr6C`DX$FbF4PaO1*F2~y^PmiGs|2xWLBLVT0GB>QYy9_IY?JTd=}_~l!wmr z$1he6%=B(n*I@^C0?|j)V@H_o_{HWo0+aV_E7bB)4S%8WGJuNI`+!Ik04)DL{kKBD z|LWQHHzrN^K;@TH2ohKtzfAbVhl1dN62}3I{lV^Eo<4xb>#sqE`n?{)3xIkC{)OFF z{56Qt5=S;p<&qWm7H9=l`DpNMQIdW3zRKIluB)cjc|(kdOXOmteKvb;35N!&0W3JmcgzeH@-WgqxB+3OfM3&`N&@ zPd@0IfX?1a*3;;M2?xDiOurUGZXpIHBP^wtNk0lM<=K49Ks%75@UGz>5ZsAy8TAkUogQyI`w#!U-&#BafW?C@<*)}| z!o)rKYlx{t>J>vLmTXkK+3fINAa_q|Db*4{uKQ^1=MwP%hQ1s6htgm9Ph=qHyTE^i z1ahVZ{sr9QpegS#fEU4)p?$3cJpBbpkJII}l{US9&{hBM0vwFM<0b>BRhNvVH3lO|fGD zL78Vv`Gj}d`gp;oT#lE_&M3jI-3P}26#vrY&n~CtUQc>Gbk$S_IN@RaD;JJ`ds>f^ z!ry_bGOfVhZ}=bBw{Ug2D_o5nN+-!UqhxAcK-lCnXly3qn%4o~Ki*hpe+7`C@W|j# zO&B0tvF-&sJHWv6drVUUV6eK>QUMr&N-LA!IHKS$9H*$9x5WVVp(9O!2k!I=`548d z9CrtP{r(E{7=_#V7H+qTi?n~F`vMOAY!5pE5Utu+Mu)?*jH|G^OnbU5{Co5eq2kdX zX2EZi{4_*Uf001GzM?^t){J%6!yMV%K)IK=Wc}p*c8lzaEy?L+$1e37ae#FX8O*S% zKzmLS3Ks6bEn-&4mnosvbGPBh;ce# zI{{g^M5%KIgC}Dqy;NYUFTDWhfU#GAC`$D=R}ExJ&T!G?%Ln^C`~dt5law=X8um`B zs)-`SKNo)+?)e<(9YfPOy$S|GT|awDfzRx%pG)};p}X0R;A^gjn(?&Rib6tL5tmM0 zK_d|ob%eb{(L4%A?x+6p8eSiVN`<22D>7(I@?(B(-fcQ}L4_PSF3h|vv;R-=} zLy%4?WF2_K@L9I&cQ6C`c(MwlI zR3#Ren4;Lf((x`kG-RCpn3;t(Zli;%2C2_{qZ085y=DO^zMexseE?RxFw3Ga(7BM+ zCFsRxr;!)rKabZ54~dsvccH6aB}fvGtFEs!Ez%!>q3Az6^8x5L2V2GD*>(T?9~KP> zxR48xqbwaf2H0$K{s`62b>9c79uwx@fBjAoE3$scK2!Ts-M`8GC8I{&cj7y>UY8?! zxM{?l8lK?C2(|@P`Bv~*v@J*XYT!Ox2K96ivbaPug|}s@=(z8uss}%WbZNstR-sG6 zmw%ZlzQC0uwdxQ1X^%fuCj1LN7hH7M-L3j<_5$|^U=7vX7u+?8qn0CM!Vc--hKG~X zHfqk$b*k>7ST6eB9!JtR*$u=&R*_8&dhX6<6#rxL^NWaXq_Lo+MT1Z_t%J)q*?)H4 z?<1ej-u5vBhxm$+g3gU+u8KJ|fY;hH135jx!0E!__vUZM99O=TjJ_YbLA2mE%^e$j zkbL33G`d*R=pL3^MK;SZIi^!aJ;_$Xksm2g@`ZD?%K@FmF-@u-g2&ivJubhwJ5Z7_ zKJy~k$C#Ux=_>JKyTV?pM(UoMBOC5P-lL*V;Nd$hxXao~mUdk&C7V8)vfE1b zid`+mrXm*_zS#>Wn0yY6m0sS4WFD3z+QT8$t{PlV23^=JuEK$p)BR?Rc(g_g`N56& z?hyGdn6q`ni-&$P%gR;NJM=|>Z>{KF_h4xT+IsNL?Xg;FKBBvO@- zU;N>fPp&Lr7SZeR!g5ZfQ_zGv^QpW%tY!*e_*=7>sWqj506rWHgyw(v%anI<64Mi< zaB!McVHw>L4~oA+Y#<&eSEuTk<&cEq+rtj3n?7jVpfE0NSEcH?AQoMh9>KyQte{+C zM>XY4NByyUn8IZ>mtdau_~(ea=TB1)0yUYreUs%Jn0id(Mf;gYt=`@D@=<(G-sY)J zmw9HxTVSEGX%S@>K2ilZ+WQ5dZ;D5!$HhO-t(%jIaxtl|z5i%%!|Z)7d!^$HUHp^Q zmLu0b*5u8>WXn5l30t*mGBqwBGeva2J2WlqE2q_@(0ek}^j?vLQiETBg42zG{+2CM zx}!w{Tuo+1`|u={@Vzy*W$<2VN9G(+clO&%W`xlmJFuAu=h{*6aKG*>up|D~t#aNF zn#`MR_I=3u^^FcSS~ag#?s-Ns7yetPI_)__EIT>i`?s#yQ1-~6rO#cqyH+D|TJ1eM zHdv45*4OirMx}9@&e8j{ERG6#)^Z~(I^D%2Dj~soo%X@0SMhn(zH{9<%=UMCFKxzh z%6ykCRIUcMfWIFe^lVyu7C5tB2vo4yLv`^Ot)+x!m%A=C4skweX4tq`!#`!}^HV~U zy}(0vOn16J=j$`8O!CiqrH*_L6*gj3{qKXsqH>Qe2?3ANZ4OV5QnhDReT@IzI6d$V zZdM?x=@_tHZTTOu|3~h(J?2r0W}VtQ>cu$>O}Mjy64ptI@(ZNU45)pLio0*n zUOy;ho7m%+M!hP=1z-T9xa0b^GNNP7<0hNc`dT%z(naYAXr9v)q<3rSUW9@X&OQ;P zbT0xeYMZne+`D3NbnA|bx>@fE_o{WA(~w{G%FzAn5Yv1=G=G2TXrntTw(e@#jhv9* zg?^BU{IQRIWle^}(0A_XOwGehg^}F>pW?H7_qc+cyCmaZ{S*wtbj0Ek`qERu?)tyOX=FqCVG2LOrf(p`nDvz*J12TN55kAP3eu9vg+?vlAl!X+`BISahTgCSRu z;JUB&vpRr|Qy*iX3Ecssz`uK{uY5d4)X*_Dp8Sa?{^&LEZL`#n@c0Yx-(ElKJWs9&I_K%y3XDEa?YrGoZI;QR@^MU>u-zvDZ=iUx z)3Z_N*^MPPtMM(9wdqDnipgvzLE3VvZS+N)4#l2jQ+zKVNKL5ml)_yL(5epvGZ`B zKpk2(%f%}M#QKm=YJDct26YL{o0w(FH)umLe~MmA;)4Y>m&2lX0^7i|?2)UW)MBzA zPDIziCC15>j#KXPy%eVQBG>%wY*#WDsQMxFhM%l9)t$(M!nhvB$*!T#SCPM-`XLFx ztzko?dm;dInG`x3&Rx$&2TZZ0+p> zSv^`(!dIP8>vso})HNP4TiI(MQsxV`E~rBZt5Z~ZbU81~IR^ke0Gmx+Pq(*4lV6B7 z*xP!o@8~R($c-s`vu4*;ERP7w#HOxM&M=5v&gJTQ(=7kU0dWa0dfQ1PG3QE)-5$tx zKp(~0-hzHQsKm8I1i_><3rTTzR z3(ySPq5oR#|C;5$Cj9@2JQ4(2?}!%@iPefGN*x)6Mm2Z-nV6aDUKXVbKe@7JvjW+W zJNj*Hd!xQVwxH!|D^7gH=D}mzJ+EcYT=kf)z2qeo*_`D~`>VY6v%Mc0TP|-uc#k1d z9^G-5m*u0_p356(Y*ijo;`KwMf(NYME9|vOYMBv(q$o$}jd5c)Y~Ai>JC)DZiEhZc zF`##s=&_BtN8I26%XT-9;UoL<-Zln1HZTnCDc#Z9V9YCw)j6Y z{Pqux48|b>Z$v$I?T+P#b5Qz5q)giwk9_+Z0k3zn-A$WqE<_{o#6q%GF3#g_Y4w#mlh4%$#2zD|JTlDJnoz8tIvSLdD+BrOLU@P~gJ zr75>c2IsMOPYWySj0ac$Mm;a?THRlK;I&weITducoN1eyDtV$Mq~`&lC29I3Y(S`{ z<+CjxeCL(LY-Qg1nJwK^myp2a(F0zxKa5~is?eUGn!P}S69R?TVqwJ%S@@-a{np5) zxkh8&ca0qjdBOWTXBJox*vD=ugN>w?Dx-*bhaSZ94X8z|?p_(|V;+m35)zNqPDJwnoDGGY`I4kqQ28xwC8-OR|$uHnE{WG&G|a3J>vnK`F7FRQ2AQr4pJ*w>|Vwi zm}hd~R?|x_Z0_IX?$~Gl!ZlYrsox4F0RW1&9Vgp(0Uc|nex=GDyogpP#a98-a?Yr< zrhSVPVrHK0Oas@{79fuXiPrDjiqdyIi|cT&+b@jehGsdN3pAO%2{La~8LK}jU0HSQ z`ql(Lp7*RCip8V3d+N&ggv!`*(VfaFdil6xylRMbeUa`3rgs(#t?x@dE`<>_jt=<= zjWRWIM(@fkXmz%cAMFkl48|;iR%vdn3G5NOH0pwXgclTQ^Q6ZDzuveIQr-Z&)Pf@~ zm1)>W7g}aA4(eA`hX(r{m$8bpl`^eQYh^Z{>^Cv0sur>C-}6Rt$q0OX#|piF;b-n& z&$sz!N7m)z(-f<EqQ7tneVY~Xs7J-eNP*JDHzaU=jwfhYi zg1`nX$J#liwWcT7y;>v3Qn_U^oQdI^A^L)8`Z|wt8H)q&;MagpJ7W^DN7%X=Sq-#g zjjTtsg0qEX<}`=iGVE>GVZUH(oz60%Go5^H+llRVuD)lkmruo@Dh69SaUG4li>Pyd z^7C+K7d+ptJ+_m);_pj9koAqr(>hrnNAq2+ELlX`<(jyT zgyyvRZPTTMs{&qU(zmZm)n&&UwGdt_O7>>lw!DxMrLe%d?eswOZQQ+14)Q6VCjTrC zzvee$hzoglWfnMHonWHnaYmg<+tF%DS{!;;i0>4m50oT0Al<^)fe9VK3wcpuZkj+t zZ3NvJrh zHv^Ut-WHTZR9R?HMV#HD)B=xrw;VCaCl=yCrME{L*PikFI1UhG=`nnb`m|o=0Ko{t5G0=FX(RTeBE}e@v;5laSuob3&pL*BoK;rqZ|e96SM)HVk+5bWkrGR7oNpJD z@Ow)gRk==@7#ERO@~-Q{iTa6B@eFxcFnM2zk(ilq4UBqS_uqh0uX%g$pD%kiWD??J z$_7q?V4aQ2e&iiY>Rww^}co-gpI{3^82ooRYT-LV6Z)uJpVOyDzzk2StDt z3tpU{(YJFiQxkqE@t~+hPO^E!IRoZ&b{07Y^bbb9OhyJ zB-iS38MW8%8Tztye*(2=PzAz1OZaX?Zb+-K!zYIfNkfdiY$!B;_2CqOY{{ zj!y2C={2}WzPI6zz%+?W=c;SCbag&vrweaRR#s+ASc}9d=ilz?T>IP;wuM0mtfyxE zQj@hJxwP!#c$qPk>n<&679zRSS?@~cS6>a7idxqE*Z8p%|) z`lT7bJC?yBwrM0WU?Eb(GZpVp`Nu&7>FH>C0{tV1bb+w%7R&g}In1TiEil}CDBN?+ zQuI|#0Y3fB--x`m(swiq|E3KY&Z;gJywsi?aOVkycy8bVM>{V~ZE$2S(6(M9QYd6H zSH-(c#x%lCDAH1e_CvK>$zZPxhVrtgP zhb?VJ;)QYqvDDOAWh!l)V3BRNkMeS5cZXw$vi{Uibyf8n&tK=H$_?yB?=E;qYE{v5 z8bhmhDZ@UG-8D3RIe+<$pZNIMw33^l#G=*si(yT0v}}wrQ=3}sxwx7$Ne)$;v9MSb zn?;kSNoE{+izdC&q6MPXj%JVb4dC4D6jl5kwsw?`@wBZ(e z)J{=fx5z`*P50MtRC~!CZR1gO8fHSYHY{p(QGEc>S%9&iCqPJHMRJspz@(YF;PfTs zN{YOG^JTa6B9Gka0j$f=;SlAp+FJwhYfmp^GrARQNyk{jzW2ARBQ?{Gj4G+_+c?i@ z2lRUjc%>%3+<_vOM-o`C!+AFOp_Xbi$Km=E+Q+<)RX4UJV=;u+t+Tu*J5-)+7%{Fl zF6C-IBj+7%n#tfcv5~Sz@48Wz)Jl-1BYH}Skf`ZKFV&OF!>fX-al&#hei6xjGaUL^ z1w9=4l+GnRS-OV`Vw;`~>K9O`qjU{y@?*nv-dbFc|3uExETyKDlnp|QY0l^`RZE3k zU<>*;&HbS9g}oUeTuv?QP$Ouj{~>mPGtKA@o-^&5`u2ZKSS0aHf2E!j>}0(|~qW3q^R!xR4l$;y-g`q!;x+*iPb!5)Uhl@_uC9 zw6V0#Qhn8QS4+*$bMms+lgg8goPlX)#(T0=h?YX)Fznu!2+j=|0r)jd4fUK>CFu?W zS8_QEUcsQwS00~?>G%7S&lQWI7Ew*>ogb5|pb`m&RWRYaJRk*%;~H?$`OT%@EM*i^ z6uNr*c;M6?A1Myna&UWY#Q+v$5V^jw0JmyEhE_e?EmWgR9i+T zHiX$~s$GZK5{mq6F+p4nXh|&E*me@pxAO59iABLo+ByTLJN(JxDGZ#C{o{uqpB`cd zo^x#elAZ~}SbvGCBbznwR{8GbJ?`wUp}gRb>F7}4X;4#Dz5IM>)z{#W3_4=DOK!tT zmAkI`4-~+{`vvJL>WA$7u}=%=$9Ksh3%i2oPJuo$I1dAT^9wO7Qg-NIZ=16NkUdBg zNxvd_uk2*1{#1=4B%&5KCg+MyZDl7Wh02Wd&+@p6YxPS|RNfivJqxN>A4o(2SIK&p zJMD|v5OyG!fefN+{TR{OcYa?a7hnba3`_jLdbM2n(GQ-(R@d_iz)dWsQ+R}|hx*Bb zs>6QxU-uhaSW&8fa!p>qnlwv)5?_RjaSM!WSS%5Sz8*NdcQmI~IVsD+_itU`Ir0IiaeXT(YRn_T3`Lg7tSq1nvypuli#1Q?b;i7 zE%}Sy*5Oxb!iFXlX@m@s+qc-I?7qEof&bVFNqmP(XzuWqGRkWeNh4+pp3jZG2OYwH zz!}1!r&VTG^EH0E5r|)1yy}Pn@KIvbi1ZtQaei}vFeOt$DTTh~R!NjZ$j9YF4da6)+`zpS< zxpKQ?(FMF*Iae7!N4vOg_=HhMEG`7>$@@|p4KMRDi3MC zzBYbMHo*O5B%RyZ<72-KignNTi4|_1D)PoBoq2%Ea!#8#M_3tMX?`*uSh(jJ{$b7Cd0*W&mKv&FJwhtlUkhteO# z6qh5vx}&w!`-vPmoGXdF*KZOA+FMa8mMzprYV5tX0zQsMwi{ACdxY=Rh)CO*bxeMx zC?#;ED$2I!z$gFzW9&V^no7R@agnAXU|B_J*%c94nt*`RtPNICVgp1;s za$z7w=lzN24pA@M%dXy2%+8w;6Kv=3j*wH_nHG)DZT8QiuO=L6t{vapj>K5Cf1ZOn zFjg1y!*^bi_6p2bFWfxxju7UP%745)-ZCp3`E*B&YHh-o=)V`j0@BdOc(U_9Gqz_8 zbj7$|95-#s@f_cmkn1V3YssP22MAp5SZ1+LKP%1fYpg3M%zV;!w0Lzih`P5U%rec4 z5*eO#npp6}Zb?gXIs?fVO(!91mul^oOQ_%9#jOiO3WtQtnF*H#xxs0~{MB7z;UcV{ zvM}3N+}3MNoZZQ8a&AZ4XwyD_tP!!+;e>;3`0>^)(om`UpR5sjz>S4V&2NXQDnxbJ ztk79}rCokeB#Iqj;2V9b5Jz#)3Y-~ozb!m{v7rdT5_FRlYMzAGtm%ddNt8-zR6SN z()h2*;7ifDA9YqLkWP?Sc5334rtIK0YbT?Dh$M!Q!)mj7ZL1~ zz@CZSQN4wU)jbaCQ7R!t6p$#@1#1N>^>m@I2KB9tDupPQWL&wkOEQBOniUw3OwU;< zJKShAZ-m|XJF_KpW{QB8&~s=@jbFOx`vODy3kFv5s@a|Oo5u}@%LYM7ylHI5wri>9^siR_{yXGq`9MKF=L57)(0so zkHnbnYVp3+<0}O#DyzcNcFrpWsGK>gtxn)rHD?8K19DI0oN0#JO5Qz_=u;iJ_WRfd zXSK)NKYLW;j}`y3XpXt>!Tz&U&glkYxV#5|{6t5tSf}@Ap;I(ZEY?}d_)qyvk!+3X zm2AC=klw4U#vZ#g2HiuPgADGg#&%ep95Wvm2~K}E95V+}|3?`YeP!?73SUV98XP;= zqT{zem)?IweA`yLl;l~ZbYs|{SI@0Q`}00t7L49Rs-0IpYdNOzxUbskn72RjN_ZB@ z>KGa{Tn7zf{>XdPJw(+o%uDLKmZUk0mw_2#`4zLcKB;6ME$9!Dj!GEmaLf~X+@XV~C73w4xU#yU^; zcKm{DfWgc~%=%%&{#N?%>3v%_dmNwYv_BtKK;K|^`^-HZGk?nE#?#16ODSL64i|6r z)@R;Q9r%8(N@WtpzxJ$Nd|`i6$RX=t|4V{D@7mnAOJV=KR8-y`7*UzVciR)uQLinS zxl0&_UVib_?Zn5ePHl@t&IgF$8#^P7uR^9wg5%9L{3%I!PbG#6mXAx$!T%Ukt_j1K zQkF7q#a0-fFZ}oTkU#3qBTS#V!Ob=&5wzH`4C}aBd*Q6v;b~Sf@ z*7=#8g>f)QR>&fvm>kv6XMRXE*IF*9wjLqtQV;wv2%@{mIs^o~y5C02%Tx`Ns?bX>eozb{qS}kRX(tKxilVeOtIvqyw zz(!!}QkJR8kvZmt(k`>n$gUUJ=4kiS>W$w&>NpK=X3whs>CCWy7N`=>`)(2>{&4g7 z!%x?awuOGR?NCeMo7IE;jc)i%RF>0$UY&4E( zvk`Hfd$qD!Xidce@_WB!p@}W!+eD)~;S=Q=!sFvs_<_&PA2ZgR65$jj_rwm!hacz# z7cufrh#D);#`0@wk1mR`4K-OqLn<{@<^B-^s3#9bBHyo`bnDuhXyDO8D16}`akwE1 zvRKmB?bMqjD!INtq1z9YD?jPIGhdla{G(a8hkChcOG@LBnW#P^vwA;ChV}07tiJXQ zxq_XG2;%W#v#!sLW?hf3=f>olznY?+8MyX|Z5@m=v$1vmd?De;&NTabf6N`0^HY7W zimK}Pl6G0-NlNBCQwsNVu#o1{ibt;ATIk>m{z43LUFeug-s8n49wp$8H1$|HWO=L{ z`oQjv{H?&5bm|rI@>1oNh+KBkmF-Ch$iU&1ryqO*0>>`UCcQZ6?~i>gKO&lFdw+~A zb^1`y`tibDHlzPaao1m;OjUpRNuS`~8+Gz{#+|*#bxY1(DLs*ywe8oFM|4m0<~`kf ze9+&}9HDKl$|ioKM&Or)Vkuj=ibfX;ql@aOM5>K&u7)~3YtvNKx!5Z(!u;HaMEKJ? z=z9bD%?Q3B+qf+`i)!JSdF;BB!MxHAk#@!nO$Izk(4sSGqAk0P8-23V*U-e2LTN}@ zcJ5n6q;#V91~`~G`boB#V|U}n#%J~iM3+EeMwORiq6Jfivosv!#pN4#bC1yhq~-I= zi_z|G)eg{$4S&9Qi^ThjVcx#qmV91nCwZi&cs9b58sWR!&0tCSrSyUT(g{g3<5z30 zLj|20fOGCIp^Q{VchTL#e73x=7Ix2t_vF8(pI_^#a9Yr>8JI3M6M8Hx*I+zkTQ#R7 zwh@ie{+J&7$WasCm`5o+FtDgv5;rU3uX2a&w_158MjKIlhaLU(#71G?$=w(igwNfs zl&mP<*Zo$#jU`^Iv2WWssLXK6d$kpsrb;@@I*~pSMtUpYpmMkyBl2;Vqpa&+YUh_< z7Kaso!XPI8Z0zw;rtM)tX7sI*^yhy5NxXxH`~@(qDXvJ*6KUr!fQ}l2)4)jk>jLRn zdt8y~Ksxlg;Cyc0>#2d;djsqrKzRnHJOgXXvXfHwT{9%El@a^ z)Qb5j`=7_u*vdUN10wUFahm}m@_lVYaSEbHkJ4=eo6+IrwP`M3hKY?En-~|^#q^z4 z^MBPw!$`s1h(+6i2ZWX7F6~Cc;t#rr*+1Ni`mZiVGoD>PJy-qJ+DNh=Ha^-xv_4q+ zW>&p4IA*RaG3=7)46U{@8xfV{;j?h}6(-4pL|5~3*k%rCbm|o821vk&w`>D1PxpC= z-5Vh77Pd*U^2GWvO=mIhciwn*)n}IWsY%I0)Q^j*M9xMS_%HU@E_pEAXm0O5^BIB) z5iAE5g2Im@bS&bB_hPzYA|0t zXLL-t8AQZdpnmlvxcd^^S98QVra~uh0Po^HKVuzLm6OK`%vYKgc=;9&TjC5KeAIz? zd*a%;(m}i9HTc){Rh6tyk;g_|kJku|FT^mFj@Ll#;M7t1MOy@m@OZ4!V3aZ=`jr%U zsn$5)bzfa|Gboa)+wXf6nX!A(L&D@S5GdKfS1%G9ruD;L-b%fM=S#1s4X}o)0-;rY z^PdIq@d)QGo6)M|Wa_J1i%mzzEjZn}qsAEO?@iC0n=bl{zgaEut~fvb2L05Vj;~E- zC)XxNoowPe^xAv%C-m6u80ZOu=7u9c#l3E31%8yZLcl7_>&wpP%|Gz4wA$|zYXxt7 z-@LAFfe31oh`3@=+f5J8{w1@4fQilo_`}juOa6v}mnjwItmYC>p`TSG&n*7T`^{Q) zU(nMiyKeEB{_Gx5J?eQKq`?-|b>8%-c{_P#^mt7lH@C9xw!im5o-iP{jsQ;@bFU^o z3@?2k%Q~*B*q_^r+3hSg)L9N)xZsPC_S)0w(<)>3^fF(yanDbRpWbC#%v-LETYTPf|<8 z2}E+4^X_jzwsqlZba(&~R^*-~q-yE~On-Qwe@D>yi+#O6!DU3yW20B^??8l47Mc?R zhQ`#f+%J~NP9q;f5SL8GLTE0}iS6G+Wgk^&?7?I6A1BHtE z?KW>pfAdZ&K`@&9zFsUlHv|8pKdhn}GPSFm)|jQ`N3uWLn`YV>mhvh^)34%un(2b` zYNnu8vT*O?Fr(l@?$sFM^yQ5-p*W|7;6RFC$K;=b1m#Z#t{^Oz2T>#LLUZ@JH-ccM zOmdUep(}_@;+yXX*~?OTE=ul$&!WmpY{&UlNtRvXzQdz&dARRMSaT63D?&%4lD)iF zRGb~LPbA4+))S@WEdOH3!(h_0b1iHbBfKDoZLD{g_E6{$g6u?b-{TQb3oC9LcTbP0--Mc!@k<#&NAip zwgvam!UGTw>S6EEh?mV3)1U*BuuNH11|5C}aw60Xb!M#^Dk~QMD5~CfNBAH@r|+;x z-wt{Ya)+h3nD7$PA=~D66b-Qp=-`q4PM|eY-Z02!pM^}qXXVR9pLI=5IOc&y;42De z)EJ7CWNO0lJy5_=m_6`QjPcS~nYSIT=qP`8*1({*7I%!bpZY{F7v6Ev!O2hur!%TE zp}F9UX%C!Kn+{ekh#LLuJpa%MLo4mMx3r?M;r( z>St*r#-5;gev@&vLOMyjXPFc2ftkF=b494cS>NlAE(8BIUi9hZ1#(`o4HX438!43% zo?E);nVg^C^hWMxg2x;teFKy96j;zJ?WH@JR1Zs3yO{Fvw~dP&Nd ztdt<3MQrIoE9^|uL#jmGnhs0gny#O^^iD#;Tw+MCh6{E_N(v=+aVOs{Lb0!#9ekyw z%VON0EZA(OpyvA&g)D*1TJ?Rxs1r^3()rTm>5S^74;LNImFW9A_!4&eIy|t9bqrCN z(aFaD=@=q2qho}Ra}3!?RG@F7Z=!r}zK^SAUlwL+Cu z$VazwmjnOKz}}k;!Xe<5lg7*QI(X+R2E1 zAxPKRZ592(*Wn!F?BzHydzdGf`tQ0SM|H6AOPOR`JX8iIkKH8MtRAJ#H|MaJS0{Lr zENxh#qh!6E7F|vxk5c$1)D-EW6j1vPF1a)FnRqfh4kCx0kAXXUxuFpn#4*%_u;T+0 z0^?Y*feEa5RxB$H)CsIOk_j+pp*lLFLOEk`A3wT-5r+j17)>TaV{`wW z+rv3`WeV}G8(nBF&^rK;Y0>O+x`qb?U!g~Jr18NXjFVTuznP-Gu9i%!EO0*wIBpr* zitZ5M_EYBFkLrLB^ifJ}UUNTQ5ig5ehgX!|t)@$mSEf?mbr<}dVU=JNS3kwarC(rd zN^MqFkFq_ur1JjFYUB|escfpqBx-BeUh*t!S!Wv^{Z$dKBcFuUPmf zL-jWu$Q?%qxm5HnFzOH)hyvuUqeN9*u&cIxVwq-|9(`B`(nV~LZhzOU_sD3e3h#0o zy=i<8`*sENyAqf5t~+o`jmYE5RQS7Y)}su>&)A8{!wt`pF2_RBuZj+K37Cg`V4W9q z29DZgvI5v@CvN)3N=L5HQlTF*))b`>T^-BQ!1<&!82Xr~0S0X^6|Y|agD)U<14TD z$RoZXcCH^MZU4>)>bRgoO(}EKjyJO)*Kt<2AnndjCT-55Pkbj?_EL|dH#TTD81sh! z>nhWktlYXxRtCCFWUb`jD#Xq7{Xmy#!&d%%K(LQ#(CQAXfXfrN(GP---3|JO?v;UD zqtfc$bwQ_o9bB2X541;ouXp`U(rr-w?8YPjKvcj~pIqkHA4`j?0n+iZfeH9@z^F>p zM$0zX^E-j`f>x_|TYxrFE|Qa$UeLl5?(DEiuzho(X>1nfqFpanuMnwFBMnI{b6i+Y z+=2E4R=ab8nKZID`J?ZPjHZO9xM;x7kXaxP1f8;2Dq| zbJUn7Wb;;YGQ5+HYBXBwKSDYHiC@BoI>?E3^bQ=sA`X#citkccV3Y>dgoA*#gFaKY z)=(D|dw7)adI(aU>8p5*d*_ z%9O9jc>ruLVd^pw%#w*^fmu3ME>}kS)A`h9a8pGcKUHTou`Jz`9-iPFJ^5tEE*tEQ`4`f0l-Ql~D+dXNpOk=|T-+$p5(NVPUgO}H z7R(W59q5>C4IzxinZZmg zz-3FeZI!NZXaHme09hm;)~*fIL7AXbQ4mmLL4ynjgCT;rP>oZKS4~ijO9vbfd5DY@ zxCw3eOkIEiL`gt&W;YhX|B1hse-PAb5#Yhu&1nQ3TxPgw{clJ3c87Mlr)ny8anMc2 zyez`Zs?@D_xThATl{@xtbV&$*Q)gc)5GbtL07<3%9m##Di#*Lp8auWg|IwMt#ECsaT5D(5)Uj5)-t26ZwS zL7r|^OQ0lB;tXOb2?p^7u{Etb$l0wP%wFb6=C4=aCqi9AcZAk8T$}oKW2D>S^NWn2 zPFEc&P*5Co_i`)LPkUM6M)P zwgv;;w0K%9UcO$wJ{fpsEjIyXJUAyh030!17E8*^6{ZH+Di*n(v0)*0rB(qXr*(|Y z3mb^?X!C~c{GFjJfYg&*MD}j2k4FO5g-t|dbTsf*J?K~fAnbu2_HUS?R(o<}EL)Bz z$6L?XNK~RL(QN_jkWeJYp4mi>0aU_xVJtfpXg8@+_n5I|bNLb=1Jlhm=EyQJObM76 zsm2QvAnTzUwAX>e6bb<9FcT+3h^(#YkW>R+Cy(I=G^T@rgl=`OthZu(ztbf<*;@#^ zz0GcmP~#3-F;+1_F)k6*xb>vCdSLEJ(LiT%U&)VJ<-^E;xZ1p3v z;~6p}pz(iCR4L_-#Tz7BL}vk*cVGy-%e7!(np@ZPfOa9BbqpKmBn4BUJ;ln!ip5IBs>Oyc&ojtg4TkB4mPdBXK#I8y3 zA0v8Ez24-W4KJPt3|0FrKZYp=3KfB5RUjDxZZQW<_f$jfc%psry~dEGt<9b2wD|N` zDbVDgAW5I}xE{V4t%)Cohpq<)+_63?3`oL(Jmaw4Jr!*UbbA3a1P#~xO>Y(Q4&|Jw zOkt(pi_(OBVO`c?Id6NBk-2fCTR(K0!h@SfEW%tu)e8+CsasneQac0#*AsWHO`)01 zOc5Y*|N9gsG!8VxGuMOJcRaI=d1NCC+OXb+8f3ZB@cR*qrJu6&*Bd{4mxot#e(q?T zM)bwz{0>ew8pkb_097U@!9~%TRIh!H)Eln@`U6*{lDC6-R-B1T!*YN7-{JOC$=a%k zj>b4ZBm<^erjJbF1Awb4>s^dFt{0$i1#-&wUC?m{8mfu`nGTQ@0H9U^WaEG!cQ2T4 zodBK5dF;Rz&bEgz{1E`@qtXBY#|$%ZKQyF7O! zf^)%bP6TrWK(dOZB_QP(>xdiCIt{Y?eW6aFik!EgqyFbe0{%Pz&jL6>5_=Vs3r=XQ z-mTuiElAjN#{~tV7Tq48QEaf~tAwhC!Z=z?TcCM98^Cf0tVoXc2gw3pi*Aif5CSWB zr=L6KL|y(wWJUuaY*~g9m{`Hv-kK;eR2LGx^4PLKvlw(iPCfrIz51r{*O^pN=n-&x zDMIHKbwIb7yCGQN4FaiMz~2x61heOndek4l1)0n^=HYvS+e&lEf^M&1B@+@EFdRLT zBVN1!;DCwOG)^Ir`G{Fc9*9kh$H_xwF)AWMzTnO^|9p7NgkOHp4zT(QyNqcEqTy>8 z^ntIYfiCw}lP3~)fGkn(f(}LWoD<3k0|1<-?%UGA*LCj+mfG(u& z1)X#d9~fJJ4y*y+LqTXofzYb%OW%|(PXfauGUjV>qM4BbvDSHv$r^tn@uud=8&M}v zLIQy%It;A31JtVm&3f_B4ha-U%vnxugT(0p`7j08=Vd*V8Qz_Iep^V(Q%)BX29P6& zt_Q38TJAeaerhz8mH{xhHDVB!5<7t5HV~=?8qEPINp9db2QV#*C#@fl!zxQQ*@1g3 z>K33VTyqMtX!6yXpyFh&JVrABA^?00Fp?%9{3IZ{qAml{$c-bGx4D%J0j?Bek>h~G z3{U7bfGYM02yC#th5$usz$6n8`#zg|;w2tAz&1a?30tFu3o^URVESNA_B}G{NY|nl zR&Oz^SrQKVO+dc^u-zTtmp(j`YB(90E*qX;i74RK`bH zvb|ZMSsi3ah32(fsokt1+7{-eIW+yoeQkax6tfa8xj9XN(D z&NYM$#gOhhrhP({udjOeKCjEqBGk3n$G%LxQK7-6Apl@B3OyY<52QG^){!HCy4m>I z*x5C8o2nG6a2HbP>%1WJ13;Zw=uz-Y;z)ODYi@#u9w3kbvpnDmLtfq8g1sM?bFcUd z<|xsjy8K@|OheCeT$urYTBc!lL)1Bor4i-~b0@f_#(Ktj?sL_tUk_G|E-xHIWJ8og z3NECgjT(#^ya65sx=JCi60LPe104gdqdCh=4S)+#6vt7X5dNa>(f?*io4$dVWcnjx zb^+`KWG!+%7>UUBjP(nJfZ3qIyulf04Q3iMtAN(}gr@i=U{s`Hq%80E7mh?(x-1=x zl)xnv7K#TFnp#_0TfjIXJ|>1D+2Sp!XxMjN2wKl4k8}iW<-<;uvIm{Njb)vthKA&VxSWRTTnrUY`Jx~u93HI~1HcKu7NR!O2 zi*RuKjkEoa#?f707Na=3@mR&%V)5Pv*ia=qYH0HC2}BipH?YHQFMwDE;H~-p>(gr{ z{Mk%9jOBe?l0@~51b0-l8L!qlU<&U*d(TMrVsg5U0>R15%XZpilO@qQOcE=ILt(m; z@v(^saCwq~cJWPaZW~_rBl_H?5LyVofG z0yLX~4nN=+#)%i;jSyvE_N&5JMs1kc-b3|U;Mj8-o^}?(G*z_|sSMZ)N69*o1L_E1 zPh@UnCIMEEDC6~j<3Xxi4+A13yX@peCjdby6V`ej$c4(n3p4WI$rQeOLa+t-B_HI*VP4f(3&woQL(&4-Od(ZRY6&zLV!Fwju%G+ z@FH8eWF-(TBzco{CZ~X0mF6wY`vLCJjo=4%UJHT;cShkLU!Sna(4V#CeKt#En&p~z zH6H|`cBAz9Yte*jg~sQC0LQO0QIvvF5GnBkIlXI;tXhU9Z~akKniIVvY~XQYJ<;p) z;R&&7W7n%+zmAqVi}tcIAM|?RB%S~e8(5D8F)7WzklJihc8OVuhtIz%q)ltWsa(b1 zMeCP5HN@VT?}g{ShyUKJfXBDb2DPwNKSi8i!M9+vo3-(;L<-HFOGn8X5BeEDM}!JV zPe@qZI_(9leXSA~c2BB+Jo&&e1D2!A1ZF#c{v&yU@sY}c zbuJhm2NeeehYWCQZ9}g|{|d$lEO7Ay4_*{4Rq5RsK#7-Mbg}#mi*J(Pzmkmf7Cn3z zpO(WlVb3n;be(&VF{wY&z47H2wNA#n?(MCjmJ5qDdgs4gCB3xmIFSV_1-o;nz!sEz z|Hgjh{_L<>v41LDJ9HweQ~D0B(4S1@mR_LDj^r}@%53YqjsTf=&%ek> zehQ`plpG&3xgx=BMand4eU5G+R@wtCaF9FgY z(@UV}#}XMJqs4kA(AFd>g(!vOo=Yv1sh14|euOLbE5LE*jA*u`jc~S>sTAlnn z+3M-RncE3qz06!L0QzjfviZk)xe(}3;s=D50xuY7T#LA%sQ6}(&ZNZCqVgQ3-5H<%1bJ|E&Un&c4m{^f-DibFp7lc z3|Y|CW}a+;c5*#|GeGKO>XBv7FJRc2+IV?9cL7eZpFNC<2|YOpZ}j;U42*uW!>;Le zAhi_ePXvyFW}XB8slsuK7Z)b)J7RX?m1Us7Zz431rvxB{L6+sy)xd^!vaqSWb*bsV zHuk66(^*S_6KqQJmqmlKqOk8$-Rsg{Kj)JFy~6$-Y&fp1upNPrZlLVPK41x$c&_aO z+Lp|g20e;-a$a3^;M1skx{I}T0@cY+_=;)D{PzO;f7uC)irEa(=r5@Cs6G7lEYEZ! zyRCNmtHQGZ*4 zHuXaKbc@FHVjv3IGYke53PL!Caa=&3Byl|Tr@jKS;o$Zd0A@(cO2CpFnBfi@s|jL* z^q|Wvw$@5P%Or(?lUMteg*D`w=E*=p7dtLW)R!#jPn8VF3^>_YO^?zj>Oy3z(m8eN zBgij6%rAV;EU7U#ISb_RfIKKrV&YQf==0!QYV$$R0V2FwE8VfJ_5ksRy?Wh0VOq z@D17Z+$S)jZBEV(X2e7JfSo(sioQ$O%`%6nLNM^ zS#zKQ4xhk0dQUAD><_-eu1!4wB&qY7$4}d=pFbkxc%F1>;l2q;pSCj{Fd%JR#4`O* z?4B-i7atRso&bx7#lqrXw{gf%=k+5cTYYlEB)HTG7Rj{1nCkop?Z?Rn9yyH?*YYIJ zXa%$-h;mJSMWo$EoGi|%k2-z%Okm5r-_?=s#oB9A$1Z`r#Y%PSY`4@xmvVps2HsFS z`C@Dq^fwN@$OtcW)nT0|cif3PKT*rInm%keepm1kFp9urbv;uA7V-aH%7gi68}rAk z6x5%YzE@d^+l-5EN%nmzA1vOspRs9e*Kyi8&N<#>eeU{P1u#*SHC8rOGL|Lo^4jU8 zg1#}{0%@CWonFNJW$@Hh$6e0-cUx#?=$l$DEXi>v zjb8Gg-T`W5P-}r&7S!88y_R`3ybR_=XWHt9`x$%bsS?>N_6eyBe_Iw_sY(`1T9t@D zd8v9q(E1D$(Ji+aJn4=3Xe>L@YqH?0$teRauin@h?Bv;1syChmUYe}EhG=2v1o49swW_vi-!od=-%3!DQU!8bs#6A)0Jx*E)iF=H0ml*aGPJn^_$ zBXdNkz7=)Pp#P1nvk)r@oGF0vEh>k&4JxOZ(QKzro(9K)D;Q$5&~_=r!my zsPSDm-b^26>Ia55(}fZ!50;9aqP|;+pbS##IyO|U}ci=wom!)x26cF zS=nmaR+Q6%Jw|e%@g;<-uK#!I3(Bmo)cQ?@r<@Fb-+sy6>z?UV$xC6b)hey zXh?N(G^pq(G{!c(y{oPQ(w}2|Ef_gk`@AmqRc!|1sW(vCW>;`fvnb!yCp`N5$YB1H z2#bY!>Kk0Gx*uY7GsG`=O!9VDklz5j^I}L$Zp_27<>T#2i>r@t0V@lGdfzMyz*`xa z-Z3^SqPv-9B+1hoPZBcC6w|MuD;B5vbdG;k`@D)g)!)}W)G+gl8ZX4^P49)>)^7+g z*ukI5Yv}Cr*Wo&Dr|OCJ!(o3e3&y*MwY)v$f>V^n@nOlRb9(!X$;{`Cu&7Ch(xx zCLA{S{w_-T9B&SB9YV3N#{Jiz6!5~K=$w(^h_8k;>Z(P}b+`qjDD!HVU`z?xXFn~l z&cCZ;QT2Vfuy0ID9cgc+msvj4sC1*TKivE%ez2j#P>pfnN^!P6de)A%l6{$5(QoHB zGe%r>u!eG-D@n#3%Uy2=rl3!6l=7|eA5DHw>P%(`_6;{TI}Gw~mdfX|7v49x-bET= zmhi~RzAC4k;{^FplUf^hoW~X6xIOm7v(HnT)W#V zP1s{U)lUkH3P9%+^VCy) ziaq`s=0)ncf9lYg$%lSkbRlPx!TIT4TriC%lw6Oj3Q-S z8Z1}7)buWqnm(%!3r&0w!BGw?<#i?QN$^S|*-|_qSa{1Tc-l7SQt&k7bOm9lsaN_i zs@YSwvQ&)EH_pA}N$|8Y>te2eoh+-idhO<;i2OKtRiAswmhjyCn8Z$! zvS+RUQ`jj_sG=Mcx=nr`nKcSAz15PP6zqwlsr*_^{$`h5M_yS*WS$Oq zrC*1`LkOZ=ubQzX+=r-|X(*4QLR-l^Yg-{I@V<3XfcKn#xs*8RX&xP&^IorV;Nycb z(d0uV!9kBkUGqcl^e8-&*A`sC?4 zqp^ns>2;Cf?ij*6EOo_0kYCEXBp9&;l^&9Yu)g_~L|N{6@14Ij(?a_}P-MXL*;ID4 zZ)5=V&Fpu+_0(rp^ujAMr11wo8Yb*o`iQ`n+(N+XBzQGhvS~XHAQ zt7s^l_fx$nDOHyQ(iVK8-xI`>AD_5MJ}5a=iU>Sae;?6#{N;UfHh-PyA8Mc@BeCXmjpzFh8^v+}ajztPd#H;3sUh`$!; zxUss1(?1aJ=hy}W4=j$G2Kha*@2W_(rWMwixt43yuk6FyEI6>s2R;y@6pCL3r(4?l zO*_9oDEkrH*dDRVTZjO%hqgKBvQvG^bfJo^fP~og22A8t6VRTLc4XM4(&!nxP_FLisPCI!8G>LIN>z3FNh}D zmTG=cg17ay*P3`6NV_G_#|1}INrLM%PnVx+m#~`sfy>ud34aGStt`hA<_BaqjT3aZ zQv;YK?nAZD&KlDLA(lRqTkEF>inXqx#j&C>KijLKZ{X`<)C<%GPh32~WU#5W|MeCI z_2pmFHS@$HIqeIt?iwaa1JtTDZ^yv9zl}9kJP#JO-g``#x3^CoC)C#)UZX9L9zPE@ zSmxweXBq}9Z@zM=@7rz^(zKk_sFv(u@8q#CP79FgM>!6JUnQ~GH9BhpEi%G;@JioDDY+yS|xw1$pjs8S`e&rJ(mq;}z#ObH2$gzA2g6Ez9RdG!8)%i;>QS->~G3RQWev zAI%S{?QGI6%MyQvt5XPxiZ*6GpHRjs%lC3 zCFt*>6Gd9PM+NQiZ*y2A3%9^L*@!V}eVrAe0k0cO@NdBHq=vi=h1cnYG;L9{wmjH= zdvBG)4jf~$-E8q&xmjVNAku|C1N%lVdzEt3dB6iX`K~IJN;`D3eXH1*;?ra?EdDgI zBB^%CM|va)6!Ve0i*-V{Mkxs5U4%dJt}t7$b4F+KGxavIJ5*(FIJR#l*+=WkO!Df- zi0_Eoe))c& z-w*V6wG|?YSv4<|ultlQZeI@e31TKW2m8!U<>rpt0Xd0)E)meF0y)Md9#AXnxks); zGp9P;PLCJ%%;%M7S#R$&3v4q3B^c3vC!&|$-B%ZQJ!I+?Yv2RDJBC{PsxhN|1e|a1 z%hv$XG=Ma#HXDRXLRWU*Rq*hIwX$}iSt)t)vKtjwDH>+uUoIUFuX?#8)HAGKa&4cs zR16y!a5np>O|||jI55ZmVLcUfq`V}*arxlHp^&Qqq4KHjxQH7WE|iKs{ABJJVay=c zqX-&&DIna?3~LsCMz#RzaiAscZM0YIhqulzjZz6B-(bNN=E)!mOvC+>=fu6rYQoK? z=%AS--gk4<(TU3Zu_kv~LxkXT&~?!S=}8(sJ=-%oKe>@EPVn{$fBT|uQ9mj;&G+3< zv!&BwKe^emlq^D2CCopt{>!)i;7dW~Wp}HWjY^$nkz_M7I5`+Wj0cW6BIe5!cs?hf zNN+7={J%{Cgo?jt$Hx#pzQ*u3gItLAPCWCS^1e+F|XH4@F`j7{# zfW!OEpsg2Y6fZi?$Td{^DP5$(^gzkod;EWpvl-awJmn~*FfrfrjIT^3)>a!PZXR~e`49~oAkel(N?5A|+J#6f`m_3cyOj$A`Aa?H- zhQrPDS~bD1W;FKD*N5l4vi93uP?M7Kwy`qhtw(7}GO#K+KOK~TSHGMv(DC!1S-CL# zG#lG|VW^jZ{q-_p>1{a8A-p3STjtx_OWN_Y0$uIhTXhv^2u9F*|9jDVYuU?x7@T{< zN_edE>zu)ExOvW^1*Mz+kOtZ#dK>Z@d;WWwMtJqvffD@havdOdl&sS3TRJ*aS3ge8 zfH2^Lo!!XXo0ISb_f8T$HwD{hvRfJkH=993?dDcDr$m8aX*M+R^T8GZQ2#DLUAGSQ zPZP}kTdCvTI#>)EXJU{?wKQne+PnW}X-)|S5(z+}r$+d3Kiam&j~`Y(UJJQy%Tur_ zMmU%iBMc`!7Mwe40GL1kW&nUG2HqYR7eLkPL9hfTws;S965c$^sa>4wW1JjE-8wv; zdLlm|UGj3*DJUDgc{ zn?0N4yZg@Uo3u^K)eZ1`>aEG^;V;IeOJCl)aecoayl+4En}lb`s-2F`3IDicPq7Zo zkFF1T^u;!^C#`t}ysl_wDvJ0Z3RR4sdY#2B3{x#}JZi5!HJ%;*C=99#^NEB`H@4_j zTX#;;%jlk0h3*@h79Jb(Jf2fxc7_;G{VL!KjW02c+I|jU(z}9g*4+q83?bz$t~;=c zYOShc%DTLF#xA9!Ffre(IYo;LcQNwA$qP1{)i=&kKCq^T9xsIN#hsqf$DQt1r3C&J zV_+H~D6E$1&JdP7CZqMh(_uJU@El%E>eB9~#-PuxdhO9UwB?US=LCg69-aH%vmDfW zQJS@DZnbne5n))xx%+Jhx?M5*73$N&bEEDh3;KRHRwm9_4mg6R@4|e1?YGrvTRYt# zZ3`!b5q*odnZtUbCa0Em!d_QZOpCf=!5Q{-#WbDsdTA%)KuN{4UCE88Wa&frXxK9V zq9=d(_rBYE0~g$V7u>@Fe(*OkCbJER&0g}9Mt91|omQl>_-Rr5n{300lp9r3^h1%l z$?WL5_~}ys!2|QzjJ)OF`|0=&I)19p4(tg$;5HIQ41KB@)9BiZ7Rl}iS3;rf0{+?! zX^??uKV{Ulj^8(*Z4~%z+xgr=kF`yJuo;Xl_zRrTH|1urZ(@x1&ajRUc>?PPc{rU$ zOD4<37qc*helt*3_+*zeE_CAJY8_so%QqaKE+0LT^A;jrTT? zcW4Sc-U6PD*y9c94W!1Ez(Jh|J4FekriQijTISII8mKaw9?y>1Lw($L7|yaMcf=uoSE80iH*zXy-_eLwo@yhR1f7}K%b^UBr2 zka*22XBj5lZDA-0A%Y=O-uM0`pMKx433+^Npkn&h9uf?z>|fjN=#8-DX5~fo?n<10 zkT?I}#unjW-<5=v><`FoH4J~dH<+9}v0>Ma28Im+clrU zP*RsP$V_vyOV6D9>U)CFt?zslYb?hu^<;qb!&AaXmTy0$$|PTW;_^tj^8S49>EDf- zOgcqs>7b46)@Ouu8(PrqxfqMM72`To)uSi&8mbx@PIMl(XiiaUU?feSMBr^Rs0+!a ztW8u~@6N4#@bR{llNw`sLsctJyqiAM4^?3pjkmPGGq2-sct^%v*?$BFDJ_?~+r$iC zt*@LKSS@hfk63n=^s!DoIhQk#{nmL*xF`6sWT^B0R}sNvrSkhP?6DJ&C7)t&vUtJ) zo&HqSBYmo!cQ%X}{c$<_@vZc8odt8?MR(N$jHsIDsce6AFRzyS{_)t+faea;u7h)# zIu8&~ zGrsn~km{X_?`>_MCcLc;Ip;=o9n3C9G*VlabE+L*Es9@I#2c!5vX<|^N3`sz&lakA zCGQVXYc%m_>K3jKGl^a9zI1XWyW*9y>soQ#amDKk z)K30c==a+yyvWA{_CiGK49dfC+{Jq)I=C?UeXv0|sn2OOPWXTThL(kTBw8W%`FsuY z6v7;$(?YJdDkm>sDV^UuH_Ebd2QS7LUuKHT)XPowZ7zg6`hDv+d15+y1G77| z5e~ZZqHF-|^;|CHipB`?@$1zywcg)60hhtJ@p9vp3J0~|+*RL$ZtxUB@@qf@_DR?3 zhBe+>rhz|dET{?3Rds>)DR<)j@8uY~?4Mx38>@kgZjsqpd%&A! z3Wl|U+VU@_tQ`jfNB?(7|CQ)p=Yxv@nEV5w|0vI;0Hi{{$@Z8Pa8i^As+RQsgWvjl z{%1#0zuy`r#edjxYC|^^(6y><`k#^e*G(|RO|PQ@ zs_?)6X*Aml3=&Iut=bJL+}fDM`2Gj@7qE-x3&LPRX|3bRKRUkre{8)8Sd&NFHtdc{ z6@@BpkXl8mQBy@lWl3ABR8doF4N#C&QF&UHu&4wGiGmgpA$5rq7gDvBrxlD~B_K;c zkSHP%X^k2rff#{ONWzv7vi#?b_Wj=P|NmnSGr4EE=9+6c=bAD1Q2OnUVepWDW&61# z2Q)`WNq+j@)MGQ>4HNb;F@nQ8Mhl2G$@q}|`Y#*f-&F}1XsG#D6C*-zZ-nFzoqOBz zU+W<9tEwi{=-<^`)p)$4(LNJ21l#@>e=>VW&s$8G1ThcI>373+iEupk&Oz@UfTjN_ z`2Wg&#F%gD>fb7mP~wOp-67-kvhKqLASn6e9l_YbeMVUyxY8=$)CA=YrRp4*#z){~dexjh`^K6(2;$yS4xSgryhW)*DUl zzPuY{)1mUL_b-nn?2v{52v2!CMH@U_7QN%(f5x)A$k^1?x*vhV(r z*X1>0F=3u)*Z$gP_dmpRivBeNGJL&0q#lF{Pw8kNaf&7lOU(5dP!iSdl81zxtzR7CTXC1=&)gbz>&!+akSsujKC^1$z z)!u=L9rI2k&<<97QNCt0W#~vtX;dIaUN>`~tYcn!!k&Yf8@*Pp zm)yhBbTIR{oFLoxU(v?)JAd|F?fV8RSNyVp2OT)BLZ|pykzJ;h>$9%5%)Ct9Ax&?{ z{;%Vv_N|eUpz9FjrAd#l05@dc+K#3r(?P%a1n5V84*KpR^dpar(Em3bMfA{MpALluO^2>nMt32^jyXLtdGJM7*EI@HGD>Fc>y z_0tcwY|x~4mW`9Q5rBc!=j!^m3Uk<<2zz>&g()`w9=7F>>89m$2Mbp9CpCqzk@Y@T z^o<8IKhp?1FHPu+1I@9G!z&4zkq3K{;rboy@uEX04*U|6UPerM=AR3$#oC^_%)r;; ze6%o4=ps7W?eT^l`s_w(<`FfY3*ZNzYlIlw~ukXYMhAv)p=>EK(q{!bubu?4W$ z7Ds%OoI!gW8WC0z_pB3Sdkz2uH%aoB!pYYc?T?3+3O*iD*}7ZhXcp@jPEhpE*-tdn zit_I|`M(QhJ5|RJ1{qBzBYE8B?~jNG2SG$l(NYciY5pR-GIBojwF1Xt$>3;XHZI)c9YUpKC*whi3s zU>yq~6Jil0Y&}@^Tg5D=vA?@+lwACin7|Kzhc@aK>D8ES@JJ8r2HVMRVDA@h8^2sdC!KtgS1}{w zFVWR?H>4Xw5ZgCETK-8ZF1Qi>aP$EtaBxC=62`PDbl?iY|MwpUB$4ObU~Y`1W4Mbe z8ep3le>q-Tw-ZkOIGZqqH}z(K<(qm>a2<!BiLJ(}1CgM!f&j%i1os&u zQyyWyc4WrjeJ~A7(-kKNdB&hsm@)E^%}?-IqDQ%Rs251c{vJUb9GehcuDZ1wWvUMb z2^02DGrxgttT?qNEJM^aYFD7 zw;EQwjTa8$umcWoHToEVgLME>hl~aFnDWk^M<~gw8{r8j8-$>V8O!hK?|~SXAa-r& zM*GG-Q6D14Ra`=kL$L(NnF7R^L33%sR|l7UMA+ZJRYFAvw=LFVVZA$nzYfH1GJhe! zk10(8hYhW6@SVoti9x=w=>*}?u4NcX;}f;*S5QjWNG!;A51%Fgr`)kJ0TY(_7joZ; zTI2LFI{&*}YaF%>zXoZ=zqRmJ^tTo++V$3fyy$~1ury(d6%-mgmjzB>fjv_{~m(Q`&yc>K@^KQ@3ad!d1-AHsF9m$!!`%w)6 z+OqLGU{kvn)Ife)|6GotaLfP;xO?~nq1f8L;~PtM=3ok&WM958Psecb5<8D?JI{c=M1DR^Mx4d5ArbL)Zwr;gsj;MLqW&+4-<{VOXF|8E~w#G z@vC-u-fSE2+oijbVBR_9n?q5DqNX5iLt2Iu5f!0z2{wNf>J;S^wVUUH-vHWFyw6@- z?2R-UX@2p1!%FS`ZwGy5d^~(@V)1`v!QZLWc-1eX5~(Vq%I}D9l>2D>276M4J>K(M z619`(68WZ}#)K|F*zN(GicMNGTpE z%<=fW-Wc4UFoiw0m@IfOq2e-a;n+AL*~HoCN9ji?M&rGev$U_r;w@zdyrpc*b~G%H zV&XmJS9niZe?&7{Pb9TlW2HV>gL_->mI~FtiK0eP@tQL3ZmGf#uakwtL7WN!yCz0 zkU}e^NAL=tEneZ9XNcEUci>eN%8}HgsYe<8{%u*6l%tFZ;`cb?O_L3~crMN$ER0{O zn+U>AruBv?xHaK4l6w{9L#wEgdDI6<0f{s!8}a+-70LpnIM4G2sFNcNNt2*23pcb3 zEA>^lCt(!sNf?ED5~ks|(bG-SaX-sKquLk8V?hc>nuipGN$e?b2$I)%gDcM^cq-E9;L(=Z zCO3nlmZIb%?Lxvk$I0BW)(Lp$*u!9_)prP}RorC16u%VN>nPgCGlIJcYPu?ss=BJ? zLJ|}VBUg#bUC-l>TunlnT{gSk^+M!m=6Iw>tvNrIu1HP%u;;LLD$;f&s*+o2eG^6d zV@At(B;u#bXRE#D`{7c9WyV+%Za1K^sD@EUKTGUMV~{2w!6UE1ECeXREL2LB(gEo# z(oUo%BsZknNU=zL%D(z3W34G2yjlL1$&#w*s4@=n zL&}rbGyW;4QKQJy@ZmqgF~wtwKP>)m1TV(j9Cs6SyDE_YDHi}IdjGaL%DVrG7Zoom zo{6-kc#Xkc>!Mr_uyRC#bx{WV+l&7+W}HBV#D23q_NJV1?;qnutV#x;*)yBN0M zy|x>b+p4xzJ+6FQc~oNW4*EAR)Nyd7DyUgjHTrMn|3-&Lt|wB2*u(n(|T&X{* zvB4X^Ha#|+QO&kPdKimr4k8_Gm$mXu$braKd=C^dCxFgds`V=B|R$e@xCPH`~TsnHQFloAURf1k{M%g zt;&m#G{$K07|vfIX{jlAGi@y1OdIVy`W-Ml=+Inj1SZ(0ubJ#Q*;FL4=RsyGoO!yx zNymR0dep3c{t?G!X~BPRL&5mIii}$|ns}kFX9GYYaj9+?JU}ZnxVBwL4`;_NriJ>$ zPx`a9AzX)$Ocx85CRbp|KAuZXTR{ye5i1mvYtK!V0WWZ&isuZ^8TG?9y?6g3h*!G| zwm&+adw-s2uctgDtsU?ggw>;~ zTik8EAdKjG%#9o64o`|-A+eW&2oprWAs6m#3*CAEBA{kj;?T*#r22vyD*Eq58MyO> zh_fa3)((`$FOBx22yV8ROs`I4C8}M5TTzJlQk;FufYg4NlMqwCD6x;_aK?CR#1gQb ziq7B_=E<7En(|X$SJ*V+{VrUS@-M7Z&aK21h`<)jp)@PzfHkV@VMv-g2*dnZ{w}DI zgWFPxy$15U4EjH1SwmV(<+p0AEZnd;C`1j+?G?JgyY&f6b>3QUyh+Bl!S0A1 z7~8{h@y2v~Fk33m<&A0R(;ADZ|03qXs*&u?bn(XG;0mAkMPe@iwI(c-wIONJgrzIm zRdzo!8{*9_x_F*6(RS(74>BQ$=8!Z8;0czQ#VwXxlW?egaSPkJwdS{CU=AvpLegT< zEE3)ZkBmns0WgcTm^TDbU-LZ97ax(>JC1X#2|EtYxJA_5{h;kbR{6x@kC0{+&w4JP z1$R8wQ+$Fvd;Ht%ffJChFD9}PUtfl#JwjX)K&WUy@P}@%P`q$Cd|M3+01^e?fVM7) zZys4|D-1nKCQ=GH#XR(F>k?M^yQ`dm0q&8=IFy5~n2gp|FfYV4)oSV9Uh1vvSF-oKwdfKN_@46lZ1IydR5{s zmQlEiWgHRZ)DQK0OwYnd!NKuqgsHV)aFN7b0U0GheK0@;9BG$@bhBq%%dfpj*0l}a z;BUGd|7`Jmmkrn6Y#uvju<`RV6Vx}J2K~o=^PI+@3txZn;gluUKRvT5H(<;4_;Xj| zf3)1}WA`Lctqh@`@KCv?>%HN;a%t82L@F&Nan0tNye@Xfyh~>;k<>dK$b$3!L;W>% zp-Q)ohOK#?v+Qa&Xs3C;Z+Abm^|tm!8eh6Oj~%&J-Dgjh4`^>c@L0qUN2+eU?%Lr^ zE$G$O)Ge?l$N75a^p5X$e3DVKKzH2mndfBQJ;&B`ZOcQ6Ofv5>o1;#5AT!SR4?V4^ z%W|Pt%wuei8(%SoR~4f5_ngVAR%!WZ{O*LIwY{G{lwFg??}|x0C)}RL-nLgAhK^bO zLkVoJS5piV*b6GA^CT+WwlqEy^}c)emj-+1uvxtWookveG<&P%_GH=@dF;f!Y7cv| zBHKUy!<;YNC(-Vm)$L>Z?Nu*M<7>9(d9E%f+-=R->U@q}es_v~p@bB*1 zE-2_tA|~xE=q*7BttEKqXic46n@#6|MRd+Y>M_#xJkvzZIO&!=(|`7=CE5_yVPp=F zjz;pp(S^?WFg{W3syl1=t)?zkJI{1*ueyY_oU^E)*VEIEdeJ}LJBQb8)U$gJJv8?< zUwAR5B{;yXl)6gx&rnSrWg)$&tKIg2yV9|%My!bY!eSA=@HM!YR&r*GlNnV)@GwRE zgJauq!$3`4XJ5!`_rHtzSqr6_gxi@^g>S%Z5uO#bOjVpcS&YG^2Om@T=9SH&)M{Mm zmJbSg?aRh-fASw%V47}OTTtl5{bvC_!hdV{>w=Yfr*EfggST& zzW-2HO`Sr?)QZyhVpMuroGI0hw7b(ZTR7gfd52e13&o@yd)J1g5!<#bYj5NMq z8{g1gQzuq3w8At#w_4n)a3EXvSX=IK(a6?%+zK(;S#0DQigmtRs@c`dU@X$-9es3!&5ZKjShI~t7J*e+~N4&^Ip6GE4?$* z_@bJ?wtV!<5Y@^T(tDCil?1U=QMKHa-ZENqByMY7nM2DY%_aYM$1>ZZ_QZcaE9$!w zw#(!(-1<8&(NIqkEfNnwvY>YpRTvG3&Qo%P?lziD8{`x#qfoJR`a2Ac958({(h<}y(e|J6&_DY{aj7E;jsGQe z{X*HJRUQ{11aH@Z-V#F)J9w{p4{H{IK~bLbcwcxXYgPCb_sS^)N>r2;4czyf1R0=NxfW z%5~j_%$mBmHV<7*P2E}TLeJT>+BnoD=PFAb$h7-AbzTN%&t(O@2R)r~rA+X5TOVVU zt2PGQp3Rz2VW&vdNc1WjdonK2t#NaZny4Zg=Of*QhcdnPf@(pSMR1(II&oD&Z-`-q zr$<4rDvd9wq$yn;$W*?6{M4Kj0r1XIdSAMbo|D?Xr_|!X3zuCK!fbCr)FIe1Q=Rhn;t@VRGvTrAmU6HpJ3dhv}QSwN1&(8PZyTPe+NBGrMvcG8o#Oi z;-f+K;qoFw{t~X`OyL2hUkP7PrBTK?kSX`lwTbAUx^FPo)RB~S+B3-7>~ubc1*Yh| z>g%k-oKrcMjIC;S^m24BA0NP&@?_(B2bNhkhq57Lbt3h=yf;DHAU=I zYp@b^WgR-#J@7aoqEEkBnD?S^iKy2ujh_XGgL%;mKE@daS0fe`E>OnSGTwRte^yaE zVEZD6G&q;U-Pk*{df3UDY5gM4fYMTUmbSxV%s6@de-i;<&o$8OV&kZ1}>xr+X0Jc zdCm5snz_m;+8@&Rfvt2F`sYW7jbKl7V7S!%$&R9Sn~pn4b3-kr3Hu+v+#jjlrd?FL zd9Qk#16d@w_!Q{WNx<9uf*7CX>2X`~n%5QdzG20dZQQF~raRBNQBxPF%Ga$)E$*svtFB+k7Tm7L&nwesQ@HeUfEax(og>Jt^g!-Ue0nX3)`!HrHy3iYwC7K`<40Z zReR}jSi+jRL{)ioS55xezNV1J1;ZDtrL9R1Ug;`Wq%y|L&^Klsr})zS?27j@4BKT*|hqvQY&iPgDgPo}fHQd&O`Id1|O`-oSnH1266LVv_gDbho}8 zhA-F$LC|9O4|^-}5ZwyaC&;a>qgme~S7|?CvynS!b*wLmT=(;9_T``a+uL8SwhE5X z<_k{I?&m6-w7(e+vgde@6=X_lLX}nQrNf2|+HXBqVTb_MN8WP<$E8)Fs#x7RgC{#O z#`|^OnZ6arV)ya{^F4p~{-#2E=Y=fM+xdr7RiAF6=RC#{ALVJo81{VUG@n*m-9}8s zCp7v%#VlTJmNH#;-C)n2UGY96lTz)ce59Mj9`BqkQAV?tR;*0dm%LK=wUTvz8J4i8 zRLo(d3#(-N(G@3b%m;1t><~;s2YSppJh+)zY}<<2iVOF%ht{ykIY*e)BGn|rRJKQj zgW{+wkY%CgbXx6M?QYh}oMg?tIMrg-l8U*Cl-#!O04+|mYJFQLpag%zJ5)KWOEQdR zQ#sS9M?%|dbQ@TUII|GaRN1Kl4AV^?}f+i zE@)`0_jHG}+`wBq80O5BR`=;{8`gP}D3#LIcHJ1$7>+Ygqmt6N3hS2ci!IpTmP!*+hgYt$N*F(`XTQesD6i zlGNs6xP~?)6;Jz>X@zAR<-P#TEla^kJ2(+TWF{BO818W(g-WP(H-wp%Stf8(#rG8| zjdmphmeB}U)=^1qBwdWj!7^Ql9%c5zN~(%)a5TADR)Z1~l(Fp+{IWTf5>Yg9zIZO5~!JJB<4rnm(i@AJ%22>wYJ+t6t{ zFKRK*Ep~U%y|C81xUAk*CRNope}JND&xZPp-nDMRjJd6~tcd1u?zP*Z9m=L6GP&QS zJiywGu%vofRBV|u?y%`n4Mh2tdAE!LBD{${5P96aW^OCJ_>gnxn>F#5vgIgiSqq{b zWh+|7iK;KQZHr1QTio)VNaCbDP`se$h(~K?v0KkEcgbblOdx~SNS>ht##9!lVr!YgVEC0sFskCbu|gj+VB0 z>6}>W)2-ZHq{H@^G`9ZtKWKyb4n@SgL7{~T>K1Qo_B}SVhI6-Sr)w8#t;Z96Q zP%9xFqe*gG-L##Ct?UWTr=&F-Vh*rAa!!`kq1|D$i-l4I>C&q9)>z%gY-ewhU3Il? zi1j(DY>Uk)x-ZzHE2i;ku4#`OKE&px7MmMTW}J~^4?P8cS>UI_6SJJbHZ`)|!_MY@ zh<2^#Oh%fd^@f&j_#16x5NE|2v^fMx2qm)Cx!M84CU3k&()x@=JW__4b-!7h^IPR)iY*@~AM;y^ss`Fwk$@xK3 z)dZdtgpB@mc05y$Xe8LYXt$a^;7pX(*r`&r3k-Wa)8*7D)RUpD674nC8qRyv%uto9 zR%O_18poMTO>0-?YMWS7bJ7L1Qe_D%7-9(3d3sX8Q7p?l_(x1TzHF5E2*LzNoHGd? zUrSMQ%yd!v4AYXK*`_(18I&4ft4#Nq2{(3%v(aIhX%WW*1Uw88rsW(P$~{e+Ui+b` z>Vj%G%)&U8^`k;E;^+_+sXe-A;gEsk`m8;HqH_()^o`EVaRRfaz7AOlKXzjmmSja)3^=Supgxm^^aBcra(wQ0cl!KOI~!mPOy;DtgmC` z-BvQFDbUD@amxrM#CY&)k3R5h!0=bvq1}grVl0vO+|DQ{58Pi2q+#5bmwen}yQhV| zSwFv_ei!})oN$YEZmXa7*`-(Kf;4t%wuP@+zCzh6w7K)yrR=WbYu#ja@c(IT_01pG zyg2pR$gZwATfBxD`94tWFq*2+bP-5x+i)pcHVHuLUXxuCaN_pthXX?g(k`YN%$7U5 z6%$cGsmYEvqxE^TzMHvRv~O(g6pR66!EwokvgwgCOvW-~P8e$uh(w%l>#IfEZlVz= zx2!^85(*EX&;Xf~*|DMRv3(e08LCC^q0bTw+J%A$?K5`8 za@O3kWj)E*__TF{-8gX7vH}fqr-dHaO;s!|xVa(h0LM{2(0Q4tCdOQiY7zRsLP06U z(@e*_Lr>hMoaxdfE^0}aN4AG*P#+1Nh&GAG(8d96m?zwB-^|in^p|C?cH?Gt8~ZqD zGMu{BEep+V5KTdj1i`Yu#hgB!-(cB#Q%pK%_|`d5@q8c~G=tFrI8{-x0j&?2jZbQl zFfF_4q$md4U)%LCMxm4q-+rCY+lq!}RPit&@0B&#L;pqZYv@D_M{;P(+Yw_n{Zu3A zz4LNtHbyjwQGXPjB&|oQgbY%a!GHoHf|=$$-!SlP{50>=6-hDXVDHnGUr=)vq-c5GNsxZmagaRosm>a|s1@?bLt1BQFdVFn|AjpnN*1fpo;UR8^Gz4=o#bC7gm>sO` zdQojJAYmn+C*b)gTdRbWM+=e}R>hK%3ihXH^8j>gLEHz1$ACsX*JH#s6#9OK_t1i9 z;)S~F?EJ&t%WVnJL)}T#tuUNa%5F;*I%6bkqwf2)MH7VmCWtwTWgxr@g#Q9_GH}Bn zxY><@0Tj5SKryTBpUT$>#*8#cAH-9<7)0NIXdvW?ozysSPEuH#91qw}X}ejUX}c7? z-G-^&=aVWtz^E&fNShpeAZH%v`ho8IY)646(sMlRew->%`=?UYq)tp`kYx3q%OI-+ zv?#~OZXl>3=0L@8M=_iYXdQAgRn_FiL^OMz6~1baY(P6ZD3EH8X_3)xhi5v^>JJLx zrdgbM(ps8Qf|H&}!^5z(zDppIOAzrgb=KTnb2B@Bx#)4E)eS`YFqmLU^x(D_v++eu z9~$A0CJnJ|wXue`NNUF^58{j#&uWtt@~rUxzDMXKgmA=jU@YID;4{-4f#y)zH1Sb} zgxTh<4KzGf${s1Uu*b^k9y9w&{^=9L=uMGmdKHZ5F`^?_7xNtZhP*2^Di_086A@2A zQkJzf*#WXg)a`j;?H97MdP}+o*_ff}JM<03xB~R!!pltiQQ&9r^|s0kWYZMO94=I6 zB2=eGtGgC+(%#*+vih=9(g;y|Dh5@fm`v6(;)u`U>Igv5&53yP7U!`-Ww1)L9jzy75W7jrPGeh&q9g z?=O428h7g|G+nL6jrD_i>x5$Oqz%oZ-0w}%z1(;yd#>tEv_o^Twq3GnbMqf3TGqyU zZ*Qtez@LRXP8Emk?ptpm}?trEG zmThdM($vdrtwVX)L*ASCBkh~GYf$QNMi_BDEjV()ex z_<;R!yc>I> z_bmMqOm43JUg}KDC&li5Dlso2x^qOHYA5jl=ic_Dqdc@@ukxO(r?l1QDM}xi&-Psp zu)c0jX=q$w@Q+FK97RgE`e8O7SV-PCF&mv>E&DSt@+soIy~xjM(+sb{Xs+^Xw^T@c zY2B&o1jhrO(A)QQd&hh1Me#d5X9?0$F|zZ?ROM}0j37gLubtq;QIH}f z!@b`Vq)Nfb2rQz!Vid1(0Wr;Zr``vkb)e$1_y*&I&x{pvg@SVLT89s&GqTwu8o$p- z9tf3RPjjytY**}OIk4lwA6cs&2?n9;cbI7S9b6^^Ki-w5sTyQo43oVMduHOUHXnK& zrX6@4rkeuhnM=`}u#Ihq3`=0RmTrn7$S^SBaeeiW$h^$(4A(^HEfEH~aT3v7;-Gax zuBnMrrXhE2O=A(-D%I}uBuwBHYjVyvKrUy`88l2Yuf6eM(`2#tl^1`!wmdbvz3O2W zzT&!R%LnyY;7zX@){X@gQjOhnJz+Vi+O5O!!RSBT^l{Fv5d^fQ(xDV0YD9T}H2oZj zVlw`C;LXmGHG{{zT2B7do$vxXM&mlr5!A+Nn?ZLZj08D^k$IZ@PzOe8_b}7DVk(u; z?`Y0cD$h~rsO>Y{M_cS2;WdBzrlo$HX!-j_ST8xu!p*kevR&35kRXD}O~~D$9Px2Q z4HJ6cw@g`Hb zb%&Gw*>756mOO9JJjKug<#j_7k+;%x?FP4Dy)Vd7bdH7_D8%0KAH@c2E+bH=(TWVi zD14;V8*IwnqYyUSUQqW4oacp0nMvuxRv)9_0aJy8sDHPbgn-3uj5Bh5SeruI`?_m* znNDETTP|3+67FehB^NWnJ~P7)4r38vM&Fw#79j$>{I4!$hlM;2vzUWVy2WC@c^d_X z^8FgNaLNPR`t}DsYKZ>mez;6zJ8uhzbFxOPqIM^IwfJQN;}sgp?j4G^CR_(-N(Q3F z29eyC;!tLKY|SL{C18ozt5WV~2M8H0o;W<$+BD9z>=Zs$X*s4_neHAB%VVr*OsxGT_@f8T3D3kd@$BiJhx{Dp1q50T14-M z9w^TYY!SVd(wf2*uPsgMUfSV5gl1;xEX6p~q6KBxeS{;6PuQcp|BJrF*7ipXlGwUo zizQ(&I89MAm@w!a)_Vn~?%TMthQ4feB>i9~Ns6Yj*Lq(?j|IBvhX0}muhys40x^(M zhE*enTbPTrdaSmRsH+~U(;14-P!*qeSG<m)$o zFKA6$4u-xop4BdXeOC7yNDAnfO{ZZMdlOoPo(HrLIEbm^fB33Gp)~dyZ(G66lecf5 z=}X++rqb#j%5DfXL2Tz26_!0X2;-pN$X*z^qjEZHACb46W_?ZMtvgr;iCooaID^qC z_p_cW1Y4pHZ|*gmqxd#RD{E51`sOTrmg3fCt?bac!95lKF#Q&VH&*&c5Uf3I5 zWO2{Q!JqKvp83>J(VTDEP$)kZl6U%?jW6v`0F%&iDH)mB)@H-@MbF5m| zT@o1Y_pJ2K9YtLwg@xV1TOJkvjUvk}lM|Kcwj!dyvEmODa3&|J9!*Ap;K^9tVlc|M z$1&6qe7XL^6D}b*PtGhX5B`eo{0ViGyo<759n#6WKbWvBU}%;xh1`Kn>4)cfr7%A7lYhNzxGJ=_eT5&MGw7av%-OK5$u`!QnXV_0*4MX2r~E`1tzf6y2e z5N~Jn(%y%VXhtuc3v!CFTzkC)LpmttGR~Ls1!~jZAIS%%1iW}Qmpj$bMO2tislZLP zk^2J~rtxL;hhQd6d}{7FFvBr~vAWNouN~LPeQ^o+*ShQ06J1C*uZ0VysWx;GX+E>m!JfTb$YZhY|%f zyy~VD2+xt~teA_j6^2QyO@yPUQnX1`VCuBsgvJgs6POm7J|WmwyQ*x69u(P*qJfls z>Wm1lL*ZQx59=a2<$D7aU(h2rC??1gz9@|88WElOmje(TZCz4kgx5y_B|lT5*2R&t zI(&=Q$B|{%h3ScJBGq@!45$;|aLij^(CS0yZ1~`$g6+_p`uSnp`8lv^fNManaJIZ z3hj2}aYlu%0e-@*pdLCWoE)iMnKYZ>)Li#h|6hg+%D3JP0optv9TD30T#(5cNhgGM zk?NEVyL;~AM7>r0HmbQPf$O5Iolxq*!kA6apdF2V^Q!P(QBF=?P-?|g@V!s{@{U>e zp*$h!QP}-Ec8YdOB1vvMQP`W>Pio76N`3lCt;h4u{po&9A|MPP$ljS+?6q{ zd9{#sT``{bUZi?=XWV_q2_nL_TX$6DmwA|b3|GPE7R3zS)JU~ghrZI$M%0_rpV;P` z95@u(AeELKc=jySlr5{j`3oa0!fQ*wkgHK}E1$8LZ2iKzplAT#r@mt%xXVue{{9_b z!8Ptwx$)P+-t>M-TLPGJF=j=Xu`;YQKPvvTht4@}nbG`l9GO`+^w$pW#l?JilStx< zK@ap_Y~7g*BTCmCp-qWYJ9aW^28}ZUP{5txPWUX<)K$Eh@Yz;H*ot9e(_=Ld&b$%pE;iAlYZe& zvz{s8hd!0ohz~@nQ#(la#Q6WX)J{^ZI5bjyXq|X{U8;>J#?5%3m=Q&G&t+!vCPu1f z_Ak?(hUA>h35NeFafKl#iG47NEc%6+HjGJ3=%1?$f#k+F@G=YYg-gj)n$@#t;L?8e z_o}AX47hd8h5A!o5*(EFvi?U}%j|u64~0j2~kjXZr39 zz2dUvuqgm}ie;)P{tdl>U~721DCTE7mQ_h#-eDUAz1b&C@&l{8jdzPfqsYRI;+ftb z6!W_pWz{wlL@`N5qv2;IopYq`+O_bmE05~*O$uIw*WrL6Z{zT-e8qCI!k0@a8fe+C z?t~_LLkfdU8DMJI?+N2*L=q=pXp51o3(O82T4KDRl_US&cthube2y_pTZ%l+V)^x2 zS!@*9`l;2X#if{U{l)5_nbTayZL}VbvyD`XJFT^)5D&HAs=Nv5o#f1DS%7BOt&W=6 z&2^#}&cSmL+%W+|GmU|_x>G+OE4Fgoip&oC)Vh9ELAMA6{?MZD8S|XwH)iO6owbGf zzT7gSu(zbYy=@&h@HF;mn;^DX=8rwyW61&<*So0w;={Tk(l434=dtQ^+YOCv`5iD| zo{*)=_l;CHKT|xq+C4-=AmHxrs9%Z|N?es-s03sT&J90ew|t~vQ?VZwwc#n5s&!u$ zaV2YW`c|FiEG;sBwokpHKjc<7Rh?S ztFSkqKXi{=<3o4;j52U)Z5cvs!B(`^Af{JZ3V{6Gp;M9N0F)9tgCJU;$l17+tyd*o8B|K z6)!2~w>L_w15oR0UD}Wm81HRn&x03?BD|p6ZV}n9$uC6C+e%;FlvU6jx`?cyiK#_q z={~iYklFA1#H+g9^V1JQ5(3t}(hM8-nTaoypduORL0upIM#lOhq$h$QSp+jTrJ zeyQ2tw5gR|amKR6L`R-w2@V(fo#B&y=8m!k6~9HIneUJY{SrHH$Y5L&5WmFybvXXA z0YCQ%4PnyqfcTZ>eIr4!>n;ed>-E4sk7p+n19~c@xlXsb;}(;dG_hBadBuM9)P5A? zqF|GFc9D70e)Y0WQOyQuHHppbT)Qy9E{I+suyD#&#*wL?SVvi~2vfhXeqeElBTIh~ zq;U~!*)>v+aSqMbF zOZk!S(Pvp7c_vRkpUnJJJl+}F8wpOahZzYTT%v zP}xov^*(Iou16G_p2xN~Z+tQeW|w{ixMqoRl!d|=^lQ@Gy@*~-p) z-J0YGvqM09m@&T~U+^KBxmoN|G~l;S{kYRzQp8EmGp*y1oTOWyftb6}e5iR<0L_OU zxe-w_BFOyCK-JOXfhEh50@>_VdZdqHsvQ>9i%*#+iGcWGBl8Cu_Bu|T9&JsN;~vlP z7-7)L%PX_h2vzm_%(DXGU5%G-}sHJ^yb77c{$Q+NMv(#3EJE!)gXE7mZV$r)qh zT|@iSXS!)ey9bUG#_Smm_%_k&O5VJ1>U-fr>N&n&)bPP(YJBcleEb1ixG9 zJsTCaim!|L(l_nbGV!OE0m9~WhToKQ?<`A@rza?&2^+`%fWMjSXw3hB-I)$twijHm{ahCo9vFzfYwR9 z-wh~sGfK6KfY+@%VbNsnY?zKgn>v_#5Dli{JsT2CA+{za$CUYOE zd?YDn2i*6oclF=6l^?o!(;wD47QBDwITE#O#U;@2km`rV%Z0rO{ax6M?W9L;SImW< z{OLEhG3LsR_X>NtZ1eiVv}dm8M*=muv9_?+wO{aUASr-uIcXs`Ux^}fw^>*B_`{B_ zTW7{WVTwj>syn5*F0N5=Ts$dKy|{m;7XOXHb~nE=lq%^tTc|U*BMz!5O!zVNSL-Yh05EnPb$#6-1UyasG}TLN?xvdO1(C5ZZnVB{ zp~RA@0SH8Uzc)toGr#l-J;@1U)8EirPIAbet76}-2A4|S?rDf!M5pY2Dv@`{s*>D9 zF|o!sh79H#wR zBv@KBP_a*4TSQuhZSFpGM0eNyqMWmNW#wjXM>}!}KkgUBbUO<2B86+4?G|hpyY+m- zy)%LFafuc775{xrZ>b)%);MB=o%n(yFg!gISh6}PEW9iIVO@SlAkIs+(p!#j#)fxg zKdf8UJv?5X@E*ARdEK&r*D{#`~{zP#^0V`8=N>nZ|`9&5} zW5EG0rIKEeZ8>1t5k*#f#?tB6_}qFSVv@kQx$bhO zhsrHEFh17!SeK1u0*7j>sHl+`!r8vLF0he#JQW86&-w#Zx3OHr_H1`jZ;KW6hV~0u zw?TZl{erf`5TApQcB@<9LZ;-Yc#bay72n@^V;%jHl%rRSBAqSa%W@ec(&Z9<;1f}$ z54P0@`X5J$>+|a$-&j}YwNkWynAUT?{@hunV2%d%9#JYfqL((;4R+J-{e|7zGUFZX z=))#yPc&VS)ysTFn=t7FOfUo{y_kVt((N|r$8!TsghZP+)i<5YBgcGQ}`RY^LFYy!nYMs9PI7DimPcTFC=%L`B1>y#T&Nf*w0W7BKPZOv`$4nvi(CY z>Q}TiAdl-;v_6I{`mTl1Q!vf+PD(8Wry7m@*L3Na?uW*7tu4mwG`Ii)E}pm!aCkJ zE;h(xAtN<`zRCu+q^SYYQo+-;eryZDpW>9{N8?MEEbWWZ2X8)e#;Fs~mu^CRaq z*9n`%nHRBdpWDw={t7c&WWLC{3^Pl&EGvt|TD8r(CKAz@Bo>i{2D}japj-(4X#ZH< zANBbrgu<R#rSV{X>#u996>2RwaHG>hpB&T+{22*fjH0NX*!5} zBqD`cq|_$|&-ua4$M)MP1=y!AGH*47VcWjd`mx0eThK=7Jua$8LV&KHxv59et0g+$p^ierN#2*=V7=~a5dk{}NunkX=E$!joN-qzdi2qwD z?A<4}+N*G%Q6P@~%6&*)Z;zgTtPl#aMyrIHVJ)Kw9~8&0O6JYz!QSlN`KpEF2jk zrc@V^PUe+~%t>SAmiG&La|ZR3!iNK~+w0cY;>6=ee%vFIZsqzHjF6L-DL+%0hM|Lw zmPN5-+OL9BVrcMehij`468_wnW_SceyP7W>(qVPU61>(>1WjJxtZpIW=<1r)PUF

a zW2CWE7YBdbLinTNsq{Ao>-2$zA}cJjm`}RKeb0&w#K@K#G)Imo$BTMX`t8~nu&s5* z_9z54f?Te%3_&X8iTH>Ni==z6;pq;`2XSNujq4SR|A=5-6;I;+g#1_WZ0LH6PZejC^4t3cIzLLim+#5rI5!}!4KkJ#Z*QgN?39owt1ow3gUCI)!70|tXNbg= z`_z<9aZQo<5_X&B_UD5)&hn|(t?$b@aX5~?L~@e5467g3`F3O}>9Ft7W*Zi8k|VI- zAS;SY`IT`h5cV~KSEzO}$FcgbB<5HW%Qm9=8si5MPN_*9+{!>ql!CJ-(U!r|vwZGV z>m<1)zOYx{uLzL~X!MFd02M`F4BB{ZfNoW~g*w5Om=N;}PGNCHb8Q7ZuJH0MJLPCsZ@1;@lNXw4IG%0+CZO8Yf!GokDg zoaw=U|B=`cVJooa;JHxfuc?zJ;bEMn4qCMx#@X3PyKjf`ojA_gn6ud`zaa4O=p343 zVjIV65N!HA71qdc3Lxm<-rEfk#~9VDE=W9^v(f@hyEfA9F)-l~qeBprYH==G3bP^L z6KHYJ*vX1V#DG&;%L;fY!XzqMC-v)FXAt{N9IU8w;r3MG#W~r%e3PS@!NO0NOg3f` zD+_s`6U@uwg{3j9d3)DyPbl{zu#L$vv72^OU{4lzU31b08;DoL(I1#&dBfDtfQ{3Z zO(tkf@dWrTQA9)(Q3M3OZO`+* z@9%rQ!R0xJv(L27-g~X}Uu*4iPF*lKGen7)nF4%X(=4stU7iZhXBn{o19R>T5Aaza zq}5BnZovQPj{^LHu)qXJb}&;k*0Y}AwrUk$Cm253*mDZB(r`it;K*2|XyV6*qPQ!- z$=6~_GgC~hq7CtzDz&K* zj4Jvr09QJsTsCp7-`V&WYBdUYXa=pAs{+ugE-Kq*>Hq@|HQ3p|LQFA-h)W1ofbTrk z8WzA{X>FLB7?Ajg0o@+lXhK@5puMGzPOUDqNhGYGo4oz<>BK}Rb`EyELB-xN5l!8l z!?eJA23R)E4um95@C=-`1Jp6B>URSzd=ALtpb609+tnv$qeFh?&iw%&7nJX3UIX-! zpjmDMR9Rx1UQIaQI!-w`u@|&w24P_u=#~7|3@Owb$=*3#%n-dw^j>h zD1h~Q8vEIcA*S-V3>OcC-}IiK7LtKS0HW?c0)VSt(FmNhuXK&$I{AmOi=sR%7v<(0 z6ifp#3uswkbrK^Bpk!W&w0=5vO`s~VsZk_V=jF!DWsx)HIK+c<=Sh-HK=<*IC4T1u z7EUS;PwaYM)I(-MnILyT&PL7Wf!u{%J2c4zaC%B+_x%{)@DFv{x9NbiRBrd=k~bH* zM0e-DZcp+J94qWx%n3L6O0Gr#lDCggo;QC}<O3bQ%!&{IEf-5~| zo`GTqo*@swj-MR@nEQ<&9v{Y=17ghIkvpSIEuVlFNCA9SFS|4Gq{1ym+zns_zJt~t z9ulFxDmo03H5G1(U?po}3@qVF)_4$DIw?^TbLDzU)VLWq$^?vAklyNd?xPUwfQ3$t z%I3|Z0&V%zTLq?(F)aU(25P8J28LB!105>fG7hLSdA8(l_QEI!$E*t`Q6RvfJ-Bg@ z0l>s%<=1E$z-vFle;}Fpat;*Q4zs>W9&-4>!>sq2K-K+3zJLc)B`qWo?7UT-7X1b+ z7pV=(<3SFd4U&t-YyRy)1KUZL;U*?P<2`1Y8$$qVb3+G!iZGLTj9URcze`P@=>d0; zMZntt#Y^m;9o`f*8O)fC=M)K>Z$nI?fej6z3{`VObbV z36e~}6FbVDFb!$QFd>F103af7;1|2J*d065Z-U) z|MJGb_Me>ws0%Ux^%;PXpYbQqBrqg1B@7t1>g$9hL1)WT4LB3*&s109*1{YvCXx zQP#%0i2?_thiQkmQ}2VQNj}er3ho46Bo?@JTJ;UGv>NW1AKqAXNsZ4WG`<^HEa!=2 zPYyfL6!Am%dobG{YUDlssQcV$n#&tO-3?RXcD;+rgUyerFQj zr+py}-9}^ONMnN6Gr*if@I5j(pjXH$sSag6^&|WxNKNJL4Xt%9^F!!{srPXonl830i0k$;$-VbiIVwgPG-W95;FM*m$ z3c|6I54?#l}%D)}K!-c`BZWv$6O^|mrC2Oy)>ClifQ%F z;`Q#LRXYewrH!g-{2p4|rw-3%)3Spx>F-T1BPAnxla07BrGuxUvQKwv2Szm!K=`bV zhoE?xa|L0>k&KdqzM4o?Y$|*5Y2DOI)zn3|dwAn>H0ca68p~*u-|F+5@Y@(5&E<6# zF#8KE%oWK~BQDSghfh^TF04w$dxR67PMB)lM=xk!a%1Ht7%vpk&5dWRoL;$ZMklZ^< zND-=jlm~@+s-_F2;Z8i51$6oii^0T<4!rF%rNza?OTGyh{PyZF?q%Cl7pBvct#8@s zvKV3e%;fQyb7?>upeAoCQze7OCtRF^v{ot(Ee?Ys@LN*3+A+T=Q{I5KR}nrq&7G?a z^}lLknmbn;1>C^0(_KM=coqGHG0Hb##$Wjn_foH7Qu0_)SHwL-?6w}tN~FIS>o8+B zd)IWI@$Yb}r-||`zLv!q^M*#da4*T-n?FZA=hBsrqB?0GPg~QAs+)68cRSOJ*9rnK zouHL&!f|d4ynG*27RhZCY{Zm?PHpwqp1p@b#SM%cF{~@Ah|0WEfJvY7Z=R*0%;06! z#KdUsw9)A-js3kD`E|N?V{bQjb>Z8I!OsD8RI#q8_skdvHI%N?<3b2>oK?&QC90YX zEPI&S%5dWcD%`Aw3|<=Vq6(6YMm-$Hpvjy*ToUqQ3V>wd7SmqnnIW z(K{MoI;r5fyTtI81@xX&JmjbehX=zwY$WxKxbotbnMPdte&I9eR8%cZ{fuClRz@`l zZ@Clng73g%If=%ol(817bg(#r{^+q-*jeg}Atv7^P61MX=g0UaqLyeC4wA)r-?jIvB%nnnr$~ z7{70*QvB?!Q~-4-sBXS;_?b(eoPDIj6#Ax%+F?o+-57n+sE%$&>75JmJZTRl9@6L-A?ut20snQtSG}`9F)6=q(l~iuYoI0d@jr$k zb`SBGle0>G{*K`A_m1I>I`*C(_tJVS@@Jc%+D^W8xZr+NA9APBLq7LN z@3$eeWvnH|@ZO%9Ms9H?+spD_1v55Lc4hhY4=MFHNO?AI(i-EZ+;G5uMgnscffsl=%2J*reGr=#G1^qbiXzox!2+k~H(`coqtfy)ZqTyevq3ErF08W^w%$+zO*(C-Q8*9Mr+O9Q zMzOG4#%NR#LRz`NEJb|EX=GPqH|I2}G_3lu{WdR0R2!lXtzI3gcX#oUc`!!uuiKwr zwIBWU*3q(GEM8u_efy~X$=hodEnKsb_3N*G3Jh!96&h>qN%zk_ItP^eLHmHBS#0KcGfB+fDlcedh|F{_!H z+{Y4K-Jv(^8~2Twx}1h89$FR5eW;fb z%|*t3FAsK$s9hB-sGefSp_;lkPU2jCGoHkWhV~7K(pZGwPChwD!CQrWZhP06^}hNo z8ml+!xHN7;;pDlmB;G6Qqbf(l|=Pi^NcR=_3^yG!F9eu`M)(4`V zqrTCfpZG>6U$GXKCd1!Q!4qOs%;$xpZ`O@0>0JC}<)~{}%B%>7)_tFnI`B6!KK_gT zX!-Na-$IFonPaMBEtzB7zO1k=PD{I{gr@y?FO7k@m+mg5-&xKW#UW8Mx1sVUB`)#W z32L7-(oa435?b(SES;%oo(UlI1QZo3LiN6u3su6dfyZS}`bU@ZoDL-{=UM!|rKT)1 zV(cc3C(jQcWLf5W$}MQ+vAwE2!BSmJR{kt5n0vx72yb}YykdZTMfbya`11=|+Wm-nVVB>>=O^UaQ zyI(m(c%t<1`v<262-W*&5^Zf}HB&3Uxpw?Y_nBq^`?BH?64lvRxhRes>?W8TV8)oT zB!c$GvrL@w?JQH=6RL<;XKYrSw$uFeIh;4MC(ES8R2&oSep_JZaXc3J#`0tMnY2%F zIH%Wm#gC-U{n=lu#IVdSKSI z!iBAPoz=HNz`jk~|DHp2-}|1UWnR2SsL4b?p0R}zxR0UB(na~CwJzoGXldp!}!rRbjU!E&Y<%lcs`cvZMrzZslSe2*8cw9Ce*G( zl7BGaAEtHy^*}b@$T-)|ogPWZt8Pv||3J#D?s##Zv;Hn|C(-5t+u`^1)hP$?j=ijo z$qA$PgBM$ZeG{mc+OiCTb<%QeZJl)Xc87M>8&uFZ zvZEn#XNF}#%_cW)$cmz%guwXsinrY>N~R11otFiaaAE8Iwjstag(NE%30$ z<%E<<>rHpJ`i8$7u~_iqLv_}@FZ+`@u5@F)sSPK}3=T8u+l3d7jz@LYB+rNWFCsFF z&$<~sjI)U@R5iFytVj>%Q!v)M_)Irc(wb zQ(#hOoB6O0c{FsNjQw1FAgriARJC??Ysl1}4>`mK4$CH$PWG(bG_5OI&F*|LJ362C zF?$+IbNb>rdZmh}SWGO+S>a6+SI2Wy%I6=yiC9gOqBy|j=#?8v62ouktNo-p+u6IN zj?eB?68z-n2e^(%dUsio)rC?TwY26kam?(F=lY`=&OHIX&eWuHZ}*J5s{5tJp#}4A zz!wwq??0~E5i%~gp!wd3mNfOZtk4dZQDoOc23P_yUq2Kovx?Yg|7)A0+s5cm9%EBEAy*YqcSSlr?G z`tF;tDW$qoE8S8y+$thZ2FfMIGh^k{aCeUOByGjQy(7PDOlAAw2)TNxz za{6z5MncO8t&ZcO9VQE@X@yDoaXpJJ?*t~&2b}-Px3DkPg*XVzi(U6^$$qn9Q4tOT z#p2#Umb*c{j~3cOOtIqkGrC;8`siLT{76o?l0nL>AWQ!&S)8 z%pjaUD@XSaob>e{T!-13!RCU7Jh;gE8=)Q#ess)rcs! z7%R{(HQ3+s91l3L9kt2Lx`12uBJDfwT`6m7>#kij+^fo~DEQf+Sp0(smQZ}q_B|L+ zG42q|%}R}mL)p3YOyHdA!3?9z8W819|M1?0WDLe1?5%l_JLVOC@Xm+sn;UMF&SOCf z;m=)M4MX(WI_<z=uAQ*g3u7)suO8$x(|K;$gKlI9K(f$#WNXL^dufuP|-r8knTia=;TRWXlnJ9+- z)H$m=4Zh4>6Xl9INqjY(tGOVyQ@_u$`vM)+AV>73-Lp0Qs5i-zO3f+aD>c|G%GO+9 zA5y;E6!cYm4iX%Myr8m+e+Rx9 zaTS;R_$tdk<<9ifDg9Sdr*vLfWUuI#81A|~LpZ7PN}avpg6iPLcb#?{-%Tf3gT4P} zDk587&D8%gFR*Y`v0BZL9~k=CZ0u5&7|PMmiS8<{CKR+IC}8RF7}I4_U`;g8&Fc() zz1M6?vigRkR3Lvi^Tj27QFu}Qz-bOZk&h*{`H`CZSC|2yRqq7j>dl!`i#RiytVsC= zUMJg}S*pvK>9la4+pG@a1jvim$J|K@KvzxIUdi#e*H;yp&g`YF7gw(3Bt_aL2OO^Y zTxXu`0UL;UTPYIjBRtvfCWA`P?JV2yYsuFGcZ(KF$MYa4ROzx>WsFjioNE!JrHY~5 zq?-9uMbpKT57BWG%GYv)&;E5;QFz*6`gFhf1xaE)<>Gk5c{kmjuk(x zjU^P=x1GU{^*NCz;+~xivC68_i(!!CMh0>;Hl6472dsQUK;eEjXjdn@C07jXnkG{n z0`y8sbx`@81fKvD!LNwb(20@7f4hs#g0t2M;y|!MkO;XFlM^3@d;1$%C24r5Uz=w5gCxw|@lBpZ+PqC$Bh` zW%%HPjLB6t(2>fZxys3vbQ=2v=qZE5cJyhmg7FbaIy(@alDe4fcXxHAxj8@tUS4l} zB=`?AJ`xGX?H>l&+iWYI70Ek3&HNVjme*;Qjze9{7ejGxEc&CKt9QbGKwsN0UqGPoDXB=j}!| zj@Uehca{I{Q;_gosgCr?!LZU|tlDTiE_vC|{!C|`oCk|0;cGe3#<8(?Xr~1OrA#r$ zj-y1nT+ff`%_gM2eWz)9AIourKV7u$j}@KA9!GhsoO#M^zWOyK(57Z~4#DeE)CrYIpN)O3ibB28N|g~b#PZ(ea!{Zos9WmiY8Y2@YJchUCO7;^yV7Zxo9fi*Qq2}O zB3Mi&1PXLe%Oa5!aU6Kp{^-4y@a)JHsItQ?{HfXI6eB{ADgBd35u2Vt2$HBw$%36a zVakeKy!~VWsj_0W=fTT=*x}#qx)XxnHv|*2?|y(^>FRXuGu#p!=z_agjUUHg_ikcs2tKW&pZ* zC%uL)pWcuI9l}e#WkM1%;LANJMMOe#)QPsG>iUXRh@p%)^kmFnmxOz zlz=_LG6+_`bYW$~*;mSn$f6*w_S45j@znCgWz#;kF0H^B4iTOBioH>tS#Dg$v@CQT zMyX2#Yt$qA8P)QptSDK*u>olxZRXG*12b)XkQM7;CQz4fRx5p*+Td#6;$9S z(D9xxp3U_O8W5f2(LaCc6JY&7UfNw#p?PbtcT&ncqnW74cS7T z;xs)`Mn`rBHX$^fDK{**gx%{no`x6S05J^}PbIuApRWAi|K%}8+I{)mW$p5$mIAtw zykd0kZ)3zR0Xi^c30vjEBKwuQ%~=&oNC$N1it!6@F1j0q6$ zL?UBG#V4WEIA7xK0b?p-8^XEk!9Z5_ov!*83ND$tifiJjjqEwKHbqf>n&eO#ehpC& zSv*3s9+E79a4riX!x}@0ym$Lt@n-ECHp=Dedr&3#W6{))>02k`hlWWPp(<;2GnhX% zH}7UM&!hL_Hoj%kj~E70A*#!`8ud1KZfsW9e-VBunuOh%0Pi4 zLiG%M&5pBgQM`q&=S|+-7^rKop0~r@p5&fk=4f(T|FCBNJX7~Wq>P~`9LK^K3~}G?)<>)M4CP~Mf~AodDJy9)Db|t(1e?SoUW-_0Adk9tM>j#;ZkYXduPlsDj(k}`SDnXdT>}?UTDypOu&!|^=Cdn zZ&UEe6x2Ur)UO{iu9h22nqc`zEZ?cFA-=AGnnY27|BeOGv*f4ot`>KVkLs<45gmz+ zdh1|%PZC=X*EL{T0o|q~w$%)O$MRRnevN$!0V4!VWA8&^{;+*)3_}~AAU214xA5%T zr*+l3wkgJTWCNH}wn;1RHpQe}Uw91M|1Y{4N5GHI`_r`zr$Li@83gLbeHTPqBkejm zDn1c3M1F}jiQ<2YLd+rN_}`}Zx4jwe!t$v?s?Z9{uaLRNW$}u%%fs&Kooka;%!PN zg!FjqR>pBs^N?7n3n8;xDhxEDzx7r5f zqNs5TLU(|1Bso!SRdo&cVFn~ONraDurftmDYt<1Z$Tlli#y>>bL!Xda z?S#2+3E#KH*{6`bM+{;=C>LeFB6w{t#H?H*GC2OhADs6_>MO$gt#J>K;PLL3Hi2+b zwn#ZYp29qe`DZdQJn|9KKEFdKV*y<v~*QUM4c&e^B129M?sJ-GnHfK@<-_mHe`< z6Ha2}8T36lnArX#Vx9G}jp)R-?-Bbp9<*ycCoGKcxi}=!p=EC0p#9J_92gO4y}t;v zPgi7crbcLye;r}8(T?3Q5ivjWfI)6@Tb=Mn#FosXCT+(emQ*gxv^VM4D*Pwn_sTW#(0FL( z7R*V4K?Jy?DTmLG=YOR@Z=5sNBwAQk^WD)s>BJ>>GFp#7}ya>OM%%i1H8 zaDe2VP<#+|6m^sXHIlV1v0cjE*=!$~d0i?leb96zVfTPXMijq3i(7Nidplkks=hspo#s zam(EFHh4R{y;(RUI}veJkh`e&8sQwN=bxZsWjStbMRg6hVT%a2%3ZyVq@JuGC)O4; z;VfzPF+_0%5vEhQpqDasG%5$A9#qxt9EGw%Z6^Rgq2O>;! z*B&OiE_>y8K~HpDuE=A~u2ZRyP$E@x70^jiPx_bx@i(A1zIkQ7+BgP7)0I0lH*oW# zAr&-;VlN^Lg(&$Nb^2lfO^{ovSs@opt1D>pWQn8N1F@TIZyEndG(#KP>pe@nMM-Qw zEQAjOs%xkj_L7Alq`xAhM-fsNASd&&t|n)0UYYM3T^RQrp)A0x1g$?GdN0-pj04!W zoSe_@&>vp%)^U8P=z8%h$Nr@vgY%%PG>pq-a@m^LrM9VA$DMNX+fc2jR&f`LGZPbG z4W)k8Xty&hlZqfQptG7Fr1l6Yaa#{VbneL`bk;8Yp&v7-4pc|@u$9amA+?D$RwqMZ zkhavH(!B}oc@+NCAc%7OufA*2$SM7A_`kvb7_&g5>Q zc6sw3(&Gr}4uteFqNJ17Zypz?%PEcRgCK*Zss~3~&KI*DIOcW?Uy)hI+A^~GHlh2D z20yiIOCN5=@^{JB#TGzf(jhTbkeIm>9=LhsP_V1XFNs$^gt(eO60aNzi$*c1$OFOs zihW0+PxaaohihbB%3tHJBX^)RO~p<^Zy7>a4pA(OzlQuBjogYx?n2X5sU{C`AEdc~ zRL7GmMA!MR99RA#x<3DvQv?8X(2zpjP(uYx5eQEG%C z$aVjg`rkGlvuisQVX=N?2+jDAe|~tY)o@0H<9U;-K8UeY2hbe-sh|;jXXR_ z?gvTkr%3L{NbcuI?nm5@be~SKI<;;0ho|Si`hM88vtvo+h0NAvgp(xqd&S3o3jb;t z=UG6*2qa$F} zo6wGVr-deU4Nh%?zb>&{1+!cWv($&N zwxfahCLAO693st@Kq~Se6{(PlQu|-ZUB=k&8gM?>jvKLxAQhRA3I;^679lOb@;S8) zv}DTuTa^8`Df`C)yaiS9HDamE$kQ>%sV_#c0i+#&$p% zXwHy&T!2xHu2I)EsOuUQ)HW=rYe=YVpe9pvk|}dSe_ZuybQwaLhUI%<`E%wQ%co%Z zG@tq2v(+i9VdQl%@)LHeH?Z;@m=4}83cGD!cmm5`g5?JbgM~?0{xR8a-D7F?*sM=% zlMY@RpblQg>EYjHXJU8Q-pN99)q4xcR|t2-l>B50@&05|_%sS3T^_qweGd}z3=;DI z5<`b5{1H+kL`kpH!}m66v zO-W0l5cOejuzju_KC@4R5$B^lH;Z7}&1lVOQuSY?YGB9Dld93AYG+c$Hk!dsHxsm{ z6D{Ae)o}QZ3>~Y_Na|do?FYhr-emdpvLs4bG9~I3CF(f7t=A=DVOGO1>tOjOh;8}Ax(1ip1{Yz0%p4)T zqO^`bOv>1dW**~#7oJdpxdIbq%2&%k57mM@ud)vdPg*BKtn5ifX6Te(n?~Wv`)5f; zzoS!fa%WsE5MjWcXM)2|lQNP&AK|M1cK=kNhzqC9CStqKaJ1Pb zwAoPuzV{p~$NCte-0xN-0H59DUBeAuJbw$8KPTddutJEHBgqJkc3cTF(1#fqz)Wsa z434V|8r2KSP1wh{ikcD)mjBxrJc*o|eWLYa#2$}-094O8(Iy9E!Ca4aq_8RM#sTlc zdn6{=@fSPP(pgyAI#}8&SlU`xT5i+C>p1{`<=>7tQu&_%z`T28^6SH>qr|qGBkcsf zPHlrZ5c}JdfOd1mx5HTec`Uy>0@pnvDt#mxp8#k85KIP(xP+wUohyLDXqHBAir*Sk zWI+_C5K?a}pACS5P#IVFH>6^7?_D|zbE#o=A(VJ6=ugX>1rb+)dbp&*uZJj(#Ta#s zOuhKz!dIXTssCs;%|U)NX|@oeutG>DvHW^0-(c8a##O&^N$-Ebh1-<$WD025vXwA5 z26KJ*!&#(Vy61!GEoEz9WuSN+tZWsmY%Q!zA68}nGq^jw$zTnPwM7JTxfi?3-J_FT z;^G_sUwWf;>f+tmO%pHQBNeF%x! zXPaTX8Et%w{FDV$M~+=vq&9HP8?{Z!kf^Aj+W2+ga@(86rfAJ$KxmT9|HTggVN4DoZQ8KH&->~WFwy@TqXJL6+V*fL`VZ; zE!1xyF)M5nvrN%hb}hNYRj`(PK?e);&(>wbH?aI8vMsT%Au&rB*FAwwLBn(B6i9wr z2P>K4(rOBH4&z!^78w;iCRVRs-=uk}ed=_;g%;h9eI2|IP zE|x#1M1UUK%Xrkc1>JW%IB!mebZ~_mvHVP#V{95E#*&dvpU|m#Bv!nO;f2e!40oa) zH9219iDXjyoS^^m3*O!#?rVstuSaMk z9L?N>W^P9_e?v2OqUjU6XSn&YSD#qKL-i%Znmu;{<&*7?XyX&6va`w^IJutbcwfyQ z722!5oN}b*#{U~zOf9qPKWTmc^CAByV#(nT9}?sl%zso)uIoNeO~8#dqdy<_&x6%9 zoQhbJ=|IZJ{Ol-L2@^aGZ?C9rs1Wu<7$d?w5hWV+%0MFKKHTP8RF(E7$yZTftGThP zbBUQKq%YPYhw(>Eg0(c#CdG5%kX@cxP z^ms+tgkgiLa{_k&GxPt9A)pR%*1|ZsqBinv3N#mx0gRI`>d>ui`00cEe*wsUIUx3y z&&2Z6-hO!7>Z??3mDX}l+2Gn~Pnre35%68NBEo?AZo={(M4UF}jpT!;YbPe0BLXVT zdv69EF3aP#i-#j4@RhderRt@)sS6}l(C^|SeI^615rnE6GJ_a0Nl-r{846?Gjrtfp z?oyLr9$JtH^X>|8hiX5}ftA*c!zn*f;y#ZmMz^C1}F{SO4DYLYiH#Uf=6P>Y8*t6J=JNqAV3BFcQaZJ+N90FmyQJCW-R{+ zmj536?Zb@mF-n^5!k;of3TS&GklBE+7!Ec#_`=0uvp>mt=ZazHqL4dV=l= z0Z+VpM-TB5K%Hqn?7d@im^2GC!ZzD`Sw~uO{F??`r~j`ish!onthQlUT|@Hl5g8UC zT^+lGafVcFPbwrjt>E&~we^~o2a^fDO~OH$1j}D5TdLGUNU1WaY|e*?UCRKt=BDRi z+FDqC+a;MbLK+L4mV=~fO5af~Zy?x*KKUj|Q16LpaHT)$vk!h!*6LQ*z#YcPA`#LR zu{sQZkCOY2NY=q5Pvoumx(3y7yo`X5&I8^)W?mpKF=V&RKEDaO^{iXIiRGXc^pYtc zW-**AJEa6x1fhh)yOZLsArDg5@Idc7iIDz}Mk<3Spa|(X<<59VQd}0&Y0i;ZgPBE1 zpyOL7w#I1R^QJK?T4q%QpPeW4TK2 z<1e>PAos3;0hG*J2ji{cEom`2nfBgj2m13C^a_0#@22z#;#!*PcDQ|BoVz|J(~< zx!2-9_CoC2hxm`8J$v^2=Yf07E&lWLd#rZBFyVjpl{ex8yomv!NC!m pz*RQ=1wVZ$))&+O61g-y!YeFdu1c1gBX(O_nJ?YC^@tPte*q3n61M;V diff --git a/extras/Images/AFSV11_bottom.png b/extras/Images/AFSV11_bottom.png deleted file mode 100644 index 71d5d46f32b5a8feb4898414dbb84bcf4f139e01..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 103904 zcmcG#g;yL;&@PMy3oc6n3j~tjEbba)gS$f@1b109xVt1saDux#Wbt4DvbeMO5^QmY zkKcRWd;f#)%*>h7J>5NBQ{C0o^*j@$rUJ&teT|EPf`TvqQAPs=1p|nJf_8_E_M9VL zZfpO1Lv_;te?X}or`~%`U|2~hOQE3DCE(qE#(YlWIDgc4LqQ?v`|m;>bSgDRL3t{Y zmyy!)`gHJs(@8z&w}$7z{_7Kb;}g+aY$8^iKssg^Mi1s&*^FeRmX|hBV;S_xEHd6=N6(^h(0Ldc z*?XcM9Tv5h?|A;psunlaHa1@Q?|67RMdmkGH{_l@%?On!)H#UA5@AUF&k4gUzfPmW z4*s7rU-P5x|9ik*$ojw8!3c^;^8YO_1;N|H{XeCH>Dt2}nE$64DWa7R?f*AB((#S) z|ILLxZ?zu1euK8eH~t?#G!PmWlO^Q}lq zj&@#8K4nrvg177$QtkAX_xbro95KLPN}i$9|0Mh-nYL41UfyP;av+%4h#d-%%}Ok# zyT#Ez{I6wV;%^jwfe=~y#8T|gC8#Uc_o~m-$K8T76(1Bgg8r+&kxxY$TqvvfQMbSE zMC!+VyGivOcEuG7Ru z1ZE*?yBV(xrVY;jsN*;OH;Ovx_Ix)vNv*{E|Ivh*{Tmx%P$8?Z`MfM9^ZzIliK57r zt#amYqiJ1ivjMvGx#xS?CnOh({g&PASrEpTO{H|Q|Mi53+epRv4Oa?i{TLGOzCWJ> z!mV(rPIhl;YorU}Qh?YKes4^CV+`Z3i^0|2)1`=w$fsM7c}v?it{L?%lIHV5RRv%R zgElWPbYA!uXSNgU=LC6ryEEU5XTjZJU7w&`v3iyE9d6%$6o%pLMPEi5Ygv~URXhv_ zCpCTAh@w0S_N60D_=t^e^P}vZv;Y$#J5xSkaSCUNW}iA!BfF>LWV2h~B~z!JH-V<; zXv@l5%-rG=n&`QEIg<1D&dBOmxs`?oUS?*i*V8F0ayg_F%BCe&TceYZN6|Mk#hES= zg(f7XhL@vowNs{AV#OJlH|Q%*6}#HU2CMp(7yrmA)k}5w39ZeQlr3e(H2csef!l81 zTvf`vqT>>1f^O6EI9_G@o?UA|#m-*)xAR}9Jhy_}TltuyH^#&%pDD;qWnN;@;OE#n zfNf+Z1E19q8ER9;Njji{4^1``Q!@$4=OnL4E`Qx@qt9HCvDkd3f*_jN1Le{G&^#gC zM(hV*$*xleO%qWuYnJKE7x}__LF`&#%(&+leZ2T>etqW22Oqyt7=LJ|C-Ea9AHq6l zkZ#_v?|rG0yjZBT`rBQm59IC0laPhQK5zQOwDDO50QFjjttYrGBf1%^3ciQY1a+Ch z)Tz4+LGmn(bd`If%_=QFxq*%O=v0M7gCVw zBJ;FY^Nj1ovR>q})XEqAK0mpMv8Omx3Lr&+LF+oYo%fe`6}IkWV#8lD`)gCxIiyT1 zc})EF^UjAm+KX*gb$IG^$t(p@9X@y2gbyPn>XaTv0f4T_iL1wdYY&H>&>{2iDO9Ab zHlOAU{gUghOp3xgN}PE~sq(7I+J(r720m(t7Oq?|BClGzqtx*W2m43e#^SkrG$GR& zwgjTTqD?l`yhgwkz%FQQAEV^^?=^}R=hsGcKoz+5p=^mJYkwRbfA8nEsj#Z4+~qPb znA%!lv^U(55|u*4Wzt!dT}juA9wujc`+X6mtEG}sLnP~Gbo{;DgzN^{2%~0|Z;23> zOhgHlBdO1K4mU=*b}mT%)S&u#PVZ#7S-!gCM_x+bOaUjTpVj5Y$!@KoPPxTEV7`~> zaY>8GoR*50;O*}-t>0A);y2q8Kl{!>eMWt9n;FIA#(fd507+ixjDZh5wRG`< zFz$hMGL7V9{+DMN^Gfo2UpZ=eVeJK3;RQs$mza)S9-aa9W@qT5^O;cIV;z3gVvGi% zc)I)HXaUw&H^h5iTgy;OnF(ET9I>rL+)P%lBrKoYpZ~pGA3JyZh$)RJ@g~ZFtj$Hzl$9^UgdBn z2u|4`>?cSbK_cl);>Dd>|mpZ&|w*(eYU?Gt+Mt z`?;ifGkGwnUSPp)*2ID?PvqCemn4pV-@h@$+ z9HJF>y|;tKaJ1Q}?g;D&U89h|KEL(%UT;mZ!~?&Q9cfP?kV|~{OjnV{e`J(eY1s<& zz53%16l4AhL2Fqt*J)-Bs9e;)pjxjJSCeH{`JxU11%&^kC69Qd_~c{u`nm-7@L+q1 zx_&DfP;SQ}FSNj5*mzldLRnWB|4BSMSMaB4QSu54#&T!QVm#RO<|PJHkOsAR(9eD^ ziBUMo&&BD;F?3z763JMb(KQK|a9nL> zw}{~G?s!}_{xqF`*5TYQJjembsAa=#_F+!9uR>`xJPPiqTvp_fz0%>i=6g1_>wmgy z>HRZbN8(n*r0cLcfNk8p$MPfIlKA;;f|At-tr=zuR*23|04wH?l<{Pu+2oUb{nkFT zoR5oy$iK36IP{y#9tFm~H4XA?NC&c!XPI3$nVm%atSm}+E7E@U(|p7zPxB=Pnf2%a z>P$Dyv=hSk5k7kYuv!I1V1s0q`|-rD5Wx7C6jLGSoO)2} zbi)go*m#ED_7m9RN3mvXj06GrzG+^cit;Ng*>vJXq$f1RrKYDX<;RYQa~4HuUBZmS zgIcg!gk}a+QR-6vEO^pe^CLH&x>*8vg?E<ni9Z%ddc*58Z3UAG_Wbr>UG~1H@D)kwyJ96 zc9^|kMBVvtn~?KxNeewW+hy0&^04h4|HpihqN$6)-YAJH@xYDfh)1E8YFnQNDGt$M^OOfwdG>t@BffQg(E&%gL%Ih-PJvnfKz%`!B3=YQ`@#V#6)-5|L(A&e&9T;tLL)oHUWIoGk>!ga2M11=>Hz}+~ny}QbmcDYPIt9}8u^olTW(hXy(pY~E3SqXG^d5FI8{ z0he>ZSgR+RqIU6rls}971uPH0`gbB*GK(#|dXvxKhacU?K(di!^nwVlt9ri4Q3v|j zu-nrM*ikJhh%Os;FVA-1qd`T59cz>E5kqw#!X>cqG9vox*2%lKO??g8AMv!ye-m^f zy?o2&!uSjN{BUC9nMG|8V38P=F$AHP(vm&|=?P6f14mFj1i^xo;m->>IdEXs4?0BG zJKm|>*!kztv*7zotgl=wVJl3EEjrxCCVk-w<%+OTM64YxsLQvg&F-Oc-icQ4mleoX z)Z=6?x@Qw$$_fAU_3|uDneyt$?;iRqmxyuWMgGRqLmQzfy2G79(Ox2^s?}x4=fZ+O zLhmG!9!48t;z{z)kQ!F=yOb*j6@Xz2v-u7ra< z_`pqVh)ipT{gIn`&sQ}_7V=|rtQeb>2V03}=jEcEit4|Mp)Z}n>O?ece*6M+`7&4@ z=6N7C;ct!bRIr2Le+C(e$(50vjelP1QaX4tBribiI#za6uu06hiV$296*f{I`W=Vm z=>4V759NK343C9jKiBQ6P88EVzPVvC6o7~? zMdXH9+ewbZU4z7?A7{x|47H; zwARvFr#N1a`_#G!OW3+j{VpmCsA$|v_JOGeFIzU^F8J#(ObSOX?(D6>IRfL=0~`JI zAT7|^e&IjM*BW>tGl)J>mYfex7&o_Uv(?H9!qeh)QIO+LBYwWq!0R7^jps z<|^&M9p_oQ@144X27bcGH`8zsHYXM|73YPJUBV(c-t*Hr8M+j3|i(c$PCMeFn;cDzZq`q$>COSY})GR^xu6pgSdSF*3z#Y-V0 z`DnnU3tgk3l7WJH$;q9Y;FI5RUCv+peOP@@WL}AMF6}IFVqZ7gy+T$Cn?YJZ^Ph~2 zwy=a+$(4qEAXyAe_&T`-U@WLnl290=!?#c50fy>G7|p*H7eDpOgA!;>nJ|#hfhia9 zE@QJGa{OP|ezjn(VhmPlkn?&{_Ht)!=qZ9Z@j%CM&($pyfa1^jeYh4;nQ7co?+!s; znOUF(P!;s`{vnN%ElgEA2+c>dLk~xi^$8j#Km15fAFf`!zs-yw=5rZ}O3H))Q9?+h z+%(Z!E%$+$D$Pm`IcguV0xqn$($IFi-i$CtSlKBykhhk_)egIWe~=GSc#4_*8yH3# z3<#$JCQqsq^!fIf=y#nkOF!?)T%;bGwY^>!^f`t_)@IHgMbmXZx;4CLBnRfy#=(f8 z@PudM0O+snAwzHrBV*TS1GdcIXj2q8r6sUX^8#>*eX*j>B0oF-WMuGhM}s{F!@bZi z17ly2FD670i@WCoRhvknlW&T>ob&=dC^#4J5JDOeWG?Qj{ncLyPAlFKf-tIP z6VJJ+wQDr~%H(XF#;8U<-4S}LmEOJv@&Gi&ap%A4LlFY)uJhi9∾1Bo)KH1#&ZA zf+4R2_M$o4VdRfkGaP?#>-Km26&q4C^+k2`1)C3xv1$($@K$f&tJMP&Rqum9{B92Rtiwh^{jpdihFlC&qzFxbzWh>*0Tm4ni77S?jM!+un)fX!McM=E^ zO5kfkla`;?zM;epBI1>E7k{IgUPB zMg6{a<<}SLf9Qab%Sty)O@UQ&JVi|ZHdVvr)mwg_-iWrG_4~6X5=ecBUzx?vtoXD% zZAvbZQ3~%)+cVPl;j#cOt8<7t-fTgLvTw|)Gt9n6E+gRK^?_0l(H$sNcB+nGi9Dne zt$1W(()7ra8fe2Av;rh{DL@A)FNye-?jx{Gkb_QP9XOHU0H~4YfVWFNInw%aQbBPz znY9wPRo(dn5nVQn1{p9HSE>u;`PQCqJJUc_*7&*a#h73w|ED#Nm2BGUA=)U?Ul`fL zR1#k**#0D^Xr|vwudmB$jZ6i8<58;p5jlo<=^ktB_4|aT6CJGx6Ee{5zTf|docdcy z`m2vigz`_QyNvAn?nX&0~()6Tl+^>Ua{m7t^(ga5@S?9oWfIvi^-PWK` zv}Kz8rdgA#e-i)g#0~^ktT37XoIfI;pH4K{o);7BmPkA#@q{L`5SsS>9jPmZJ{EqFI4{7t17ypk^ER5XYnOo@DGh zUpFoAD2597N_-a=Af0|!(VS90;?aaQg+@OB02-O_PqE_u*^#`Z3wk}t#NB#RZ&6Es z$ZAs%XBca&RvJ(3`=-Ly(Bp_W!skz4*J=8p$nggpknTS7gdzbezsk?gg!OWPmx@+a z+d`~i7Z{Amc{YAKv8@ue@cC2k%bVa80QKEg$NWs2mR zTc;%E;ev;G!=j}p>agbl98W%;S zhW0;y+*cJow|7WPV6*+J?&45T&IOg(C?H#jBgG_XWLtZ_hBFzYQ(mGtia6}I!J@2* zAbbQWnJ)m~aq-`+$MPG@SW<=?D5#bq2?_^-XY#O&#NJE1MF}tKjY3Rs_5{8orUYV; z?uFlnf~?{!ta)4(QDNy4o*T_ej-+=4k(gIu;K4YujbNqo`P;}|g;WuHbbof;xFTD3 z7yyW;y5Ty2&kQRkw~R zUm61H%#%?@mYL14EzBr3>wdmO`^3HdFB}6b90|mtyiLbhVisi^Fb(a2cl==SR^ocQ za(l5aCQBC8{Zcw<5g!V#X-T#`fb{4P58xBLa`8C$r5r=ML1 zvo1&)ZR6J+2PW#S$DBQ&hN>%qU#0BojMCR$1w_X8oFWX z{l?AzK3a;ntob@ ziPG%WT;_@ozm6N?J5g|_t>Kb!whC$b#S@C!q2%*q+i`AB38hLQv6){actAHfWUQ8& zJjoBs2Pwc1(-0pL+y7H ziQvG6Mw{>RH9eDYPV&&}cHUG+qPls>7Y-}lgX2_3AMzbKE>$SSauCUYcpr0;!0j!s zX(D0?g~ed5F@AXRbo2hvyh~s9vs|PD_EI*HDhbYt1kWK0<|2i0nK(%z_4(>m@4@E% zJjH&wa* zr92)PP2Fbqx5bk%Cy^&^c+A>zOTG4cANFh4K|YamkUi7;6c&CtEFA)SJJm9{i;GbV zq8qox{UdC8*6w(|{w&_EniNW@FhdLcWM%9{HIM~@-S0q?xaLbEQx@wV2&OR^g_VA! z@b-}c?^DEjA8t%MDTMU14BpJK7XEn$3i6{YK5iWtkM{HI2ZFiDA6D;fTh~ zN7o-GbRF@*Y<`>(IqJ0B1uoTeNzcuPgp`}5`n830;ZiA`uZrS6$MPfXJZisnK7@<7 z+3;n{5!bUqd-+e1#gEGiUwm8USXs^gi+%I9h+rjF)k^ocJ1auLX!u+XfJp-XB$@U! z3NyPcNnHW%A`$;~Z`$NeXs@^ZZ%K(DOU!I0$UsL8@gY!c%7Y`JI*CtQdusJ;G{I@P zdDnKYPfXSSCMMV=-$8jNypw@?nk-KsQ zmRO!6$}Stbf+9~LGpmCaFDL?FR)6Z)ukUQ6u}qusnYs33VQ* zniW)aTNtbbdO?ml+8-&%=ED-@IR*KhI?$o^i=VEx$8seC5Erx$rfUHo6=4e=$H(Fi z=TnR-S#U6#6d>p97h!n@-{~v%Dwbm(IH{-Dd?Mf4%2n9$;hhs*hPqo6W6ZO^lwEdbf3?TW27t&^0(eYM_1zfb&|a>ys(i|BQI zQO14=l*v&bi75%mTFlF++L~PaMJTq;oEz{^CE>ecm$Ss>W3nte-&ex(}V_!t)O0I$x*;eWxSuptF8&*3e1z$SdFNIY1_upTAoEbm;lG zV)8UYoBBgRLstPN>JA5hN2Bta+y@&4w zTphHm$7q)sFipB1#jf7vW&PwNmRh-i4*pKr6;Mh!ebq4M6nu(wdV)V-1)TcoOwCfv zcMK6`8%CW*$^2$^jP+SH;6I0G*@jn@VurS43dr=lfKxGC>XZ_E53!E%`E0Kd7h7)3 zZ$D+Wvm-|6cM70=EM#K|ydOFI5Zm-QPTe+20^4Y)^gbKGOdx<}RI=FIzyiIiQQ%Xo*XGL-s(iW@=-T00?0)$A3l{Vv2t<=`4@H8*Io|bEYJFB+@DxX0chK0Y znZbL0lXHzp%hq{0Bhh@c?zFF8 zFDbm^r$XjVLD{vKI}rKO*~^bnuMKCQ$@emJB)moO^5Pf0QgmDzSgndH4ZN@=by*Zo%qFs#KTzh zSg}`>v2;~j zkX-@@q4s$3+9-iQh1nsEKiQ)hJ`(>d_z@@R3K6p9 z`qt>cL9_zDbfXz{|7o7gLZP&^6tLHF>~*}kVeNKm!*fje;NLJAwiH|sE_x;(SXLV} zW!}((95a zrIA<_Qr}LTW8F;~ZqaANlK!zyWR1!m_p97IdC^9$#7=Jq#Zipt5-v>2=;c)Veo*m? z7HXg@SF~G%v_|Y^R~~kPl1M)wfhI&LSbk-afiRMwpVD`sam?nL-f?7S9}li2AV;W&557 z*XwVxFQ7>GI*w8>cKJMx#pT~Kv(fdH<1_Idm(SerMG>)o)1<%>F(=MAQ}b@A=3#Wt z=P4Iu;z$DYI?3!hQ|28y&0{bS`iRGlKo3|C^*uTKb$mzm$0+#*_S^OkK{NK6x8P)p z>=K7abr-3(PuU+dx|TERC-0xOZ2AmAE&MY14<;`Y;oaXFk$-clBq4z%R%khlpG?~} z^zPqPRC(kQ>dSzYnFs1I0rbXOmo4;H?uXqoc)mDXpTv+sNzJiy^9;mGCnK&+e!lRdZw|gbTw7|ul^!m_gJQRnEu&1Knob zUm}{)e1M8{nZKW$viLmQUxlOU6I%u#X67pm0Y57t?Y&6dwi@rhOXY^ysi`N_P>kRE z8{gV~-f;F_UHQq|*Ew^KrbwLHRK$(%EpmTNv7EAdr*K0$YKv?Gq=IOgubsCLd$Nt4p6pE5>>h zL8P_DsJT1)Ru4bp^6I}Ag-wj%wb(or|3;U!-_2-Pj`Xk!xnCYEH24aHDvP{MZF3?R zQ-jNgMmCI#!lF)*JT-G}&I^%R+3I^+#V@W0okj0&Bm7nEh0JvwC=9FMr+oC*is~l) zDlB1zk@>82^U>N)OH|{^0xJy7)cG=2jzac=yp$q*Nj6^E##W)arQm=Io`s-{#gKgK z#A`n zRu9%!Rg$!ylOzo}XwKJk6}63$5Y`o__DDRrs%I0fI`|p@ zd4J|}PPR!#b;#dUik&E5yX<~RPh5Ar`SlLU)chJpKzcoCkkTM&ra4^vW$OAA)XJ*B zzx z2hN!!jh)>I5^IJ#879fijo0dd>q%_xMAOK>pRVFN7Mtc9 z?0wUHQ(XX~r*Y49kdFs+=`VL}ahbLR??EH&uQ&3E#1k!gk>-DhPkJ3j+RXgy8}o{F zcbcSY1pYj@OYJfeG9YR2Qd#dfWtgl-MHy-b45 z_bUij)=J$C@Bf(b699O@4Oicny(%cJ3RU{#e=O-;09*XP*Q}%^uH0)L$k-!M; z1*L|{6SvRIecC31qQdp^V(H_ddehIA9`cqVzwda8qGZiS-5wJ*l_SnMEOz_v+z=F1 zMJMXsQ(Hy*bUkQRBGhR+TDCG-d=AK&`}8&LI2SL$?g0RFIsBbQm~jycOL&-4%Da=(r#G={tC;*-rlYx`e}E!>$EJx&s~ci)() z@Fz`0w}12F(>WN)+dW&taEk}i^#ig_!C1}LQFMmOwAuM(rwGYkaPfOnx<`aLnS=J` z6{>M?LBpSC>O~mX%Joa%eS~&;ql8_cgz%`g40y99*Q&wVI^r`Kc6znZm_ljjtHYe`WszWL5rT1L92;Of5P>KO;n(bI?R zF%dqzr>3kANOL=o{zBY8^XE@&`WlM|^;QeZD4b3uD*H9@n4ggjFKlR}D;RJ>BdT#><|lj_&OpFns0AzPlK&$cTv4%C{- zT)n7pE6N&pozRT`Hxc1ge))03#?iYkEMwI3Zn!5`lu*4V!U5*MH;u-aIQBK1IKM#f zz4+(fZ+6>1+#Og+u=3;3s!BZYnn>e(4es(57A`;MC%hkB!`NO9ahjjea%3?XDcMg| z(1C%nM4)#^Pk3vxs>m@3@7}3b$?Wcy;&_@hwo*FQ&ND2A$TXOea#ME8=V@PeUv=#! z`=YrjBa(<8jej2>Bc5b+wXWFZmJ4(PuHB)dW%G+CcnjZt+6qIk8?IdhlBZg2V;raALO60>+8aW)T*3z^|GO zJ&z(%hSjTef@j}(@6750 z*VN>hm(jvOSpL_5yT>if(|oiaKN|oI`^{^9r(5zuWmDyt5z%yWm|J^%OEsB7w^PHu ze!oDDqfg=BT@B{ALjS$)iIvlZmxVO>4Yn4a_;&gV`tTB{fu#V4f0pwnIY}5~>Vj>y z44Na`_4?uwI`tt4Iy(*4X0fYfH`jbj9S7y9)YR1a4E2u;FIN$bm3WyR55f>kNP*xM z-5M4rt)`E{n5EVwZXQ8?fvN-BLK>~;wJ?cb760<`12?*)du9e3V#ci=ki`UB&w{p^ zrH_@6?}aCSxLywjkg*61Cao}a>sM*;9nO$a;O*}Hi6Bs9>W4T6uw0A_~e;12>ISCmAB_G&sG8&jh_7#ZDZHune<6~trEtd)X z&{Wc8Dj)9>Dyl$~r-Q?{A1Y<|GySfz=j?WK$nS{%o=;Dx)*&QypQGqC1N3(<8!{o0 z@t=JP8obXeWx$U+T8dr}g6y##JmU#ESSvfhMK352RR4eqANBJz@;oXD;J9Q6L{N+J zxqO!IsI9beWA&P?-DLB8<_)-(JYtj52`7l(T0>8LI$&+J$=>_+9NEKC^e!eSjqlcw zy9B=a#-+~?-j6oM9k-$E0fp7E*LjkhCH4#bsGUE&p)qq5ky^291L(E=NmbR=D4F~Y z?e16jj3y5gY08Z!^n5vsc-!}8Mez4%lFg?Y(bK7Tgx@xv_t8xtXj}fRj`)<1Z{PM9 z59uIgNQ8j4)Ey(~5CwAqNI#8E5!AKRrHFgWe#IYu*SO*0du0@40Xz zby7SH=dhSmM-VepmK?5W2Bu*M^QhYZ{`@`;Nw?kb}JdItazw*s9Hnd;&GHZ53 zqwoWvP^jZ3GE6%so%2nelbbzrb`0)(@;x#4txyZ|^nypo-(VpxBNSeI~n?A7n!M{xelYNY36b8uI&tvTQA+@65> z#WPz89?AF|gk>1Sq!Z>mHl=(Mx}nCJ)mqyoKlEBVBPTSJ#8BlZvg$Rc>)zF4#&Y65 zi|82z!3d&DcoaZxtvsIWisBe1|gcQREB_6pF;!Wy^)DsO|8xx1@jMX_(Qy8jJ zUkr@4Je{6t>L*>CQXX7S<_wQnKLKRupGobES%bx^^1wuj+JTz(v#V{JwIDX#>2yUz z=_KQB`dIYNHwn*Ot8FN$PW)8uYy!L<(JXk&U(#av1$#bBIZAxeDVUBvGI|hK$mg8N z{v;A6)MM#Zq$&hEv3}boZPDC1t%@RpB_|;aXVT%0{Xz^J6i+2p{vD+f0*btd0YQg~ zf0}p`eqfE~|EUL?|2V+y8nJMTudhi}2^U<#r+H&XKrL8nGgkwylc4xfHSx!&6mU)Q zgD()k4;>4_zg;=@2SB?&e6SvXy+pY5barP91}wdxrY zuTTu~8EO5;U!gJCdc8XgeEXW@69U0FmWdUh;$MH*2d!CBB*2UZr*CLY^qtoBpAlBvQ!>2El zx37Bfs%o$qsxQc?59;LA4)`}Pj)VjRBH|nb!~(lGA8}tfd7>3uo}2CTy6&9&?);I3 zNm$fl@@jXkKysSS`d->MpgMRI`jY`n+97+{Ez1e3c8|+AU7+_qA2daNCF-;7mF#c> z6f4PhRQp*|aC`UW2l1KVGJ{d-_(mQ`c+bWDTpzWB-+@)Q!}h-r3^XBOt84`F4RL>% z0Ms`uFs7kOkQPu*EBnDFquFf^L@O+8Xz=MAJg8$YV`cfKp|(=G-H5GWhF}ju07c52 zshUb!3WfY|H{tlyiT&MT7vJ;8Ez4U2J_`#!IqX023j=KV=;*z}KurCR$zYjH9%p!x zfahz*5%lD`sFbM+9TWHaY56IQ2bg?WWW4{ShQ|>JX=-HrkvTr?Dca+55MfT48Xg{= z#Lcj3vvB~G$=7K5jr7+9TL?N&QGIkcUIM|W4|5yQLiYtZY_I1Q_l^J7^zX5WY>~8F zJ?+j$ln_ENnnp(|0YFhH>D0#5m7Y#3C+Zj}NrO6=BC9smFkvPHp!e`kSe}OJ%_d9$ zG+wjjYU}^1wTUpJs_mU>WkU_9V7_EpX+B7WG3#F*n8iooVl7wc?7X^A2b4rcJ77_` z@S!I~#g+367g|8_l2T)sa_}`Fy#*na@+DIiJPzp}QQs*Xb>r@Cesr8g37827JMy}` z%OEfu%Q7^dqa3ePmsR%WCToQaD{-rHNl1XK@R2el#2y0L6W#gly%ZGLis7!7TrFy| z6C5=@4;ORmc;#++W>KwBdf|c=C|aJ($$=cERMdwlEj~6e2NmdZ@--HqkX zLc*3K)s(`ycl`yM2GyMt1WLTgYJKOoX!Q$h<@wY=qtC)?ui!AL{FA76$Pb>DZYP)7 z3t@4Dc0xn1C;pKIW^{eMI?|2@W$4I4PG6DoW2xvfcf=wn={9H8?ub)h2N3)PvlO8TMH`x(tsBbw?X5ut?FMa?>GSERYOTkJ zlIKV`ruj*^r*6{d0RpWkKp-K@Chm0RUI29vIGxvC(+RQ@vw(}6qy1T;BFJz(ycVg> z-2Y}vR&8qiHrUuJc~tAo?R{9pjTytn#p!Sq2~fZ;(M+?go+{hEz5F)6L2q2wzJ>(- zD4+RNs))wS_-=aZw}L*M-g)ML8OI&P2E-7PtsIOSi3v;R(DH_Ckpntknxfk(=(qV< zTE4&xT+tuFd-ZgS>u|G+xi?13jy64%n*H^YcZ2IjKTbbEM=eGoeknW%IO4pn<6TH% zrc;$XTg_6#mfT!beQA|4;N)k0*f@S0e8x(%(iI?~`g!~ZM>X=V`oZ^PbJWj2FUUCx zS$iXmbx{TvrR%?r(zZKLKHNX=J!F3X5c8(W8=z+65Rx}iBINWeD6Zu1>(?lDFMB}u zy`XM}bB`O|7_uXi@*A||48Mcli^kQ5gHD~UfAjhfX@02nVC29T+6c(ZSYa6FV8bXs znr-?YhOn{%lF6zZ>y0A$z$e`N{AW5-<_oVL-(k)s6xKJnpS##~<}Hwz;qh5~A9+8O z5CQtJsr=z#R;U7Sm!20bGG|TT%ubYNM&@icpg+tC-#N|h?gRu6-+N(V^c4VZefH%7 zyxVUYUU=bVn&`rt2}P0JOA=qjC3R)KT##oH(xj(3?CU|ozAvuQkHq=U)nhmchrUIV z6y{|u^0!&f*c__7_&!Ri@77L-`;!L;%${zq#?+m*vC4T{m%+!rn`dilSMM&B%i}zs zX4YuF>)JD_xj20@~5K-&efQAGXHec}3Y%DOD+K zOdQx2`zb=?pgr5Dp=6pPCLB32@H_k|F&*}Tf4K?u~6;N z=5OZ{4+*`91;gPafl&KdG}_Ij4GG_19MKUh~r-ul_-14LEVP<^G= zx0EBa%BW7K*>fLzqf}7j-+EB1VH)rQUGq=YmF>GVg|MWoo|)R~U{RM7#@E*Rd!jTm z4Zpb^O5{4ArXrknlB0<0^?ztokpzpSKH3^QOz77DW*fs4A6Z8doP=uA8y%;}#TV>_ z%QbP|s!<-_#IWk7=&B@Fr(0^nO&$gbObh{Gs!!i9FyCcoFZ+(P!+7+57V6Crt(qke z1K&w=Pjb+a6|x#x`^i$CRM$AGXKg;xV}sztuYD|k*m9C($%9^h<;I#|O^IF_ZfbN2 zsY51lZgzQb{VOP@v1`q+Ww#%Z6Q^%Yx zSMyNczR!|?8JSS)O-3m%Pv}!`+y*=UGuTHU9cRA8^a0HA*VLTxVA*G?kqFn>z|>3p zZm}(!H4fMOFmrs#BlFjD`53*sV_!)Gh5(lUC|%W-%$GR~{Fu*cCXJ>=LO7E@HOYRU z;jiUvmQ9N>2}PojNU2~65Ub&Bo$i^lj%o@K>#awbx}LDmB4Y3}wLisHm=l>KfauJO zB~23_kKB<1?7136mgM;3n&RFIJ5t+pN$XqOCW;<=^jHGImG|;;Rpmu4)HK5jSb7lO zQ7=)tw>c0uzogCJuAptw+GQC1t_u6}P-{)ev3xyo5yqG?2q1bVj5`09U5Tzvt4X=# zBWv_;ny?=heA@1W+*=Mf`t={k-juEgE@Py>0~4*bdvhJok#xGtV!$|rE~G!BYehFr zrvKabUt{=`^Ni>7)O5whv3fr3cy`?xC)4|9g#<6wC&v>HIaNI!Q7^llT1qN-dS!hRjV`!)QL0H^oVA5i36l+t8mu z#3+?o61-RVF-fhzSp{1)8#G>Ph@)!I`P%CG3bg&l2&{V}rK;B?*X=)TK)> zfM*57r7DiTdnGBu$ek_A_`4ja(gE9xrVH3QiJlL77uX4|;N}jm2^gZ!ZPrl*Rb_M5 zF#UKY!?igbGa}PWsPT?UrskHBKj#uSI*}jx>>O-r^O+ABhx16ex&vOHv)1^^a|3@qs)hepb#nvF?XAd$W-Bzb)4=wCK=auD6#AeI!*=& zp`>s;0hituV7$D%*lONWk%Plxf@9w*t%(84#Ou_JHuhw!p}JJB?d0g7d<+D=rk6Mh zmP?6N<6J#zpJddh51}@J zXUIedoliOA0~)7Px&ZMvq5#%m$B&)!!2Dr45XEdQUR4WW6eER z+{^M+*>jV<)DUM1(kl#OWjSxUQgQ6u-7Cqx zRB}ef9ut3B1R=F#N$|!(a5pz;p9D=>R${!>luc8@5{fU{U%3t*w4XCo`iShpi4A7t zLPY(a+3JV{aP}?9g_X;;ief7mcpaQtFn5->5%<+g&s&;OcirWEPTkiw`Owzx58F%K zJl03aOh#}Fw19Ska7M$ME!v})-BrPSK5>&%rAV|#8x_ux6M?V$r*b8QP&%L{70>EZ!v-RGfPVm3yp5nu4^+r6cylR`j}T5zYj{HkTIt3|t` z;8N^c6wx?O*}MX>*E01luI112j6Ujyaxocm$?)PIS-Y!nNkwsgyiLEY9rfPc6~mvF z) zy{f}O@o;xJ>e) z6A#u?wyp0!|6dV<-YjQ}1Wv*?iN9=~FBz~kH6T@jQasIxz^ywCZLmg@3GXhD^)^ZE zQKKIP`EH3rY*=ra*=}MO?d=7F+IQ=qe`C~fTuBESP0r8XiytP>aUlA?DcxA|?!2=3lW2?Z7y%b>nIzW0m0IgW&|&xm{-i*^ z;~>;KiSC(!%xCcaYB}3i%aDwvAF=Dp8ghi(!FX3NFIQZ32+fS2hu3bNE|2(dp!=|b zcH4lhxhz(xtySs*gYahlhebQQzk3Wt>WASUK9NrBf}Q1hGk*$jH~I-_`XR~;v*LHo zQ!{#4PbuIgv_X?Q0Oks0@MI#%;6My3?kRy$b_aad0()UQvehCPz;!bAZ#mEu34gq~ za)I7xC}(nyQ^@b*r~ilP%ewDNHHX(x=+e~w6r;5z^KlIJzM53^e8oU<0|YFelPUA? zy6?r$E_<7?PRmppBhP1={DQu)mtc1*kw3J4m=MPZ1rouhtP5u_zzb?XY}SxE{gt$L|GJ}7frhMX*1a=%P$+njge8MS) z1PLG`iJGgFOp#;|O~L`sjAdGtHEpt%&IZPeS~rM;>uZ*`5!;jd$}Hb4aT}g|4otVt zZ!u+XOD0oF$mmBc2t<%HuzGaMzUXvM%c$|Jpd{-_zyZGr6M|k~As`s^)z{5RUT$YC5QK=NZ3eQWg;v+Mwq~f510PncC!++h0ZQ!~fsw5y z{#V-QZi~OzP-_}S6ZEEDHr zCsJVx4_X_mrMgxLTANJ`*Ix9PQv*oUSPeh%L`$Y0xI#~BR8iyp8e{T3n*-^DeAm}w z^Go{{D2^m!t7$P5JEjpXdN;WYrgdA!`?Y|wWtRg2)7D3a0 z5$Pkd7DM8)`xnL$+>0a2OAvx;-V#sJyOO>a3R}T7ljkZY2z)?36nC6S1!%tlCL%66 zs@v|p%$iQ?lM{x^nN2i`7sQ{4lX`;z|Eoeyg*S^GYD{}VhZSZmcJY zJjM_9Ck_StzAl6)wTf_KfhK|~0t&()@p|Lk-tBclz*|ocy_hf*s~%`$HdS;0VNO`su!L2P=C2RSByaefnHeX(=sJJM;ej+)9W;a&wiHR)5tfcf+4`?v5#mF zH$#PnO+L=Je7(-$j`3}8D5InhN3Mq!Do!t!GTAaJsDT_yE_Y9?EjUtx4OZXFFexlf zkC%briCIOH%g{_p>2GOBM9NhXu&7@dH?QMLqvwWY_?eOI#0ZbAqtXd1rR;Flq?0txFNc~FV_&!RyU39rR3 z*Q;aRZ=({d&?U)$Ap<596G+q74p&0k&bIA zB$?r>>+ZVq`qy^PI!)sJ{nCu&J$+Mc)9uzi!S9Y|+w>RP0!Bg^Z{4SqEP-zQmYpQu zyueU#6iL3PJ2}%juIO&UEz8%K{P3G9MDHJ-$z+lRWQJ^Al-*9wM!nD+VJ!3RQiF>N zh;JGki^|NG>+Ei0fRE>$Ky`?L;QHGobM#eJe4;hC!?b{4L2x(BNk-`dmt2e(imr+! zZ;>k%lTBhH9zy0ma=dyI75r$Tv^ZvnTE$dijVy{E)0>3qoWWdZZ8=y_L7$pke}kN+ z`q@(Y^YLew+wMLPkAd^bMXt}?!gwb4$$pAfJfob)M*Mm-+!ABXs2bEwtolR$$83WZoq0A(iZU}3 zi+(t7(5d=K`LDN?T>Xt76BdJH5ltJah%m3|0n7O{j+{sC^L@{0aeBb@ThOkp7NNpR zdx=vb&SFav-Q}6PxP|$+Xlgbq@kBzio;8x;Ow!?E9U?8a#pUn&8%c#LSXwfUsplihu8+^>)w5FJ_RFNtDL@#NiD-_fJ#WBkMjn;Y!F@utp)1U5~53 zey35o!#&xNP7$^49TfQ*a~;&c^n+A?h}TlQP>HI^5x8=S@XBx3e^xJyp|zoJV$4}^ z6kCM4-=2o--LQLqxJfPI@7FQT39O^z>zpWy{7JA7m5R^P%KdwKWtk3)Mk;TZpD( z`8p>1>z_<9z$g0NGZ?x5<4`^q`1hTACM4mk)A^rf4W?Jp8`$t{;9<-d_U$euyF`ULhvNaA=TKO_t=Stm_e40)U#0!o3X4}* zhOXwzn1-5`?{xyYTK$eD(~(SKgn#FrGCC@Wy}vt7_=$dt1%JZ58;EzQKeY9JgLu|n z4%0#xkbrYD-wml*%_O+e^bwskt;)-mr{7KE$Y(1FUL}#$j)m^m$w|%=CCSyN0v=9d zLG`EwmJ#{`kn+Re{Z~a(bC-gc=x<~%%vx@Swa)pMzT=D}RUD8}>qSLR?e1S#NS46y zBa8W+J375G#XI<)I8YJJ%;lt(v@Vfd;%%mP)`hCadGE(gNzfq@cExJpCgZp+HyUNZ znICI@MmvyL>+ii0JY#J;Z)z`nKfk%UhVkxg@tE#qC{0)hwGw&m7lW*Wez$xDoJD&i z+&;SMV_;A4UYAKe6{SBzUTUsGi=cb+v*lSwvg`l;nvPVXJBN%m{8Rwj-Um)dPeG8d zb*l6!d!_$WMU7&Jwa+9AXrQ|~v*>5FDJc6KX2)!7^y);^QVq4ck6mAK)>w>cJEwBwINtxN$XvIZlU1kh!DMwxX`&7OM;UJn};xvAFm!Z+w?z&KXCq$ z(HJGD)0hlktZi^f`%NIpXnR)tEGQCe>oZzn_x6cXC?K_FD;n8n-Tspv8KpW^F#Y8A z<#~%Ru?CdyrBbLsXx>q4p{-#Iv{O29X=!PIZk^Aqzm`R7;D-gADtJ}HzZM5VPzVe% z_*uTiWLT!(NB<~}8=cb?in(IILk5+EAwOtTLAJv`M05-U-|hgU z>h;50o5x$yt-N)M^SO{JaHgs+$W9;Y?eujmM#DzQG#zoza#6PV21l;6^8=^shLS0q zXphMJTSGo0xi|E2bZ%atNqM6X95oVjzs8v6gB3}QP5t2`H74E}xX331vpw{zs>>Nt zy%FT>PFPxisnPYu-?&F20g>l}4EPqz+tz+d?G88YPt;QCNkh39dE1`IAH_g^UA@F? zFeraqUa&ArDxaTZ-Zi+=(ru(?W%JKJgBkC%baY}p6I*L>I5TDO zr5wS-R%`VwujPx_e4YAqts70eoF{W2CXF=2Pn=Lh^9@#3=TjW2koc7KC+k%EM2El!+Gk)du2i_$ zDUCV}1}7rimM~yMhJJv1ty;ugQ$>Jkor7>lFo8~GG1l)t!5M40&TopMWXxENBDTvRT6UMyEbe1=*CrNjjP}+0?3Y&?>sV{nc(n8yG`;s4R(?sRCtQ{X3zGK%l?8w$T(p% z;LL#BmqVnCvPiBvD-uBlh8Dp@DF7{WW>7m0wzt(^Obzrcx?Z3yanK#+#`nmwP$- zqY=;iC3i1*_-jZJG?~OR4^ra@RSB(vhV(*Hif^VL|AXNg&PBHa3JM{^&5LXPXss(0 z%qFEY<}CIXcIh$tU=S>WfnaU?AB{?#rfJ`!%$sfHx4~imOTwiM5bpXriKpqt2!uf@;T4)=SBt9m@o*|;jV_h);cK>Q zG|^+9#vA$j-aZHnsKV-MS5+Wucxvem$Va08Hc(BN;)+d0>kOtxCIi~rM6nN592Ce6 z17}I--;_KK>rYqxs3M@prnoutXQr6B=NsS%!&8+r_ouPOvZb*uqiyRjN;SlFu#6+G z#5@1H0b}NA?S{)C{U|IsZmYyntIC;ha>DW*_HbEpwM||m|AjTYG;C*r>s>_Qs z?-CV*0D3)d7P*_2SY5GXAr4T=z6E!48XIysEtNklU6wa^5h9~+v{UVk0U~PbISx4T zcm={h~gPk=u&xlz&%;XEF(@iMf`lredrfr`C5fDq`>fXbJqmj*``8y>yCxUycmA6#SCk2`1qi1b5Kx_+@uVfPAhfJo z6?R9V8-+L59;NDcRX7_lvLF{!P>#72{lmGWq)BPYSs#f1zn`)P`4vo+EkpNP3e#vo zfoTR{xW7%2<1egASK)Zp;Ih?7ZfnyKY0Xy7dgiRW$<6gi6FfH2U3`{5?#Dfm!10z7`g{S0gCBu!p%Hl$7)76`9U2p zpdQuwwI$AtCu`PZj=A?I4G+qh=ppG&2M(5rE$UN-+Z7eC1Zig1Zsy@0w)e2c_PbOz zBxMbD^#e|nzqPcyVX=QyzT1|}2zsSj_88zjt0Jz2XR2)}#30Xrh7+z9>>@wWXnG?L ziP1$UnSPE1&i-s*ozXG>?QA^}J^J$3`_b=mW4N|+o7v8;{bKU5<1(t9*weSwlt7bE z$ak>9$i08HRdJ3=!>e;j+RExj!3_>#5rcHR{{j;8pO&^Qom6ORr&-@aAowUoBAea)Ew-$k4ABr3Kq9~duA}mB9k2XIh>->nA0hU%@@h7E6yUH5aoYw zQAe?X0(&K4nx?1c6yUT2%$$bYXQqGKRKC{+IXiVH%fteQqev8!iO$;2h??c@fB-fZ z`^ZLG{i=B}jSfHNsR#QxP6BCF!*ESKS-mmH1axgIyR?LH)>1vL2>W3=O~iHuLnO@a z&}jd}X31NTn3?EsBhqZ$*L4~7_M>yOMz)9$X|rTvKAO5RZTeAg1h`0T7}Nq7ZP)BgHh}?v705cLt&`jh;V0YH?HVnkV;^ zCl5CS^#cXG{rAK6@A7qtOiU$amVdI~uKWz->fzy?#+GP|UBmRmZOjF1$5c`?1O_mc zItqF!NiwnUz={a&7Lw3Iq2;5)#SEMKLFbr5XFz{2KqjO8R4m1vq}QqTOJPaiy&ylQ zJ=y(&G#-rt@;F-6M3jly+achwmOizhh?(&eq=F7AWl;oaYf{f<_;NS*DIMod=IUeA zL4uT>Myy*~TBp^moownsPkj}l5$eA4gKlR#t(py(9!`n4*)1&v5QpQ^QoY|ADl5*u zY;g@lNna&ZPyox->h8G^J?2MXkyHV`inAIsHSB~gAv`HYH1-1m&ScWB*St6J=l`@6 zl?caloi#!|y}xZosZY3w7J+uS ziZz3_fk=lnd1;0;i(cHx;i_ zOnurAZBR((=^~(usUbSdF#<}vN9F77#U=~APQr%H3RZFcJXaFVIu=@ljVlY2U>k(V z?Q7q)KF#uVEsay}{e^K@6~k8Ha-#oO1T_#lrhGW6{v3YrRCimm0npD-6)}3PazurB z4C4N1LfsDw2hI16EWV=elDf-!V+&<58E=z4I)pLl%s^B0{=fmo&zth~szxI5gff)ic znse@NP;B#g_CdrzYYx>&%t=-;g+$A@&1AmUqiUxR-giEGDzawnmI z7jDA0*??CBPN3&qX5|KXj6klW5rz-GPL7I&9b|;(Dhxx@#5YY7lnQ0%!RrB)N4SHH zoqKBNiBMNm_6%JPS_uW<-YO&25d*=Gb?^H>Ks?Jxj>rK9Z;2!t1=80TNsgAiqF5rv zCi@Cdg%+mMAto#kBL-8(w6ed7=RncPFAUCe|X~BZ8~v z%O;NYJc!X5@f?v6ETQpAA43JJ1%vRZTi$v*8bRmWn}Wgl!5lN?IC#5FTx;g8io=O6 zFy-uJtJlb*P8^7sKD~q3bYruxH1)gG#^T$r7%$X^exM@I$N|aj8`^W718X>nG+A9j06tQg-=@59U*cAYeT_G{^QM`<^6dELa zS*sGI6xA!Ma5vG7XyX<7CDNLhp})9Y)t5>_qW6*{@{Fmiaa6(OsVa6C8;;!=8nIWq zhSMEe8x4a4>;9_K$tq+~ze~sSXu{Lu4T?vYelKJ)Ef9bCao$ml&7`r4PCv69Q@MVu z(^k{J7yz8Bo*ZDY7*>H)jQrnx0i#YL*&_{#R_O-J9-9j?IsLJ&%qe62lyZg!HQ(x= zAF7u&g7Ds(9pBqE^|TCr$mJNxot|F$Y+run>s42#LDg);n@IZ9oi_E?#^W`tDq8(> zzZ4At(XVLk7A2(&y7>-mpf^ z3;~2|iiaqx#-$$2ehIrm9J^wiI6b&v_59zB_$txio`jw@qP;}scE3%vW6BH~VtFzO zSlt%JPpIk5f+eBhkdaanCrJ&(kbqSVa)Y4h;Z@llxCeR%N!b=aDNqU|x|=ejRIDzl z{bg5p4Iz2`ztFSCq6c<0d%y)0_nszB<3PctiZ=~_VqW*{l4K*~6i)=I&0jLbhlWzU zG0xyu^kr9)=s;^I>RO`}A|E4|vbN0jnUW-5HJytMf!pQ+gv4BNWBT|N%jP{4Ut{k6 zQi*jM!$I!rsRSnT|DfFE8k6|@)8jGGhURm>mf1bzi`m{huT$yBk6jsWF8>JpOcLK7>QYmjwK0de+UoYL7wn$5Khx@ZpQQrWDz3~a$)N5 z3IGI)!PFa^FrmD@P2~pYE!mU2PPc&Qgg79(WamFe^%<{$&g`I8mH_}Q!;-8pv>Wnl z(og=0@~w1t4Bp&uy{!hB{vzEe#I)Y_QRn!InD(?QLP^JefiE%{dLV=y>kbTxKqA)F zdzyH!sQqo38piU8xqRw#p*tdRs~yOqx!OAv zKElMte_P;aO)luitH_Y7-i15;%$Iqn0ockj_w%mv`UHQZ@U9kG_M2)@Qqu)!zwN%= zp$qwN-nUK^56d6R5@+PX$^MWfNOp39J1+x+3aqeJt z1s*MKcOR4bAO<@cEz8a(7lX1Pp)6^NhmpeWuK+*cNsnz0P^hv99lvn}Pz*G#&Z%d~ zmphv5u!n+xrR5$nOv{q>{>nM9?o2RCF3_rb7O@kF@bFhnQJFA&+dpIGOC>xRpyVWF z8qk7Ln#vXg$i8}xx3?h~k%uh`pKI;2VTgOd5Nc`bnF~24a{A;ND7F(|p=mK@b+W;~ z8$F^3F;{{9nrQPr%_=XCS?*tIa6X6!4F$rMM9^HQxEXHJ_aoE!_Q}fOas#lR>>dEkqfF#> zCHQ-|2H>O!09F*<15KbBt~*73V9cPv2tT-EoWl2S#HnGLFoqumv-QlTh2!`YXYXH% zYj8?$NONC>Jm_NTM!NqD&ZtDZfpN~QXTnVJktI6u?@R1n0*qsIPcszJIZak?=r@}U zrw`4gg1qmI=l)wIBBXGMP{gX+5bZ%zbk0G#TY4}C8bBO6fdfCUCDgR)WWwNmMJnKT zxa>N>+dNOV4Cq>Y)<)40db_|;7npnnd0cMzO&t7*84h3#xEP2wpwoZF@~AIZsqniI z@3Ja0(6I6zVg(|Z=SMa1ZYXK3qUJbgp1A{~#%1X9cyi1CA`z|sd0lk#XR7~{8iB9h zz0x_y?|ySZVWF&>clu=!&MSU1?lDjcDh}{ZJ}V?dBo2ekfhK;#x*8ah5IUyvFKv`p8>1yjH<07!S`-%N~$lxaz$CVM7EB8v=5zY~88C?CGtnq2k;*dyed3_LK zz0eLPgR4-S|BgJr<{&ZadMk4dQVYsN73WV&iYIB5fFD7)IatAezG zo6d>A)2SO0ETmaM!h5rU>6;;Exj(7@^M zljq~)Gh5v;ecf}a{x-=mH-ncg%`D*1#c@JORCS#3;9g;pfqs6m0AhSR8$-Wtk`PzC zC-49gx1nsyw&A%3Y24fEsE}%%$dQ`uz-*f`uxr=oZ)z?BySx`o zfOu#C>KzI`Wkp@3_`j1*aebP7mH+=iwCKWY4lBpjQ<8WD5eoConY;o?q!c~P! z7CLv<`>D@9O=w!FxtxflSPcDxay1#}tX4*^QFrc2V#&+BmBN=&K$CWA=*P4{DfxdH z#*$#`z9fwP)?^XUgcqiO9)=bq#&H*JNk(1eD?qJ^{sror-B(c#te8Pe8YM=}#^{_% zerNGH4md8XFv|zSylDiehWr(FTfC#2^uWV%k*x4N-ug?l>jmY8<0%M0mjZB~UyL)y z!rOg|d9mm%EV9dl-sgpH-Vk`Z^7NQKY%n9!n;MO%9xux;K-_=PX#F;&T_%8;1fz16 zgTncQPdg7C*aNzzMUW(`%n~F=4_Z0@0n7fu2Hq3rc2UO^&y5g{_T4s%@btfn+v^2K zA&I|w!r+~NXY(F{FRDU*3r+q8WpSYK-VFP|vo048(HKe;0~9g5rqFquKAFfyD`|z< z0xBgRfI&{0|DJb-FGIW39_~6A3HCKHCS(s#+o$17h(jax*l|L9|F6eJY0CbC56N%~ zr@q>_%%@8WWZ=lyRF`m7rlnn}OMAJv%J@rbwY!&9;mhOiAc={#aR0hw;e4d~> zAoZJ1L$dE{UE@|yq2!+yNb+)PQLi};T5B0#h!VwM&HZnngy>kJba!^tCHAzTxOA+v zLFj;$6lcU;`ftznQPB4oOF<8(;N;dl_d*+}a>n?`8<*eqMp$NRu7Zr-N7KyzOwT4O zql92%o2VS7dp_MnHHr2^(73;VzY)Ctl+=tOm4*QHPNbFiAk*RA6OY4Htm5l0IYf(( z0)FTLf3ZbIf~0DAgo_k{%eJhdb5ti9ZOq-0zLG8khi18LChN zZh+9vb|WVuZN2E5r^Y~!R9L_Z4jUt{(Y2%F2!yN7b)*A8MeZPdg;D1_Ljl$(tAYk) zxi_1&Do;aB8spdATX{sy@?R*p*hv}Y_1GlSkdshI+jZysXANQGN?T9pHRPlmZE2W9 zy7HoiXKfjNjX?racQk2kc6@(aGj8z_oN8d=W2#j^D~hw#g55U?v^!&XEj~BO1COuk z9$OC(d|;@;4NI7UX+ZBmJxsnwr7C$NW`8QGcbDTG!rev5f=sIoSHNWaYsMv`1ZmLY zIvW}W!N}-8!H#R!IEz)4l=Z#jegiyY{H42SeE~M|`SeP5_T1!1$TG}EoqJ~P48y6}AJpYAFhpV;mnRrtkojG`xI0Kx?Qi=+J7@r_#l9_dXA~=$%m_ z;aS!#Wg!=N+Hl!6i_6e2L&28@@pdOav?IEu!8@U0zd1yS`{%2ZzCkR{vF<YsvMOCjvVAhBR2m!2GA zmkp7JEj81g`ToU3e~L0}9hhtsMQsioJYi35CKdDy9Lv75u19k{`i?guAeJmR91Oza zO&+Fz1BBUTPzPew=|d^*3yln#w&w>xzLuZzS<44AQNX+9)Mx3`Cx3VN?qta59yL;b z8UHUYrBy*%+%c^REx)`TZ0sB7^NM0m9K)8f@s7yWy|HFne$DA$=6$6*l{f6tRUNZh(^>}Roi2e3;o z@FgprzDm;f&IKtZLuhRI*e8JKdGl_<;wm&taX<|_kAy5$C!gk=JY zx4B<^PLhLxdi58t$KcS}S3il8Vj=@MsD9qqS$&mWR0Ti5|Ej1rdJ|7-$kvd|^xJNE z@Tc3b4@vhe5b-ZVi0^LArce+}8rcizid*ul2?w&`9ZI)k4-s5MXa3FDN?-Tz007Cv?MuB}Y499m42tR9R*yjd{m#aoqX05T~Kx@9W2;*kI`O4*P1thMyJ&{Kfg*f-WCN=a(0%+*2Po({kA;4}l^4lq%okw( zeY^h^8iCiGDEM@>(H?Luw7j+HYc-_Ev-z^sPqN%)Mzda%<=8)%#%zdn$Y0#a zdBG?{5D+#(ekF*r>{fV&r8G3r?%4U*^?26ePLoZf_y~dTCYgKdn%d9_!BiA*k#u;! z(gM?t&`^x?WQELYS$A!JAQ12IrLK2~F`F_X4o_ry#4}f`krJ3=7xzE$AbHo(=rn0^ zzj&W^e!qSI`N_ii+vwPSG`YgPz$h8sR52f$Y3S`jhf2sioTnt8<>@zB4nf=}k?}O& z^$}+@iqEpa3w?qeuGkqO5>h7V3)^*ye?L_Tg@RQ|Q2qn(Jid4-M@4)FT z&PCfy4FXfQl+I8^&g1zoqINPa&jf%@Oro6GhV&{DB6}Hir`$2X_H&FS>Wisp+1V+e zZ;`)ZjU=rRyPgY!1ep~tcS>v_K@~Vm2k&pC|CEm&=zl$tYLeu$CPmhkD%=mDk2<#~BJL&fM;~G!E34vdwF?6ZFliBBi%f-2J!l9G zCY|noBJUu<@y71~Am8UXVVmxL}g zw615?kPJF9k*5~CVv>S}Gs0wFO>9iW8yxZ8*}E{6a0l#z8g>O@fK13NvdbuFi!9OD z+WPn|198x1<1#fQ`;b7VmtxN?s>@_ z*1x;pHZknI!GH45#4+d()7mufd@ozO-?JcVJ2*L9q5~{~LJSR>ocD`<``xg7jC}^# zw)Fpa`I0=Z??|+lRcfi!y42(4@U)l(yHwq76XqguwfD>Sc|rTz4odsQoQJ{Im zRX;o2K#Z&`5Qx*Giff8%NyXR84T^5JlI*PExto3L9jY?hGd9Z-K>a6GEo2*rhb-=5 z$Sq4QzFA8e4%yEtXQ<+C<-zvX*xI%TVu|mR`2;0+#-#|^av__y4+(3r>#kt!_%0VX z6FmNhtugQ5L4!C$@G=wQG-z@BD|-mJ^{J4E^qY=#WaRVM43zs}*$T-2d>V$^*LiBm zks=CaZu1D=u&qdC)NmifZk7$wVo*UkA@935fBm+hVjTrcT}2N~;C78_(YCv*kZuxq z|H}Rz=91vLEBI*r*gB{(?QA-GwG&;24kkzOJ#(%mi=sLd-^Fu`)IE}n$`nRT7*nze z;8McVnU^%~5+vOX?S+bzO8`~75#IE7!jXe#TaG4+PcUvf;Wv?9~<4k+?fhLETL ztWS74Y0<<=axgC=gYOtXq82u6rOj2hTT^&fqaEyY6B5>+jkwm>ZVYP0>K*(}(}bZh zc;92?5qZmGE(YKuniktJ2kOM#>BR27%wqRPpD+r|V+mCE>iW~v*oGZyTQAH~;dyKo4zabZ>odC?^}vh>ZaF^CH^hC)rCQhOav6CeT7GXR1x1SU z6!c+oJ3`q;h3xV&7>y^iZ$Yd`%kT;<)j4idJJ!7l;f~8%A6<`O(&JtrdOSsao-03* zDP7xZhyUf$qvoiC&E{LV=AD9=akhPr#+MvT3 zEP?AeMW@ROML4MAGk@Hv;s-wknC?KPn4ipZ%ONR|LC4fx#Qc%|XJbY=j8p zGy!je$yRc~810LQuuxH5F^A&2*c5Q5)J#%A)|Gv2$Vn1qFq$!Z^_!R&|F{%!V=Gx$ zyw|yqYp@2R)~I08J1$lsQET+9ViF0P!fa@|f4dfqMdzk-~R9dV_>wso51)&6DNo+_K2_yL5M0p-ejP=dGakzAnM@teL%B z=UUV>oI2YtE`sC6DNL)P{r_A(EoLFOJ1uLpA3dwi0oiq6PA=d6+kHuvFI1+<=NLHr zPOFQ&HF|*w@728Dn%x~EsURTf0Xk2NOjvB`wA(yaVRX7!hib2f*Hs~4)Izv=kflyH zmEE84XcA9IMxPns?e4RRGq&fw7~}Tayb{ErJ4v@;?6JvjH2;tH;$!bjhlS>^th$+V z>i)709wdSMyY$oprGs?ZR(Uy7YT8BOv$}w?P7rnUPahxI-&uC%AQQ8syP}pV{cd71 zjhtcLAY2f)9UR`~)>1#N2QgM-&>;o($5k_uJIirNi-*R5gc!d}1}v4k4HL~oi0J^{ zZ!&Um>H#B#DAu1pH~vTqkO~6FA82G+&BPLCHX)xJoq)6SdJHd`SsZ zNu0DlMhJ9=)Jz8iuWW?mKRXt!V4=cY!vJgV3D>(-y6TX*s>#X`>R?TY z^|34eAuAhOQ1`N1H}NIx<8_t*Fgke`G7F80JLD{TrM0Kj$$fZ6m+?p*TV(IjX|*63b5@+bHb#6SGa|IUGdoI)8?j0 zg`D)b5M+>u+}jnrP*teBSl>1WPGaaly9DY_MVsdgWS|EkZCn8hkb=0veuz;+zSRK~jdOoY zRzA`zkOaXKTc~YRbh+jV;-kh~jlkIsFA+1EHs;q5=WtT~VBo8FYYIh4hMMzfITd#$ zFyA!bRB&sBUcF9t2-Tk(0BvZyrtNJxKNWg)LqVf+xdz$XMzk+**#zLoUsjb1OQ;6& zskb21aG}tVE2#UykE6+kOfi2AaFbLSGc?RuQ`2iT<6vixQ6p7*dfrQN{lYomN~3Kd z<9_-Yk$5O`M(Fe0R^zrhXhxfmv^?0{(Fim^`|u~cNZ>{5fhWmk z9~1sbn7LkyXe?M+^#r}$2pu{1bZ(11^@p{#ULZZwu@XTt;osmJGdMs&m|W|BU-?$( z`F9}aisDg1{rRV$&X2#v&R$f7<<^RwpMJ`3iqLY(utZY4I*h-sv;dOefF5702N7r(O5AT&E?g*YcTS3Khk zxEa3@#l39s0<_uO$>^%)gPVS-M|IZze_Qc^A$8ioC5VhUCC_{vN(>2@oDOjn8SUIU zqoWMNRIQ*>S{$ueqvO%_c->BHm57$jB=9&QfzvirBJKpe@Tc(zGc(%3_vy@j1STCt zGszm>@=9_9zRP#cNp4{V4{8RXK@2vb66(7(n;~ln;(}X}eEZ^5&C<85(X^Ibmecmj zlR`8+6M!}f2%NbJ^9#p?Oc2QMz zo7EaUt&#M8AeSJrTBAY@`I}6-Z+fH3%JA=`D&{ACggxls5$rHtbnrPfWOd}f!}Z1X zSyn}{Wj~_FugFogK*Zih`CM@YeHv92_DosQf5kbbS%b%^W%lI~aZJ0zjcU-Kwna55 zW)f@AkkZN$o#L$LI1lA?yO3w2GZiZnaVAc-9v}Qv?G|VWsszg_hCIZ6doWX>9U+t< z8vfxNbZgo~rW6N|(_@McJz)mP6toE6tq8*a@Ep>}^y>urbztc3lMhf9eQ`xKs@A;5 zQUn~{i%|ug{>6Fh(O@xI{yi}TigUpI<&r00N|DS?EbhaTQ$?RY9@)hvtu5jbx*z8e zW_cid{^(+fVv4wxKQPih8*|clO#Jhlj4p1n0*tqxHK4 z|Km(xCb8pc<5vTElZN~C2r&AUxAWN$$HUdDk}vYA>yZPBY^-1$RA*ps`uN8n3=k6T8&--WUZii zHyT3e;u*{p(Ec`c0j!w8ue$SxZd`fKx@>6d9)NdAJ$^PkwS2Cm8HBfdf%;F_^?K2A z@qP(RW&!5eMG<`b1@=E>#LoJ*c$?H%tKXrae$&7I!_--ZRTZ^cTN>%wbfa{4NNivu z(v7rq2uOE#Nl8eTbVRb$;-Zy=tzx=JU)k?xDqf2+dV;m$1f$ z$9}7_@)oi|p+KVO!N~X};V-f5(k=t3MESa6rKwJh5jFs{zz|8L4D#dy~C>vVmVJv=8$ z*-xH6goC`|D~V^+H{UpNC%|%xa?7I!w251o?%f$|ly=;W~K34iV%L5Z3o4L#5%2)&t%$Am2oWz=#LhJNn z5o4pS;_p%nUfrIgB1H~-y|G3S!9*$}Xa|0%lcYk_PwTz)9!e(o#s`F;EVQPtyFtf0D-!!iULmLlA*FvFwL0EgF0x+&d ztggWJ)w2;IpqJnKkSnel&p%}r=C^Vx=VVx(DfBs~gwZLOnUPyKQO8hmd*JNlB@f%|CLNA9zlJz=7pXRt^sm>QHq z9p0K0JI$0CvO5>W=yOMR{q1)^Tq>AXk`fj(!@#}15s*(dC56((#EUV%UDWtG9UfY> z=YeaaXMnAlz4U3hVxP9-90})O892MJGQ;A>x3KHqqT84~H%f{pO>xnUV^03TDypK* z0-&X=7Uz>hP5n5bNQ+1&v0q9d8*E{mdTTzvvadj&e)+nqlrq7HOx~j;pHG6G2te7G z0MbpaYX1IV-NxznQ67n6m zLSTP|oX&lvo(IY3GF_{x8QCaHFb{*&46 zLL8Mq@)}U5e~czw004%(tW^lzD7Ek^ep?YJkIOWS)LhFMV*pcN*{ZTs(rJ?w+=$5u z)05t!+ibO%AL0D)bfu-}Z#N~`kgVb|Q{_xL*PrC%M2Q-{4^tFlH0;k)ZsyUJV2UfB zAB^u0RK!VIN3u@KF&&qN2LI~k)#UcvRc*T6uO+eICsg|&no;#d>qVnn))sK?zr_o* z;U@YGeg&4&`xUr-Wb8w#U=nm>SyN}DsT{3Uy?#`=Dk+6q1s@bzL`~4V2_R(s@NLwu zwoy&5=`(}w=OKWJ=M|Th*nSTXnS6E$a>jW`fHucdzY=a@0-d4o8#i6?QSjsQBK`giKqMjQrx-wRh|!8PqdCdXy#rD6>^*Dw@ zWCB6(adx$Rvj8svr00%-PBl)(pM(bvKS3?^1$~Mn)LU;lf>-aejKM%MQG? zFA}JLVm)|g(^O)0(N9p_OUQ>&8}!5lfg$g~QH`yfwz*vhf}L;Gc}$K16uqb+6BM7L z=|lEp2|Q#n-2e3gY3jhLM$_6+rT|edZcv_HJ4DgiFV8H25+_)-lZ1RnOdBr}5{61> zQpkpXO_AoLSA6#aR?nt&S|>zUp`w+DT9AF=2Q$z;hBW7$OGZsgL3>!i@Bu2E)u!*L za&tvb15w~b{s95(;w^Ir;M^{XMLRaD+BWJim;_;`?w0;ds@>DTMf=|Bnz^@+-trr# zf#QONJZ6p^%`0iF7d4zZE)nYZnFLCi1~OUcV}Dr7$7{K*@$9)1hb)eXD7>@BP6H2n z8u-Ntu>tk}miTF4gw&(IQ!4mdtdSQ*!tGp6N@68<8xCCZIr@TMACD64Gp_)=$oZ!u z?%a|i{+D6@QEVL?#@bj_tfw1)1U96C1B5u0VyU2k;7An3dw6|P)3VHc#Dp1(y1cAf zWqZK_p!0BRI{uJt1<&`1Mob*&T7D5WE#3QU?ViP@qjrQV{3bjyIyMreLv-s;gDE9l zBkltRNT>OC0t0bLg?ZE>9V*OKDtw$ACE1n2n$N_^K8FqjYr0E9)}&@Z9wWJuyTPC; z2yoX6W{v%YvNEA}WQqyRHqD>%ls{U^s`>GnqGMxPPv;hV$AwD_`o*3KH6oORR37@3 z(z^xf{N)O0?Kb_z>VXok?xXM)cwiq4Ta5ppQw%BC;)ezRA_EZ*UROgcgR=sMvy?n+k@h_bey(PK?Eg-+ekMf{xL}>E}uU<2S)a1;nG>1 zk>H~rPmA~cc1+Fubemi+z>O&r0*LAw$3GNV^iW9ua$MU5+bi`8U)vA6E7hUqO0Bu? z#2vcl-EkrqCY%Ca(t=dbq&P^bhu2Xogi6~!A3k)Z(#S+ zD(qHg{K)E0qih?F5jJ}ZmUyW>C(`Sm90u^~X|x7JP?+=f>Gp*y!F1Q&@d82%N>AB%ctXNpjm11TWpnc@m9 za_*QDFBKz-`r0FISOic=P>7yo_4=T9SFZ!C0?o?ecBFu?uKDY5toc+FGIHI_ltD0V zE^_$91ZazyaefQFs(9Y|eOA%7683^Mekwm*)eKbz#w|)&e89rjE!$~nC$QZnz>kA4 z(-(ypww!gLjuSfeGV2znhNJ@^sNvz^OwOYy+V>Sl*ctx1Qu-dGV9B04zf227C%v`b zhTTBLwas#OtgSBZIXvgo+2|qPuvKf^`*TjIDAF(%-=qaC6FUWI zMpSttgKsHSe=N{wD$B~X#(HmQ1VafgwLpGHM)hveDf&I~%e?fMLOSJqELMXL5%V>IPF7fRYIh~)@~UEb!t?`F4(TTT_CMf3i~ zcb(g{f<;CJP0#8!_$Xa{OY{?Pe*$2&Ris-TBB`4j`6m%@7M<~(Z;q#nR+ zf6Vy~H#f|mW4Yeg00N=*PhTh5N4`URt^LL>R+7}r+YR*j1%;JQ^%{k@S5v~s_TlyF zDA{2V;4tn%5b8QP{EEos`c?DMXT}PsD0e0&{NcT@R&BvHB)-?7D%Sh2iqwnH>$S+*KNHUAD zSR6IC$bB$z{vqVLlt+(@sYV~Z-Q6eVp{gd#5?EkaQ&YnrM01^Hyx>BmYT(z84M?%V zct6$GX6qZpqLo%qD#I*upxjvUI`t+UxL0juTh*s>9hX_s&qS!S9xg6jf4INV z4c9(rT@WeS@Itw4{?&IsQ%dr(zWBk$vhj4n4Sos%;7!B{y1eWV^8 z#XKaxmCL5{d;ilN`XpB{#dL+Jht2-ke>R+$o|^M*624kAQs3D@1WZ_jWRl{`L+WE7 z$RnwBSxq(Z=EFtt&4>FSe(kN-OcSGFfHGf5SCV9ErQPaFZ8kz;;@IX7`a`d zT!+B&uwg8GZVyT9Se@o_^9t*g7SU}Yf+41cM)LUJO4?mJ6r#ttf&bP8{x)vcdzVRm>f}O`P_MgF zxtu=c^hu%#V{Ec78JGE)fYUR$D z<0~FDX96e~eNScxPQ8%sf&Ihw+o$%HU8vA481vPc?rP`Nl$-f;j7;#y@HXwZvU*00 z9cto?;O`8G`5V(Q>&I0WRvWOAKpJOx?v{{f!>{2uFoVOK^0e^ZfNf3HpGGUV?^DU{ zaX+5rZuxl5xZ{r+1z%45Lc%X2y{9hy>VF=?w2zI$M-D}^8`%K9sdt`BpsBCR-P;l8 zo=a~;%e0*hob(h6r*ID+opPWaxeh6pt9C?1(LgsMQ@duP`1FIifiAY%U$-1kr*Z&Y z5A}$$3cU$u`5AeY~8__(9)R_LqgfvX`_5QAcn4Ad8Z21+F-K29PkX5 zb4++a3_$p5Iz@F~9zx1Zzq7fuv5;$bwpaIM>&!9UD~>VRdPnPnGhK=rs9IWcx$ zv5jF4gE`otYi#jxwhG=gzS%pT&x*rIxR0J49-5n#8=(4iKr&JTnB20tx!b5N`?3qs zpsT~U!9bI?Dp4k1U0t?NMSI>N(0tNnVqJpbYPD!<4?jC`^RTXvN$G;{33dA=iCuaP+{a@2`gpF_eOQE9h)ijXQb}NtdT=%|(4^Ie3IhW}6 zl34Uo6dE$IP*xdGJaj4GEcIkm`wL;>TZpAM!hT>;ELfJ7&&-Qpv{tRr0VG2MP6VbS zAfXP(F;&x(Us`+GCFt>?$#lg|lB@enRDHqD>a^H{8<;P8{hlMUV|sQbq{>t}(x@uz zd(+P4hhJ^p})0tTu7=$bLLsz|?%L7GmLahdvn8X%Tl4Z09$GP_q_D;$eQ+vT!z}kOY z#8ZmpLjqc&kaa`)`p~a{c|2}hP!w`TCfT&-Ez4+8ZUAnl0X4o9L|ZBRfbW&{qI4MW zus5q81~bKtIaa>eoL-hO`uQG^*6jl=;D0p!r=0C-)2z$~UgUU}Z|6W8!uY_EHVTVb zR^jGD?TxI8ghRfB6(O_V2;~bacXsYP$*xz0NU?-r5C+_U2mdnNQhqzNYhR-DCBf*> z?_cw)n-G~y-LXXRycD7LBgs4HNA!J?m#e6nPJHtXZAXmH~ zaGH9te-O25g*EoQ|5xib(bwnb%I9usrK~Wnc{kvu*orS=3LT{VA)Oo^3)3c)eiqT%oZ1n4X8;e!28v$c^6S^-Au62Dl1?Dlr+udY>nO*5bl4JYGU` z*!$9%zCSuh^)>rwB}d`of}i^MntPK6=VPXldo)!OgsUddS@IT|=DPJ$8 zAFTPtrD2zE-G_sOqgP~>A-e0MwN%8x=c#JThyc-)t;Vm`c8=7s8_D?Rw<=7CFs?Lu z8=NQ50G$ml67c}h-Kv%>XJqOBG)UU7w`Jm# z5BZ=!9RcoG0qO^MOmH+@Nr_pF*8Ey5F0ck_dq_3rs}zNUaK!0Vd^TG!seso6RkXNW z0;HhPr^_+L=lwNi@|Vtf7R~1=-+RTIqlLV`Fl(&r3nZ38#-R7$0{F zG;CW)6i97;eV$Ml*;Bq1K0;K1^~;VY59bbtzIN=rnrV(|6Q5 zsxS~kE&i^gum8qp&Bg4s|NmI3_9ce%0RVYDNj(4@(5O_PGv#PG_F?jfwjySujk~#B z?#ntj;mkEg?NX5LL#o~#7Vue{I&nkr9Z#HqGwS(48wm7oZdCl+ESVtj>#!kSDk)>QS~ckvo888gJ# zTI63EIIt%Y&@R&!Cj=drbvZAn`xDWTHq_FJ7UzvaSG9_c>+<>V>C5Hy-;-^EhMp&Q zc!T`kN~02bxB0;pso=b^jM-r+U1N-yL}z8*L({X2J1>?o&x%{Z;CXu`RWq?~i`2i# z`c0Kg72$tAsiHRb_uRlWlXi(6-JWUENGF7nFEF`~KDyq1kMWYTo^iWSY-6q`w$zfR zcqqEjAopNl`EPGI;AeMu?R&k6^tQwZsshu0B*C%36_7{e*6v^L*2QDlQA~nZVPYCS zf&grm0-K$3oQ#g0^=@oD)ND`B_jYEA;$h{R6af&J-kNp$eeG!x2+{!x2VS{E4bw;= zUiq#_YhI=bJN9y)cbsW5!y44Nx=3@RMPy30lK7z8a`HMRvX9xgfD;Bx7X(M+Q;mC@kG9j{{K9z*BKSzp{j_agA_W1n+8Z?oG8|2oyT3{#4E3WS7sY8r6!QP0Y7yRx@nvUcj zfbQ3*&`0&FXMFvza;eK&jP{E=uNu^_i7!QIl@sy!5*eWG&iw{ci@NjV%3>v+G<210 z6NVwtyW{rx>L&~rh@6=ASslJAF0cx+s_POg)c$6uZBu!0KwiPx=s2r@9I7`E&X3p2 zuQB0VSFH3bpsZOz@NxMoA}j^hhJwD3&%N49l4B35GeS4AgS-pr82AJ+(lljf@_h_f zDaan`?N*2zY?ZIZz(Vx~N`6HLKj90I^TI|y??;r6YSvx>OBum@ooFq^9&aM)UG#PM89ne^BhYY;6;&?~Ao)n8e$9F9CIy*s!wRzuo}Of{7{vc{Vl;*0J=SquMW=ssqKpDB?#apn zKW|04_Gp28UYE%Bo=oJkVsQ0BVdFxxt={iHdahB%!kBlg`VIhA_3l#jL6;6w746E? z>}_sxHuzs-<|JQCnC-!Ho*PY4KMfU2(dt#K@+_#NN5Jl0dzS3D3!!IYu5b|#|u zI}~a`@^kCt*c8*0bYZrsYuK;L@~F5O z5Mc5iu9qK{0?O|d3t%@_rSfgOu~ z`#7kSuB1V?VHb#JUHNSYhas+4%fKSlVoPE1$f}>6yWYse0ic6V0aWo-i~jYHv*sX0 zbw|a=&@-BgYNR8VVs$J;w?o0ZM5XTAOszvH-kpCX@)k(nhpv6?RG!mZb- zBC364kvFAizNJ<1NA{a6Bp|Ud$!3oWP~%Sr1g6r~Z-$fx%miDh4<2jtF~ulzZ&km2 zWl*w`KA)z|R*st0Fn|ngh*}JbBaVZAR2Fw2KG#p9y_pO!I1O!&3tzEozk!`2P*{H> z-t)!{Ic1Bx4REmCD@ZHb7A96MK|OZMT`%|QHl-?G9zDhRo?nxyw?QD4x)%CGGM2p#$3M!g18f^r#>bc_}dilZh!2PCSg_ioI((F|W-i8qa8 zS~ZzWLXE;{!ZK5aE^I<<4iC6}Ox58$8bJmq$29OtX;lqrAE(-v_#p9H|`T>w5eS)TB&Rv<;s>|fpGz2+lw z?v2yp5|(5rTH`?7fiNrPBcx`lr-*}DKsY@QUoCvo{1TW^syT={=2UJ-_J|05->aRj z^SC&7ex?WA9~f%N~1EBC(J|fJhB8Q z=!)d&!d$@RIT2hgXpp3-AbQxSvI=&2$BLf5)CFC5{`#HteFC7V=huFQtDx@rwYWJi zND1LW+(!7T`9B#2%?1P4xtH7GZ`Mohh5X77Zdvo6@==JGfX3m4sWc^II4lo-LPA?} z;8{Z}K$_WBJzJ1Nt|v{WQRkw@7dantf$Ka#_;ikv(M~8+^>WYlG9WN6n#5RAP#_}} zSY&r7HL~+_u0A|{)BOSW2iH;hh3`vw`}#){fE$to_X`1lAxa!np-}hXD5ew^q*E>i zTgkT{IM_qj#Hgg*1hSPQIm}6&f?-WJKF>Xhi56jM@JA*#=G$H!$u~f)x?7D`0$QrO zG>#mC|8#iF!F3uCtpNtn4<_~tLFcHNdXp;Zr4FA+spG{i1nYSXud?eq?fE?9+8?RH zR&hV47Khy=^%Q*T;>!Hh%gXxW^5d+}spuC152`)q z<`&2iQq?1FuP=2yJN7`wA~vY9m+Y+nMP8M8L;GHAk!%c#OXmxrAao7h#q%x3!-C}ekj@I&(%yeWV3;1mhUbXRW_a%yM5uwI z!r(nhROVOIv6iV20BddNF~myD zm@w_1QdeF3hDl|iTlDUs((7a{+kO4jNxjh{fTUiN!?c?u>1R{Z6%&Ist$+Ew=N-?^ zT?ZK7ZZ0Z`phrq)^^!&menRM8t#mO+ilr|Idk%CF3rX_cg4tPo{`<|_KkIwO;+J6C z)a$!QL2D&0kuApn)LaRQO)|5ayqy8sG0!M%h?k{YM3XNOa=G5wE0jwuV2-q-Fa^ z(!K$d&;UkkaF6_?6$lswAMz@hn1>k?WxRM3%u3yvjF+wrUS=rTt~}CfavF=2xF34F zt{(${L@DhlF7MA;RC!g0R!bT)?2JH*#i!nB>6JO^2nPHkI)$3LpB1uF#|~4L!$$q6 z@88y~NaD!C5F5mNg=pH_wQJxZKxWj`9StNE-XRHzgNaa-QgPK8ez36MB&taa?*B#c zqb0e1+GtV-NLvgwiJB}s!!ItUuExZ5>$$Kb{RGvr?-L_YR>HR7nzomR*k>yk=_AnbR4 zK|ngD)RFAc#v*BJzuk;f6uEmh9sI%0-iJZBncdz{z}w9ILf4YGmAIrqtI1^Quj!As zJi+i2vhz1*%u`!-O6j%~*TKSUn|S>tFj>Pp7Z(@RmXng-wC^9V2ZL@VzKWjdlu3T2?u$2dG#$Z~( z+xA;iZ;~=Quyb%Bu~lquz>}3D$KBALH^-O@uW?Sr6 z@I19gx7z{Ax=iGYj|J{DL|ZwBb+p}nJ^aP+3E0m&Uov=UX=Fv#R6vF(D@TvyE2fW) z84RWCj}&sbk6jjm!%+y-%4^L`xmABK5;CThh&lXj2c}UI`ebD4CZ(r$&@b7vw&K$e zOaT98{pKdpZus51k>9y)bUw5(m4au-MjZ7-LYAQ<-&*VeJo~HamN%$Vpm z(N%3%6-Re)3=i)|t9>^k%h_Boe=ta;=gym2@v0?MoXnVtLHpR%ho$1DXM|iR zckg)F%R@HYbgc^$%E%l07%B!Xi%A(&N~c*BQhP`hez85Tu#$6zdoORm9|?t@OgOR`L@#XU2HXATxqXhR_zYfu)`)dmlH)x%`Fjo^3Hv zxPYEBw>eZxf4R%Fhj~q%xf4IsU(_4IvOwqVau1wiFqd$j$AF0i2gp7iZcbmmi9QZ) zpaL0l|86z_Eh&}vajTin-}l~A=S|GZI(w7f(iwCo8~!9aa76~!43~~3YXAu&2<;MK zMZmm5i5Q%B@^gb#D5V1xiuG|-r_q}zkKg4c+%rd)Et-k>`?FHf>qmc44lYo$$>CaciV^(XeibL`zKc<9D z_z!VTAZtTnfPHAxIrK~&4!Tj~7W0iBB5IDF%=go*!PIn$F{@aR%TPcdobECMK@L~J z^TQmVq_;DZR}ORh1BL{5P+9`h;J!caxO>aw`gRD%S%9rIL2WDfUQ^m0Gii#Ps|JK`t+smJ05KBR`*|^KFHfia*MP|Ekr>YPtdilsgK3{< zA|KLD8CfJOt;rpXsq{_>;^tT6M`*`OEX9~jPe}*#B3;VUf}4Fddxu%QNfd-0tlKW` zdD7-YfCd8~qhn&7a@Kq7>(m;N2Zg_0`X;4JOzJOvK4pBrcqgu?qkKeZO*CO$wd}>F zTygao@tkZ+VpY7q=7ksU`F&8%#v<5S&&>g2;GO!yrf|dQJP;gVpnbN4^V(3Jh*v)3 zMEW{_X)5D#?sJT7JmLhI>?dE8@;J89Q`>fED%L#!tSUneU4Q^u>b`4jgzRPMI88%b zd;6ceyLQ4SXaJ#9(L60EvQ;razUG%XJ|Le()Q5zYfB&*^ygMbF2mf6YjnC+JKr4(M zo&_tTOL^8#GmDmx;V8LB8}!U^m~-l&mS4M>3+OBNXIpa0)#=Wx|AsNwK4KGv{T>&@ zkSr77JvqI#_;j5VRk283$g}##5r5PX=5;d)0562u8*Chn`fYY~urZb}d|lvVCGPWT zf~AX|ZM5zhC@dcw;WXG|iH@(8hNa=_!pCNG@5aCb)>K{XVASt0{Rkoa(*$@3h7s*n z$~o_$!9%eW#wPEHj^Rrnmaw%^^hFS`OeKO5^n3lfmwe28d&B>p{_ z@+J{rMq1MoR|3A%T#A{6deuZLl87#Za`~o`tNW?+cZ^}uwW6tz-Vy>da>St{#`N{~Mj8xjT~ieK9ikbRqM^EdkWMCO<-EzzgXw7n=iEUw^B7yG`ZxN4e0b zJ1%h;3(R`#4HaRCmI3@)*|CPFN!2VrPH{ec`Ow@jDuiA1`Vjl!e@>n^TCd8OQ4r5j?^OlLpJxBge4Bb>m6FAlHVILLS3mb1wYH-GKq}44hze6^4*O= zQRV{y###jhmPVnJ)MC6#KjD-OwO478zfS_nRuqAp4Dah@#TU|O-vnHYkF3p?#|G|W zGmRahE`|bGO#s3>?^jE1SG6IZO3M3GoWe4ThU^Uw#aJq$nROcrg41 z1!k}Updf~;EK&k$=+1>$Dx96(yg6I_I>TkSF} zycpnYj0>$-fs0c^It{1qh+edxt}1e`avAUe|5{qJwk1KP1zgei)19?^|lSoDkn z-bULHE9aSO{_=C%%o@8)RODQYp}zG9B+!U0;TRS0d?e7=ep{ml!}a)CriSimoa-sf z&N{2UoUT1?POafhZvGEU%v2eMl5scbGCs%31MxnHVj7RQjxq%4@C}l`Z~Y_?)jWD3 z-W?F(c_Z>XU-)eFx6bu!fg_2D zF}Hh=Q0DbKqBhZJv&W&60hn5DzaaXb_EZkqUuG#@fcUv?u$o(vdb)v3HwayRYTnWZCX9979JvBf9UsDNvB z>K?W7kirK+WirUXScae5q>KOssS#5G+1!frPW@7k0;9SXKW`#a@sR|sGv6=tSW71I zy-)AQwD^5FaU|KjH3@#1LQR%Km@Qh28o_gs?G8D?6=AF_+4Rv_V_>z{U;;$E^+F3A zH66541W7F6^^qKk@N%WeAqy8Vb{emuY61Fa9x-owBf^Nj^eAuYVkI5kW&R)8>FC8Q z+ZS&pHxt~qUhC|<@2{MOrsd%L5ibtUDrkHpitBIK+yF!-oKAKVSZBK}x%KxR$pT84+S1z?b8< zPmF#xaWe4A;gppOb?T+h7FhXJShEe}yb&#N%#zF>w%VuAJt za_A#^b00fVQelA4k>n%q{n3%Ni@KiXo3TO%enp>?K%-&9sS1NJMFX3KlB1rc&tN~K zm;Kn0+ILe5C-11~u#p*+!_B=yn1MJrSo(?d&t$j2sz_MJKcM1R>&%1^&zxJkbSa0VM@PhZsoxGs5J_D|L zMyFx8RE+#@-y&`pekIV6U6>&e+1R68(66&-379m>=ZIxOT@+N+iP~YOUNeg>c|PF9Iz- zx#~Hh-7b9xFtVgV&fxZo)qk=_KlrJ{Jj<5d_#}IoDqE;AX2NcWK5hahb{Xd1fP5?t za;yc=eGXx7mC=VAb-FYyu*f9PY2r*g^hAUwyMT8n7>LMm*b=6i>>Bx|_b(dr>G3Sx zK&?mUbDXX+7`?xU^DO-s{KkW@P~n@f6Uc(}KX;yaU*@hOn1-F$!<&Oy6Ao#SYz^2# zdMkOF=dqZU&vR;FUZ?GSke|FO+eC8u5><6COzsQ=$*F901)i;_lM{Y&cpeT1hQ@DR z_CdY7{WKyP*~uD=4U*hR2*^+kIN{Cg8uPKk9`exRi!JRx;aq^lA2a+gOt_TU&s1w1 z?LX}oh=6Mb|4_>O^`TDk^QGd;w5SSR<2AzP9U~}(JCIm?E_RRBT6|LeWTrKfs~I`FJ0){?`Z(Y+7J{ppN1 zu-$L%C87@_t%>y%=%E-uXu~}t^ObDWs0;JyN3q9S9_gTDw;=-~S$x>tkn$<9>kkg$ z@~sMQ@jx_X+`vD18=3sY0%PHL9Vg9)N0nUO3D32F<6ru~{jRy!97K|Q*CG7<@f4TW z64D@gfvEfn!VUjX`_M&vqsvb|46dthu@9I88xbSAn%tC>^1x9PEz_8W3m?;r7EscK zKjgTsLItG8U;XUx*rF9sWIRG$<#pofzX-+&SYcM;#zJQJUqUZw{t-Wk)&HzlsRKRM zQL+R$lxP*j$L2p~Jd?{v6AXD~5vnFWrz;+Rb36*K+`4!5MD-297yAM%S8E2<0N>JUiv6Avm+WQi1e^Z!l`|sGhwiSkooVUB@@VR* zzj$9Fy3`nxP&g37{Y+^96x&yV1JdmdGaT6`DxObVEv^1q>CkuV8bp#=ouHYvB~m0^(2ED z;sj*b21wISkG~3T$?A!^_z9ka z9abivF{emd#{cX7Lyy4Q{Bzjc8zo0hlb%e&=ptmo0>5-69#90VgVAw8cqwhD?6x&mb-eNv!}Y>sA%N5vcMxKepLva8bxyO3xZLm$O%9 z;@x4jHmJE=ud7*NZLZylFrEGu1GPxN=eC<*`Nf1xofB&)fz|VqV_btR75oXkMppL| zj4}+J3+bUT9?3r?JWUOSZ=-*J>=8&Zu1_}WdN%9r6kJTL*qhrg2!Fy4aR6X(Wp-aO zW!STLImQHnnirzKftp>juT>p+a&D}BKkGU|8d3giEALm;-xk5@d;nhz*~o&3NXQS3 zH~>q@l#m7pkib-3KRwjFb1>a-u%VKIP|=h|B3de=MyZpu0sCXX*ocTGc0VKn7PV?R z$hrQVYHzD)gtF7hs?*sFBgvK{A|uoeOA>(yJmdcmh9%PfqFZZEry^SVQ?DxoRHwD? zCn5X)&j=1TLY5b-7GILoFG3$CzZSN>10Km;ZIfZi^jGCh`~2XN$d2h`d)aORpt-BA zId1$~;0H*ve&RlmnjJav>|r!pk)>r+<1y7Lb=(;YznEoWy*4^g<)UPh0Rw+`u!b3`sY-6K6w!zr&}>?%1z=>9w4sg6YiE`mZ1 zwiGq7j|%k^5gP+|g~R;yKMZEuMq9u+x%;=S5;_M@|BZRuI%vTtlHDJ^PFD82{6HME zG)Ppo4q#(!KSt?ihA`)fL0|haKf!ARw&<7h8kAveKYnw{tCz{oe?fSz!QuPdd5)&l z=n!B6!2_o8DvmOFCLU1FfP{-8MYiM#)04u9{opF==E6nc$vgUMVtS_0&IpwmlTj1j z-kcK)!fHDMG>B>r_3L56sDe^m6)v5!@o1#b6AtDhc;xL5cz}Pas_v>jG^aGoOXlm#oi8Ht}wrv4O5c}QC&|P1{7!GG5(Og}}R)=9WGndsbhi2+r1c@p< zz0dSP2DGnyB@|{&b_Wr5p`DR;x%PzLo%Uo1l*t!E@{onU=I3FwV6JY zp%WMhA~7sos zAV^A=Al>mFp5Oa^;Tv<$%$(V0@4ePu%cZnmY_fz+w%Uq!{I~O`zXU!m?SJ(PY4jFZ zF77%7P}3}HJ7?NaVF72j$BBTSKX^ZkvNO$3$gvIRK;>2hHD$Pm4D>aAzi#?ioWdAH zG5eT(_|mk84ToTG{c+$>Rt-z|wSrmj!{g&hRsYIL=eqTzy456MW1Nv!Yad&QPK-3@ z#Hf%q;`68!+Us6>Q(zR8(AeXO9N4mcqs(aM7gfP6A(lb5-itN4Gm>aEyoxVV{L$7bdUT41wuO1`KWOPkO?H{-`Bc3`;*#N zGs+f8Z#8uK>NqvURg|9l>%SXHgl!rCE>5)sNkEnLt|y0PzXde&FfWDX&d@)a(gsFWxd-(hCal?qhEF9>mv9D2wXfvoczIng~`T&U;9ZGWnn zItEw>zHKf}-FMl!+m~*KOn!9qEA|(V(y+mW=MwRnx773`F64~fOg*7& zN+uloa3{F&J5)ldul`LKwnA(r3;dT8+SLH>y@Q{&SiIM+7#$yuD@5mNME^a#I2^2G zeW>=UeyRNh)&=g}q%4U!V!Uvq7j2Ta}0gQ*^D)QC5@Oh_y0K3{!3XCR*}&B7Oy=P zd#jcOiv0RkfQ%lyexMJJvBH-w^@x`E8;sx4V$x+BP$+S*v$MVfrKf{hoFj~unw_)t z{ezDVGZGdkuWQ6B)_ski>2Z*&R%kXQw+LiDl@N+{(;@@ep|td6MjW#{xy-MZ@=_(E zh-!mBlP}b4E>61Q*wgH!dp%w5Cny4KlfMmucIG}k-;O$lRF=#g=+I{?1;1!7l&y|B zxQ46>s?yp0usVvb*DHLATe;P#uV+UGmWzk(&%ALs-Fn7A`Yl1HOezk(RwZgv7{y{{ z^Ra~^_+?9ja4+QYHvsxv_k9wpbT&26@@!C&`}chSqZ@@;Lq>!dm#y#&6_TMr@Y;fp zj`9z}z0!Vy*f6Iumq~f=R4!`}I&9>8^LF9Ooq(FO7T(S@`x2*$%YD8iB}xH`kJp5O ziXQ$O2Hv#fw>xnR^(d{>9k!=)8$v6I1r)V#2<|KhIB&Nbp-w^72|8y$h7l_;cS+dD z-tr=$A4{E(7Vfev$56@YALfgf`m%#cQfv2`aB`(;=*wfnMSqMPpgM>o)rQ(N#wlrD|VNhvAQrh1f;Utl2uz>Zw2!!W#!Ab2K< zQo8mKVa%1wEOfboD$*lc%9vlPvYo?EBS5*SDr90<0ftkutUk!i2br|0RWgEr9Pq`; zIj|Qk=mto8s8^1Pny@3%ymN}bY2#Fh=aM)6vP1D4^D$?BzSxf^BNQWe$ueQsy9e_M z8`y6o#E&`_bdH)w^++~G0~sKkTq7c8ilGEOs-zd%BGMZMEX4AzP+`C5eNZYS5}vP} z!j~&G8N?!6)IYiHJ>o$P=o|I*pCz!y#Ww>UY1lG7k}Rqiywj8#Gq-bS2arg1Y|I&{ zyd-g%Il#pt^Y_* zLON%RH!#2%Ip1ZG47GPqKvKkeEH6Y@%QfeAT${Z@b0k(s5c>pXC7i(~SafqHrlsRN ziv!d(fPmPJp(_R9(h)+o3@7eJEO>Hfg0Mj2%gS}_H^5GdkbNS;UkzhM2Nx`c@(07h zzayco_4ZUS=Nb~qQy$0gK)CjVs$omRk{rtMA;e(-H3D3d*b`mmT08hHo5;1lZHwJe zSpcZwQYD(F~UF3Yi8F-qz!Ts$o`jRx$t8430Z2`Tzz?Un2WjE`;V&r;435D3eZ z2xB<1M0gn!3K;B=11K??9yZ<0Ib5aMolAj%z6Yu}iv7kS<{U6#TE26@UXhTpP(~r% z?b((L>c@XxVF0dS^!gBybY&qRW*|kvey`9%dNTz^!`32P=xiIiuX%s8T)@7BOO$=c zvof8QtATI1netw!*8&yz-vr?Kh3w;qa4l)Da1?m$!+iEljfCfFlqo?togW;H0xf_YM`DP&jL%`UR+4Gj}=sWiwC@;|OaE4&AX=Q4Fp`ci# z8bTN7E$Ic+y)>}%ED%x+L7HfQ(gr`RDg@O`3`Vv8j2XDlhjb`~{P8N`Xd%f=_`$)i zEm^E5T{L$oz~Ua8j23?7qOF69HZtI>%6(J*$kvo8O;0&#C)QBCH%=XTWuDIz?suNv9X=-fJD0iP<0zqO-+xGb5Ni+4jv=wifT0@ zDp++I4Y*(vZKaKlAPQt5dD9u0R|1}^Spub)x0JmAb-R#H60Xo)wvfrvosTJ=0>Iy# zi0FzU(2I9JdfnfSHytshSEiF=kZ#8Am9Xmf;w+cQNiBPW3L>ElzAeLBDZbV()AzchoX9BK|{Zma;W zPZxf9#UB(3nyop1mSt)I=R9>*09&Eavd%@fOh*{jcGADnim#~X@c9?a?`wXz_pkNM zO}deuS;*Km5{0kCf_F|-dnUfUq<18h+?$H>{!d3-gh*b}n@W@KllHM*i)mP12}SqL zRBQqb%$rr8b>X%9S?%i|=l6#0d>J1~|7!EIRdqkvn#DAkX@u`T}i-B%p#6zsS{3P1?)B=mY|gN8cgN9U2r zzonvXx2Hkzb%C2=0TzR-Z*EpkD?T=}Q33zD0Ir%SJRl=9gfiSLJ>l&jc10kBM%W%o zg-q#%?ffH-QG-y+yfuFKxA!t=<=AI({3JJbS-gyxWR?i$E(sT=AyU0c!}u_?{k0MJ);I%0yG~DH z8lxW=2M+mH?XwnOF5Q~lLU8jlo1bzqZEVNfi`l{d5|KTYr~sxQOi$a!PBqHX_n+^i zc#1GV0sA&c{tRE5Nm73#D12YoF0Fl@v%X%qjTmi?JVupVSo7ckBWOu=w`H9*~q6y zGVHsCx302dJO~pCOhkkZB@f4Lt0XA`~nvRB2n9{ak$Ya-O@7iH4{ zd&=#8f6K6T&h3%71@)Z=SA@*%G<|fy|Mz*VO zhiMpz={2|!#ispprthtVotDa0?2(9g(xp?lVt*h+hxz6fVBtrVN^1eTb4^%#v8Kv- z;TNWj{*?9iotdQ08Um^J66T#(-bOJQe7{@eWlY?Zqg|&gPm&64BW0u_p%Ms@Q0#`o ze`}s4oxyy!10=kZGn-T4hgkx+CT=LX6fp< zQA>S2S|QL@4d*Tjw3i%X6N>ag_>8S1^+*8OJXzHb$EqkQ5M1oi$Q;M#v4xx0u>*(sX&&gr;!;D63G1snS8nW5!6zVWnm)oib znVrme>@LoFu%t0(EtOn}#A`83`ZIvmaNZ?=4mfg-q8|=|xj#Q~X_>m{YT(mlkGo_~ zQW$^xFzz&3lw;)MG(Iu0S+!D2=MRYa==&}c5S33^kT5bWL_tF#208DRv(E7WCmN*d z+FLlnb4FLqK_vzSH1K&UI?&q09gv~tdSc?y(wzG_uXFZt&GE9il`l@}U(4u)0FJ+N z`cbbct2|aD6ZzS3T!Vs4U9;y--ias6`)U?)H{}p-U z<0y%fk{y75%HM(ZwVkKY|J)F`w8ZQ~Uj}t6WFC z{dRX$?(K2r?L8|eEm6}qWjp}wfAJ1 z@_zp{a=I(kjqJ*|Cpj}!$Vr2?BD2m}$G~jX+zm*tZ{?V1{r0?!@?oZITa1uEUF4Ct ztsjZy!`gW|04DY}J4ey04#MSf@xbMC;_YA89dw}XHz=B1hD{+yU=zfEew{3S=!&y| z_kLsld2+94rqA_#T(5Lf8GkGTl?Re&>_j(Dp}@qNAfMJ7&FKV-c*bs^+q_K;Y92-8 z%>xXh!WCdENDdz-$`k*fGphUO@?Is~JYHnGhBSx_=wK(jCWFYRBF)6}XsJT_zO3EulAGT<&U$(I%p6QXyb zj~rY}mH*+azr>z~@k8Iv!equ4jkZW!229 zcWk7+1W8$M9%sB6IObEH-oeHuK-x{0j-D ziKMi1g7;RnaOjDFd^5otn*hyE*tQj$VAEGzGM8YcFCROKPX(QHMk?XeQ`ie>;es`# zt-c~`E^9z8YDwneNGKU(tG8P;Llc=I?DglwEDV_`K+QNVv6eR z4*dR6*+qVqJLQMUQFiZvx(5Da?Fs_m<1kiYV$0_uY_>u@>3*{2x%2DTXqH%BUv#}* zky_?o;Rjo)MM=$GLI;lRszIiJg}`y8;^00#>G_(bQ^%V+p6s`;2{tuLR91Ze4`%!4 z8H}jzY>}^w@nuXD&r8iuOOCaoo>hU^cuh0 zQ=xqLxAt`6)AK;teM7m@sdKpshb7`RDSAT`P0fL7E?A*Kn3$t)_+qjU#U71jLbWmg zVN?S15|%l1FT=`Gw=f%X9JkrbcRKLd3b=X1>?6@KB1VgQPZ1I%7|xN964=@l{PQel z-`d@ZVWffZUhu~XBx5KvVlZbOF=tyJ?+@mlW5*l>u0HL)4WYVW2|U_RA7h(nOZ%Bv z-B___w|bo!R!TG@rMt+S;L-M&qP@V;?z5H|{Hc~bzVyR*SJ1M0(D(86M}RCSrSqqt zv^CHVaT+@ob+~d?Pg)bE>9iu~E-vVz1c-XQ7Vp>YP@bQcYM)5vqB?m(``1D9BZ7bD zO|QtS!lnj)w(*LG&3s=6{T7sKBhL*W|ALf}(6Oz@Ha1x9aSYo~g`>GZk*z7Eu7reA z68tW!G+W%DmsR6B%uzo!-n8e52{Rd#;Fl83Dir25NIT=#k|g|Hj@7{7Gys7~zFzC( z2c9~D8Jj;4xO+?5`I|pNN=h^w=ieltI?(!ujg}x3hwlkBJBwfZQ`dwG9W+1iZX+m+=>6ZO2w1`zo4Rl;G}dkBNAf&o zx1*VKNxZi#?D1ZZYVL9m|K%Uf#CxFSeg9*=2W?GQP$Scn9csiP^lAz@F}P96 zDr}^fu)$74VJqtA>R<8@K_FeWs;kgrEYVZ`eHtLEeg7pr;Cw?|=zKo}IWC^mXy{zd zfAy!M|B`1k6i{K4nzD;*S8!yXiz*b-01iR^PgD%=NQ@xNSUBTxUN$!?p6Y(btX2^# zu0I<$s`DQvOng?G0&ZOV?9hp8Ch`)85f{@sSX&$vNk>(h+hv>^QkgUVntYd(H}g86 zOR;+^rHNcbSyDNvzAoL(wAlrp$L|zD0Ly39+uNM+#XhPhNUaeEs4YLkPt$fd)g<`Y zSa;j-;WL!QlnD~35VTu1WrjiPSRJj_UZjr|kP7~V;uRUekUq-tr(DHlk|Z`%xD44F-?=eda!)^D~i2uUWhOZL#9qZWIO|=AX8c z$6woXFn=PLug-(q--q7k~e0k^2#4yB&Xi5C==`m<3slFF=lC-%ORnl&xFUFJ; zHwI;fVD1_5fRopp3iW8JUS;{+C(|Wjk|yM^r0YkA4_!Iyjkb&EjC=-?#8TL7ZZr`D zuf@-O+dud+aY+RUH3=~C&2@~}{n=#xV6@0MgUs>nNDw3=^Lw>l`FPFBPC;Ylc#hGi z$xjwu*Q564!a+Y-9}|1Y%Xls&7cMz!AH+l=Bp4I2D$YI7SI^up{W&5_Z(3Z?&<$@D z<+TefC4f#Vu13pkk=-wxrDi5ELl}D;@>a&IrP2?+A6}Mg2zGys2euhs8>firNnrm# z?h*w-Xl_>(^Z)c3FNNW|w@e&Vl$E=9#we{WmPiqD6LyytrWD%uYIrT5!QmukIWN~% zb3{k8Vov5PWea!n2Ru&AVO?9-P82(sz6&^C($UeGlIdO3Qe0K6!$aa#+1QHy^7S7R zd%(ST?$JJr?-VYJj~GnLJ-4gnN$-u*%2R1#wo980LA0@zz&})Xr=|O=n#MB8q?z?%d%nCV;{&3ZSU@mcz&SX$DOL1?jd#}{P=YL-wRXsF zSS1Pwm$1(X&%)w^A41~V0W*;8V^V%I7$KmB(|E`de(o&jo~0q|-!MNV5&L2|tV^Mh zL|q7#q)r{%(Prt0w;4B{I{v+RZS2mTi>Vd@Yr6naGs#YR5uH9$Re&&XYEttfNqgbq zlfwUjSh|m@`J4_`R!6jeTwdDBFP)XS#koFl(9FjI&i^nekE6t?xJpqJZ9G@W!q6*&VmVuaR}!E#w^+pYo(0 zPaWN;8f3L_A>ZZ6(Q3U|CM21KxMuriXV-MC;Tl)8B=8&pWb<~%*hF)>vs|X0Dr{Qt z{kmxrK0)2-T?33DbP=troXO-YTur$xYg5fSN3GlN^YWFC%hI!Q?ZQdtk5<2o4*k~t zYjPjM8%gs;Br{h^Uvh|^-rsLurV`q<3#FXj0bi$VRK2UYKVorIjV>5_&}2;~P*XFg z9C}Fd_gJFn>!=PNB68D4lX05|-7UdI!*CBr3mE5K;@Lb-ul)0bEl-d~rBu02IMnxG z=nW&1A2c0Oo@@4_`$I(60Ay8BLx-V#(6`Jg5gIF#h9U0Y)cF}hu;LNN!Zinx4Toe~ zrOjbaR~XL9*&aubo^2K76An@d^OPU^+MvI zR53Y~Q=+g`C0qs}`~6i(qg6jkDd>i{u{8OE>C=Z}-a-_OLbP z1UlVq+J!&;u7>`m)UKZQrHNt_xjB}QZNqz3{@w|%*Q|Pfg1oGJf(_Uxq1mT=MwPY5 z}-?Ki1Rx#rmb^nby0KA*C> zIx@ZZQeX6--{m8Rs_zb8@pqtSqJUA)bvl%=&uxW$g@2iQ&<5v$w7F4I)^j#OIg$&r z?teS$kW#NI~Z^k4t@n9uls~vhVrks2PK^;olw~ zKYvSevqnQ`zq?7s%NfkGB`K2U2QmH^37eBQ^6R>8DPx(~XZq5r^uSIgsUVY4Mr1-~ zFin+$#`r$p?L}M^eD~?TmDj)-HuG2do9BC1{_@z-b2-qTkJDjp^I~*H7%uY{lVLhD z34|PiCkm9~-)*KNau^Mnb42u&!H)0yh6Wa}Aeb1kQ3mo{JaT561ZLb1l&MB!`$&mJ z3zkIoCqxHdA4XluIPx)yndduS(Mh5Ar!$cb0$j~9whIR7SLX)=)C7SAG|!tUJ?9)^ zbyz1MFI{GBZjVUk@U}o0Od=Dc@rnL&mPz~j?vXAwUUNZzz}#L;i;Gipx=SlJuS?NI zml3~t4$Mr_uTL^``N-DXEdN|Uz9_<&!|m25;pKIl z*8>OBcbQb|6cD%H%MUT7AQ3CbLgZjJPxf=#h*{Z_#|_CLnhukS#Wap3)QhGJI{y?v zl$HIfJnn#@S}Oov^>iASAeVJ1$&#o&^WPl22{*0?hXHEj?2F+1{4SuBkN0*_WiXoA zP`^-8AEg8iiBHmN_MaL953JV_w_BqF2M(*Ewq5oI$$4n3`ws(+C;! zDJV_00IP};H``=DW3_z-Hfy6i-)S{7cyf*ZrPA5;7G@R~_>&VnR_l7uB6h!D)GA?0 z9=c5I^0utFGdfAs7|U$ZN`3!ZY0?9xV6UkXH|-OTPGsqUn@2vm=A4U)?1Jv()XK+` zx*kM4Qf%B<0kRA-R;KL|MQUvZl&yJ@#LdgHw9u|KN*&oaH9S>B-FDzHP<`P<96$HH zVjakYlQwoia5K4iyt|kbx%jy!{&MFU{EyBK{V^&60y9l0(Q6DcgGPEUkJvj@eBRRY zSbRNX47Pe#p%H0t{Ko3fBK$kxpLf1$=e(dR^ZQ=UxzwU!Dx8B}hG|}U3sqTc&!>+o z4k-gzsE;k9TGffKxhdD0?3a&T;rm2r>9%mU+|SXoUs=b(zn|LkoGETlcBcu;U?`+( zjNaNS?80*uf6RnJF(#D?g`^fiJ3=#3zgJcqw)yxn#~8FO#-bWmP$ec2{zC>gC9e&# zy;9Bbe!F$#&B%aHKZk9z&@C!NDb-3-Lo{af#$tKIQuwqs8r)BoJrcONxmkKJwLjq& z8L)!lGj<4rmj*p$-)Zy4p&i7-=s3k%gpO{&W1DbL+cB}dYwxF@Z$yznNYuGRS2BRC zf2@G+%YFZO#l1F)wWG$&%ga07Q*$gl-0VE|?I+CjmF@Pt^X4agcv!WoE`*d47O21_ zw$h5bRbal~Rkp^H#PGTT1y2U(`;_s1q}(Vid|>YtEi*EtZ)72gA`W#@xy?mA=a^Y? zuUJQ3Q{7~Ieeqqq&6lP*zaxXSK)=0-Tr@N^KtFZHKI@h}FaFqLqv`yYp@8jCpaa{F z7)f>0{5~^5Q%yzPEckg`U_gdGW8<&s&<_~0vR1DoGPT;NxW-U51yAoc`Zx4aYO(w{ zyysEKFz>0iku8Z1K0`yVJ_#4?9JG6Ol4x3NDJXf10s_o_l@o_inaK9_AurE^g9z(v zY-}#e&8fV<_}N43k47_47rLuVLX3OPS|3%B80WGF0gzJ?TY6}p)EnG&_GWEt)LD{Y z23Er4JIWIkt&CgtwoIUita`azqIUa*l2Z6SO&1=4o!horOK*^Li_Ke@$0j@3gmN^$ z#vs0lkcaz(kY)fvukZMP-G%mF4x@%4N{ zpBo(f7xI|K@Up&OcHeL$e#aej)R&X~RlA|VK^`JiQ}u_5BGXF=!^sio{mD2%6{$C; z2L@_c*bam9U;#i0Ya&|$3o992RL)AA zU$zKfNvdMuUXk_KllOKtGX+73N@&j*yZ8T+0nBDcOIj6s74kVqtn=f&g6tetJ<*c( z{0>`JiY`cWbNj0N4=tm3l%n21SUU@(@}p^j>SfL~>L5|mivJeJZ`qQliIOOYuSJH( z=WtHeZEqk1^+CP0x^M|7!0FFT%nr`&0pBg80c@F%bt;WIq2}#?x?5e8DIx*DTN#ky zb}&KbQYyf6;ORw~O9Kgo^k`3^c!xF6vLRc}>=#1qIJJ7gY}X%)#wMl~S^oaPcG}Pc zN{O1_jo|M*Bvq%sAx{FtIAle^Eui1t2l#hF2u1fT)70z*=j4 z8N&>BqdjH-*PPPy{^_8`s&!jtG&B}nPvXrFHi%%VnoNuR95&Fj499G8oC&9w!5Ofc zV$j4{*@j4+Tz)KQ3_YHhY6P;F?lf{l`&V%ICDHj$ndc^azQpT0629!5CpV%O+yR7# z;c@aM6Lm&%DYUt*EV!*Ty}Y$2l#5~V!A+Y^$p@w za+2$^DllIe9g4HR^}xn_OIy+%2LSeba~@14jdK^3za`lkq4B7ZF} zz3LT{9b1U`*OzNU@%6uBchSv@!+Z9?CzpVhk;B&RtBoCiizkCJ^v}hQRf#L*|$WMV`8KO(1Uro2f6ql+sT$j)oU z@A@fC)knB7Z6p2tR@Z;k8oFmbANOGX)~nu4H8`BJ&M|dL-9Ym+WD^P98WCwny+Un| zdF1=5)c}2#g_8vwgvR*uuz?P;*Y$j7Xya*SBg_UH1&dvgF=GWS_#y17wf*cgn?3>$A-X3X+8OHZDUc%>;4 z?XmcNy9qN-yKBY=B{)1HQPZt|>dGxGf3fBlhy65z>r#d+{?k z`jfZp*fl7?;*pt|Dk@gWWw*;$fC36c0J|UGxXY*X=0AFbiuvPdA3#|6#ZhI}zM0!8 z=6#OnDX*UyiG8x4u=Z77DH+ewORDt`5rVmWpO%qJk*w?!jZjQGB@Oi)9gYm4q&`Vt zb^!7)+9&W_E*}+uJb^gr&9!96|8g#{m#%y(6q4LqLLeJ3T)$iBFEQ3W8yy)f=*JQ+WWqd0^ zoytEd^`6s5t$oI!9H3Wtvd(GO&}C*JugB9N=ReR!3MpStE9P&++*1Gp0a0|ZL_A+W zs39NaX2KOmU+sT$DCi8pCmQMbWLG9IYNFssDf(&3{>Qrz z%0n*Fe-n2Ww$y@B_PG&T;3QK4t?^rgvt1XW+@jr-&EoISkDI^KF}4d~tP>1NWJ0Jk zr$ImFWXW$Exoa2=ykUwN{gDph;~-r$n(5&&A9JdhIK_Z53@!2`CR9BlWB zZ{fm;XIJ8^&z@^S;NyP2RHRqR<_fUnys*%EbL9NfoJRvy+)sRxRbVdAIKV(fkq|7@ zOpug>&|pgGBZuK|59){=p(wr?-hpSEI6(pm;b1PCT+mgo42L8~<}WfRf`G1j6F6pb z?^jmrz9YswiV1zrmvi$^qet{#H;M_p;rQuBZxnPI(H00iIt1r4Tp~JxmEtb`nct@WCdOQmu#7zv@f>^)|7^Zz<{UN;?Q7oGl zHdN^%sifDOESW;j?3=1xT9oQE?=>ekU7KKZSMh15?we@yV1Qkwj0xB8D2J)~m=~Q& zQfYhX$UifXasnb?245Dz!?q7Qza>TZ%#N8k>mU-_n46O@CkN!U$r`vB(yzCXW_6ix0A|5e7$kC&}?wDVl{ zTC{g2p&PM}$uzT|u7br_SZ*8-8sq`FI^I)QrjJEkTr!zH7!gD)pSEHu;>1nL{GiPB zC$_Qhy(-mz+PxcLm0$;Ov;B0l|2b`_ZjIDSrHN>DDPayEbP?UZYoiSF@hePTP%anS z)gP;A6HIx_jIG_UR#{(?11-)d1YZQ$)^C8COKlpQ-ewP*F=W3l(`NFVWpzyzU081I z+~8&3ghXzYIwbI<+LB&P2cF4wc2*St233dcr6I9zKP8Frm;%&YE|LOeXG;mrero|a zHWGw-i>bJpKGPWv{>s<^ACYV0d{-s&kQQJ5@0`}8u&zQ`$G{6mkl=apZr|#Sj781f zaZNNCos+Saf&DywFtPS^b7OEk;$p{ScSm%h&FH+6pM`J(GeiBU(dY5HiL(EARV0Y2 zA@HcV`gd1Dz`s>tA9KtvBx-9sFu0&7RHl*VBy}lFU})%y=;GV_)4rxPZR|5A^9&7Y z6Yf)SO(XVP3dm^$d?G`HYaeD__e0H;wMbTF0GobmQ6YhGWRMGwz|Er!!WfyOVQkA~ zB-Yv3GdX)W4`~@O*2z>g0J{6su6!_1CBnK&C#y;^DEgN=d`g?qD3vny7ke!oEE;UG> zmxC;VnOLulXd65JAlq`h@Gh$GZnMj3J%ZpyWvqZoNA|13uxoC>&Ivzb;#^cenqWwO zn1~cDpmK04=^airl%olVjgLpYMeOrcK%-{fRzuL$<$mLpB%+Tdb=+D(+9oYdsDBxK zR&IbzFk)Sg!3O+T;kd_Yrvt^Bod#<%>NN-H8OUpfCiAIqH*O!pSvg^dqjFI53up^avk*Dz zZ<{QUO(dSu0>>(zmKLQuSAXUv&lPr3h{-PqMaUiO_R{Mrh)W6f^fIyiBE_BYZfx1p zvC=lLj)S|!dvj7v^epbmb3F{>{yQAjpLYsql#f%&^%?0ieJd8y_zd;qG6_F%d7rK$6C_MB>>ga- zyqLqO?ZkGOmkkGPaA7xeo8dGiAghl=g5{`2K-$(6BM@F*3GVSGPq ziXZST>VMpHQV(nNHGe^cEhwpc`@ZV;_D-aYG#wCUfw?O?>6!4@eg(j7kdtiLc%*@@ z)17sq)6Y`OXw<4gIY=}X)f5nH-%mSpuT0b15hj>FP|rit)K;kgbU?7W*;t~Gxv z0O;lQ(J_)tx+~wAzS72#Ew`!dB?l~I0QK}EYyyC=r_zlN?h62TYxjSKyJ2nse-I{r z-ZD(Ks$O$zK1T#T`@E;Lj)4MbIuDNwf##cOyW(nc?I)tr*giQn81N9PRJc}{eFn-r zfsTUz04+T$0llSw9UGg2`j^H`6*)~XQFK^Oop4zLullzrNN8i|D?4u0XZWc^M;H8a zPwC?Kms>V2o!h~W7&x3w!!ig)&|J!oP?!Y2i&MVtj~z5@8Z=RmD)?o+4O<9;Fz8-DT5jejZj$mrT_?Tfi5F3D@g3twty@M|bTfv}BOU z6I>e~39tr{wkgHVD&Dy8Ff^OoR8XrsZ;?B{G- z!>d2mG107>uOIun4YByx8OB7$<5(Ao8Oym1KiVFA3&Dz`(m&?wUN?nIs3_k+hLpJx z_-UYiIlJP%;l|FRBVO&oQ~g;7v2d<$$_2xP^m?)gOXQC`+y!-9=nyFw`(6-OCYp7B zRfFrb=iCq51eR%`vgd+OIReb&2zM+79z-$^$yRpoqcPa`vEOfFg)-P)Gozt4&{e2t zjNI}TI|>yNo``bVq8QtY8tlOcEWD5!?ae`aCP2J?55>JiQ?j?b1uhBxzQ(*vLYn($ zQl7N81mWSAcgx3MRqIc^*$N4}8waES$zx~1HVFX4VMVS>)Jtbay_zdn^b!moy;)qP z@!UTSrS4-DN>#Q>^BYhnOM?KDPMsl?gDr;oSL7#uy4ruv4ton;F+o%EquNNWua~=s zq*|;46&p6+2+@X0wjar`VUmqd`;X@jy-fbye^v84h3Ejgq+k8{=|(xjl+SZ!;^zXSg$2gN(QVD>Mcwt2p$pTJB>i3{d@-0*wP?o9{ypoWNB%T`+q|QX(x+J z15>~&8Ic4vk`>v(e+*7hPyO;hJ|zQ&KeG&>|Jb!t9`K>g+R%D9)CeoH;FUe4kdP5_ zj=w_roE<}PSE=rhCsY&}1s}}P5*S^BKa4Gd!PV_4mZSdkq;u)DJPtJf$hfqg~& zd-ZbjseaWr=I6P-~O!1`l@Js8LI2)Z+-G}w9|R{ z`Jq6jw?@U4`aYhVl`oC#z^$$?$H-XxG2QW|)Aq`CZTl#`Z#`)Jd`0JUstAQ11}1Gl zQAScnnI6U9XG5s2zTxTVCWmU2!|Omc5eVAw);}^Cw2y6p|86)ye!ZUQp{cYw8Fao0 z-YW$TAV2bH;_1{mZ_$jg@!ff(lc4@%q`i|)!I$O-*A71;92aU=YYe;ZLUH0KGqC4> zW=fPhT!W5w(mF+SEVwfACQG>;j+OJZm}2Aqm`5Qiz8x2_v;4(m47wQIh*AxgI_hJP zjC=cIi1FWyev(S}&@xvfl#lD1;=>Vd;yWa)bV^`z#=yvp zaPz;u+zm#*8@S?~P%dx9aQTJ5WE%h2tM+_l&6!Rzw%Z3Oi1EkQcNs}=;b@e*vj1Oldl_F5B{dMC^>LqR|EITZ z@C4ryKWc>OiQA&jcr-A=e#9;v+%AoW#P?>{@V^7 zKwl^$|9d$g`_u){{y{zG7B;FGGz@Z;?E((H6i(jdejRQbeS2azZI<`f<;%g|0D8GI z4OXlDN#50Xu@nu$CwMlO4Jchd4fp-%q2p^I8%7v#3}NroH0gA$j1#VxyLqH%t?DEEPFCRuCIQIBEbI37;uv`nFudznve@fo?d1jRezm0t_*?HPaLzctF2k55P~$fD6XRxb3-|AT;-Xh}$jsOhVD(;E&=4Kk6^)>rw}@F5oDHx3`&QYNTULciqi6RH*?5Rtwv z2Etw!eA0O_F@?rYO$!JNvi*5YRW`2If_p@Ur)!>6`NqWP$!Qz01D!$}6*L}YPTtB! zYwMg+w7Ap_apNKM{-R&+Zd90DqitbMRidk*uRvzQv2wVkpH-T{WZfONyHI!qJf@BO zf0ukRa%M1;yu_nsOHCakGxK>fe9ZYFvgb;{lnHxAikz3>xJ3pt+FpgB))s{bGc>=s z&z-bo7j}V*qwBo7N;4H@ToxfRa;5y#^WVcry7t9SZvgD`aD+A2uCP=_+eTJ5vce!F zkhVD}sH!`-4g5MwJ0rP}`&E>&h1mea{Zv@LV+=(s_IyatTOJ$8IG-npF~++kl`#Q& zv9LO5u?AD`zbZy3quJbgyw7MWKtP{mU}kgca*N)T&CN_&k3(CX^6Bm&(7&jZQ`5%T zbrB5dmAEWe!H6;xc&T#p-wu!Z`zs8=huI{^#70La6cEErugtb?OHoQ&nA~)AW1d^A zr7%~l9w2Wu_y5F%`j{pk4KHSb(Z**u?hK{FNh#>mk*6HI_?k63IXTJ3`jg*XS=fa^ z87dAGuKt+1HbB`Y3RSLaC+XtB0*2V8$&)M6B6BAPbMKs&dB1YyvqfbXjD!q>sJCab z;JkZd;tpX1sRvB0PqcTwg@MnJBX36(MeYc@hptFMxI>EnB;;BDP1ONA4akoiz!yMh zH8S~8=UWso8gD=1{)e*AlY9Z0ytR>a%25lH;|w;q19cgh$U zT_6Ns`7a4`_8YodQi@`Tf=jM{5nwNVWE8L0lc+AM>EZvSc1yQhhT0FLhWOg<ogEW5Q5|&) zVG-y4vzlYgAdluE_}m>vYx$HUvpTK3?Dk{*1e^KO|7C#$6d||TFHe;{`4}Q@Q2+o3 zxYDhgzLkT&7MdI7X^!gjzG&|2Li!aHvzpzan{ob7KtEcIGw@!ooq?W~fNlQbOJHRU z*=JDm@nUu6G+r>Fx(k8=XTAeOBan%&@qg_qq4_G5_)TJmeqPh+F*$u@^#$#$D0W<_ zjIKetK>XcsGdyhcvfZypXnLpNr339yoaaw|N?v(n$B1&bi}(6JXbkzqFkE&24SYYc z{1%H8oPLT(fJpvQ7+vD5df%MC*csZSV6`SjJ1Kvs@D0w~Z>0L(D--c}nu_sxqvFL9 z&DquKI?yhcE10$0=LGKIeDzv_sHxZ*g=tX4jM^&&X$s%0}C2W3wA0rNjk+4ki=xTl(6@q>VZ z9a3lS%BI(G+vkI;23_z`9G0LsV>xD%7a0RA$2(DXS3+rstsD;KC z*6AKYOH&ilifz#E3yJ0``2Y5iH12f2duKL{^|bBX;9p`k{WjI6rp#x@)JG70BS6jg zh?_}*p=RQ|(=*5X2h0E2ehN)N&I2|LaH;&S8Yl4>i#VAGstLqP5vV=sDTd zD4a`WC9@EQlx`=t#vjY(ue7`F!IsgM5HSSh7PR@UDY_5>l za=m!Kd+}+u9ow2X%CG`7W-UsXk7Wb#N+szc*=Pum02f)UMtCJ$4tF8-aL)ejg! z0C|(n_pPOS6Ly+C0A7dHBEPq3%sHn30%d3LPDe0~&`swrw|SyijZ>PAi=8c}bc3a2g4sUefG_{Hp-N-@tf)aoLDUC{$nVr`mHgGamm5KUALL#r$`K)K+Al;8-}u) zH&l`&A{!jQR-j_8vA5cFxrX%?g`^acRuRTuaKkZ$P~J_t=Z1Ch=CbV0@UlyG0GMH+ zyD6Cs`SP=INH)F}73&U0h!j&thGhnFEyCu^)_1M1yK}*Dm+L)u&k6Yfn~k-(Pp6hD zFSi7FFDmT9kNJi#n-sNwyreDxje^g@si>3WcIg1TV%S)!u4N|CSix$|gQeqBxGt-# z9RYrm>{+O}WJAfr*v{<+8qdohhQf+NiQ`vE zd|c=unwh^>{%b8N1UMyh&0^L#97|si_B!q$=>Cy0hr*8G_g(;t!Prb#n`^;vP}=9D zFTv>U+=l6pKmM?zFbO3RMflV7Pg+QZbzZFDp1Oh$ap$K+hsBO=3%&Di$A{tSx$sy0 z34YKW;&%ChH*>wOLywl~nFTsuuC|nA*N$vJSdO^ma-^=A&VlnhOa^-hq#b*mNn-O%FxDq_rFBtsjq*vB=ggDHF)m)JYXg*djLYohA13;^z#$W!I z<>@`Q>d+@qrxcy_7Af+jF72zZYMjt$I+neOt>6i?=;$}PCp&XrwP)Av2CGQt!CV&$ z@<)xsMSb#jFLz}*C>D+Tc6du9$pW-xwoW?yN{9O3yGVvp|J@>a{D`Re|0GB_8MDTD zaJO-uEcm{jl`#VYxnPD<(b=*S(W@_gY2ig)KwBzR0OY^<{Ayac@rR>w#*|7=i)Fpj z_-rM99?aNVFkooOcyN){)0NuN)gqF(ps`~dHfTe7kj{^U$CYU&8Z{>a`A0!^;CcO~ z`7u1DUwv-AMxO{FG;ontibs@T{$luLv-8_OkiupIb|U_}?FfH*U(kZWlHEa?B%01U zg191hceTAsS6K7*#Lo>ficr;o#4?(!82<&9$Z6B62Ty}*HxPohK57yR3IPD^?4ee$ zy!zl;HMszqv6fm$>imtC_p81>rmqgf!cpAN2JSx zMEuJv9$bAkkJqxCjqYG&7m}A3k20OZtixNhHC|s9B7x6f}5VAjI9_=c(TEhJY@NigV4eo+ANMaCX4^H$OPen`BnHs>lAW<{v_Hlq5vBGN>y~p&#XH12Y z4aZCOX8uiiZfV6V0r1Rzm2@NpPe>YFXk;`>&}gq70nXb+Q^nnd0G49r_En} z#JUF4vS1{%)QOX1fo4)~do73Sq~wLNJa7A;?p*mU*l1Q89LrBAvuKbvE}0^R#G0V$ ziWD%5s)37m2PHXRTifmNbhMm%dPl(hxXzp)9azNgW4+gmUaikICc(s{1^^p46uQed z?^{RkA3xYoeG}nSG8yAN$HJku2!RQS#C$`70T1GP0#!YV4u`k|exJL6Y|I;Z=!3Vr zeDCf;uKg)viDL*ZES?PeNhlz1Rb`>mZvpDbAyhV)E`(r_eh_#(X!fsa_WHXTobiH( z1?neKbqV=TX5~L6qHX|P)xi>&4@^gD{jV$6y$*&?d%>XsE+zsyLoQT)7D`O%V`6HY zJKO~w)Xb82OI#<0@~E`zfPoHzh-Sa|ClE+8NUZ5i4TcaUygnV+Kk|-MXchND=KDDB zc}SR%u3*8Ei5m;dfkm=90~70oF}eg&VWP6AZL@#=j6JYn765llAesc(ha;}dP?S{}F3SHYDNzF_)->{o zXD1OWtuiYf!LpM%XS=?43rU%m^OH=F(}qdQ!))eOpEjnpg_d6LF{S}7C@CY8P4ctN z^VY+?<*!2*s5J{l8d()u2N4G@f758QcdUSoNw;Lu9(bW7sRh zrfPOWl4^p*zZ-+*r69gxRh>~210dw=!}`yt@Ks4@ZPk;_Wk`C@1&Pq@>Uz-wVwBsJXGFD| zaxu>3+_vdIEEYl{|LCZtWUg^Xj|wv-WljRqzJLF&ni``t{(g&EQ*!U<(lKQFHhc{j zz8s3l@Q;Ti4vz(EpF_V^p#Sk7ODZEyWg4^gO;q9q8~k=xdc~3qk{XciDC!)#Eq3@q{37ULS_k4ZQ4bGDJL3Z(WWoJk8c>VdKFATwPj$4KZq9>} zjixeSO!uhszOk{aw8;NzN)vgIm`uxTr32x7$M9r`vd}x3R^Y2ep=9{i(s0G7@2!W{ z%I^0!1_U6gjE+7dht5d*pk8yBxl~*zZNvzAW0sbzN7~aVh+rk&72lh-wWdeGId`#sE3k*pB- z7d~HRk7%INy&mKy?KXc!A#6&5%A5m;DsVSM_h`@#*1owvm?#%A=#j$cI4 zfC!W|G*Q8}gIdtEvMJKDXmpX|TMYahtEi`pHRQ$p5SP^Zje1D@Plvaj^X<{amzEUn zguzsHe;SQ1L3<=7WGZHm}ga+z3?s1~Gpj z-G&pQEE1_nKaJG18PHMSdbafhG;jFllH-}JDr9<_Z-^tK*IakWT!-H{n`u>ksHLS$ z3T@VVbMsLmA>X|gI{#?O=w6xrFqO5HO}OmwZFK}5$BZl(iVY!yV@i{~x<37!Fw0hy z<4g^S3N*w=S`&op5^RgCr5c)s{LZRbDY4?d;5nkli+bi**HWyR%jnU9bp{<3g>E}%( z(B6VIj@W2CrO(J6BMK4v3VJ{VwIx5G)*w)Jz=Dzw=%cg^uAoM=I^Jv1xf*RJ+Adr}|+^9J7pnoXp@8-k|vBWgN{O#P*Z&?WdTrn|K#FGLo#@~_X zyL2bE;$Pg%q|kZ5zh672f0FcC;dVUK)OT;P))Bgz7$uVHR*y(lOEWl*jvw79m*uWtU zYCAjEfVu}lDUI}>b{%ei8zH~BLo9i}#k};#>|b?p8^-XG@J+xRk+f%lWcqw0J>{7?bq&(OsNCgAX-*w5Dq9A8n`Avip8tb@RbbC$!P#`)pDR{;>mNCc*2b6o6JqU$e z**jt34CESShWvji7e(EN3=X-G@_<}^y&%b9FNqFnzUyc~l7FtCSuIwXu(Y$F?@od@ z5Yg$G3oJ37aOn^rjQOI0a!uP<+zoD<7Yu!GmMnW8wg$ID}X$g$_pPo&|>e+ zWZ5Mtl|a-}LaoMm1N6{nS*8HB>>Rc0Hl4PNRsv>a{ep_D3Jb6hrZ-hQ7R|&R@0Suw zB-5>bwuAV&=yZV{f&PpLfkk~{l(mU8AhVnMV?+9vv+GZ^%=FMRAY^BKzVn~g;KZNi z>VmTRgYHohBBx@I(a+}-t{?Amf#EkT2VPjsH)6k!xd<%Z0U;6l z?G8H~csKEn$!o%gN7IHsvfrreyVlCmvjAdg#RKnVBHeMxaFht3U{~$~An6X(L3ykp zO2SVo#pQLpWWbr~%@|zEXq@!jGZIg6v5oEG(kmXm6DXc7fmb2x*_jvGcw0dg?}t^6 z4cxWgHh}d6*ymWMelyosGfnQl@+wi=4}6)606xia=KHWF*`yjmX9)INzK>Gzm5WDP z!yq>b@vpHxpmYY9DAW~JIFq62xWGE;i^F;7yzr^v1wPEyhXT)uN64P=dtn%F`#Ro! zbk62G#romZ_%TClx_I0n$V^iu5RxM?t5oO_b{g%!(HW=L^$s|fPpt~lA*ej!0B=_t zKo}4jG9KPa0TKq%awojjl1#_@h}Z2AkpTRY{s>`e6(4_41g(cR;qAD<5l!#~P?WPq%PNkeg`DATQUYfq4Bmst(I~3QAL4U; zMtn;kSb+V!+ekK`5|pY&_Jk#Js~;getOP7b!M6y?$QtpYUtr?T z6oN<3^%ubU3g^A)t5oAzA~R+t8rn)Pi!N{c?Ev zS{Cpaqox+riv_ANi>3j7jUqi2NIN-f%+;EJ%kb|CuKaw z4CYnMTRsNQ{hy~4LVgcC1fUwhH+9~tSZv~yvw!JnguVjSc-#SaR=pdEa>AL3HL@_T zpZO}eSoAvVvl(jt#v85@k+$*oW(j$-zHXIQCIB8l!!ZQTa7E%}{V3E(AjDuothE*) zfr{}vPF{qykQo=o0=tY)vf8wg8oQy4vZy0`W2F-s+Hn+lx!5OLHpDen4LidY;nGC_ z@`#LB`bzO_BSlJO-;A|o2$;9f1-VJNfO$);^LjB>+;dZd+4QGzqN!8ofxKR~QpjI5 z9%sl2M}s@Li9YgE)6$CC9zUQBypMFHs7lcB*E*WusI+d3G@Fes0k}=9AyKO21gqqq zAP`sw2Z$8{clj+?p&tLKuv2~~Y#2iRPue?}5O>)pPXaRlsfdUcFY<=UKrPHhm4z{k zo}6n4ST6b?K7pt62FxGJa&IEygrsvGfL^2mBq3mN^bugUa7M=_ zadJd@#HNgwaQ*$D0-p_l$%~|bQQUu>YT&|(e93HhvW)I;8plbbHW5gs0|jE(rli)5 z+$5bn2_G+O-YOXc#m-}*C0@8`DTp|>q#khfEZ{aHF|T{y#CL6ik%|zT%(Roy|Ko~@ zU19O`Z_lD6s{y%&_zzMtEqVj6>dzyt;xZP&+K8}%h20pm#-DJz@@-KA*LY)^N-~4t z{J|ZzozZ3c@d}zj!158kOP*)Fg?+OFd*P&lfo*_x8Sv0l;^xYX{id}-r1{&8CVNu3 zT|Rv74P{7aUG|=uBH+15N|}1A9s9eTyp|G|4izc6gJM0php3-WFi-;ez|+{$<+z;c)xa%$?*d_%WKLDdG+pBn(XJEEy7c#c2P-a2oXer6(S524ovOw^x(<+g04L z%?JQ_rs@>5L0P6OK`|^cC^hIzlwD)S(&P4K;HgC51IB?`co-{*4YdLpAKaV}Yl5;^ z5&vjQ$8wp&j(nbxf(NDk5eMF@k72q@3#lYnpu@c$4MP!@TaEJn2Qb(q|FTbW!H75m zAZK&N(hL@Y>}CFvO;d@3MZYN@lKh8(o$t3le8iW(;9+-ZJz3C&Sp;Zo^g*_A-L9 zV61Myw1|JEvO~h%CD_`=vpuhf*-(qyr1Gak4q59OODn*W{lTgXm|x2ObR}yz$`Ws` zg~tLE>?FW_V&L&_yXVrP2KwFr^zO7w)^sihncu(nI)4@ z(?0e$xiS~)B;qf6SfAfO#E+!~O-p7!G0>$Z3%_md$dkInT5sr-uj+>0_r5M=X^=1( zEV81CgIv!)?LN<6R99gFyfIgS1cjqL~IZ-fs>i6yU=xhz-{`K=ook7YxTdS>~{iEryBPU82K%i9rx3NMb8&vXmOVw|6_b!+W_+d5{k^6Jc-aCTc z+s@b8+m}DR{-+eLC+r6NFRd9|2j6k(!2)m$c4ydHB z9G{Ah^Ph5WpI2V*yI=1LOGTbu1xr{ek}9TK?@|xd&uP9R9XvB3BOn5DZO~vdhFC(^ zIy^c$VY|J>Z}!=nysOZ_h@zOl)Bkz}Fcm#&Y_U%U&Qh6_?#sPjwP_9gR57uZJ9ygz z=M*_YFK)uc6SkR|VEVgds1)_F2Em1Jj&C60AxSZ^57Vg9>e^mc_te3J!p5mlYN#VE zij8g;2Xn24LP&cmF@Rho3xFavTyEEwO&_yZa1Vn}`o`~L;nDJ^Kt{-Y-_cr?fz5=I z{|F_oWR8V>-rAH$GNyM}k`zABimazJ6eB;}Qg-)F1pJqh&?;Ib$qKNZkkx9;(xTzV z8njRz`+US5LhCeDLt6T*SC~G-e+%(kfO23 zvfhu{1XM9``4<^y8@OA@MKJ|+_0;JXqq`SLG%`cf`7wvy-dPE198%8C49fMHUhz!P zjObce$*|2`k}5zlg;?Q!Uf@Qp+ebmw_<h{5Pq8G&W=$fR+qm;^Bum5VQxp0 zFdcAOvy_fkzW-cX!&GW2c5asReOlLOB^#F5(!_0t=IpD(5d_<`^!CsMa zP|K;kXizYNVI6HPC(p|03dxkiGOMNE;DXM3Z z4S*OzMeA`Z(DTfrLn-lAOBb2~JsL5r=Ww5OD8PQQFw|{WR$L|VO}Sq#czhf9j1Wv4 zj{RTZ1N9o_BvK=&KPSU9$$9wh|_`0m2bF79E8xKlVl!{@?EkdkB3DtrPi zTu|}~Q{MHB;W1z}l0$AZn=Lt9#~sxH1bK0_p%h$ZnUlFKG-ZQC=eMFGme*WT3y2u8 zNPs9u0pr~Ta&>!AVDt|smz)j0zLv=(ZA`EM8v0y3c3?E%sJj-toJ%@+!>~eV z<$e~==Tk;1i;{>>$cA~S2dl>s@^8O>A#)jUYmy$s^SwC=%DFoO_)(3w&sWP!jz*6^ zU-|6wfrPKaUZ&skk>I_@1b!J;sXaIR8smxH@^Y`et*~}@UtN0#)*!)4U)XNl?M(Es zTrhFd33tPABnqq;8ZwPGQTa8}l(K28`+!Et4_h*KH9)R-n zEmz~d3HA0t;ItP&rre*ni(ID(ocb7_=Ahnw_nTLWq4)p#6CcxVCF^Il>76(Pm6IFg zz2_YRd#FrE!~qQ_6l4(_IB(`0;0lHkRmEd*7|EsF7 zNwZjLi8D}gcjwLN`Z?3-4?ZMwH{c^vH~~+Af2pvxcnSFgsdpE^E_X<61uujJV!%=p zPiPccfVUY;2f&BorXyWaTNfN3+^D#H@+Wf<8`O|Gah@GE5nUkSn(2iVI;_bt%Rwmi z--hn!SDl8dl8`N%Ux$PB*%u)SDt~agoSlD)jWQT%8Oni- zhC-6|y*l8pQ6xqS6sSOGMH2KCRJo#4lBz6fg%c@+hoQyloIZ+)HG$QbYR)4{m%dE| zl+2^i&-1sh^RLfF{%Uy+6cAJ@)|S0oGH*-g?}jf?fpE`OT*H`I+J#@$`9b%gz)~r*Il+>GCt4*Uzd?2h?ia za~0`nN~GBT2ntlGN{I3Vk0OX+sX;7|raqghE@KaVFWHZ_;}ghdA=A|#^pN9Te^Din z41+3ynb`tbc3)@LfC-j;<7CT+mWBa7g+zQT?!|9_dKEIE3}>`*;)7Ul#wYRL`NW~R z%Zjn}$^y)U#iNpootcUV0jEo@pa3dnyW!_Y100|NGz|XdYR}gV)&Sk~W8vdrbmPD3x5Xt1F z`s;?D0eRI~P*dOfeQfHlw)UT74F%Fck;ouWaE2&kYhlLUM->G}Vl3kjg;R?%O_QIA z!2O(}tCk@I6r6o`+wR%{kP28QrV`q>K?4Oh(}EIN&ok>5Smiw8T|;=bQfGg;D%^Acgbe5f6SB#IL#c*& z=z;H>;!(0o(O+@ZaEdUx{p?(_P^XC>o~Tv`=jg?&5P!;;173-P>LwGFiB~ zc@^Q_dGx(La)A9WixAKh=$W_*D&pi$=V^`4!qQEK6x#GhFs3mY84@_Snc}~r@rszM zJ4($Y)IDrrPW;xW-@LtMk4aqjD!-5d0+|6QpR81GCn#8UjwRk*Ti#=!jdOAvgu2A_ zh!{3+7Q^D;XCQ)ak2)j>soE4BFL57ntt`fOs7;@4>F6#h0hjtKeODuHCPWCQ#)MD; z7jnbqDjZaej-`^nEPEO3v;1J%smd6M9t1wEjBSjOM!s-5D8gh>`$Z#;qLy6Y>@ zIa$97FVOiKixnwd434K5+#vHf{^NVweQUD4pJd5ywAKDoF2nHnH5Pt@oIG&P24)KJ zq+?GQj~p+1FW*;-{DArNDJ%l3)BN_-aIr)E!XgQq6KBO88R658-M){$)BVh_s`R@1 zuV;Wk5~Y7{C*WMG$J&8&dlKw~VFD@QvH1)*>oKx?|M)7+;bQnKs#kN++^)=+ z={$5p$N@Zhm`Ic#mS7#`TG zMtHKD3Y~W*Bzfw`BM@Z&!1LA`Bs1S;Zp_ zi#H9Q0gA-J7+L@dEKq$8)p`?`H%o6zWO}{XH(`+wB>5w|tc;yioCrI(1fFv`5rQO9 zWNJsGXRyidA{SD@oaMG9n$PcgWc?J@dw0lAeTo^ErXpE7JiP}j?GMcOr!zzXc7v1% zW+ZE9iA{r3e_(|h{>fcPuBcveG6}vkN2nE@waO$X70oqU__DGt@9w+)y7{2946{{O zBN6D#M~m>(=#ozpUKUKWX@uYP71JU%qk$Ue9wusXOvWBRL@Uxa^4PC6?o}MOdqkt- zZ7i#N=?O?sd%dnDTjfb@9Lrp&+2dWCx^k=kG~}%0-0W3JAUe2@Oq~Cx-nMp+$@gaN z-*A4w2_p59v40f9Dp1$El$f5w1%KBv>Po8a!Rjouzy$oY>w`2*2N}HRU`C&pVPO@> zjb-yCIh=&}3QUIj73ySdB2;1C+a)nmg)X=-h}s(;7|rhxJIj+I8_b7pTt|k>216F& z&{Xwx7PxTVKTSmhNE}gLlLw>_g^8MT`h&U{PC|OA4pmi!G?{4o*AZZ`P|TAx#Ddeq ztS(q6o>nnEWWgK!lcQukEbq)H<6|gV(8}8Q31v$P11wiHyh2flpI1ddS1cWPVpv`D zvfbIm3Z<|1TPD!z-mv%I?ezILHp0v8wY8W`1QlMpa*-b9gdtcaJFQ$%<#&Ej- z0^va9Hp=L8hbi6Va`Tsu0>fGfD}2h=V%l)5FN_521N%=GLd_Cb{CE2_t4Nh_=+Rq$ z-p{xHG)wT;`9wA02R+Raa#M50|v;cB1U*&N49ro|C#`C?e!}F5JJ*FwFhss); z6BFG8<+=?464UPMLA^{iktNJJK@vunEZ^lvs~}G98fX0>^x_U`FIUoYiM#&M)cnel zz=QylH0r8PCVpEHvJq31qEqD08?_6x$}}3yCuhN!{=pQZxkzFXe1v>K9Nxw9u-XqM zF)t`zPE>5w3%rrU&gd60q-I~+`G0fi1Z(-G6p&$xf9t|b`20KG5x&y1-%45nL`yiJ zstXUujruPZZ3X#y8XY;!+mmn4KM4O9O#XY03ACd@^^+~w38VnrG4@!Halu_XM#oOn zXFsc`GP>ry7S-Bc9;2~(iwfcrl>h?!L4AmA*~8INqvyzpU!koN2am6fr$q*}QSdc6x5(ITM_Nj1+F?y*vwPtats(_*V5Byvr9%qJr z#=x9yvx?79B@*R7&b|WZ6{^U3hYDTH=`J6^Z_3Gm#f>N`KTPRAJJ@6lCEnFwg@F2unAd26znSC4KXC}U%5_o6pVXlqC~6xQqfGpPBBB3myfynpltxxT zEvT&z0X^%{y??1g%O!<=hI&WAX?amC06`b-NpiKW9Rk&6GL;uT5!VOD>WJkNy85+) z&&puKeM}vD#9Su+N40L-ntn1&{|^}FASe5!kv5exEoVuoFXBOp2*I>tqOfXI8%%vA z@H0y)(H+3Hd?6{M4JL?F21<~C?+aJ-YMj_sy_W*LH18u)i%IM4bGalx8cPqEG_{T2*H-7q^b33G{VEd|IzO}2s?G0hOJdW@s;-k$eHkmba`5YdkyIX( zJR2c0E)}{zcFf`TKe{{Lz7rVC0F?oL@d%zfKN{N>MUZAyY0E}VJKO7_t+Bf{+G#}Y zPFj1ZTA;`0H!{8hTj_o$%FOAmFo3jIio?dQyxzgF``G=3=?TBnG+RaVLF_6VAQi`C zXOp;;0eD>7!JE1^%_(F70YcO~({(({_wVN`Jynfq47;vd1cu1jE(b}2pE+<^AP}r5 zN*BxpGlC?XmjSB$Z!EW#E3@4FZGtcRgJsI3m$`R8%acc(Dw0HlgJQhyp$8|P+cq%z zp%7IzwIjb#;N*|=-f(n1o_O{I@gzko4ihBh^%%taMpNE*T@q9Tt16!M!;2Ag6k@h! z*ecqDK)Skyn(|Xfuw7b0m!W%n1L)MUUY^q!DMv(JWz& z!v@RE?LLTL^t9bZej9N3>$z*u9>#(2$pkBBz%|h*mUp{TT_UlNmqW}3I+gB@+UL??zj!vJaMt~yrDZ%b z+=;O5mYyzp^B@ChQv_|Ikeg z25JD4Al~V2jgwn5r*B$><%rQ_03;D5A#otLt%9!a7Bb=f29_gl$9=T5I-#Y3iO#$Y zXQ%pjn=*>>CWS{})7|B-r~F+|_a;zShxB@k8vL2z6(S=x`zI3FjPF~@k0cjE$*-%e z8#~&w(LN-t2qv2DqX`q-JE-$uK6Jpvdn2kiuRzNgimY_ef}cDf~4= zTAnDN6x5t9sw-O4B+xP&S_lF`{lj&;unNs6GMz)FmztBB#TssyE_bN6z0LD{8F+l+ z-Iwg$_xGeJ308&22!+N)`|=dztF<8F9UZ5}@tcY#e2RRlRowW@b|kC=c{*BBggUa& z3@C7rFmx6zys^+1HH<7JP`X6{QB3VBeC}`Q=ong8J~&{cPoG^BrYfc{D7cV|W=vIv zWrwGSW~fOkyh8K#2V?OQ?l&_u*NhEW&YxJUJd0 zm0(;uc94~e@%qmHe%IHFY24L1wN?OM1>gOg3HbWEpa$!rLrqqkSNR>?$S?$NFsIH> z`ki1M2z^rBjit1IBW+KeiIhiUe8~<0``u|FN2kg2C6SUoIk*Y#P&GBBh{dU*aG>6L zgw*Z_4Syw9M97i0sS6$fAxsThMQ5>6(Wh9MITDWfBpT}2_8KH~ok(~B#%)Vw|JQ)m z;*($D7lz_y452vmYKIW>7&y z3O(*Am|j0AarKDMDx!wdz$3`4?8HH+zuXOKgJS!Z8<+UyY_NA))&Oa9v$K=sK08nq zKlIC$M9i461%lAE!5K_F>wW?RY0^);92MamSU!75iu4u;ZVJS=QHHn?%XOOFzI*Il zn4K4r#}?g`giFTcVJ?XE82Vbc;yGXSl2MvMlhpwsGl^u>k-SZ9;`J~=U%W7bbFMEc zng*JeJQHr2-w9LtHatX(i2KDy2m26S+ta2r`AJP>4AR@>^&7%z;_KESOj2fC5>{x= zL8Sf0>5Z==Vg|8p8@@25KZZD4PD9@OB9!Yfb>8ia=2co*^B9ur*6bec6|ns!xc$X` zOrY)Y1E8vkJe9px8CPiYaUG1?+mcAl^6Y*9s8%Pmka_1A{U8ist7-8McWiek#keC0 zYyOX9m_6Npe{)U|?q93q@#8DbRZpN3p1(LcPYf#%ynnw)5?XgWhVx{@eWpvbsB)%e zw~Z&h+q;hpCqakl>{J>+^yR7+Ih^$7HhKN!Z*}V$wjh!?be{*u;!AZf1~R-Wh4cBk z8SGPI|6@!#J-nf(tBKF&`QAXpP9GHK1a{_)q{Y6qFSXAhP%i_wMi0F&+Z#HYPuk~D z!tu_W`|LQ(gz)+asFFCFj%Rx>=pl&ETfqW%GI@^7al&_pz1WJGz6*rK>VPN_nx8tP8yjAieMyopaSA8hH(2FX6XTWbz5 z`=x*X*M7L_@1%K7&dK;U)(}iL3GkVi`RCO^hX`at&PiX?CzrdAc2-c5L1bISxE0^O z)7AY_ZgVj7^iWK<`0Hv6tSzT(tKWXYLe&tl2X@4yI5m=)40Hd={$Q;%>!b{l_- z4zYWN_E$zCfDs{sEVv-P?&~VXl`zDFc5-9@z_StqLDbX7d(vH9i^-xhZ@VM@Fc+ZL zj7C4k5PGJ2w{`3qQ>_5;&xcrFv^W)7>4ENJA>LZ}pa^kc(zfF7Aqr zFof%FEhWT^BjXqg5ufT9jPFKsG5YMW3EO9*M=1RG@nRY4YOq>1P;-lhi0rK-FV~~X zm4FN;oz2kdK62r9IDtK$@}V#rks`o&*PqvF2jxiRBoG443r!cjN( zuuvnNEE0dl8i46`QqcHa_PM>Ok>8>rWLEDecxh&HxO!O8n$vcG`j%%x2_T*siY!Nz z4@tqV7#ku>QAsoCYdez;!DF{u=&4Cc4#88czc;$bjYL}Q35y%f@%Acr@-o52{yA>( zB&Q)uNUy?N`7Wb(kn_4y2**Mu;WCl(VZtgwJCI)je`^K%@Uy?L_9!I&kTD*{An1Dx zx;`+>72>&VT|NKo>pclhUW;`9lsXyDZtehN=p!y=iex8Bar zqMHTqKroJk8$m3pLp*Dy2*V=1-^2v093pSXqKFl>^%HvAUbco&*ZswXorlOm`TP6# z;-8@6ick6Y_>935H{JN%U?Iw|Nw58ofVoKIkh{<+Vi`_a<+w*+vNPV*9le61jlP6wtS2pB$_%X0| z>a&tK(vT885wkJJpLFJtV;&J(v21a#cc69C2;+^YNB7336yR6k&E0j6+ zHbc0;2*%h`g2u7bgYA1pj$)Nu!M_O~;QEZH5d{e5ks0- zn4ugP2g3WBo>krEroub5qLUnm2$f!9%iWo z1UBPUZbWu3o?SwCKGhW=M`#?=Nj&EzUfV54Mz$W*VX4`ws>!dPm06Tevpg=nD}Qvl zip1$sFZDr(m{VPXh@TZ)&kpPo+9Kt4uyxiSi z?u8V=l<>CH4Psi1<2jO5e$$4dNG~eGRQ~E68?X%1zgTaZFE|u*yo(r*T)6yry4rm^ z5O!v!9EpBY>2s#hf4Ed#Y%0C6UUCkvR=exEzF)37aHmZT_fk&(9&fIj(u<>QWd}?u zZip)WK1Hv&X;;Bu%ZqFzecz9g7O?Pg*PdyNVX>&qOla1L(c?WI7Wuu?&@qQjg|sHA zDLB^v(Hxnum9v_o_Nws9P?_G0zYD?4k!QZFYX;?cIhW)97^14elG`ezT+Es4mn+v- z<6sdi6W|zf4e#W)nB0-K)=Va7{uRe+=FMVn(MZB_;=*+N;Rs-&9Qs_^70YZ5qzi!& zu<%-Vg0CC(M<}UdyjvWc_EzWL`R6_7cT9U_wj6G8<5tVuawTKb{)ACd$Ql zzGA)xzZOveW+Ml0fYfFUnVIOcOd);%M3UJaV)VGYK*_uV0u33%^F674S3IAuw{eF* zg8C6PwLPd1v?Pfn=hgNBs}0hG1-s?KfZrd3o8Hv&#eD8L=&a}17yJAlhx0aG;^tVd z@UoD>IlVJ)tlVBuY`D{%OKy-8A6f<$DEjar+LYc%H;W6MuDu9}dT!W-(|(fOL4VPT zk`?DK???Cuc8IZny!`J&NbyEhwQ`-HWp^Ub4>Gv?JFe8&q>EFi^{M&mCIw)L$XJT| z`Ii+(PZEv6bhPsnh_a`NgTJSV(MM6+?gPF;m~PPdi4h={PfqY^A|sazU_BO;1&b@n ziPl6J0N%=RnXuFO)-a7s{02K4=2i?!5Ym6|V5ye&m;J%l;#Cw%1eP5POvSh+2)h2r z47HcVxR*@SX>Q30X6UW`dQ7BBL=;I`AezMsm1@7uAMOsEd&7vvOHpYF{*?AVge@sB zxnB?2{*H%r<#LmL+HB_uATzlY-P2^;VL$9lQ?Nd-6QO4Py2G30nT@Vc$79LT$O|t- zu|*xu^tntv#(PY)ql*idtK7td>3||>(e%hE8qV@hqP2_1Q=#}X)Q`$zU;ZzaFIzcA&5l#CUU!sS$ma@Z0UZ_T z4ha+l|6>s+;vUwMDgO;R{c`�r=slQHgq0%uwUBoyf&xoX6v=v&*efAf2xC5Mbv| z;pQl4?-J(snAISXE z*mp(2-J%}f^~d!(KTrH~b5xQZl42pqb(@^n8zXrNi!OTHtW&aZix$_A1;SojlRTYaA9BZ}F#y)K+RWHN(WQzmr*lnF##DT|_Q>me{%OQIm z>2QHptPaC?T{pUmZq&R2f-vJY*Y03_$Z zS4)w2Ppkyo$m@J#8OlOoW4@COYjiB6tvwV1JPc!I-xJs$FOMzMk?31ZZ$JDNj`|;- z&M`i&sO#HloJ?%nwr!)aZQHidI8B;NY&(t7#uGHQt;Xmx_x(KY`#ry8&e@rD_E~%V zuWN`y3H?OCf|&nHl1{7nyBCZ@=2sGZB@-P86aCPlZisvSKcOs^H6}lF>3{ne*W#=` zJrIqDeTV;fOD|`uEDirm@c%B#L3bG=$ieqeOj94J^1@Sa4GIzjUuF^>%RL(wNzYA# zu)&ymG{t=);o53buByXPE^BswDwGOBOBRd!D?PfU*A7|yBf4`o;qb%YRY^>r>!K96 z;w-IM`n4J?)$F+fV{3mFj%(rmD%Hpxu3>z9eet?LIh9C|;;vd=aw$smIsn5pTFqPg z6L3rG#W40^ZOs<)FsEEU;h}N3-s14QL(So-@pRE&OD|Cl$(9ftMZbtS^x zX`bt#58sKlo#-*wLMlC!THmC)c}FI9HwZodja(;rO(-By&xnFh)71aqfSCLT{dhz- zqFo*ASN)#Lxe*qN=-T2A#<%9I3PyYmo6w-c^<|02BeLhB0?lU)SLF;oaIwjg=5hk!DI7GT3xkv-TMu|9JI=e%+QsIhmBF94AAyUyKq~TqA zf8)Uj9oMvO%KRCtglMT^wiBnK$w;+~PsVBN1A8tYWV-g73bBCZ>@L@N+Zf|-s8hE_ zkB2XQLEfxyjU|Vb>}4=4nDav>+T>fbJubm)kO<%ea8K=IteiE?u%${}YpMYhmAYuo zi7Yg`d17Y0EkeK?9?wVSz>0LbehTT{v3U-pjGtn3zZDp%isnXUCl1kWXrh7BqNLe4 zyY+CFB+m>EkdQHhug%p%NShqXx|^tW2PgqgHB#nsE_oIn%VyW)lI1o3g*j}3dq;#W z?K%S4Jq7>#7rGONdH0YB3@A2hQW{HSs)n6e-2<$d`)b-ck9Pq{PW${7@sUGM#8XJ5 zH3KJ*hNUZ+C|>sjzH8TqTuxt!uYJ;ZioxktoJl&i*~lQ@n|IZbjvoyK1UIi^@zum) z^b(6~klhkmHDQtUVB60g8I8OLc^HGb1|u0; zVA7Y>(EdIPhH!pwoRC~XLFwHEL;WJXnC_Eo4F{tWM`Bw4iAo3e>VGU)c%nB>T|2}Q zES^?`$@vQMh9@Ejh9}YLxZQo%$srs{e;~o!c6k{kqHyx$OEb0+81P-s%~kqN4&cIi zCM2jGcvKs;vVKa$Yrd%=`Amv`H?uBr!E!M{aT(r8LA>)Fk;exd*1F(#9w3^`OB#7K} zZ8MS6GR%Bxw%LhYH!PhQmT{$c7Xlr8dLGUdujwMcNJ{gHE}qCx!j5{j{m~PWt*hTi zyHWS*^Hf}c^^QTLFPOGgc8@g0KeqOcgd^p4}Z8oqE zGaUT>a%Xi8Tp7aInQUv~k8}h7jRSI$Gd1E1{yGC#&^PE{~-9HmUR$v*S!3XEcV5`#Od6uGjXjFITQgZ))sHHdi zdm&!&c#vluUeN3u-H>3)y9A&UQw}gxLBT9jLR{=f^Ex~y2T_e-wK)8fKEvjB zs&l9t>>E>}NR1ghF|zT4{CPTzW)BX6L$x-0IxT`7g3Uf+ zdiWssrO$^K>PtJWy_5-w_6b|~xY&Z3bm{~dRw4~mw6p$q6P?}-nfSBSw!|03u47$r zjBO~cWU-QnR<$IKQN_)U0$a?aRGMW(1)NTAy4l=qrp>D)&c=M*{BO{y{C17%KL{UB& zciMt}71`4|l~c{>DYfGOjt=%C56$~DUVJg9-L60V!sA4{gA?;Uq#>+bSbsjJ{M2nX zw2n{$dg%8wS044ToFNkj4}27#aDnjFUjz#JI_Q-7@_+`*0Bx&h7=kLHo=!Vjz0ohX zEg2oJLgwO{MLdzQqqgUWXtMfT`jQ+pB{-U^V5kGJH-X>8t%B1k*lM`=Myn#(`S}x9YdrbCEmzLcCTqa68d zG=p{HR3?3?sX$HvSUBN$I;#CUKii>b-F$7+Ft1tdJx};Z z)jt26AVIE6mu|iAyqKz`v#52u*X9eT>#1G%X`}tE+z1dmlYcGL>M?=o7Up7bNTtZ+ zek#y!FVfFQ9yd>EMv)8)-g1IfW)bxet%><$vBC3NcEx|o5GW>#9BixMI$Vldxt6@g z_^lbTZH|14JFWO@bEcH7LSAnQM^}5tXwi2w;*q8KTLW&d->0S*5c8e5HRx7#8gOdc zr`=BC-=0_r^9Tc7zMhP7pXMTc{%Kpwr=a?<9szjZ_8?g0%oLiYeNGz}z@6{T?1@1m1aY0A3=u z{cgsQc@!Lj+Rw|kT<=LP>=hKo|GhJPg2DecpDzz@$2Rjq``QiIn98K~D&Gp5sORJc z9=-}uT&TQxvrH);W3}5x@V4&5trO@o}~WQUnn~ zaPi~C{zl#=;e!arWOYJ+6Soz`tD;4if<-3mrka#mOpWBRN<1d*KYt1yIa#N-XyjEN zn8nq^4`$QdNE0dfUQD#a{8b})yM$endpW zCNx4(SJR!v!9`tn>xLJl{JK`?^JpBRyiomGE!q8kv?^5q4uPUm!XJ7fjVb7a9?b(^ zB9Os3v{zK@PW6g}`5|Tcc0p$+_qRl`WhefLwz?@h7Z*qaqLuZPaXM4i_2do@yO~zA zv=$w%V#n{Bb1c~&$L)W^lfLc^qIDQ9s})Q$HrV?!zzP0T2Jg>52fL&v)prlbtrL7` z)36IRX|rPp6r3`Q&~X>s(O8LOu~@L@j}yAiscF*D@QHYt%hS*npxwTljP%q{+RJ4y zY|2lNTh&s^{*7k87?#o0?<|Cb+h*3mp7A!bWLw_U@!WUbYX??@ou{!5m87!%yn&Cy zQQ~b{PdJeZ3j3zh3aK4I`0SVRJ=TlYVhf*Q6F4ds>EU={s6U|VF1&P~8u3du374mx zoTxqO+_^h$BhDXd8&}kT5rsERn!RgS*_9EU%6oPY2isDEm^R&+x&NnW+h$DpauzFr zBg)cV`{j#axut+B%;(dPjQynfE%Vyht(8~X0k&K9l%e-NV#_q9o5dvBm#jDP-i)r? z8%Cn@mkSw@grw0fyXA-GTqHo_VFpu&qadx0rX1k=&)zcQ6*YzS9<4F@qJUsfCz`2bQ-nOoY>y4qE4`GQRV$sQ3_Lm4L zHWQ*Y$CmoF4w6#YK%MWGbGT$e7%XQAH9T`fLM*B5CalMIu;a5J?Uv^4k4z?Rx{Me{;w^Q6?TANcTpO#^sw@)8L zlv$vS_^|1eko=1^ap9X-Q4gV9Dt%857!X+Q%MrYh)*WMhQvq#fuZ|+uI}*|UogV5P zjuu+P!^0ffN$_xke^YXl&aX=IE_!l_tL#;)mYha zz4fh3u$&)yn1k=Y4KiLyuLKzTsFk+mc){t!izE5j-jKnpyZ;Qg;=)wlBKYSo*)vsF zXY%tMlBeBiI}NmCs6UNoua9aI5A@~B2d#FHc`E0slrlmDz&Ju-r71X9+tPCV{iz|_ zfW=~Nal91~T~0=!CpnG3)~f43BDR1vf^NfG=ic1OggehMU_=Wt3c$=DH>;)0hEPaZ zNvx}f7#6bs0+1B?m-W_GNo2Il2`;6O7x5asEiRO%ot<%MxOXtI`9-uAQkXDgc-Ds7&g_*5K&l|fH5&1hyhI79Dn{m3*yRMNZ+=qeSuoRo3Xb$|)u|^zH14ZT&qI(`MGZwK-SomX7H90F*;ug@hggliVEKO=XY%DRHq zH((#e%1n#u!B}nPDFuWH8Z;3F-SApROW@rc)R7YJ0-TL`9d2|EP{PsUQCza;;QkO{ z%aad%pBnU8fgW-QHO}&5_Fkjjouxv9rCS0M@GDEn@y}=oV)a&l1C8Dq(bYEG1wSK1 z57}EHa^>}9cvpz9rI$tqQOp{4mOXCZeg1At2+E{EoziR7_%q)L>k~usC1VaYlOs|7 z^DoVz!-lA$nuz{k`zZjeK2fI4QmMc)=5TE3wZ-lXV@d^#Y&^DZndz z0?BRNYazZx`1m5q{Ne z*Gf&Q<{f~&W-F(a!XCD^R_5a}ZY@b?hN`GU3xUG=m4Nc^1%4@{mY|nUex5!M3k3_0 z$>U|j4XrI#Y&nvV7a`m2e1zzpT?12m7S8`p5P?VP=j8N9{P>N^c(DUEzcfPx1sb(T z3QbR+weMwNcWClBEjJObhqpLkiq0Wh!|fgQk)>td-w( zPZoz_=+AQMRvmGks$^)b$OVE8g_hCd#`Yl{FnQ<%+M_{s8MYJ-k*u)^a$LI!=K?3W z5qiU)+OLkJS5`^&Vmm(9Tf&^eT3fy4Wwn+w8k{%kz7tpcWJX`q(fv!Ar?f*W*R@yW zu(2BwH|U$PM|0%34x-ibZJ7ZE@KhWMFpmC}I=hpB?K!G~{KL}(TiX0EDOg%DTWVOu z(&E+GvlM-2>kD`ce^<^2*T%-tQ6V}>0JTLKeDg5k+ELeK zm!1c=yB<@dl0cU~Nzz5%D!w+9n%fF|L0!c~6<5G4)4L>P$i>>k1LWJ8cMlnhv__Ky zDf&)%f%lv|F#ke!gl~@STwdq7i1J4);@$s$ldsAcz3r(#vULnH@cD`mH|<~I|9Be) z1s8l|6MQsZMXS^BBU_e#(qQV@csC@hoG`CYX2&UC4+1s-8XMk#T7nJs3?*&=7i)X( z>_1~`SuqR);EfF%{e;yY6Z`6#WyLR2*PT`%UhA|IL*l0g287dWkCO$`pshr@)kr1*zgOwyZ5d(b&fpdC7f`nD0@jd>usqRin4o?zOB^dJ9GGScB9FN z)+AwrWsT#n@T$9jcpNO4jueN$FEwQu`;AmXJVN@s_h7qLJajmmWT5_b&TMl$TLJU5 zO-)}Uutj?Uh{Ps2%|by*AP;DTqO$`Dw6R4&4r58*4;{&lv(A!P-U1|m5|&9$`Ep!x zxJDfu-7N#gm=i*X%LVbQgOISk7IeZ%XYtG1y}lo#qS_$&vN0&m*Fd z90JD+ezM~XE0f3p580gZyKtR7^5X^5_8uYaou7wAQJP9iuOmRg0K z=4+GeWahV#MZv8#%SFW$89OQPQRVxw_zRbw0|>*+*_&@`f=Q7lyQrKz@^|>m3R}u1 z-)EcCLVIzsY}z3XAzS`VWE6Q;cP3M2PzZJpEa$76sv0sLX>c_C@T3oSXCv(nKx*{i z$9tEyK*7@LG;*KF{G2BEI}6hvuGgYIzw$k3dC3cknD&WINEN}@<69Yx`qj^;EjZFZ z*N+V!o*7|$P67C)@}{U>M`JIl0zc0=(mzxLEWuAb+sNu>Cc)-*Yxd{`t%=FNX1ntt z2?f4Q7$hUh8Rky$MVV6zVz9XzVMp3EWtb+u$fsmsx*}&$?qmhY?+Xi3QTl77Kut z410v$E+=_0JyAf)Km_TEi^itBfyhdM`;3dVTV6RmTQ;gS$3Nnp-pYa$0z)OXn_(H| zdp~B|?jN9lPys5?f^=Xt+0TFu)&s=lmHg!Nv~9QJQ;+38%gcHn2RlE=zr(?xv2Agc zX(|^KDtOg1ntJ@uH|B5Y?$%~7T3rh~eQi55ABsT<2RQJDxJe7#^}-?;I>6HB6(4#} z+Z~!W+kugb*@UBeHH?f7hj&YL)0mUIERK#ib&*cQm4XP>@{AzC=q4r%Nr;fhMPoN9 zRvMlarb_laIBcHMvHTN4py~SW0_`F=r*kb)^|@F8{!Ro0nNSSQvcmBX2_Ke}KM}bE z8h`dOezJ|`S+m!PelwH7fE)v~O8xy5*MQZ29*lr93Ax{ky8c)PQ#buuNpAN37#SpJ z{9zW<4LRycw#bL4x(eMi{ksde=fWu9?Ym6^i|&$Cwq&H3THpaydy2}rk*LKs5SP*}Az7Wbx|+ZOhp86X#rEG6)ELOmvu6+sa%o|>mdMotz=$`zq-}0X zI);=4dLU))eC{4+s+8Axw3sn#S(C&TUGaswz5XS}&M*bU zZlgWBpQ9`idps$r-?!(CUN@Z#{6#=kfIctJQH(&2MdWkb5n(SG2F{L?9v~QNgsTI< z1@4d2Y+aL|;VqC;)JO&>9uM6D8+kBd37MdM7;f`1^lD|H)0|DeWVOjumnrxaOH5?P zhgi$)VJF8M;zY7(5RU)noecif&|h-5Mn*D_{2tMhyE1{!Wb$RQFr%FO=E81T90YS7yG_=wA<1wLC0lgn+uyGzj^gS zqMpdZJ$#Sh4HrCdfZom*c)RkdZ>_bM!_;W{Y>3h|TM`k84U{0UM+6QtQ{fP=WQezL z*w!`kTKo}#67zHx<-_F^$g3E-`dbELnJ&kUmcdAV3i*CwJ9>kW)-C6dA`2G>YZ90u zu?li{J;k301uu(~pvT3j-La;}{tDb_^w8Kt&Z&c9s8mh9Gk7xHi(cX`Zhv~vs|`e1w5tV(K^ zW7q6Pu!lKZ8QLEKyd@Jxk*6^o$Q80Cfqv%yvJFjBNGg|>_WFReB9C;2bk zHlGUA?3l1m*qo$j1#?JrQZdN5#_+62PJ4ix5)HbRsG$|K)uhhYlbcft?l{;tJ{yu0 z`%)T`7m(i8{Cn-7o24*QZ>oU32x@g4t4Pw3I5pk(be<4+QOPVu4CJo+HBdi%k~T~U zW)jE|WiL~CXSI3d?sZ_K@CF($7IAkUj71>1AG=rojr*7GAR*^0LN1Fq=dJpDEi+yh z&JsU<_v2|B^_%~ih}KIT)d~2ryx>53toVAH^aA{ZFaYlKY_3p_0b21Tu*>YO&*U@2 zFz7IV+(c}yq#Gn}Q;|6}|N7c3Dvw|sH;OtZEuNyblFEJc8YkT17@a9Jf$$o>speUJ zcO)a;|AG8u-0e=8!_7iSQ};V)E|5fXu0*EHKk`WYOJv${mAP}y#KzQjW2Kv+RpT90 z?V>quJ51eY#=X?Cj_hXTtkFO3^DJ-8d?K!BxLDWUty|<YU;b|PC(w0$*fO-09dyBDFw$>LG&t`r9> z+`jjpF`rc%$5KJ`J!ee`F9|hv&*?JMl7b0PFVheB4VB-os>{tD4+a1gFj3@%h=)qfqh_&!~LY5Z)rsf-J?0Xz#g#q zDTQNF%#cRR(3FDJNrd8wADr<{10%H5yEMqpK)-7=Zbtudps`UnoB?@sJCb4tva>*6 zlKwdH`Xx96)*LW$>*0TjoGZKdFDL_Q$k`vkHV<+va1n@ApKHcyaOrO5cIwVG1zOqT zUc{S0TOxPf{0w1Cao>RvN*BZio_YsU_vlX;GtT55rk8UOozvaBp#J+7a;I99CUI8g z>?s1yEoKQ4p%XitA=}IrE@3^o!?=A{?U3B8sw$P^;z?|LNA8-9(_29+c*!RTJo=RY z6at*_z|3J^hs+9szYg%KQzwpZRj32m%f>ZTJK?6N^I$8=)JZ71eh0JI#i+lsmJaGx zy5CQA+PGKL1?*+__st1g%sg&*_ckUQ~GJzo?7s{J8|=!IM@PI@4(t|1g2!qv%_M8`*;2o6Vj0wZZW0zvCyF zhbT67V^}pz(B{FAfUi=T1Gw+V@raFAS;|}6&|$3PEl4y*EYn-!r?;xeu@M)b0Lwz` zSQ$9r-tiW0JCzuhfFl7?O7gkDry<}OlD0ia$}=1Y>Dd3Um1+hJ1pT&SVxbVYLvxo( zq*_c+nW^=oR~T#qMx)ze5r;q&Ghbx9Wj%dre?LKj8iZkhh->#ao&jflcH~ZcSuXLS zsf|0asPyMGM}Gz%*{zJb|A=6!%ohP|glQFkm?oLJ>xmm<96}#ZP1==nXG5ME^y3jj zDgVQrQ1iU;IUl1}#x_Aoy%`_d#oP2dE=bVeM(sjB%87FFu8!o&7Q_axiqCe?)7is4 zvouU4A#rTdW{=P02TvSnfjaaZoB~Pi8UNN{jU;;nJaBJA-57Ngby~nMG&qn_*H^B0IAMEWtID#L{+S#_A@r7;L z?L1z<7HAqt$r1(?gm&iPAl=t z8d0XAOI95*D`@?En*#iU$1`diKkDcQdr-DO&5pXcKZlKMzOEEi=5X*OI;gWpc$WxRsji?OPr=1T~bTI(S`(r}n3t55kZ3hYvYEVs zG~7icR(Rq&w7KJ*0?JpJUdg{ucC0~z^q6_R=R)PJ*ccT}2Mg#EnR@nl-@&=Zv^eu5 zpiGE0;zg2_0m4z=zI4zEt&9&QWG66Nx5msXzkgpp&%agKf{Th9L6Ye-?vWX&?{LRl zT*Usx#Qiq$Q_Yh{NpX3x|8t%c3?ljuTcT?eq{%o*dc(_ZDCLO*sbQtys9u}*C!boM zP2gpMO~T_Io+PTUry=vQh4ze<6FU+Jb@v`6>9lGFvjEaOJeYi-{y~OUFo>~)U5s9r zzE2d=RD4h~`Q9ExzRztN<#A5i=F>;S@uZ%U(!V%Wq6XAr`pkR9gRa;?abbm~HV3(@ z^lr#_-Wd2okOoF)E9-iTKwGD5$D?*gwE`Jk_Kt9>GM<0yBg@Tree zcJ4mg)m!p2qOnTLNHZcdz2;-yKy}21Wo4}51Y=zmi)hFT^?9h!nk-s2z@e)f7(Q7j zMKuriUy{@k2CFazPQN_xGT5Byw5l~WYsvO0(V@IWpQTRZ_JnjovTc!@ZvFBIKpTY_}W$Lf2M1gn-TbZ+~eQt?jI(n=MsRC!}07RoaQnCO6*vjfCA$vUmA(nzIeRqCSioi3WR((&w*eQ9&yNRkw(qXZS&qv4_@p(st!=xN{{sPNPo@!wCaenYnU$|ev|X0F6DRa9GV z<@sT6`ApKKaA{Z-SX0<^!F5q|Fh^1aopdeaQW<>&XKD_vztXwh{VS*4`Tl|9Y^L zbnw|~ea0m2BRO-Ux!%mvCy33}0Z(KmsfZkw0`RvGG(NitRRsz(=xocW8w zvg`of!^sPEH6f_{H1!*`7re>8_4Rmnihk=s%l@`pj+UKJgRV6O8+AYf!k-rSBOf_m zQlrLQH?Lub4!wDA&(7$>_mY^!t(k+xW+L+WZ)5rHH(ld~(k9$Hq5+k09kqDMVg{tg z_8hjd*5?Ih|KDlZb3A$S$u`^Syu#$XU*aY}P_Dwcon+MDQ^EM>jln};+}GB{?!HnX zol1b<yI136~_(9X@v*dYh1$;{&Aeh(=>CV>hHBSRxFeU6bd{`*q{7eO*zj(jj<^X~@t-%*X%lpEFB_8)@1fbI8&yMT~- zM~BXQAx!{7vt3O{fcrKmVd+KMPD`@t^N6zFWI6lWc;V|>wkUs{me$DBX9t)9h#H9A zQ2T)37bg`l%Id?X(d~9L@^t=occ=016B8A`DvwYiEAnbU@VC7mj$yYaJ*NRSTkMPj zZQ+ZF=u2>y$t3B=m1IiLsYa*F)&6T26uOCdnobg!!}%2Q!RQsw(tLD|y8O%mE2ckC zzO1?2LcHvzx|ws;);jRPT6=iJ5tYfDl}=}h0H#2RA}Ipe&n0M_4A-8oCO={mbT!mv zHOZX5jWK>DG*1H$#)>N)_}u2rm8c%QER5WybRxxDiRj$XPWjdYPuX0A7jD~?-l|;w z>F6$u2j5{iRypX*3f~`uylv_H``L+6bjYl~mb8}vtSr}SvBiF5_lJzi{Vl{+U0peG zmCNjgvy)L6O>>Kw^)av7mykmoa!dan#mcxm8+5Ds?{q8)a5t}c_HN&9YBQOPeg|{& zdjxn|hgpzOW7#~V&#Hfw67qgfV)Bj!+`sE&G7)^*{yd;$4Z5DZQy?iQ=;%G1it;M; zpsOllW%}|`54&zqCj&=|PE2XVf2A7yen4sRPW6t~x6$c;74kOQ|1hE>VnL@>b2w!0 zZ2hze?scQSK$7|b2QjbkQ)VRE4L{5a#)13gz2T>UxO)5AEl0DT%iHh2pZfpqSM<>} z)Jh%a+N4A;D#Ak(_d)k3jMKa`(!tU}#iC5+S+I&6-qz~%1z*knyLb6`4lqGl%bZKR(bZjBt}hI_i(8X=Q|*7b&@k!reTVZW z6KG5^@%MTein70j@-Ksc-@#R-pv-WtPR2MU4mj;mVFT3{yxohwF#B?qXtvQgp1&sx z{(EisM?fE~V^NFJ4|C6n11{~ z4rC%aJA7W{#Z)5QBlJ07Ee{5n6nUAxaW~A+lIe`Wc z26nX`V%&DdKNd&j8$RrmMR*HKKa3=RApoj7UUH=2)u5!(5^ zv#^60yUyBE38Qf>kI6o6VulX8vmHE)O3?XJ$j-CE*}zEW(J-NT?i_ zW8;aEo*b_mQEAJCQ;R`)!~w&-RD|rW%+p$ty1}Aa8QJZZox|x{;1MFP4k3`IQLg-w6kP1}-pd_^Pc+={yHT%9 zTlU;x#r&8Kr}!3PNXGZYq*Gv(l~;`=gY+l4y|o{lf`N2pO!FiJSjKnFJZm3o)^L2xHY z9jyR^GYy?s`oX&SHQdOh=K53i*>ABZGLFd^)nr7H3l6sASh@u2P0kG~7BS1V zkT+ivXa!DH{>REOW84X@;_;C5Ec1xZgiHcuj;_r~2o_U|p0bixVgqDGUP;W9xy$xQ zl$O&o23z4+0BdBiXY_17oPGy}>XISHD46JzonM9|aajm@yTf90dvLKF9CR6ivB}mo zY+uuElBa{i!Sx9s4R`uD1YnJHkD=DD!)1yv&0e>r^D&Kc$SQpFEXA7&((Ow12eX;u z5Fr>1g*a^Q(9L(N;J%4q5Rd*r(vbvV%)``$(?O9l67^$%#6uk{2J#^Lg#fO4bOO~C z*2I)h=uql|3@93ncGAdkh@mHum`OEmw`Dw~fErYy5o!YB;iZ=NG;J*@xSqVRBiU(& zRa?&+-W8PCyNl)QBillO7?ccZf`AL;9;{RA(#6V3JX+H|N=jXpqBgPlE|l8i2GVV> zvsW%AJ2z#>n|0Ff2Jg3J{C{A(9w)MBklYS@JEUOdRvhbHk2v;8;-QiVe{56lQOr_H zj2s@cRn^+pIi2F_EIdfVKz^&u83Ai*uUW2kpibaqG$LwkxfGmUskB#CgvB&G;X6U(Q|lbl{0RRAgQv;9}3CPqym;1g8X z9zPzrp+syy52Ccf+YsjL+_yn;fTVg$b>UIplx1R|X+Nvz?vl1Qg+JuD3+ShO0T@fccGXOmjVolO4LGC^=P51|l zDPlwNL~C0{zgWxyxWi%KH+dUmoPsDNSZp3F;z7Krh&yo!Sa(v1(9F%lua86iDBfLs z1Rm~KN;jk?g~O=eO`r9=_HQMpi~~q;Mky=9YrdIs1UceRb|3*K0idv~Kpzpygj)=^ z@~xqL4^p{VU!up!DYG>*+&H8O^V(U0n+}IKBRh@B-tE6nOTyDMT}?}lrQ=2m9@KbG zX-P8XWN?o2<<82nql_`sHaP;Bg6D&WK=@1hx%WM!q;!KpMd=V^{`$uPn2rcPM2YIQ z@{KCkh3oZ;$qG;HmyDe@cW05#&oIisIDe{I*OgcDH@s4AJA=j(*YyN1Q6{r=DVudd zk(<5S7O+!TiO#76WY%{BMIpdeF3Ce}i&0?y`q=+I*>7l6_oB^vox=DzMCp7PS34*Z ze!{oDbsKSP4C&qv>G%|y3WxAl=o--#Esx&2J(YT)^cbGUK{eBy} za0-YDeUmnHoV0W~!@@4b2{v)lER^)(L4xXcVid^ctw1j@-4vI3_K*8#W&9$|;&#<| z5(&%byD84VABJF56!+iHG|P927)A%hftq@6UKW15NoN%~fac9lIC4`>iZFWh(#ABi zN1(gAvV=`rv8smEhduMPyk;1STuK}R*#e%(T)BL5NS%!vKGD>0hlwXly@}YX#8C`D z{!YP?ib*YaxH6$Mw#Hyz15*Mz$Gmxq^skB-;ut!t<^E6m&y!LZ>_Y|H$Po5!$4OPe zr|l;*A2Otulmu!`jLC6tgDg@dL~XPZme#0woKK=5_V@YQ@8vF1ug^y!p|ZiMWJn^= z#zJVLX_dn0z|_9WysoFFaT37KTTI(84oH2j!wJ&S+#il#5Y`&-K0Or6ra&OsWXj;UVh$boTy(hGl-d;_C$pz@2(v5HZj z!V@Mwa>GXa$?BytoD1W(7X8oIYNrxI{1UWj9n@%giJecODaUW5m0`pZ>M{v2?xO@EkJ|!!LpUZ?E1k``{QcG$ zPC+G!hyblPU}*+(=4ctm*4ONuOfDt3QOj0EU57E@;LCI_;qd1=} zh>(2I^O#5sy=VgmqX*GFnDcz0Yhd~y{8}NUq<`UJ5p|_UuFBuUYO(DCc=BZ7`dsg8 zj6EqxqDqEgLT@VNJ$GR4D;LQG(heWY3(9_dR|A^umq#tlabbsDE0&y`R2#M@yip!} z-W#P|gS^&n!z>xfUHSI-QOGeUU~lk$kMc0Y!R}QUlx(1z*P_?T-P|wu zZQeECz#REtX9MNW7u1()?8HPiS8qVrN;0s1;q>?oM&z=2c}h`$=RV-7K-_TMoMh2Vr#|EiZ$PO z5l;~}T;CG+x0%0~GsC66ZEUA4VuSSYeiNs4Q#`3-NUeSTTkpv>>PQky-tVLPHN?_= zQZD0dhX#FeHo&Sr;1@3vWirgV)2qs3LkPWj)C@m|Bdt$6p7r)Nnp`c|Uqx?ivb=o*n?7bia4r#O);tTTu34 z9*HXPCShTZYpwm3e2;L8B6S9(FxKAVj{N}{bQ6ee2oxxMYuzd*%x7T!n<7a)JqMXl zK&svUuLJeR`{~Q3$v;QoPtt!6r?dZ7Kkm*s4^KMUwk`muJi22F*`*pXvm!x%S4l&b z21Nh$yzOq!e)`y$2tA-jB|cog1zLP-6%L3HJasMWBGA|a1sykjei%}DoIe|K&Cwf) z*55d6NpvaVxz+6j@5S$)8JhTDI;nJTGl$2TE9+>?DQP{V(R|&ft;{LsM4oomOl0)T zx-_I@;zrj$N#T(=&epP~?|L0KvpliHVr`T8(?loa@M8SzDSG|$&ydZ*7HkjeLapS> zNd4ECTk?WErQgM@Q>hm8syBx%-Y$M@_hwl2{RScUj)^%gN zGfQess}?fsbcVI`-Pjc)5NDr)E&i}~d6lCUt5`K0E;hY9G%&uA>rj{BkB*-GG;e6a zn-|9BB<5&407AYYE~aW-+ns@b8!R>_WBnXr`MI_1qCy$AXTf6SMnI60ofNT8Zd9x<=H=c!d)QpOde_#7!ety?%!&iI1AdL&s_~Dn{)!krKe?- z|Hc7==iR%^t9x;~Iu`Cin{Kh!G7BZ4YT5^O76wP-gFx z;SL=5+U*j49~&2}4sqD809g*(NF2I@D;lHKQ}ee?F3OCKdS`v=jA&Q7tEWjZ(KRgv zx@r@WXF_^6-Is@!Tartgpf39y%wmpENL^O)H;r9GF4P=};XiJL;|4L`S8iV-3T%7+ zXY$Lg&%EQ?^SI)SN4B(Ds>M#rx*yeZlG3ZB`R=M|2fb+7d3h3V$}92XrOJ1vT$q2M zsek8>!rD0^>2~`oI?bPc7u~y)v38YZ&b)|Z;6*%*e7YCjh07$Jo~q%bz3NQH%B!!g zN6VB>UHWh^dj+kyRcm>>t@qEcKo7?4He#OVvKAv{{rir1r zr}3o&H~vnz&;MU^xxeIdOFa##8B<)djlOjszOkTULQfxW<_6wG-8ZJoSG`hJyL55V z0wv+XqdiNVx+BhKW+?94E$Q}b$=~aa$@3%hw(&(uX8uf``#7@s;!zH6brWw_x74GO zZ(pBRDUVb+>dCWoi_RNSx7}T4C0k$dPS;GoskO5Dd=&p#lU?U#NtBD&JIl(a z$f&wQr6r5HGiRN@zn&vxn#s$=E%hbeqt)y0Z%jV-V^8++lW`YW`55*tzI}D|TK@Tc z3l?z{9^G@)nfw2V7Wr?>{J(8Z|9<62%&8-#Q%o%krpNzNk`4YkAtvtd-W=a(mFY7d z-PnJoy*&L{fY?F{+jm0i{~oxWqql9so4DkyTOW5Rtvm6{dWX|Bi!Iyc@^9btE{Z?8 zSiOF()+7%f)qdcfosA66!JqkAFQ;wy^K&~QdO&UC={c)b@z3vAut=oPbsDRD$EQ2N zKMtF&=Uv4A=jE<-%o8V{`1I}P?w!|P_iPhacV8}Qo?L__|~ls%$^}yUJ%9IV7$P+eAOzu8l|Q#t0SVUase5Nsj`y0Y^Sc+(Y<8vrTm-K zmNws{L+ed5Dj1Zkij-Grxpi`Atr85Mvh&FWrx&ZQ1g!n3J0mO}cm(sJU9zihl!Sl! zyk=`LFJ3nD-szQ7#;)( zhI}d9zlgJ3m*GLvOOcs&p)daVPyBr_S2!V(}aNPzRs`Up0V{!b)^s0|gl}TtRxL?El}pK9lKy&A#ot3`6eu6{1-oD!Maf-Vaceg?d6bTf!1b2tx5Q0gmSAmDcYdn5J(%4`r2UW%3Fq;H%qC{8F*IID>_tqX16;1>5B+J`)TNIT)XGJe z$|Q?l8y&AWjpA^a=6W#o1MTE$W=~&M+UDoy+uOUpC%ziEXq*N~!y<$e3;rKfi=WS* z$-{*i5w_dEOcw@3?<3-)BO38L0G`gFZ$ zlSx30Y4Gx;`?U0a2;x6)@qr9(y8qoli@#c_Fa8>fm5>&Fc0O_G8fc@kyppxU*bm46 zj_h(a$?L#;KW#TC(wVipZn79j7%~DlYya5WUTdhDroly;OUw7$QQ zt<*zwjN{agH5Llzl0}g}eXTUv9>(8#5F~WK5kw%qnStm=;a2S4I+Qh-Xg` zTa|TEf4l;DT`NeGIjEhg9I6)00+zQbC802`zrEbU6sZ3*YQ%Kqti=6ZR)VQN(T8C0 zHPSj8L`TNIn}WpR_ub&KGBeS@=q61+og-r{?wDRS)i@gJxHSK7?E>>P~LW%mJV{Ap|O<=B^}JSTk!YxT{Jr>$A` zxx9Zv_j0~%kq8X88b$DzyhXG?>4Lj(@E6>MRPSv}4wzVAOPk93*|B?AiThF< zd0iZts>MZ!>`R3XPB`1)Kh?6?+21y*W$~BSyBA#M-P@3@ULIUcb#0zSJfbjSe*b8D zeBv$i-fP3r2)^!p+yoFj3Ud~8^_|UXH?rqz8bTMm#b_~$&VwiTEH^L;MURM6fY4PB zdNH#!u=+pWi5_o%4jF~Om`mCrRab@=K^}e}?~9j4ml=BrtvoC8!2hD>jVkAcC?N)G z%7A7EdE2diXrThrXPxY36_=XX#*e+Zr7g&(I{uA<^`86AkG zWB$)_XLAIv@lVHz_M_^j_@|HiP`X|Y3dWMa@V!FvUj{8@|5%=)NEj9St1)E&S?Pj- zY*nrWxpaRmaj;Ig1sRS0>-Hd;#<+*pbE5xo#yVuw(!}f{sY;I~?${jMe|RH(5afl- z+(bs)l2wMpYLRcJi%|wsb}Q}96e5V3J*_zwTLF$Vy_Il#RwM3%Z*z?QB19+Iw8x8y z5V4SZ4EFFxu&0NJt&?F|nGW4+dbOimh-{mj^SoW$%wLesNvz3L!^A0uYwHHZUjjO| zdEx6Sdxz87k9DwE4Ndu|!n7VCbl0|TsgWu9tFdtR_Ir4t37(nY{y{PLo)U!*+byee z)`A!A9N!=2?bk_)v_r2U)=I=SUcf!MC_u-dKroP>P+8?8tNk|;@Uf8@vyhzgis}BD zH`zO5HnVQ3#AT3D`;5K2HKKV^^YPuqwbK|N_A*r3<>9fcfk1PGzESN=%~FiP7BmzD zYiQYNSoq8qmn-qzQqHQgtji3?k8yeZ;=^vFP`H))TSIu5xZVG9we21BGGOiZwk1(Z zsn*H#JAFE|&GR9Z%jPIWoDii=2s+{%mW|56YJ6vM2F0sFv3B@`;`24)vRyW~f73N_ ztxQPGlv$`PIy!nJLGqainai|E$~S_U3G#0Ko!y*4>%QRWw4>w^PT)D})p55lD}9se zLR3Hgf{Bby2gX%lw}6dyI5~Pm(Usxk_c%XsiPIus9V`XX6Jf|p$Os*A?>Vbl2Gb@y zCA|B$BZuwPKTXfjL0~n#7k%#Oy^qo_He<*}u9(_J%~y(&_pY3W*gGh3!HJib7?FUv z4#Ot9flUYfq+b?+$Pw?pod;&<{&fnRl4`1aW|67^EVnobslaf`k87w7Z90pby+#ft z1Kv+8ACeKNO9c;Muu6RY?TT$W=!_!JqXqchspVc6^;Wn5N11op|5B*u+i2b^!nVo9 zi-mYWzs1&F4N>p{FSZ+H2Rub*OlD4xNkUpSY%c)pT;g6|>AAdzI|f?UBuVsy-g#)7 znK2GIhjv?Ow$nr0pbO`vc-76%eI^6XGvX?ThYkZLT+PGs1Du@^$EL)$!;btpG5)hB zV)ql!=M^wnAeRRuaP{!!{*}=A@x_CdTg(vW_+J(pyLW2ueh0xICh0J~Ty`NGtC`0^kbEjmLnuEaz*ZdVW8pn`iHV?-En1P9fJo~8&n!WsdidQ3jZ zI)s?jc8=Lj1Yg*HrvUw|T{eBWs0(!CrQs>)g^CqS-|6~0C7%wLydNsaknf9X2J`xgx72^ydpC&#gR`Crlf#3}|N8wsnnVzcU$E9`A!9;nj(lOiGVcVBOP zI?AHfIvP)mM94{SZCVsHz=SzXw;M6E{;<+Im=-Kz>Tv%M`_*X;(7KyzWq?jkle>l9 zkoX+!>H9_^*V;{lCDyG}bO?UBTW2w8gzn^O{%;=n9!)PoU}!D!A7{y*=99`&!_Wv_`)m)SHm-UqbvTfl_);M_iEwWTROyCmLdC|kF|EhvlJZU(ee;wmr49439?U} zUFV3ySYr}oVPZyQ<-*qlqw)hxkf2fsgcoEZ{gWGAglZQYxYqY(t^O7x9#nY5qI!l? zGO=ox`3o9H93MQO1uM#Ud6$NShJhO`Mi9nt{_E*a!I&ww+V`4`TIR6A=VO5m?d;z*bE|dQ@P`nR^Zzf|~P0}U&x4CQo z%>HC(i{CIYp`6**;DJ#+0lGg)_&$x0rVwO3#81XdhVh&b5yQAQQG$6h>HoTd9VLtv(!TQPd?W~yw~q0gK87v+~3fTq2 zBPa_t=avBV-umq`%S9{h!Li3+P@Wrpj7L8z&l4VoS@UD*ey^}n(0Ta%Q%H{&l*RvW zQl+}hU4kO>Z%9<pbGS#?sV6l%$Sxm3BrG~4OOM3xSAX@7340wm5|3<19|4vl?1xqY-aWX~ zQz3i3{uaqfbmq;A`Ucm#pYhC4i1aj0nsPr{PLwfe6xPo5NOToggdOQvO%NpnrLX(@41R@d)lsp;`U!DiXI2X!7Y$pR_|6>u32qiO~J19prZ& z=aXo&f4$$2mp-FX6Z$9ebxkr0CAMNpVhC2Q+WnnQi@eJG39_VpIY$~%q{37n+X;H+ z#74!EmB3#KV*ve;1l*&5O)gOqW|0O>6l}M{Dt5I8rhc`)pns(7Z<7uSxsBflzkvD` zo~;P6o!V*eFA+RnYC!lutz*v<;ur3%kLHyy_B%AtL4XIW5Z`UGPbA&k-L!e2F7Dws zV_brd&LOn{UGv3-Lw$e4oM%d8<x2<4!8itV}2T0SYOPsB5rQGq6E%}YC z`a7SI^^wF;nFy(eU-t?Zj)~h2Hw%tINb;;Sx}Cj)yx*~4xGGr>cyr`M_7Nq?y(R=y ze97^0YrZlf(J_APMBv1iD6#X}T*>VdNnQe+g1W6I>~le^u;5?i$P8Ev5JAeo<3f%ZNtmSjR}zGFs_%eR*r+_6#lt%Q|<=cd1W?2tyA=kFn-<4;UPh~q@RJNu%61KHJK9YZK>iSoOb-v*& z3W}RteeG|8rQS`Rt6)mmG)@c9m5cqIpJGV|c2BRmRWN@gOm}(QPdV$nb?S%1;1Q8Lb-A@b0jP1YlHx2J}Qvs^2J>Zx;ntCd?@JGS-Q}j zXlx2p8nn5U(y-#<2QZM`z43fXk97+MA1HY>6_@PKjTX+TwcM+u1I=f+vH3XG?^xjo zGFeyO>8TUzMWn=kBlV6?M&1Wa@I+j<_EhPUUOnq;(p+xAGmx(uC_7wp{rKu#)$fsr z#v{SxzOp)=1JFYcPa(lX3LjZmnus*Tx1hPe8H&eaI&+qg9zk-L`jX3LRpN$Ca!Zf~ z3k6dMIHvBCO7ZF`U2-$q7!~N6l2(#7mCJeUJQDM8Z5Xf5F9AZ^v3PPjGzQ&+o&xQ< z{zMh{+GUvd(mDbHZbi%^Db$#(oA8Cy(N3d+U8lvt$*$@!q7%H^Gn2AeooQF@rFl`W zuI9RAtBiF;XDodl>~3sUT0hTYCVPbBCWw|@|3{P8zXo{?mDBxWHD5;SEvl5K zf%E)jm0#Kp@8Uzlr?)F+jkyZ_8o2bGvWSa#Z%AVzx|29wkTsbIqatXHJqDN!9G6?v zT2Olyj}I4GjeS$Zl^GH5TmP~Jhn(B7Dqj4e&vZST-?$cmyxi@4*r(JU&E`MF13k#_ z2E7y^^5B${P1vxnI6Qn@d!+`j zy!XlhEqB#U_Ca5I4o@YoTB?8X{c+w;MjD=RX$q~VoH?%ceUY6oA-6Jy_W}@x-)5oM zJn**3&&?E$)Vx55^H1>AHIMQc{ru}G%<|JkOSnh{K$rhqvh##uZeW#njFzU#!kC2K zW@9vp8QMv8d%LMI`1Qrdb2Y|ngeLdc$!vVIDah@ki~`%(AEbAjjP7EnYF~_fCvzv< zKHkpOJfmU4h*$FSPGT}6FN>iB)aYE)M!N6)2A3STZs{T0v)Rw|@cx-X9rj2BZ!?&I z&FfyLijAsf+$gFq_Hm;mZJLDn1X>^|IGGz)j#V<4ytg zK1pW%sHKNT97ihwZUj*ja-?on6_57^l_5KEBK+<6LoU`d^#TFy27Tv))2UQAoV_i5 z0Aeo$AUL(JBsg*o4haB`PKC%%4&tsAq&C7ooOkRC`16yYOxG|dZfvu5ax17)2K1J_ zJ$XD@E^sf%;QqRS!bb+Ff4+lPzQfMridIR1r-ENL9`9WSzj3V%alJt&-9C0Gk9LpP zjTKeY=f&m|`>%z0(=GY<2npz9oFvPgo?N=Se-WEqT#4gD3=G7xX`DT!$)pqpX}Gj5AIZ=ZYRSk;uQ#X~H?-zYBM)O%m|0xdRRAAi2Oq^N6w-4>X!;`= zT?$45CRU$vDRDPU;<8@0`frlPE$qzWWP@4rVcJz*=vgJwbhPQ#(P&nXwq{I+yCC01_Y5+FJ2oJn`qb&cK4=Kb_9eh}X~ zF5WH$87%Ziln!U-NfuZh&pxvn;$QBfyh@Dr3)J|N{dHu%(bRvGnNg8+9dk_xU1_q7 zM^F3B6P~%O>|qL>*w-cx0H9114t-zO$}tffN5LU5xap=3V^=lVm6D9|f|DPW`ICB& zNC^KEV}L%!&);8DBv7`OJ%rK~hOruFh#prXwqC8{g1}|rfh~h>9X&(}UUP38HI`b~ zK>VKH+JpsV!w-o{1}BW7?|KD0BPn~;DJyWB2_BXZP)eCQf6KOyrT88>4v zAlu;4hT&Jry<3rt!mM z4F3F_;ll}dMLCpkJlH(TA^QUp5lxrqN7hNE9wu)LicL z2e^j^LjSQ*-C2q+^*dx}&n}&6Dt%)aYgl)Jk4L%DtH3q9yY_tO6GWNOcExYnOVVe1 zy0^EiErF(zR^Ur0rz>@IM0CCMqeD&m{h`GRF`iX73!i+F_2{X_yl|Exgq=HO%t3>I-G-a76H2 z4F09K=JcboGR&4?TD^VTG_|wLWwx2E*3fkL>{Pa+%g;osRye(xjY|(YPH9h4VUn^& zi!}RyrN|)A_C^B%S%?}}$%Sqz2)VSG%`ETa*Ct=NT0FnN@9WD@tHWcD)w1ioagj(} zla4>2#*H|x>Nc8$lm=jkj<*cT_pYR{T*%3+vqjz3}2QeRH9>8xei+>aJ5hrMl^cZ#7TE0~-aJ;Mnwd9#hk_p?%w3 z@;*`jepUFqER(_xUTDyr&|&G;3F3-3AR!1gAW{E^JHOEVJsPt3j&} zDQ4>sqVB~-^P{{)*8#!mv~7;d0A39^R*dhvz7P04tKN3bx4X);42MhZ|3O`=K{!@F zX$BpN&iV!*?fB@?_z6|Lz5i zxG_%BWQiI4<#LaWNTK&jdvF&Q;#M)&8SB z1$7iT7FR^xCo_>tbCFdotXm!w*OmT`-2%r2UBsknH!X9K4=EaJ^Xo*?{rOBnS&4zh zVKr8;ASD!>gjJ$Tb7w%b)7(FgR1% znI7GxCGVGYBYAlkVVfY@>VB!YA{l9wL2dPqV{_S}170s9g$d|zWf<`~hbGG_3et%+ zT$D*}(e37*3xckm=6`9WAFV=ngV1OXj^l2hq``Qf?#BxSPTL!Cu{GDHh_wSun!oDF zhdKQa6f0p3x)=Qx$qc+~2HkBfL6_RR%=|P|#HbyF{o9Tn?HNBP+8c+v<2VJ3$upec zEEuOPlRt`t%p2fMF*i}XPaHpiS8H#}ZDahIt1F>id0zpSm6*RvFpm5#vz-FN)12_a zGMOoq@Or@T#aYLpZEZ<}ZaaGLgzODfJPHQ5UEMUIt zURr4_5g7ltxdtj8G(cr}IDUS=cKma{;&*}~IrLf7GG^|gvijS=?Tg%YaSR7xD z8z)Z3hAw21BJd^=b%AEqT|_DUAu-qmO*qe08}lh~836;=gne82iw?(HKnVYZl+ab! zo3=)iM(0W9+vn>LD$4gUgAisR|F_)<(g6M>Rpc1iH;l@JOK(dG1LeY-h!{G*?~Xb+ z@|mnPO$f?Rh~)M!7KpFg0fdTPR8VAlU#<6|z)40=x>dSk+%bwVtWdsT<*@(qHM;4+ zRv3uNOu`BdfqZ0|5W^>x~TrWiId-=oXgL*7hhx&xR_e zTxccB+$pWqiCX8kJ*Zbz^ju-=2y(~d4-#VM78%THGDczPt&KM8Ke=q zzLr9@h^(E}rQH!4@qIU~uco%#-#(CRQ+4Ki7O+K*&*XQFAG|Fl%Nrq1LD9Z$`8j$n zciqfJj(y4VW=T&8*M<`_REvp{pX}4ab*|u&3r*8|e%(Oi{x7vEo$r{N*z#d4Me<~y z6uPV!*UpgFg50!Tp{|HazGuKRspIAeWpDE`HyC54sY@gg5)qkdSlCfA@P0uP&BmRj zTl)Dhcftr~DY7f6vJ>7<9Sa*b-mn$HhQ{Zoa67+u`QO%M8Khe9x7b-62KDEG+6uo1 zjL$zof(W{~kwR*qHt@a{wnsPHHr?zz+P_1RKu3TcL@B_Wh;Vr`=_Q^l*|G+G*%36b zXh%n;!1cs32i{HJte6;RYVMr{szjMp-fgE_Oe`;74ZfWT1#IYm@3%Z=0|>G2W%q8~ znyeK^8tHC*W!*+H1~#EB`sVs`tSPZ)aEv4sR%71oIbESxJd2YB!%=|FPz-ndHGj^a znRO5`8z)2W|3fVg3fIvQiYEIs7_1x~!<%ar*u>^Gzhguf{LVv=1s8+UQzf_%{1rTA z!V9$dNnhhFr!1ZSCxS>zjE4~w?Hf0t&mvao)I6t{%cr9`t%$>W=- zw1dqE_Uqr%jkid^n$^SJ#ZKQgZ?JzG*$;o^OH5d_P0ONgo#V;n!0uS!*LuN)mB0GX z#vLMSt{0g*TRG}(ZdTHNA`>=Np6^3?4IRj9hIu!ho$C0irEGlmW%KSzqdj1LL*seT zOJ6<5(31W2zz=pWfOUTyIaQ@{lxf@_v(KC)2!v`JdDif= z>4<(0;H%~i^X}957@bbZ>XPmMJPhYIKJ*cpRprK^9mE{UNInmH$-}LaBjx>!(alXK zUOzPui#0}}hqcjYaMi(f$d3SQgnm%@S%7+S@m{9p58 zHYOl;pOpuU7*m-%KDaobn|{{iN>n3EGOQP*#8K1+b`!yF#b7CyC^$L($-LSgkZ@m% z&6zb^w%`m-wd>mVxIJxD#xLe}X5U^c(;H2E9|~$KoG<8R;ka)LD}U|!&b2-}RWROX z^QYj+D|9kNT(H|?S&W`AL$?-87p^#dj}CynW*udJORhJyed==_2aZAM8tX5G)8;)L zn{X@o_xL}QpI)o0sOAY)xwzL73prC8H@=iF>OaqV0eyzv(XoCj#$d$yT9OcaxVd_> z(z@~E7tA?09tzqA;d&icKo22Mp*GOV6B=D&^|L0lx#TuAtcWGgdv{p?xYAgLK41c0p_z*3m2ddX2tk#I32sBq1-ZQbE@p5f#E(1*T+ zBRjjwMX#d;3Kg2p%(K3b~inG8&i{97B;+hIQ8P?Mcnf)8|eb{@y%SoR!D$pbvlFpD65Imr(d} zD(gUxfStIXP~(%4{TUImnujOBln@TVeDUTk5rM_O+PPpQt;78^1hCrnVH{q{!t zQ{3=C8o}p*dZ{6W)~<0EVqks{fpp^U4fU&^ci(yK%_0KbeOj%MwsENDoAEqE=guQM z7A?wPa4jrw6-`?-FnBS7NWEvR5f68nQHRK5?-c`_)Q}05U4zAsyQdyFMbI}Lwb{$V z1&#LxPD{<@+*uayt92W!$v^M?M;R!}!d1@)i>Cx0vb403yd%Sdo^M(@ef1~KcelaW zgM$jnNvYxI26{B);=Y%Ucej$4g^HDh@SalC8eg=VbIrJm&O^b*coq|o3s6>AH z!_RG4-nzuXn=}ng&i>9uDZxohgy|6bAn>|f`iJMMg&PZ?KiK++0=d!Hio23m!IU+n zNrZtJp3GiKPggXae>>NXiEM3KY~eMv4G3**A^KD>Eenp=DA(Dw2&DEs>D) z-h3X!&z#%7FvM-PW^sduhiec_$*YEIPc7&^4J#CFjq0^}eM3SpUY;7%7jQ@?_?JBg znB%i?fwI<$N}1m!4$QiErwC!_GzcjdpiXGM{X(BAi0ML!rO~TXE>~Aufg9iAc#;a2 zH*+C*vtE$-#hHYSpkkiU(`BdaX#4%6D<2E8Oh62vpt9P{`D~+H=PWP1 znhJ5_p%cwuyo;s&`R2Q9gyePYTgYWGSG4ce-L8et^IdwWdaexn63HGnwR-#YsLH@u z6a`uCyY?q!T+D{3?G#pytonz{;}8p5&F?cL-|rZVKHKj$jW*&hW!v4!m<2DU6ZD9l zrhcqF0?`?(Fs=$Ye5zV}B=tRO>Xabfll+WhEUu8gmjBkeR*3u~{nGiEIZ(n~8uyLr zfF|5-DH+1T#c$lC-lL&V#q<@d+f68u0~2OXwXj0*s*o*iwiZdC0g{PiJ)HpX7n&cS~Q1 zAIk8*a89R~t{`>%3;CG@g6%n=5Pnf;k{Fj)L~Vi?$4FE>sD<+x+{e1Oi3o`dRcG?< z8@DjCf6)FU#jYo?y-&;kW7r*0djYcsag_;6k>pz}m0qF+ahHb{j5d>iky?26gfw1tNn-1}YX&neFBtM3R!WxXT48k)e6=e}MId@+eEw~ypP3ph;L zQQoh51V5}&uj7>71<-0D2hf70ahh6Y|K zL;k0emal2Eu8-K7eLac9D7{Qip_1Vf#bY)cz zs#b!u_p`aV)#_uwc=L&1+E{S$-y>B+F_MY!cZ%hEn17Z|m*6Cfadl0l+UzRSZ|9Q$ z%>Q+d*LIp3oPFS!Po0ozVkhL^m&dKP_3ccSs6dR=T?pWaqO*Y)R~ z_gimdv1yQkB?0yaMR=i;ro?~qVODSRj6SMMd^ck`2ufTl`LG-k{w~M@k&-cycOi}I7oe4-6UtQ z&h&Ey1X|5=$T=6p5{49ok0@H0JlAu~A)Zy?@s++k3X2(}Gi)Y}WguRy(2(*tJa8{f zNY9;YEeHnQ)BEGNKo{BkNqqcA*tOTsr;5Q{`B++mKRG|FCBL*0w#y`a=vJMQ^=9K! zV^5a-+?BeHJA|;FZJ}+bsck6cD+es&wnLUifmi$1-f4IOKFp%+;ds5r8GCd z1|qqJ)@^~1*@Vxh6tbEa-3g!ru6H2KUJBy+g$$P%v3@)Qn7)LPN=lE=^e-MMZq(-4 z)w5C_#*IS1w>@%k5#hwiiH%P$xjt%kPZx6D#mqmM#H3hdxc{dQ@ESILdK&r-@KBFc z&y^fW;LBI*oB;Lp_pMSx`-tVyA1VCSf+8v_aQ8M?TA!Z>G@f;gDep~*Yi1)A;tUp7 zYQVmsVn*b1F>qCQ1AkQt9!slji=U1qHOn#$?hge|tJ1O1OAZ~M5_v0N66T;)0G>RD zp^_k8S9-&J?KcUomg$Ter=c|2cjWY))7wSb;}vwG9!$}=BofCh6qD6p48)C;kOJMU z)JX30r2Webpeo#unI@!q_p(6+Nxi++iloHEq`uMXk#IrH)wSs$(rshp#mDtY2gFHf zkt$e6uS<#lcjob%!KG@_NiyP96o{M(E`;{%I!36Z`b?a<+bMR!`y83Goc<2 zHXp)&7?(BY-9zK^?e7T7jgvewtITv zvZLG&Nw$dg-Lzb<{@x)jFtFDt1^{&*{FJU5emtSVV&==^oW3M>VgG1=nMhGaR!l#kpA4NimW_ip2HqXF`0lC; z8Bo)7b3gqze#)BW6yfy<^}x$>oA%lKtct#a=f4o8-d;l>r(yr~Rpcoet#?y#@iYVE zwA}!Ap4|yKd;uZrOEPCC0CFc{Y}&^A(>jI@V3mRUB}p2J4PD2h?2L*jrCIdPZ>>h^ z5ghnH2}500E*#CgyumNX!wRiA%n%Whrnb#YSef-3zcKl(6bbNNq_g;S5Fy#dmBc-o zWfS}6jQ_WF6=&!Ad<~qO^R6M~Fnxt4do$JZ<#9Y(BgprCTgV%ANPO?O$7uRau%bd% zlrK8oCudsTzY4OX^{Ug>T62kk9dYs>&y!>WdB`-MY3$rcluesQ_LQ1b!HGiTl*9|gGaJW7R#|T`PDLD`@YL= zrReNaU6xfw&VM8x##VV_9`JsRZ`V}9_UIBLpS;M6t?c4`@a^-m2AF_Z#oxkfnRQwu zgr3Y)@De^e2yP+gTR~S{QSJ*7!>Ib6n_uj9X(5>jLdRn__co;pq zn`g@j_P|RZy51cAC!8`0mi;l5!Pe6u@dt06`!e$u$2-a8h;##)-2{oc=$;$qT|ctC zO$sBMK;+YtUT{{%sAJ$-$pEY1lKb0s`!Dp=L|2mnLEz8ke>2=iV&S+^J}{ElDzz*E zruq3s^9LKIE_0TCNzVHrrJl`NbNpXC09sCb+RIQWP`3tMF!jw|t*n_;^djF2ET)aX zr?X3wo35yFjO?6C$ZyfULZIvCi;@i47;AQI=6L=|xZ4rFGD))%{*|RwF#!EB?x+74E!JoY z=iB9n^$|WU5!;@g@h7tbCbELfkBOeA-Bc!o^bq@bB25(ux{}L!wu0ffXyh{Z#OD6W z>pZ`c=8&G7i=f$?JKXO>OX0XjW45=_z}{FTTQ9|@XKRm$!v(?VZ)s^k*VEJQaD-bA zPH$!aXuU@gBsTdRQzvfa3QgUv1}^m#3y%bqf3YNGsH2iImrGHeE;eBGAZROO-}@NfaKHJwh>%V+v^u^An*6u zt?vvzd^m}Bd#?hQD9~4d=c464-zVHy!!R#G(UaWy8j#JK;I5Pz|%ygZ%b*vYX|i$I1?e&eqa6gC$AZnt`=mCdd& zj(;z|>X;~1|=E$IaRm`bC zf;e?lv6R2X`&B-#mMf=YZ<8-K>r*Yc0~OXn#iDDCBB6{$hXS4O8O@=oS=9SZOrkeA z5?^;F!eB^!X&=+UIQs-Bk4hiLW1T;hsUB@5vNaB?PDb-QB()L@71d8xt3!* zUUyLhXz0wQ(>6Qw$x{HHF)P|j3rqK1WT*Z7AfRqZ&W!!XAH3L`nE!Frd8d*uT;eI4 zpWI4OgXz;Xee0(ibpeupUE4-BiM&t|lL~5L!|~eaf7lI25^O34@mvKP>3$Q%`glRw zw-a=(Z@q$fE2=1eg@%W{(1B-P2(|hJP|R)A(#OMDAh7Ht;tzIlw<;`czP_!^Rm64r zf$4QEGp#(iO0OqJKl~&mx|>gR-N(V$PRq16=J_mH zfItEX#7k$P7A+_%V_G#><9meh#BLaij&n?E0bOSq)f6eu6}MLJnp**_>$v+g+Q8o@ zWRiXt%BgGlQ26*z{ECZWQ)}(TP{KQ~k8(pcw5vt~P8aIWYB!eNXVs>I&I-l`FvG2Q zyDv20V+yspUK)W12`>Tj5hRz{7%aI>0yH3oWh}1Fo*6H zu}EdSaFB%un8(|_(kiyL(Zij3plpQmbLm$read+l8yH)tWx8B550onyKR|*_K=7$% zI$F9O1!lg(0>_$tugKp#yVu&FvK?4jMb@!m7Y!REsD~lF6tdoDGX2Bh9RI`X8?P@y ze-6>~2SxiPmq_OF(c6=NVJl^_n%!SQY)?0h9J%;uZVu3BlVjSK+Wq(Y;z;E0#!rFb zLe51IJ2^$Nz%~O_XE!Ybt+;{MMbbcNN!QF6GvnKiWYyH~?A!uwRoVsV^{NdrWpqZF zA6PcWy?K*jOE(lcI%*0p!@6K4J%>bE>Jt9tb*1gQqhqVTj&@p$9Lj`2gZ|!bjWlzZ zt3YdUEu})UByS;!mp=KzlFzL_h|J&km;ZS?%0;f#)L6_uL6RrVnQd-Mj=J`r#vS_) z7;II&sV^p_T2BUNV^9lev)W=F^=Ej7s}2FEW3y*&_wv=IYL1PZJAL zbvUWou;JHHBeHdlX++I5N{u06nHS3tt;0@&6JrgeCiOkL#`rN<(5*T}xyz5z-{n4I zi=tV$0@n>Uk%PK*0+coNYP}3nL@69I0O^_>DZ1_nPhJ6Pmx$z8t}K@t)H56l)HQkW z>%Bo7s`t6#^KLUX30bh*T(1Ted(IEQKcv_+Eu-=jH?{VglJCu^(F0b7m(J}7O({MX z&_=FkQifvx&8c$?-%DFU@(C&!XSQZZz$5R>4G$ysn{;r;t(JMZ%m3$eTPnqA<>=ed2Nij~#h$9Fg`yb8Z@@XFilVN{=DG3xok zFz8uABX#Ldrf2<&Tu((8b(F1->VY*EfA{xMJ8?{MOI^V?_>PtxGw^;pdK|9J2e?Jd zP^eNyo!A*Xby_R3S03C@V|j)5roTG-*d1jfPE3%PaL@dWUqX zX~kLOVdym5GmWM((k)3H^kg7t~16 z_3p|h^EPTqbgrEDb(Z0K#zz~BwmZhbc%KaQGCt5{mMESSFeM!i%&3xB8|!AqvRb!~ zD|vCP{E&zgtRzEPM}*64V<;#@xj4sRS3cXjW^6;R_P7Fc^pG}Fuxk7^dZ%66us(Cl z&>TA*K0Rtc8E}OI++G3VCE>SoQR>t+lI-e_cR)TJQq5 zS}QHeSA73$8q_VupsL+p`zH6t@t_bXBKM{Cm1HZI`dMDiDB1i1S<PzZ@AUxi`xTcMxVPIr*7TG*% z3GER?>Vkq5ZbflgAAtBR_`Am~mwKzd_lF>^m`OmeD zLkWqs=WEYf%YIneDNoKFjZ)C72)tOl8s016oq|+VYM;rY>}VbNx*Q5`PM^T8zm3$* zmNQ*sD}L`+sA3ce4XSUqE@R0oWD-Vk@_Hk%LU&1GITjX8uYkR124fJJa6at9&VM{y z=lPAsqt0^Cj6K=#QJI6u%S9vnnA)wBatEsB!Ie6?dUM&@LIOCT+jckLZqwGnulKT& zOXRTYd_RU%!^C}kIEE|tyjF$P;@3}DGLM42c}0_iCvtsb(9JHN3nylx(tFw;8Z6qI zwm>FA(>Jj|1a|f@bop2%MO%|6h&9^GsneVvwt0Mj4bjyN%BNk>F62R(H~5eK<|I?y z85*zG8k!97{8++)jV=^^8TTjxpNV;YT3sgW$v;7n z#}8VFjd>8rq`L1qU1*Z>mM#Ta?%5ybNyd?(+mcg>y}(T@9i)=0svMii+hFHD zumE_}C}ZPFBtzdq^OtUu^yH=%0h}jmzk?@#o&X69?!+ z{qw)9LT>fjNIaQvDN$k#h2Gz6V(pkU8iwZ?9#s^9k>m2mV2ZIT*J(2g;?oiDPfp7m zJlFwAqjUnhr7y5RZsz;YQwD~i$CS?GW3@p;vV_tN3~To&*Ol06hrx@XzHl4)7oJ&p zp6gjAS?L5ybTns^2I|WjH$ASdi1>K<$&oB%gK(EhIq}d4-d08OSMxIPQWSfSZ|EeC za$*h^gcjv{4@VXxC;Nk>JJ37&8R7bcf{;~p%-4WhqT+$h>bqPl5<2JmK1pDCY4bzt z;@-1DVT13IfUv1 z4SzCFAF0a`!H-rDNI&5$`pj~edLPR3y6@HMPILqsC?8_?C6C`9WF62%IC$xK33?2E z(eZo>d5)?H*vzUK2)6ulCHRv&U3C94-4UQi=fT6!8T5;VV%Cfry7og%iw{2)nG7qm z^b)0OcZronGJok?@@#pLd=lZ;BA-9mD~Y`P$aP^+g%kY6i&g_P=%k_13S?vnlv;@f zOr+>H!N_=p$mv+2T;)dmJW0ngktHSi_81dmFg3Mz6NAG^eMm2LJECOI(Cwu!sE4UVNlEP;dTpV|?KddtN$n#!C zxK*KWMbJX5`Eb@v(zP?=&E~641aIKYacLVOSaRzE<&p1v=lOW##>^bTMlACkehjSL zZ8u`F`P6-B5V4&wD`f2^9QY%J>eU}t21cwGm?{H zIyobjYoEKU1EGYH{G=kOs%-f|bloZ}c=6vU(s!aXZ`R{B} zDE^~oP;sp`8Vzb9`NPjytoi|##|x)H&leB)!U6ZX<7hI3$Qq+NsA}c`SJM_x2Z9B(h)?jL zE!C%7gtOepo=#^8|2D^ysbmbKCJS+~w@$LE@T7u@iP7WL-MMgZ9Py=rCdyN>jtwxV z1PY-fjixXV8uylFfO!uG~qRKQneqI*5tC8iib8#l6;h!1wE_ zWa|`{N|7p9AkO^n-zQ@%`3Opu6qwODHQ;9W@&2yNN#3@^G!4&)RCKz?XShT+Fmyu~ zZx287bE1V8eSzhSVJ4}yCmW`w^kG2{<2bT^z!{bK?FerheP?eATe%!THFy)yaoWxr zS?#cZb~*G7C1)+qAQcVt8uyyo>}hG?x}`yWmm~2Tw%g8s6&MI>bpkCAE{I32lC4hEWKivYyEkqPlr;CmpcdA~DVGgCTzp&8c0c&G zWgfEpqBnroK25v#8f(S&Ob|qdBs7T^xhhYYq6D{)HGMvfnd%1TxfQ&+ z_M|*Gj}N_AesK5_KaKGT51gWlNmUl)qUeyg#&6$RzHIkJ1xGu0EcXNj!~E-6>fRm! zO!X3BtDi*D-q`49OX(s*?R!2pU(zSlD(a-PSY94K{E|V(5mgi2wY*4XxQO&>u~L(m zlxgBjcQ0-YaEx2Q9las8Km8&^zPT)Eh&SSZ>k?XWxx|z@R zr+tvOIdJ|BBbzA`D^XMqUly;d3gX0?7w%HtI_LwHcAhEnypbY5mN~V z$_0{Rk|S!$6EH4~kLyEk=Dy=R7=OuH7Y&L1**;O9p3A$jxS;J+TijS<=oyid*}hZz zy;*|yDN6;GNKL2vlJ-Rvt@j2AuL|*STv5MM!TkSl^_D?ZhHJPm0@B?`H`3kR(nxog zBHi7c(jZ;Z-CfcxC9&wPMM%T<;@ejoN=7B*84usbzgNuUKfC>ttUAS^5yUB zeQZB8Nuh0-nCK@JCcu58hx^9d!^NBM7hDgu)&7_WxTXjg zITeVj9o(;8CX2apK>IgQ$uEOCuXiYY^!|+INfYTXhlQhtH(DqN`vlBNrlJ2ZlX>-iIx7rT4@%nR=>GO`nR?K^h|Jw-vT1GWA3S|hY z-k5O055PzC@yeq3^N77>OJh@O+vPOPn9$#O`fgfJ^ECGNZ}B*J5*z-GZ9~w#^^8XW z%{U$6E`Q3Gza3yhW@k>f;K-|&bIli*z42Q6$@kBKzE3&R_>xReAJx%lfV6 zs=~Iy=};V3W;0t<7iTln+2*-dx`m|9WcuEQ9E(ne_v>}Fw7p&wcu+YA8BzI4u#4}6 z^^>&KO@DJyT?IX-MTu>-AEmKA1Ug90SzSilO)HZlZF0~Di|;WJ(<@WCqQ3n!11J5L zT1){a;cw%BnVqL3d3Jb6K@C;sN2MO9&)oj0ni~^G;QaB3nT$G9(t`cCbmY>m-doU# zuC&8Yd+&{I5Py5e+I6sxL3frA+*VD4|)29`^{_lE@J34 zu;}xt3!`+?3GC34H6{>Jj{22y@(oC%gzQJ}N3o@|!@W(nX4?^qelNezKtEnfLkehO zkb?cysxZ ziit+6Ky7kx()_gpL zpPnQ?E!=;ghvFwq3azaNRdh|RK-774zZ!KXabGNq;{NUE6hs=;jdqPfMtOhkP#)Sz zHpngNCCKxH{BeB-$K0JQ{Y&{bp%!cAh79+~!anp6(%wb86=gJdg%5^O3V3_hp>Gl2 z#DtP{-!}4^a+}GWK9xb9VsmkvMQ?D)5b8Xr+vLVl$SG#3E=*2w_3qA?4Da3J@r`a!mphNZesBTQ$Q*%Msf1HRBS?=8e!grNZYygu;h^g5aYuLNDXKVw3mv_QIS zc%ua72!7O5x(oOuJ2pF3N{94ml-b};dpX)z(eN!Gfam7he7Zc5x3*mz$BfTETg*r~ zt9svlldX6jY3J?rbeDfkyNl23IH0bnj}pp-cJ_%nF+oNvg#%pazjv6q_%*oQd#d|t zEMEnv&GCX9>fT(ko_jY4wZ(5t*+!9d0~@!=7qk*5(O!^WCp^0HWDD+oz3mNPhD;-1 z?z&(Q7>r_mim+(%UnS||geB2y4b@;*+j`7z&6eEP+9IGGzmm_SUD#(@*vsF5K>M3! zO-lIm&MClN`C?kYhY8`%?_Ou;-leOF>Fz@fVV8b~+fGoY!sA5{q|&!tVFbvH`)jsML%*N6H0d$Gbb1o+1Ds zi|`;g+!=|+|7q)7`*Mu&(RI=9iyN`eW{w{wnp^Wtz#dF*3})BhFt-iQ`}gZGKOPw` z`kch638IwveAfp8HVC6_GcE1|B{OyO#qHPTX-n@Q|8is>`EjDg#N7|SDXvg z{m1rnSzON`aNnJvlD2$u(zGqb(*bwd&wQW2&h))_eiZS};apA=9%Hx6Q1GUg5xjL{ zLQoHY2I*!!TquW4;bw7Y_|9^jojqS^oG;J`J74yU&U3E^8$!LDuDu4w!8P?N#qoTp z53cU@1{7mg)WOL7@l)dRjoIl-Qmn7bZ+G;O@*m)i{+V5=KPee8AmFPsnhJe?j5*h9 z%|J-W#3d8d7OVzx%(Gb8wDh}>!vMYbgK#mR)_qAP0|I^@zaxuH?B2z~deTgH7dN}* zxQAw!Sp6;(0m8a)l%L)lQPXtV-;8|Twn&N1=71S^4yfu!6|VREn^sR9n?cHFls5N| z-{kSQtjrO9?RBEsmR98T3w7qLRa`A7i9TGKb=Ypq`AFy3>Xb)KLD>eaM2(pM7aQVx zl{v=THr({35hZK%hLKQF==JY;i5{oVuMlxAMJY$hQ+Moae{>|g0Q<7$&Voi)O_%w{ z_DodnfYA7x$REkv;HOc;PhZna{l31L37^@SfruF-*k_+;?C8r^QSTgpXWxCleu&Ag z`0*W(SMVL4BT_uX5J(X*PBAAXoIR_VS;F~pjxZ~7SJgkF$@Sn$$dP-wDZQA)+>0ph zcM)~o4BK|01%8(X^E(}o>*H|V7qg9jNN;zS5FMoN=U^On4R3J9O<_rBve02IvwWvs z812qLe2PM|6_G^Jg}a5!ChFHOjYTKA+U5%}7tl4!eMxU{e{1Ra#|zTq-ER=j3nLJ4 zno-&Y8Btv1SG=7#h)&kVqYf`u@uY&+4w;w4sC^ni6h#aPdY*<=9EPrFD9u=6c2i(*@n>5lqX zycer}2il||r_Vs>_W4SYcb|aRgJ*LERTxQa-SGupQ3%}>WP;1%7wgVoa!nA{%{oN& zNz}jKPH`|XLW`U@X7RKt+XZZ6*ps7~lqy_jKUBL0mWkfaXDOk2>;I?)?_>&tT&?)C z0)X>IB!jy5o8>}6;?VWUNvqAvd~SEq7&00NRp^eTq4T28@zQ@d)al&td4Auz6mx6J z&o?LZS28p#{P(WLMo9zDD<#~Q33IGDLm92<1)7UsG78XFck&VYXXDz*jV5vZhRNLg z*HMCi3>inf!}C=w&&SB~^;=UGVh{Iu)Gj{~Jkl;^L6EM{3coE@hwh)uOpkt<{@nL2 z5A3+_RpU2SQ1B|VcrKq$u9)9c|GSsHwL4CuS;NWRmreG-DKQ-CtvrD@GI>KKbaX&5 zmLtxp3~5s%g0>t1vy;JTp2pZN@95eh#r%}i#B@fB0psc}I!SmJEUxIJ@|5d1C~}wU z{*XNs7(({L+a%V{OVn|D$4=&xcT@~@4q9LQ>ETsepYD#yQf4rB@s`-QnLt7~6=13I z(x)E=&n_o!e!N7u0_a3_7h;3Qqp7wJ{5a!;1CcjK>`%jYhGIZ>p3$xD%F9J(Ne0UN z7~7UW!PN7wr&yGZD#XdwDuM_*);mc?%0)e=#)cDrgs>PJ&HFzq1VXP)h~{LLBIwg8 z1bD}s-ef>VXPM~qOGOp7rY`ZB?b&xS2twixru5@*&127N2z9xqT71gzWbcH+ zhR|liK7?=n%?12vbZfeyY{!%ux4XNHd5TBBMB0*g{VUEqcNs`q`bquk><9GsV+nuJ zr%^DGYCivl&bsg%jG~r|Z7lu02l7=0s4Mi-5$2D0+@^iJn&WE+Yv4zsDR`RxAJi9j zK%|xH#g@`kfsytI~=6T`OtX#Fw^R?YDv7jf1b+J6{ zvd@kT=Q0Ocl_$07>&u@5WWl}}?&-j$)tbJ+It=%#+$wv^?SwY*%)cZn4ji-QOiScy zA>VO6kWv)x1{OG`Mf>ePovk)GOKRhft^z18lY9FMkX0;og&1z7HL3gp5cEEai+WfN zMR~Z)bo%WN#*HZ+FG*V+BZFcTVk1crNxH;koaG_eNud>^zm+{IM3Mo~Ba&@b&C5~Q6+Kp}mzNuebw zK{)iw)j~&VJq_$<2|Ap$^f{y|v_GxZ)*JKx#~}rq-Q3!o{?NN0N&%4&d$-r=^jnoqw@d&0z5&@2P{H@FMKLN; zKNA>Eiy0s;$78LWR5+?XaWH#ooK!&kxDh3=A_zZEHS|S>wAx{EdsaAbQpx4+IUc;} zcEdS2{a~!iBR~XK!U(HYfsOKq3UG!pI|r{Emwzd1CgE+`mSKqIj-;X5rnY=2=#YfB z>zX4jxs;Z&Jx2%6Mom#C{@NOp8yy3CF5e3MT+&D`vqkcX&i=H05h?-Y4>Oskn_Gmb znmg4>dzj?o+jNH?sT8?%$ey?-`YcN|rff?;K2AjJXpOuk@W1anR7TFt7#`CaQ1mGH zoz(zO+Rzr*9*FSua1R-gLJJLVW>R)!nYi@5fX^tZfv%N6Nix445?Z*84A2GK)SI7XEZ{!Y-ayg7hgC@Fh;zG7g$A zsXw3As>=C6>Cz7(pW^00Gcz;$owZsXXZoD3Icj4>9x_kcpE)zj*z4g+CT`U7pa994 zK4}BJ6mCf*U#Maku1e>)_<>P0TXhYkNj(mEab-(*SjidhVQ406u9$Td0)F;JMlIt1ICML3$jn;of_rtIgqN zzn5#oE{{_~zpf`lC+bNeO%6pVOPC#=gG=4XPV5&ne<{#hjjrO0BHS`jDh5#8^^2m` zod;<48Jo=H%Xdz)iE{_KqdK;p`ep{bGX4U-s`??YWcqmNzocsXkfF~JZdf)xtFeT% zX{JjgO@pJ7uI3*-tWT!7=;ULcKL@^^zY29YP#|yuc6DaIdqn3(s$sYxDfvvUqRPt7 z&NWw;g6|uoUB?|U=Xc!khOm6OjIa;k$l?4a!K#9%m6h`=s6d*rdUqJC25A_Y>4=|u zNqtqY2x{##N1_{jJoVgRNd(PnDO{#z`d@0XCg( zFW>!Obc`Xot!3OW@HjBDPty#rQ868|VpdWTj|P=qCzJ}z=CU|Opp}Gm6c5Q38s?{( z+cu)5J%Ny5&M5K_xK)e!!^5t0#DhvztxHbQ66nRBy_9Uo%D&yRxzsbs{`p~v6+Hit2XWrYd7uo6QUv&fES=InhIk^ z0%_2VoH&+~$m)mRmC5q>!12{CcIc%v)`^|4T5WkgONt>MwT}yRC@<$*N+%k84cqNg ze-p&3ncaQEo7A+&tKWYH_{$L@O=a5ux;}5=c9)ikrB}USI?(HjusH^(2Ax7WR;$K{ z7_YE3qP(i@#FV5RX}~S08qE7jFiY?6+OR94SnDB0Oq(1&vogD+ceS|*ct2LkGUv=V z5)^(NfcT(ww7HcOo{@Xvwt+ag994|uo*q{G20!Y9;)$_zKjT;> zj?4fc%p(86!sOP7&c`g0x=d=XA(N9%1$7f0Ux%##ErK?UQ=|9;nJ3~Jpjq$Fx{@aM zd0hv$dx}O8i1y?9=ipVLppe+zZS1k(?q2*VYg^+C=rbY>##BsMcYg%=J&@2u&Ovkh)nA~&kiakJOfW?h_*MICi$+(OnQom7e$1>{l`L;~$rl~p>k zHCW==um*0qyIb{ml$(2DjzmEaf<^Ek%3c@nbHx+}2+c}3UtZY=RBNwC2DLvHn%Jq( zh|CE*zJFS}>+{wmO-mxaW)T8&3HtH*>U!_Edy~3`zXtVNWnioKOHcK%d}dUjbUK>= z;HQZ0_{m}C$O=6Rl`#$bY44DjQTYu7>tLmg+FzUAYQ1MScu%Ggi;7qeH5ZY7h;h() z@OB`}SIbai)Y@|p$Ix`Tt58=FT0uXBl6<)KP}xg}glcS$o!ts*26-+n3b(3hAiZ~z zn+hspg2CLdfdq=%$Om%rc24AFE7-~v#T z1di2l{0TQ-KfmXlrkTWFJE>UyceZ@dP)orsD4I+9g5UJpL4ROEO-VZrR=4_`qI4D; z<1sp49=>*8CNulLE9=?sSNpc37ApHLeq*jgNxNp_={@3Jz}@=R3b;v0kv{;9oemKz zSv(hFfLs6DGUlm}fxh3*{3EN~-t49ZDvjBJ#@NnT;==_LpOTiB*dbK{ZViElVLCL> z7p77E^KYR!+smpj^ZeoGozgKWishK`rJ^~rWn3bDkJ90pv;9M#1SEL)%xpa*I^Srz zx8cJ24O-M+h6fgq8Skc`vhs@*O6n(kW42DOOs~0-WlJno6TpxgFd?pn#f8IlQW+1h zzspDjQy_!e4VFJJAg$l0W6RmKh`UQuVEu4M8XDh+In@Syn8NPIYrmHOjZ{jztn z5GB`te1#Luz<@7&DYBpU=zF(@SUg2fph<^)?r_or!+bmgyu10ox@;(cQORkbA4^E zl5ekfMfc_6Wwx$vB9mUs_vxZAk-OAtK=Nm&d?!6y?O0r5zc`g+!k6TKtk4CmxVZ_9 zbcQsCdZ@j)$zERy3bwI{YlO_$7s_cJE8y$4jzVaKx)6neCqC@WoG0+TYXPD;$id>3 zEwpnXfZ8Z%ciQq;-Q}@glG7p;rkKj0F-E()MqB~tRD&RFL9%yY#t%PlUJ#K$p5&X#It6|L|3~kBA zQ+ej`wY`GNK~|dkBm9Z)*Ojy8rqMw7A3Sn)OqI{hS2(XI2S1W9i;fu1Sdx&9YXUBP z$?kq#y>K51#3+kr5@^#u1`fFOg*VKD3tdmY=fbji_aj?Pi(?UkA!$1WrRMT}6_^+&I{zrqY@Yiz zw+W-X2{K6)BnNudETi}`Y`)jv!E(qPU zQje}IzS09Gc!@`kEb2SWsvH`aPl-{#+2adJ$#Ce^E=^`@5NoceBmW$e5NGk^g=VKq zo)Ag1!{~_Rn}d$z4xon${pX85NjZQY>b_$7{q0!?cUSq_c`Q`dB3;K&Ml}Dq4!ECW z9d&X(uFBKov>$6@G*~HzQAqfL6@xhn;gX`Lqpx6o_=jt~RO?Iuk~$-yr+E7if?C9x zs66a)l1i=w*7yf{RU*=Vm)uTbTC&Caoe?#GNI6VTZ>iZ-pbi1;14rPN#my%N6>4bh zl?f+1KDX7@IuDDD(z)i>2Xz40yF^Vhw~zo>h9E-&E`1>U~Gbg%-dp0PH98)@G8_PmJ}JgsF#@N>t# zP{4V#uN-1YV`FrFMOgQ3UEJ=GO9Vl;1oqq_CmBgPp8cZkDq3I~1Sq_JX4Tpst$^P2 zAylryi!NpwaSu$An3tw*j|AEdN~Pi%b6DWc?mtnKT&r$l*Y7&nnc%vVc{mqLtSAbM6wU;tf zhO4cEicb*vL(d{t)*01=ZQt2r|>>+R(Npz`6(&mm)6QRI`&)RlWJ!FU>__Bjl*}YS@J+Uef8{tRstP2XuqQyA>K#UMZxM`ls%E@AOy@G%HzIq*#L$$>_!(< zBXJBrZ!E8mu*8TNLm12F{L6wp8jHkmK_i9lwsd`Jh<(iFw?eMCHEr6y-bYR(uZXH^ z&f`sWrFwVfr$S;8xZS*fvv#T|xWGPBm*zf^c18o=Bisk>gvS1P0L_Qd)D!o}o#_{Eb`mN-L=9QrkK)Xi93BDMYZC76JIpc1QNQR#0T_mz}A=&)( zqntU->ju*JDDQ$BHnR0;_wX400X4$TeeGK(W2MW4G#%>iGl36h_H<&1auaAeAN%P= znp@kA+-QWY5*9v*ca+k04JmZqr&Pn?*0pY}F=m3G#AUu*Y7cC|z&XR_`E!1y`cU$9 z-zJ{#_1ElfGbrNwLqeEl04=QPChrX5{y@q&{yVPl^Ka_C$n9VskLwxEs6lsL;4gF^ zyYj0Fz5BuuX}09@mFnVOE)gN_hb4S0KhR2Hi{EOBTo>L`7b8zW1ew=lIM@@nNu3<<3bPkKfO6 zjWW7%ZfR+#xf5RTE|?Kf0#&TL1twzV%*tb4%`t~Q(Hv0LBWm8(Kyifa2)kjdSR2soK6 z(LkY#9oVtucMJ3Pvn#30oom#+QyDg^j=UPej|O!|c)#NB*7a%+BN|aPZAYwm5vM^^ za@4ZVpK>herb~W!8`1SwB(z4oT_tZhz+!29i?<`xV`jtbjM7*CpYK-kF%kO@@ZmbyK9_=`*!mjNx>GN6JZVsb)2SyBj-k)+q z2Z>lO|IV~caZ>T@EB%=kg%Mj!xJ97Whz6>|JC^f?`l>1Ht-?Dgsoe#+pTF9uHwpA| zb+&YPU!|NF^c$!)A?%MxkmoL0RPGmvbN%6Yxa=%WVWO6ro1r9 ze!!w9WGh*_2Ff_|L+PL`yy`yA`GhZX^Ud_hp9k?Jp#VdsS=c0kJtBL$%(d%v!#sC0 z7l+H=rjQte_%%_ABs;7gO%1q%dw^5yLj%zw7z9lw{3`pjuY{j=r%??kx7cqvGTvv8 zqRYlmF14lHdSiM*b!dW*b{HGje(r|QbTxFCOfJiPhg|6`eC|28=Gi=fQfOvC{GzFm zd-1eVsP4W8T;|z<8$py=EZX20dd1&1u@=J7tYG6Z5VL(&a83gqhaN|O%g|xs&>D58 zk(8_u)X-JMmwZX7lC$jFM%gv*&Jcd?>_U9qUQxVtoUq;}un6uF`)PiBf3cAUGtAsV~ zJ5u@RhcFzfxqOV)agp}04ssp*w9+ypL0#f{GAgzAX{RGxPK*%$^ps4c3k|EEV7YUTWH@l}&6>}k{rF&}GAv_Xk4lC9r#twO&@! zoNuQ@iW+%?hUFOXJt+cmQ8bjlgUT#&SGH0=flMfI+3n z?|KAX^ZdMs^(b2%R-I}c|3jGmM8nT$qo~+%_$pe;7;It}UP&C^(VuFip>(eTSJL6@mtCfrCE_jNB=N>JV~@b!?oAC!|&m(ke}?$b-Vl2Na~`xS>< zjJG$Fv8v;=4U-$K3Z?g}J5_12Q8U&t7 z>@A#j#!ub|E-bc$>*yc(w};|F8zxt@@RwB1zfqPzcG20rJj1p|*%{qi0;9}wyIFv7 zsNlcvi6-&I)g&trn~CWkxWEBA?9bdS;(#>;(SNg3wxtPTPk9_q`j2Evv@Gp;Xzd_S z3W^th!jEl5ylc3;iPysqa@=#eFr<$k+xgG|4 z%6~v?@c*Ts*Y#f`sBeQk#6$A(Rj5KJBBR74MJb@WwH+wXS^MBAP)JTgYOipA?MHAu zQzTx(hISY;fJSlp=rfl>i>T1?|B(0C{t3Iv5OZ#P-<4@ zTB5z&jYz1Ww9NOs)(Y72Q;kH{@EInVVJ*!(E0LuNl9VU>40v+HFQsT>KUe|8EYzT z;bh!py(!ZU1n{S{+34_6oV7}X-tRB~6*(tNu_Z~8d5TMuvke?6E=1@dLj2Se)6uAg ztPDw6&PZ?i8P6}q`H_M+qU3X_7G=g|iMJ?8%VEC!&tSt^K9b>sETf?BObT0$9Lw*P z*LDwmf&AxJBO1Kfa#j|w!m8&yW_@PqOHYnKRW!~Q5@a>{+#^d(c`caO1 ztr=o@PMidUUj|~dbS=Lg*KR+8Kx@t|tP4bquSIjR_%G1;x*DyLh4;bzva7Xa1BUAv z7w|-{LUu2^Q8-4LW;1=A180I!~K{%@}(HQNLU5f4-V|y%?`M0v%E`3 zDLuAop6nTP8>P)@cc1Wy8zJvU@_MskDf&IIz9^*a8zSST=I3nU0NkZ?lSV*70d$xF zyR$rJHUv}bKCHs@>>o8Cw+pyC9|Rl0;X=PEvYOc8%$>*Rn!`DA?6o5JHIljZ9LR^d z_nBJ&V__Z^5Xi$dKkD+i4Bg4|A37g9rCB2pse8GKJM$VLJS`4^BP-gpukn!#c&eA4 z!OZ-l8KGzlJOY&DMX;)eP^xcuZ%$ArSM~&8%~0imP$E`nM8%9?lY}Qceb4xWFRQ48 zKZAApLKwqA@@#`igFz$2+_%E-rS2Rs1WBr0!HegZi<;2hp~4{~*2kY$nUvf*t7mEh z=3E*G_%v7cKz=N zIbNur1#kl>R=nK~Spd;TzebHYIhxLeT!QK>3bD9<;YP(5w>Yn9C+uvrw*ITkQ`KAi z3vtZ9F||mJW`dDWV=Gqu{qvteZuP9R-g6~`*Ii7yu7JT^O$HtB_cC2pNVu3u>xu7C z2qN~eU_{@8t3HcSIjZoe!>5`n7yV4()DWh_VUSnLT@yE;ZzB=ROfbRiO%ZpEN+U}6 zwxQ6qg#@fbrO4=f z0SXYJVL+qdq&&f38m}!BF7ShnzU`;L<9_gqCD_ph-)%mCe9j~E&*&5Af8(!04!BLj zJs=rsHWZW=g8`?k7wFHjYlXU6pJ@6}Q99oNm)qg&CnvG2KV*#*=j6GOH{EPT(#&PHG zGW!IS6?kMw|Ea4@k?CfUBwY^nYE{-%}BTzUQdtj zZJN`EcxI$@Z<|!SB{k?L0FZ>dU~N@fS%%NKue+70dP}*cK=b`|Mrn|(Qz}yyNAth8 z7(0?kS1m;YDs&yYHinr0=2vF7qvHVg#a2{zd37}f0j0YVPkK%9!w;=MOoYuW=*EaZ zRlKdvB1_yRd4-Z)*5}dqcS#6i*Q!j&j0p;ial45y>1s5Yx+u7DJq?n@G?RGsit1nA z<;(pa8Wttfm??6$hEDR+Je(%m{My3&%+i7mXqDg`rNnbf3dk0w_ju_a28#P zhI3E7vAl)?@xK|Z2E(m_PGKA^U8j}LX~gMYA;ww9q%mwiLg15u$V=m;w zU0{M7DApHdKKteFEyYqOgnh^dcy>lCvH$16wE-U7FOmUS;w-NOgSRc#+^g5v+Csg* z=jY+TG2GN0I~~7~alIz9Hw=zI-+o-qzRFVtP7>nf z*WR-~sO3d>q5HC4e3yB)XzkZWg{>j~?&w^@B4y}woroU!QDgj|e|$*Vo6c=8jlzgNV*Th+Aq? z8aeyDq<_01c{d#U#_UnBuGs}B0FOb0^r|na;*ntK*2zP)hjA zFdLSx%Nf51V@>uuL>|B>EK4}arO9yPYP=98wZGFGR7<9KG*gsVD7(x>mDSfeuVk!V zS;6Ka-Xs^E4k{OzUF3OB@H0W{YK{n~ol`t$vBhO2Mx(<(>IjWE;iLFpW8NRcbO})p zH3A0|-8Dr@AM)eZ>4U8tis#0ub!D7}D#s#YpB#yu|Rj^kX_kS z`%>#wNKMXgIsOC93_n;PF)zWEl)lP$#dJ_;#g~~MHI(TXuq|;|Sbh4MkjmzC5ySQp zY?H(P%{P68fy1SdeJlx_%DHsx(B*^?*A#V(RAoAd{&3}Q+7m<$x~xUfY6yXo@yDD- zin^~d(}Cwbo%)?bF_o3bK$CW*aRH6(0Ay%)5A8+dxg}{kEM?b3$yhW6WVZRps-w11 zn(^C8Oz{*V?a@HV$ppa> zu!3zoyyYBq=T-pM>glUx~kcF!`#aipj0<|*6=Gcw20-Cl|Gn7s!4^f z?WqK)F=MpDs=l55b+QkoieieRrK1UH@BCRN^2=bvL&EDA((xC{AwSC|WDDs4mXf-!`u58MbI9;+j$4&XCb7U>8<(svg zsB=}I9cUtsEVnx^m{zjF#xLx;ZEG-qi3;pg47OdyE+{{CZv{SVU zx|8s zG8HA2K(ei%v#60O5HXl0=8paLH8AiY=msmiGfDB3iM6Y%+;fDG_{k!a|KB*fABcZN zc6z*%Ou*E6JyToni8l1^!Rx#&3#eqUt|)T~w>!Y*{{_4dC$=hV`hV#N>Jaz_W4vXW zsPT>sa*EV#CGw{mozn1g##s~x^sp4XDKMp60Y}0`-YF+77}@{Dz;!6{mfMCu0BDW1 zafiEOih`v|lVuJ`Afe=`lA~QUih@fHhu!NFe{XC=O)^U6bScx{@Q+S=gFWdcA>w;G zd3qTb^*ZiqkOsyS7I9{otvC>AQ=z%<+wDJAA1J4cLyW8WYcmq*n9g81$$lR(({z#^ z0yi~IC$p| zow`NfiqC9AFONOV0!1sqs|KJR)*yA0`$AFbd6iEm7Bwd@1Y=spnQ6tt*Z=2S?D6K3 z(CI7iQb!yf=YwMtFD%kD(cZC$k<;QFO0;?Y%Pv3wmSM19xkMf3ihFyvnY@xicBMy*5l4PQcaSf1uJ5^^ z9%5pF9Q6Ju0R_B~_t}}u5&G>li2_Gj)=ZHMNLX$Cu?%>nDw4Iu3roJc5CT%e=QD%c z5D$-aQA`)^NJ}Dtel-p&eUjn=m_5Qmh8>^5q1!7F!k?|vBHWDxB~>C@kP?b(Y40-ry##DU(p;ZW)=YopV{*?GuBOWf=ePApsAqBoPMP4C#m0uNjAwY~cW*70?dlFxh`Vh?AWfm$-e07@*?0HS0S-)FOw0qIR zfhLWEiSj~SesC#0el;GT083z%2yYuQIk|n`!$hHX7%G!}tWT>=E*6`u^{9lrIV+9n zp(gafj4HwSw36xa*KB)%zQd_xj5R6DkkF}y2`=;{F-y?vN>EOTZ`ABSS~lj$!I#BX@(Q~QOo+3i+ zB;pczFs}i}2dL$95Ap9iKWAt}-|I;9Y8bZ}`E7R_7K%+S`2j_M?KWq1t*Wy7@+#cd z%P(V$W-Q}1ZvgSfOUr>>D=JDV@xwvGE8`FUmsrGSM#XMhzpfJ@l{x_ImL=wOMED-s zk!Ht#&88*9cxq&ntX9WaxmJCpa(^HPjkw#h$2o~el$^OSwWKGN58bVWP z?1|b0y_N)};h&Beh7DnUKhXD2#}4zC8C$5WEX<^X5a?5^&dmrqE<>pV0ZS_LpR-$D z1D97xyX;!eql~6^&e=@8fyWSU&7y}5mqYb&KB_p|XO(%5 z@oS!aaa|_LH={b!Qm0Y!zy#c^B5dXor~T7Ftj-#scFzGIA1ft^9xu{R2Q^I93;u7011VyY(4L#dia1hR~OAAd*RlkgMm%KD#ppgaX7 zBS!?4*Er3l%RYyL?I{2JB zVI3C53eQ&t!ku-ZWgm_dxf(|KPw^*(Q3UUUw)X-+6} z!6wk++BN^g5dN4D9#)2nYeFrFrD000%8n5Ua2S;z`YVBIz8a5{2%9e+)6%}$@rw9N z^77`%*tAYP2=4Gx)<~tg-g$k@ z0$RXN0a8KX*W~%xgBt*UHeuh6LMQv|i3h&+-B3B^=aUxDP{Kmb85$M61Ek{NA|Tb>WN0Zy1D2hNe%4Ydc`B69)}z=X>OdMTU4>bGo|fsP9Z& zQ0s8vcG_Ig{vcq1DK6+sgKniqz8Uv{Qt`6Lm;BRvv` z`ADjB@h%UIX%H^a5$-wAF+1OfIZ!-W}xY2Tp|(*PEq}n*SxEZ~O&CDGuA#Ui5JHf-02sp1-lZ zEa!Qq`i;IOdAskUEiNoS4gBXC=wLqiCOIPeBTX?6mm_!MgHnK)&cBZx&G=)68jp&+ z9mf4NO9B#i&dEM^;cl>;G*y&j+x0a6>?@A*2w$Q+#wuA?V#Ln`=k+BxWy~&7b$T$e zcZ~y34*++m6XP0mg7ZR_{d!7}DQ!pmQ`9reoT(!zTxTv`oh>i4h2mj$!)Q9b1>b^m z;5XaP@A74=1f^(W=EpQ^L8a!(fJ{a~r-nsU2dyA#v3{3LD_A78^#g^cKGBMJ)uDl39-~h_5sg z{b54=UZ8Ka5GA-&5{?zb{gePV3J_>^^9luT)8GLXQ+-piBdjWaN2)G8a1X!8#rl`9HZyQbZ@zsa+kF zQD@OgWzAH>q_yh4%a=&I(Arps%i~#m+Vi*8nP;mNQ!A-c+-ZVf6dOF4LRr#Hb7`_5 z-mc8)VvzGOecc_oDBrOMmaS3$;CDEuZ!cj?cbUIbicM!j`GMW-)xG8Bh~0;s(~ihh zhi}pHAGX(&_S-5K+`?w(%80b+ji0zjnUZJSMFyY`@{SGgi~{_ znKiQ(Ejhg5G^`xGW}`c-b&-il?b6Cp_fvmEY`@qqVNvsG2|Is%f&@yiBo);WX(-Bm zR*C|83FK}GO=k48iNjPybYO%9l4ldKmOs<1!W&2qS*6t0clJo?%>~qOt!7_Oj`1R+ch2J`d93Yr=`|NyWR!CP|7gHj@2qST%5N=03%6fOq z*liMq3Cjt{uJ%Fj89@*E`@!Rfwtdps%IGoUJEW&Um9w`Ntm~$Gi6QLbvOM~jNpn#q z@;j(QX!BQzyg4Er!$t@?=k;9r!aGSgrq#4-@h7L*|t zbEfE1fiy`hsv*uov^vH7RR;I5hj9+$B=C+LY^yK`we$&&W~A?7rv!>i2BqILlYf|K z)Bxwo;7yB6Evq+7dnSLlm;CCQBBFT-pz`a*p9?udieoA zQ}mO?MDQJ4SUqWH^VX)If9HJZe(3M4WE+5Y;`eDD0p?gm0G&W^AjJ07FXTUL(gmN* zjUVa3(~+z|N;uA30DHUf&>(s*W0t}lDEV%Tz!k@Lab2wENu`*U?{7emR3zTHWExf4 zpGe;(ExepTtMex|Jiip3WQPTP0lec_@b>?e)q+Rh8Xk%HQpe%y3X0$yOJu&IjV6CBtwKq0vsCRbEnOD+mqQ zn`s~)L^7rQLi+kJ6CASFShG%FLccytPU+Szsl>{`aOXAlKreE42EP2=<@v2FSk5^n zw*Dz`&Iu9LG)HToOMxojZ0`>jbMuYnpWV{LJ3 zls&?L3KytXNQo$UZB$2rZFX>Q*cQpSW_O2w6j6C#_np zVXxIo&;nep%p=Jf2|WLKe^KYlf&`n3yKwYGcBvl3gHq1E|A*}{b+(4gkVL4>9AWoO z{C@?+R5tu0NqL@aB(M~@`uhy8*6ycpm^w77c?(~`>bRYz3Z!st>BmRttXgfCdV^ck z{v_7^xkPX97}O{)eC_e-YC(LSK{v|1a20YW@iS1H_llMGna+gD4Z8&31dmx#$Rk12 znN#NqJtT#%ywY#?_MNX?ISObSB)RUXm?=FJ+Y zw8Q7Ae({!|n&X_EEF*n(h)Wq+2(}?y2mehzqhA1cV05_0mhJcl%I3df*?UndFqTzw zklQkBZsRx?iw^ulz+#+0W>w#QDc0ZP!5z3)!bo}rW2$+aST|-oe>oq5W=b^yxKr<= zY=ipBiQmM5qjes2K|Ln~ibx357OE8@R0L5}1W6zEqk#5@!nQN4G92beOa$SML$Iz& z;TkJtAvELDrU0u!@$4}t;Oht|auv|8wx*`U52OqY!fd@#lOO`l*2`s<3<4slCTWq; zRo_Zey7uY2tA^7?(SR#7q2@W`vALCJ2U-cRP5!sA35#i7n;eymXyHSoAY2reYEaV);4H>CKDkQ{DMOy%ir5c`zAk#=ZJ{nbzX9HoavX3DixQ9Wh zJb@CmL&BSy?l7(tf+GQmja+OFlT%4fv?w`Hmyw1;P2T|K$Zq176!tsUjB*`V?iw=i zU5-->xu*rG#jH1qakfh7Vw&AXAqMW%J3-x<9ZaQ}nR?nq>PEr8(oc z-47F*pVScL&w74=(egvs8#<_+SZvD7S;rS0xZHzpz!c^s){37}YpHVUb)6CjL z!DJlsB}wFSQVE>Yu~07qF1wQA`2vmk(lJv3qb5H`>6e!U+6R0&l(*E)v zJhilQB!M8SO8fJ4;8XE8x^X_atD^?gftDfEI$wW$k})@5xtL$m zevz(mzge;|(x_P;E*~lmSn+C}qv2QbgdHRy?Fukn5TrE|yBy8xCYyZT7GbS?(3a&4xBBofSlftj{V19jzt#;h)TG8rH>c43jC?;uc1@J?&&C zs?fR`R^h_6~#fG_Us~zK6z+yP*aHaB6anufI z8f01tk{!1so4f?T%>rAW+jH-kYVs=d%f}Ka(`?8;o8qGNF23sT@7?OC!i7YvAS-fr z8>xZ+|GsO-v;+`2_FGs5!P{Ku&_G5!lW?Kc1(G#I=Ts;* z*w+w6%ld<5aTsDrT~XnXS7UX?#W9W3%chtdy9_S-fB++3?geE+x+86D8H^3r>FYUb zY{pq&O<9_dz1-57{WurIN#CDO(0LQ-c&aZ*2KJ7Yd;@}ukQ2O%PTv2;-Rj+W3x2W3 zXhosBr79~o%43;GSFwotLkPBlr-!?)A}(t@h8qSi^wtPF$SF~W-@!R@tuvy1nLdp9 zzg7G55Hy2nG!3zBrCrxe{R;-#m6V4g2}S6r;R*$l^0k%~W7r#g>c1v(P@+f zDd?%LdOtl1`OR3X87vV;VP5Cjh{~0@BsR3#do=#v%|2o5mi&nvAVRu?KI}2dP2Sz$ zB&BbYMg}BE8;eAOMR4{=EC*w>jLpMI+a^P)fsgasb2IjwaMe`ksnClFj`Be)7qARq zKOSH$mQD?n(hO|l>!qiu!K9l=^i%&6w$+jZe3_i7-GeP#y}(N>a}#0hmfcdr zo2qr))&b1@2EKi9K&Bv6EgLg-VbYBrdxQ|SUE{pqtK}wH@2wknoZkb1H{*3eLdpsPhkOAj%K-Vw?Yv~MBC&kl~5m>aipP*L)p`-iA>5jWaB8%xEmHpfps~Qxj zY)ZA%y7^eBiphe-$0DXc{(gLlmJUc|BfpHwL#C0PdO&Ch=QT#kJbl%87BJGXOHr7o zkXRI#Xh9^3qE(FNwmnN57VVTcKOyei;yjL?Yh8|>1zo3@sgVB@0_(pp{_%vKDUA$% zs`6uARiZdM(^ByN6CVqUodW_jcL(bH23ia-Fn+(c2D@Hv$8~# z3;)K5lXbAoh@$#Tppcl4>3k#g15C%+31En35r>;Bf#U9wa4)ddB@D1q$DWD;`_Ib( zD*k2E7MNh=O|ERpEVFnn)H46QNoN>i?Ii;kud6+tKpwioh75#4Iyi`F-zTU*mvt| z5xADtCc&$VVz`)LrDz628_u0gJkSySZLig>$@0_G*hxw(f>HWYoAkIG= zD@e5;3tcYAgbuD08izhx=%T8%UnxHM+~S$+*YS1ZIvlBSQ$z@RQF~Adv*n=xHG_yns@u z{bJUY_Q6+WaTR1DkVwnrghabU1v_SNYN3e|5oE=wRhAW)2sFBx#V-q{gQJ*CrJYI) zx`ig}s*s+ra0LE{oqlO<%Lm(=NTK(42Flr$C6*W}Ll)ZN5#&v1Cu#zaKSG`B{cEV} zT2ZBYR}cy~PJ!A(8ovX(gID5jJfWW=&}8G>l{q<^W>G%bXFptW=@-PgM8oShNKjY$ z`(yenZJ_e3gGj>AZ@g_{-x*ev5Sl()8m|ch073{ac2vJ86^<^WkCjglknZw;Wf5A ztySGspc8A)>>QbhwHudm^Y&jmp@5A%63hh{YAIpF_v&NQhd#IQvH=TgoDz%vu^(Q_#*Hq9#|8FWi+< zqhpfhGUJ%1_cKegLf>g<8wRJ&L?$~l?kRX>**x>3zt%+DVwdEkP6-creEEFQahoo4 zQj2j9Y))mVKqk&G^xT(gf7Q)czC7Bei9cSWKc8Nxx+9i}XM%-i{dQ5eCYsNL5bpCRu&T zVL{(6px$N6k$!97Bgp>437N?VsKFtO;fT8{-nO82s{|^1)Q2!nO5&*`6J8sAw-QN8 zGBB0pL?y5g70IBC)-@D17uMZn^khX$vI=)UCKS0hQqv~Hp^yT@B<+=I(DM{+icp;S zl}5UNP8XD|-X3H7lN_Kqw{~i5Zw7wJtG}(t-q-n5zu+odK>;`-IK=S(q60L^W5^l5 z@gY}zWWDI*Hz_}i4SqCMj}QxOL~9&^Y1;c@S`ZX+fhaC#rVX~Nka5H>9vpCvBKG4( z2+1;_=X@<3!WDB)F;+m0eA?G z?bRE42v?v+$3wVk1>tjv*XMP}M75X6gw^qBj)YVA@`nST!iHy(2X39cjF#Wo^9lxu zoHe5+vr9-;Bhoy+AGMX7E`Tbb`O0tm>NSc-y|VR|ah;p$Ksq@wC57Y1;t%%4fYgvG zM|ipKnvLHexgBP1igtoHG;O%po`@#LfQ7L1Ns#_EBA6`xg_iT-{exR2=^A+;DSxv( zp{zVyP!FlaErP!%Nv`Cx4We(9PZRIJ2$%dl5GlGmQM$1I$D9;tvJASlKT|INX?%+C z-V7TljSd;Jvi2?{8Cte+lycG*6gBt4l(GZ$m>~5(ZYZ~)ddcP{{NtL4UCWHP8-4_9 z$%g;OVWmS}K8icHBH z_Eg%Dc&XDok}AJF|K;ByN1BAYNV&ZC*U z^Rc1}SZPZN+(C%N%W!!mR zBf$}hPJgqGHto6x+_KH&aK6|foIbusfYrfxs30J)%i}hg=TZlh_6;xR>2!tvrv_~F zfzC`(n!^c+RY`SHvPP|u(^x>-E<5W_!BcaL(^n%5;l5_h!B61S8!fW{t@ z_mLF!*`aI$Ss_=?NV{APQcU(RyBH3Tz1QT4!lOUeSIh4N9Y8~2-bGPDgNnpS0fkGR5;~)ao zeKGVzzyA-+vEsz9&W#D*tRIfDO)u$h~K$4c!M zJuDdk-yBCYUYcR)&76rm4vZfu^ya5R16!aPuFxdo#puRvl-E_&4G`e$-z;pw5+8*t zmZ`I3<$(P))mq@9YXX3T&pXPU5hn$DTk`m9f!>hR~mgHEy-SI|9J!#t2c&4xi@^v~&&viP{`S+MVKm;LkM*wI;`mDwxW|`(kyKif^k-hUugW@uv)$&^_Ok zsRGxd8WlR9Sl4$r^Z{d;tU$P$x{x+LUWKjeygD4Ew9f_d?ma>JqEw7xvXCYVU;@2nsA9UnWI1q*0?#Tg3#FPncOB7ZHm2(bIc>Oi$#0MYscVYxB!H>a9^?|Ar~=^%wbd>=Kk8uM`n+Q}0Rdu(a{P@fI5gABK0#$uqQ;zB~$3_`bxAFic9 zlOEn!M$2u>yw1`A_QH~=OSf7%)lmQy4 zq_Ywuc1%$8E~WVU1Ze?d`5{KY*LRg&srx#Z}=-Ft{%O3Ish~e9A8#1x#2h^C}~Qwdk4r6R-ekpm2{A)bB3rrmFHPa%I*_yu}qU|y;&BlNqfov+&{ zXxvF?jP{OaZ8(y>4=p=aNos$oTl*rWQAOOfQTJoG^h27Qpma1&(oPz*khhlB8MnZI zXam!SvsqhbUKKSsImy_Ecn#9)C@`-tzd}BQ-)|drYfz?#jzb% zGGX(aNZsJkXWx}$m}@&d>#J`-fI?K zAKS*3YYIK+qZ3FWqq6M&9)!A8~bvkD3`iI13)bh7{ZHT-X;%Dcb=NL zQ&xYhOcd8M%RnE#Af6@(7OP=s=*Aa~k0-VzhlNt7A}i)k-WY^u23Z$a$7$BFe%3pQ@X5`=GTq+P$ODO7x;W5z$A{EUQC?n=W6eK1MtRop4@J>}ZjpcYk z(n8!zJvRd>RyByzN9&U{N%9LXOil02RP6Yals!bS@O#*%w}~a8+;BDj7AMMAY=(Tk zQg;}z7G5;j5Hu}U`3m^fJpHd{@xO^13n7z(Wg?(l3ef0lydJMkgC2M2^9K9C43856 z682<%W*h0G78f$*@AiNafT_c1Xk2`Gd1+bAw#<)8c64kKCJfK}P2241GIn`H!P&JR zWp7=0L9UPvs9yGJrNmU3aH(r%XXq>2YAC;wvlY(&?pa$rS8^COz;pgs6yT5k5sxnW zc6w3<+VFdFTiWhb8};#wMAK<_<_vX*oE5cHeVqWrMEyZ?utHZ` zM%t>rxUQFYmk#QD$SsFNJg}0YL^dww`eVme()`1%kgaltA65jM!}pEyt3mUt8=s3H zw@9wMqQYbq(V@;{T=7sRP3fg~g1bF>V*KtR4Fg>c(%#SVwbMO6Lcmf7;7|om~ ziZrXueEx6sg&e3<6DNTLv@?GON`3&*%mr=ZGu5?-SP|!OODMOW^DJMM#2&10m>qM~ zUm5IeIE7t18_Djr)jzcpEoTb3-9tohFYh0*>8b~h9&q-oS7QQFSHGPU6YZNsDx3wO zh#)m>#9&+W61!m0d$n#9m=b|QNU3zfg|w*1nz0nW;3n1l*p121&06`Ojqj^dmfReV zYGk>+#i{Fqi(i02ZhhIcW~Ie`7qWhm`G0-7;|;DC==^WH@5I%>rBifA-Z*fJF#190 zzaP`0B(`ii<6$`A!L&>-L44hBqlZ{2a&*O(B4+v&)3)sCx&M_T<8q(2w$H|Pe@3!b zWE}b~q;F@?6+%3E^7?T3uLk#Z@df%i$#W8S4=COvgL?D^dt7A&$zXf-kBN+<`AFhl z4C8N&8neRwU@s|80GGG|W}n-Cc9F6?(|PrlLp{p)C2{+8|Otx06-!*$MuC?1ds0te%aBiVVjLBJL+;2OwNF0Q&8T zRHsFdxpkQ;SOPt2-Pe%T9b?0>w$q&xn&-RA`dy(S1Bh#81?62Q8Sl13L(c6i}j=yjkyc9nATtD(mJmmc#0Pf>GRL6#wfGZ;dU_BK@2SDkwb)D*7tv7_$ek3 z*ywkGwuxM-nq8h3!pK$iS+W<#T4oBMp4Z((Z>eg1WadxFl)h(v(9M}Cl#M400*Kj& zaLCoZU>WpldM&EH~IlewzaBSFT zIkQYM2Yvyy_zkC-mTZs1nED;4DmIu?-UTJ9Tx`3ZTig1}ZYvAjO%}9m_V9q>tYhG4 z$%7eVgwLs1?fKn3p0w}!^s3q~U;!3vi^k-Ng@9|?0 zRA+yTM&?$|~*NN5GN)M04=;(X4C~`&8 zk0v@0Wjqfv^1HQZnz(p%$c-GzbMx$aye9l=YUE7xfbZ%6a$$XL7om|~opp;6ony*R zK@laneYX?DE`r7o(@-qpV4kv6qbt(K*jJ0x%2-hKmz1orbR3K^1sK#?Im@pHn$lHI zks9H13Q?#>0foI+yzN%+h2n_%=jO5PZY;O!s+~4!U}NbBu+vP%P+}QJ=XrDuC`1F# zEMT+!Iq)hFx$S;inZ;nJn|r-kl+)wgH~EZMg{YZA>3m8+k1Pbf`{X9m z^P!{+SA7I)YRoI<67Z^g{Vj%5!7)~TX@)c?Dn!_NSJ8Sq3n^d)F=cHE^ZP_Ad($FLe!6y zcaPpYAe`_}9p(RCILr_Gm{K&mXInw2J^ln6H!%g)52NvG=|!B4f98edLlBLlAS+U^ zHYQ4AK&mnL6>F-cnLAmp&q=hn_P8Bg#*zOQBQ#nLy<#?j6T=4dJx;6b_Zi+$A6yd| zsmK=Mx*12U9JARThy)41Z>HaSBsz;1I~YgpD^pbtA<;BLfgp_n1U_}YRu|VjtKcJR0yh!g3s znFS8qu}8OXKc0dORri3_N=r}d5ERrfDnKykQCg#HyU}Z_X=}stqk0hq{u<@R)tX$_ zp5GOW5K9*A_BY4BYXNZOCh!vG@W&qAQoj8>nkn-&_6^<7Lxjwy%Z!X?J<3njrAwn* zqFcK|RRE<;pxk+j4a>hNtENWpD|Ro&cRj&`yv;ierXWZ}^_H|RD9HQ!$JJ$K;`iO( zkz@vpGhmXM7U`DoejW2~T}@LkC;y+;TT6Dy>_S@w+p6EMZkd+m`T-}!)Lp0K!$WyVZ@CSA96$*72OzRlefb&@9Z-0$B>?u>GgO9#!9D*NJH=#`jvu- zfTf|>FuThSJ$*OQ)E|eZ_wFZf{r_H$T+?By7zUs!&8WMM)B@cR^S_bRI(ymr8~^;ErI2a zX15t&M@1EByAmR$N)Ag5K*_Wxl}@z~6`E4_&vqDyUv6U-k!l8NUM$l=n~s-Qg0idH zCE{e=uX&RBVf{pTu>>mlCP#Q(>WR^vfnR9`$g8X`H!nYGD@Pss^Skl!b*+BV(h`5E zrw>4Xky&t8e~f@a{8S0vm2A|>+$2K@ikhsNXWEv5iK{s8D!IrBXUxb}aC*2a`Il~ka2)Y()v`fFmjXNK` zdgG5G>}mZ@`);&t5V=ZDZ%~S=&0pfc6A+(tfqMTb9bl%JUfVOfj%e{>Ixv)kXHg{( z;P!Sc(Mf}lBUu*1QWBFk>cED0J=R3d+3C^`F$<&t{1yhs&e8NV65O zf=Hr+JIBrLh2^NnmV4_i#97ExQnL{LeZ-S~SqW`n?r})G;`C9${UqP@w88zYu-hhm zl|-k$>HWyjV!KJHi*Sp&JLj_tw1SS_@P2Gru9OG1X&X5<&@v~U)XGBoI&X`Wikn2c}VmUI50zKEn)xzb=Ma`C1{KU(S$ef zbDzbh@j6mbg8ey4EE27^fR#E0+sN0n9;5ZbGtiOvHzU*-i2*pZ56mH1hd6*$yt!uk z24Y6MS>#0+h&O+M?S($ru+G2H>vkO%RzM6+MewEcFpz#Qak*OitAM^WuZpeI_SlAp zp-5R>oo;a-ExkqtNILI)5P4(2fIE0>Kl%dx%C^|9DuGTB$b%4~6?_G7!X(aygfzM_ zccH1zpMraMCb5Yw6Z{m8KFxY zU0$xM{co_gA?#r=k;L&)*+&qqor`(nG-%TX??IsjI3uuixCfnog~0pzi;!ZrEK?-< zg#^Vgc8UrI$o@PG0f-l3Oi3YSQKgezMYl4^hH>82J(a;oiz={8HO>lwl2o#A@Ter8 zsE6B1Oj2jaLrC%t*Ig{l{qxy?`GL2_6by_rRzO#_LI;y{V4tQiDm2ab9q7Ul4@JV* zH^8z}1}ajYc8l%blbuO%m@gd&=HO)Ru@7I>(jsM~FgxYzKhtWfiUn=G7jD(L`KhRk zN4|mHk2gic-ARn0q=iXq089c0yz~wyBFGU({^%7Lw;;iQK!?3Sj-79x-9QDl1G-As z?O3hbo{NGVKhN*c*LEl=c{(G9FXSsN^jOe!8TA%r?D-C}q~B1k{_@MexFisxY|o`a zi*$NIJ)!hZOpt5162O8aWiClZH`7F6K>6X6GfW zp@v6i7Ksy>(1RDHi{IEY6Bk`&QyYz!a*he&H5F6v%5BK=o;l+glY6y^H})LJG>#^_ zMjTEbA=Cp3%{!isuCl@@2I$vGOcs3R1AQA|^xJOyA>lQG*{JY^4&zc2s`mk3YrgJ_n96G}6lUAJnLghXWitRpoO?yL^kTmziz{t!9 zIytLHHXh+0JL||jO*bf~z=i#g;9emfcum?vuR2c!Ynlutnq&`u2{IN$&)W?hFVLc)mFeBB9q)XMkvakFV;3aU}g_$xiV2MzrCyS z-Z8tT{sMXv;6efcbQ}6V7%IbuK1Q(5-&S4IH)gsE&jlUn*pNF^6YW zh((#+95BK28Nj7H$e`P|n(Ux&I8ftZz(z+yhbPvZbM*9HSJGO#CP7d$i7t*KGg@e! z;=ssIlTvPKSbNqM5tT8nZB|7>P555A&?2P&>`O<*clbm30WStG(~r!Cv^M zf*i|s>ui6NHopk&E%0}{K35?0ATgN@ZX$a+=uv{a;|ZvZbH?@;_Q~|-FVQA6wA>{^ zp?0%MFBDYg`d1w>xNHTKRgg#|6r0motKpJE`ZFGE?{)9Cb4C9=gJ(cH^+<7@OS!W} zFZ=Gf6Z$k@%y|At^dRbV>dH7x0DhaUos78H;UUmDT$QFCxLWc^JJJz(l^o8OKDQB@ z388#0G`k3Q_&4_$LbTpL0xs6LdsQXVGBGA#YT#)FMb-`4!7wXm0BUeYx&+j)hW^q` zMF!{|=9=bj#vt-}n%h{x0h(O(L96>*SOFV!?Z*lw9ZzA7El@u`8y*S$9PrH6 zKEc*kY2xE0B2?O2Ai!{yZ7g(C9TIST^%L6U$=D`o5@BVyr2JdyfTK{ zs7f=s(O~m9)TFdZHn*4RRrNE5ciC(YeWrN;i+fld8z$(IyQmP;2vEHSAP7FG-q&*V zN@TC?Q8QyCTVqk8Z~!tmgd$tJT&h)rW71Z`$N&$704t(g6zO@%=y)XG1`TpiBvG?G z&cMqB+rAQAtO^c&U+>3%e0H55TDrQrnp_1oy&MFrNabKPM8TrYI}&Y2)!Ih8c&8j6 z|EiIMwM#!xui3s?5GNYp>WbZawX9r(RFNki!!&57 z=CmKe3TA>QYf)0-njWank0I?OjiFYI$Nw#r&@yEz<#&|pOK##%Z<1yJ24MS$c3N=u zWs2L|mnP`OEQ_R@pdTkfyV5r`j$?=*4ja=@#c8Gvfl~6m>uVzs4)Lt|Zsk+!^Bw|m z6$KqWaiF$?mnfrwaO3l0Ar{I@+`%%}lq;c{Ycq-Yq}OojGqgjVeGslSdb?Bp+VdFf z#Sgf7=lW|lRwl!ZylA>Z$H2*O0z4c!pNNl}ppUpq%>!gohvG{3D z2HNd?uFc`0EF!Sk?{;3?9(p+_1ho`oIEx{P0AC}(Jq)Mgbd&_z%~HZl@esOraFeAF zH5V9Ax2Nd$`AbwZtVD?vR$cDTI)^j@&u22*jx1fLirinE#HiZMSdCOe4cbq#>qdKs z_>?-$&0R~ZMdi$W<0bef%DM$cXw^MzW0kpC1JACl!9zeqtj$1(tah^qH!%XvDHYE9 zb_jy5kE#m3`+40+!ZlkM$TJQE039-*&FwPUoouzsi)p90GE+0eKuJbQ33C||U?jI~ zBII}Z{`x>I-)Vw8`k_=C`3IQ=b1768{o@v#e~7o8Oy~8<*da^YQbh56``m6{kS;Vo zyAvgn?J4^2sffCJE&BHxpcrRbYN&l2auofXfqVfygtUM55goNLK+!QH zrxL-$Jp1#Gl_svKkB$4Td_TmSen*bbu$0&6epjw3SoMD2O^=Rz8Kzo$rT4$9f57cF z$-65@n+OenLP?>}!&vG8^Y3SopT~l%*%~&u4|&lR`)nZ*PSM;y6`7i?yLo+w12AbQ zbUR(5)-tK3v6>Xu=cm1BjVT6u4y}Te8ZTq|e?DT#D#qY-W%Y~OdcFi{64~C5f>j?xC+L+_BXPZog`*69i}^JmthGEFjAFl zj9iT;`Xdk}8tnF%0Ue<1?zfwPVSU%ytbdnne!#bQS3VdxuKz>w1|`*T`$rMAqGoxv z9b>ZpkA8Byprc=}c?sjB*42|w|Nfw1{gRX#RBb}5<4nZ!k7>75I@|aqONPmoXgo~oe+Ds` z?d{wOoM0PFzfKQ#?gY?-)>CR-Bwrsdi;S5|=V?BOFEL8&4QUQ{SgK(Qp2POm*fkwL zId}#~6I78z`7BAWE?EE-tJhI0`q1B}nIb!f2m3iNw2cw{9;!ciHwJ8Aw4GNd}#a8pux=^+^sfe_!l5&4-*{zuY{+;NS7 zr;}ol=&GuN5bePEC9oaF?MBb_Ne$TdVRT3CDoZUo8jmJ%qr^37R$e5f3>_6pj6x_^~x@ z{~O=ygKAhlv)z^s*H~;`cfzjkY;4{HrK3yyla(}N_mU4(j*lk+4j=&^>9z5C@4W>o zIxC@>2rj!k+WD$dt1BeL4)DWcC8(V0Pv`T&SwCO*jO^ag#PLmk3#n80z)uQ1CkBrO zd(Nmjif~mE4S-;yzRzu3jeR(zbrH<_p-~k}I$DhGz6CDfojUz5@)1&iZ@2qEEnV6Ch;;3^$i@pYX$hSt z=x-Gw;m2cI3Yef9AX=59KHRx4k2Bnpx_=Tfb##t$8T$*(b$G@C5O&Z(wL!_5NT2+%N3(@CCDvOB`y*bVtO}|fF67S^xZv`@{GzSnS{M3A z?Z3x8u#r;KhwI?!iim~kv}8U~X|dQC(2gCg6N$bFo|D?}O}MZXgW?{?-(b6AH(5#m@kJvYNk zUhp%2^s@(@U%;0jQIj9kq;pd%wFx&H?}m9$k2#(~?D2QO6~e0pqVzHN8Exk>3-vLK zYCVO$83TI|aoQ2qIz7(XUCz)yUod87a&fx}kVZCFGLjjio!znb;VfJe28Ib~WiPB> z1+IYMEGa2zhDmxFi{j9u(EXVh;CnW;l1g>1Cs8Nb$NPJSTfWac%;2Vj^nKoO)1pE_ zYJSYkuuPUSH~X5SAyLuB1mt;r{}%p(*=C29Tg_r(`YMXacqen0y@Y2nbzy!SJ{$P~ zmM2=`bjvf5`y2Z+Sb(8efXxljuRYh@f?-eAWX=K2J@b>pS{1h@rzj-nxOTPHhag;4Fk+3?|C(E~@N|hGgXl3(Btv z*^A!9=BFyEft$8WqcfeC(o+k=7SgpB2IgnlYtmr@?9u%7Rux4=AuZ=)arbXZojo0l z_V(HMa24C_7A_boSQPjMCpWzGnKE31=%QR$a_7T(!C*J|8Od(rALpNTSx~f^YGGsI zS5e~|^&Z0IsxNmhW)6CujnzILd_ONF(n1&_@+L?NKG$RO{FTdnplZ6B-{P9&hXXHt zpG@tqW!}wX1gn{CI;kZC78q6Z<8MoC6j5d`A!9t5MZeZvzS2&~`>lfrOT9?(vjxDr zCY%!FnWIs5I&={nF!#P4PfkG?ud8lNR$g`2_}M{q269)&V~c25zg`(Iw!XF1^cZwE zEvJ^Nyfm+!6YNTuqzB+oanSmKrH%n3)p^NVuipt#%-u;r4m0TpiA{3b)DJ~z%+rtY zJfv?{BqH>Hu@Z(hho}3-u710*aMt2CZKqwY!bbwhCGI32{Jv>IxB|qjCZW*_K^k}N zPrTBc0`v4qpQXv6fp1Jh`6zGwap}`gs~nyA$5!N!G*|Dlrw4qc!YUt~&n7@b)57qp znXZhO6DgEPvC)vHA5j}aI7Re7SO8v_sFTHMJvn2*t4;;6ZM`p4y#{p|=S1L|p%H5X z&O4QzDtUt966EVj{%4WWjFC?J>RjzPVf;H?L03vp&d(?5whmwX`(OdC3H3@?-?*|( zs>sjJyY@oU(Z{ zu@H|EmHW9gQyE13E+CnP#jP0etBPt#FA%Zi%K;_}hczFkQjpyTi;F|Pts0`cgl+VT zG+x$BoQX=}?j9bi5ttK4lPuI53dkl`KuiUmSEZe^-Rj^Jf0ebHcsLaUzuiEo1+wk9 zVf?Z$AU$*vok<@#09VZ7(U~Vxa!|n$6_1@EBi__ZeO}gJd4H;*op^Qo$Qp+7*4q{c ze084%XyrqDyj2P3@{LhyL<1ZUTV8u)DU(O>F@*Yki{Lbj;f`(Auj$>39Vi$W%W|bqdw;*5hIwnu5&&`eh zkfxsYd7V-308+fdZ~JENYh@b3HN}|jVVBQOtZROA!9Uk#kj|U^G^zuNt_gn2#H!ic z<+ZvXZ4}v0)RQ9ao^F`VW3wgy@sNWOMM#+tjw#FhtkVtZXD6|jj20nMNAjm1r<%AIqUY5}u%?_? ztgN5Id2jGUw*!gzYRb+#0mYu!MlmdcB$gFYVi!hQ4Xc#wjVZ(8(#ixBd#3MW;k>_2 zE9yG@AtaJYwR@}g@qI#_@9lV|Y#@UePbj!&Dl53cM$w)z7M%u$j_a>9*IwA{7OAc` zP67iQn50jl#h?6dr*#M)Ka5L#n>=opfn7ECNjZH7Efw4v-InCz_7B*_q){$)qwwGx%dJ9)3HHq=dX~j1+FvUcK8XsNHQrp1g+J#xZ|h zdxp7jT~ITx-4e;K6Sb}7?hF^$KoOUY@eztl=>_3}^M3?@@65cC2XEd#B>MFPRzhcE z26%ZgvnXGgqx!<Sw(T>x{sN!nXq2U!0RN~Cn zB8;n7BToy?zrEq}>sfM3dwG#nf&NGMJYHw$;@*>dM1(x;VS?p@x28q zg+BU^@uhM)UZaMVs#sZwk(>@e}mdKQHST4 z`W{1PoP8pGSkJWu-gnTJhR|2Wl!?*_UBgjU&T%En?Xbsws9Y=q7G~u6TE+2XaoQ6P zFK}g0Frt;-N4iTugFuKC8ImFzfHLzfTuC9k0-IL4{4vX{PX)7kdg&^wJg*tIdkzT$ z3v0;7H5}vz{LL__l;m6kwLVTJAjYP1I$%yhGwy87e4j!Qg(-4LbtK48v$ zp8~SY<9fdMlTMXXoyx#!XofiItlRX!`?6~Qs!Xvvs3EmzIa)zFl#40D0f9ouNNg=8 z^K9Hc0(f1qRyk~T>{_UtZ#y?C`u|1<`(3L44DWp`U#jr^7(|ER?XcL~@w1~=0^^mX zd$@c)K_-0P!u|&tP$5Wa>-vFY_!yvT_&{Y%?G#D9BPyha zg*Bg+<_^+{dh#jPaHfwY_~By8dd1f!^0YQ(df!wYhLGROZ3!{b361r0tm5%X7A&CW z<#b)(Dvix70BnppAg9vyl-y+uFHuKuJNyU4#$XR6u-C4s^g2sp9MQA|nAGQ+73? z4x6kG;r@|E-TSa>Pu5cg-r{r*_t|h;TO#O7OiJhHyMIw0g@9Uf;KhVASl znU%ahNt+Uz(f&Me;iHGgxEjeAOD8LUJd~uJ>H-R)LKG$AP>6T;>WqkD@}CyTxQp2St`489FM|KaK8dF}QQ`c$HEXDH*zZH5iL*Jr~8 zVxCADS<{i<6BAK>i5tH5z~2Dnsc}Wr8!iO6MgM(D>T{2QRvNEwNgrgW*@=9jGO)+> z>;`-M7~=!Dbm&jaa_2T@c9k|oR;b(ABWafqe#t+oQWp;!$&$^GFrirrb!ZqEd>&`> zDPX1tl7#}Br9cX*aoIyf?bqL^>|=^nAzxBmz~A_c(8u4`ryFGOoU%Ew?I;%UtQ~Zj zN>B2uwpNn+nf6N}@bcm5)#`Mfura@XpvdI=Lssg;4jzT&-x;Wpsh!yE{y#fOHUz_{ zbRjy{M5a!?sD6W`H_ZGOt-CLP7NcIU5DSy^j$Z<`MzDkC=O$9uaEbj+}9}PaQhbmF3vJ{ zUHHk>RhX6X-%oV)u<~MpTTdR~&vlCV`Nv9h>EKrLrETOC*if8PPpa)_wqK6#X5QJ6 z=c6kTK10}V+qVHLFFwQhslhUcTI_jONNo)jheK&C!lT9%*?E^9!=u8A;nXw{-*uvs z-E>_7Pz|~CG4W*?20seO#QZD&jXL!r_iSI}SSSyUDMw~V`?<{F!zp9I%v^jdO)aN| z6Zcs>0||%q9t;mLMc)Gw2~Pg&D@Gn67%E`yuE+irU%z(V)}75QK}6%;>-%llA}@JY zV0P`WR&ha9QHN%z8;%Y!q6FD;!o6e_e($GHv_kXqnP2k+R0OM$b%KK1xN~Y>KcfA1 z|-6hd!@UnWgdn6PDg1})ta?Qk)>y@B1 z;KdMq--mx}>p8oN2EcMTcpWt43;aCTIyWCWxQZ#TAE&%xL?F)JGoKwh5Lao|p1Q-; z6DQN=)h$=LJ1074_CKoY`GO%Xm*5NVx{@GzjL;^7SyH2qWDZSQtKLJ1`0aU@+}}oC z3d?S=OqxclEoH?CN!6AJ;736eb28QJz0gVp1lg43r)SeDetN_YqjzG;P0td^(2 zXHSE#L)HF5ZWh15Ms;qM{t;;rDhHO?O`ywD}HV>kf@4LXl( z`nU#i*f14(W;59q!P^J$`JRizVnTn#?OIQXv)m*G(!|1rp&tgm7hSUV*#hXaMX#aUkME{EG;4}&etGEs=({FQyCU?E1K};{43}KV1q?$w5XK?T8R6IkiU(M zn0=EYTv$COY$K890j6H zl&!Qw0!&|eO;M$^avkP(*uWt>Go8;!F27n7wi1TAxlG*C`4$%NA9uK9X$~81<|=KD zr+6C4(YCx#TL7Z;eV*g(I+_GcoidVcZ?<2ldh{w^i-yR#Q>G9U&PyWgRpuIq-;iR$ z2O27N*ah`!=}RG>fr5`!h#!~6oqEl_awd@j0w2ka7Be0dh~75I3= z4fHLC`NKBITD${`h!XMYB=k-mEHn|6$-^d3$311VrPqV|eTPKTMD35Iik_g_VG7!- zm5$nJ$I_N&sXrqQi{E_u72iZ!bN2#6NFUQE-kA5%5#Ir)wd*YLj-=?9*6TOPwJj1N zpFTJsR=1%=iH8ZP_`$kQBHsrVpbbV+(Kg@jtCJ%&!6fvQ_FnyEoKm43zQn&PMJ(fq zVXWE1aKzfJcA0jDR%2-6|2mUTHMlQr^yrnV>7Z|Czsk`Bz#d+yQ1{;CzAVxgW#(}z zGK_uRZ#*8wIIpnf7|qmgo?6EF9NO!S&Zg_HPv#}ID^$=l9b)eMG>j9} zdoXT{QA<*8pqJ$EluZCmrR}>g>Xp!Lq?s*b`q0W>x8;x#DY8jHOf60n>O=H6cPp%n zB^sv$&s@N9C(=P4$ zd6BSjH4v{$Cjnt`>^&?UF{EozqvMbPXy$oB>nAn@9RE_i(d(CL64MxH6qu1)LaHAr z>@;nk#2+Fy)?qTtI!L~eK>pv{-Z8cqH82_t5?2c=-4o{=9M{ifFlvC!KspO}KE6Zr z3+)EOdqhZY%Qp^PA%um68a6h#O6mx8{&cXJqJDlvLSEr@WO6%>XK3(oDP^2}T&Gd5 z{SPG2ffQ6sev=>Oh3YeQD|Awix_c1y`K5H=Ki_joqN-XZ);g02$ZAyO`o^2xU7d?kw}5 zmOM{UB0P8pX~zHlWQ9qQj`iV#UtjRV$?ISEfKeGC1uA(QvyEU(@7lLVvd#flWanp< zSbqUffoV@z`V(zi`kg~#Idzg%FUE_A-*l)gu@4QppV)~Dlkazq)xnCz5BOTT{{6I0 zPHCv$z&BL_s6n8%z!wwW2EA2geoA%gbiR}W5cUCFc^q~KnVMM4zIqEEo2QS4yMX_M zq->L1)~5GcVJ7BO8#5Ml`dIiV!SU6I_qyQvAUZ$fsg@GG-t*#OC>%hhwzjn_g03wl zHk<8xv|HE>uUcOgntmKx113Wxm}-kX#LxO2@zyY^_5}d(XD?G+QAyEEBk46gD^$4w z{&OKpbENfZ8xK>ZKHfrT$K-OE%q?SWNxbya^r zZKTp3)gDF-5mc4eZKKq|*Ug}Fgq?l$i@^Q29xsj|qTTwa5Uaa}Ix_9W1eG*huj;8u z3@qvhO4nILxo>P<+_%RO>4ClP@-=1+8B;~|e=qYoJ$6t+5y2=e&tt=Mmimm95p6J! z*UC1uNqJ-jL6M!ZyF_W1#;8E4t{!pXPM2lbO0e~&iN~spEJAAfG9{Ol1r{hyEBi6xgCWhMFEkM;UP2zmBVNes{2;LbQ_?QpsQe{P-e%(X0M$w?o3 zUvb%}q}CPS9h$}z>AC|DG9=(1UR`I>PoMA>q-o3X0l{k%biz)osz%y^$*RvHi9Sc3 zR2!)m10}OOiA;QfaF0K(TquuG=|e?m4Q7BHOo6*^GbCv2pjaqWXv#oglhH|<_$w}A zt`*$JY;%m&g6sxR&5ECqkeu@4I63sl{nD5Qj% zKCbK2YhD#EAsYQ3^fEqLC<}EOv&pfipOX=yoH@%P9P7I#2f6uvfp}kSN*O;*Oq;L_ zR)#x{O_9jn_ER03JS#1NP^LQ_7DGRPX#^HAp?Cm2y=;&3HQG@)WdNoXKAQFaK|9N(uSb=sVpB+`&vMGAsmeV}{f=*K|kk_$PbJ+z~o@ zj`#5liqvm6vfn)#EWra;@_sk-2gR0MUk1mv2Y9vqOhm5K|4lpy><@vNaqzGG#g7lz z{c&G)>y*3zGy)fzmc}2P;a2$}UVD9!(SP%A3Mm6g(Jk(xUdiZBRjICeaW14*9ZZ>{ zj}`ml>KDz}UQB)ek`?fj&2yA#wS~v!nWny%d&Zr=o?+@%S*csEcGtbG9XjCKfi~CH zUav+kP2xb7`QxuBc0}88hRW>^;$Qk_6T;+YR~V&a$`ZymF_y2xwh4ms`XA;`^WWT- zAvi3H=~B)=^<#T(iz!;|xUx12(KL_ORw8chej#85w(GBD{gBQt~^UK<>?TRPll7s$I%?B`Ug9cKlxgXQN->vg0>XpBCqDKGTse2dv zHOuQPZU7988@44DvfX1iUlXk+#9`&Z8ZtBFR|?<92}FLQ&HcMVT0lsfF~3lbC3sfq z3wbnDQ67*|HmbYqZA6&-MPQirSIC_F;R)iJ*?LLR14K&~6G>@|t?+&}%MR?-lb4|1y z<2J$|eP@PV?8mJ}9?0o&+ly{i*2g6`ceUK_aV)G>pZu+&bbVX?aChl5mHI0(m~Ay% zgW(RXf}dB+V9?DF8o0Q)=%TL_90WWxWe+;=>JPb=S`tK1hglYUUl}~vIucf9$);j^ zp_x`^Rn6fvl=mD{ZaVamQY@p|q}64dqM0X2;onl0^WENBmsE?u)EH=R^{Sl|Xn?*7 za@4@>I{Z>}UOl-&ZbCv|Kup8+YX~h`W0w3%=@64iaDQ74a~z~d<^1$(4nr2%az+fE@i&gP zY#V}eiaA|}48M(aotBp$^z?jinD^J~xPgmnbGc1%!Pxy=kmAj^54J`xCxxLezMj3e z`u&p3G=vi0a95tH{k0jsyw7}it!?Caa1CQs?(i+X`+{!44^x6K)RdZQ>!e=OdHwEJ}HFdN?Nv-gWE^Q zLiWfhU~tgheV9W=E?eQsxF$eXI=iZV6=X%$PPcaZHDyd5mFAkpmXk#E*h+=J)>NPG%R&9kV4uUj z8$*SOtC=g*^R6Xiy9-MkDs?y$81Q$RUSAQPR+pHkNWS^1eyw>t@whtT zQ8|8%2zc~#-X=&Qspp+DC<1YD6V#y$Eg=S~@qU9ghl-&N#%iYbV3-Ytz*x^;>ZG=j zWkBIIg*n-m)wM&-iY?$5%jktU-}%ny@`CcN`HKDgnnWY+kr~w66JSx|e0X>8;%Hf` zIF~yxreA3FT-A^~!K8VqLBT!1hEtQ}y4e$S2?T)XdE8kl!B@FjTB5cIS`7f`a>u4<8UdR{z0iMpKLNh^M}H2c`%<6NEbcsYm=#te;B*S^53C0X9?M z;SYOnqrq1@tJ$fX7f1T{f!A)w0OQ-57vCzCrq4b;bcq*Gwusxini%F;H`h9PQ zFK>aR=PY=U@1Af(|64YMD@Ak=FM&9NAouVI>7CCJ-}p-$m-h31QrUy93fJ(^Tm~|t zpV+(b9&r@+XWWeZOE1ZK;{5S*?9j62C{y91W~hGE=0>OIiPhyApV!JzImcLigW=No z9G>|qIC?*^-4O*sJ`a=jb-f73v2&SwweEMECy6UU$KiDdW@GL4uU^jBtGZ^77nrnZ zz#zNf8-ytN!N^Py!=H>$F{{qS8c#^Fb+#Eh?dBuNLFS42^c^rkP3G?`6iNW*SRepm zKDCOR4qmYA=t8LsmPB&FklSA1VhJNCd`~FyS(AnfaF}<<+IOIDw4Yr^t_Rx%ncozjOKA@6TuzTYg;i zCaH6?t|#7>vVAi7JWy`2D~K3BW_s=6&79j#%50x_#yFcUdO}`5qJIpprI%36H&)kW z@fju}--IZv3Ek)CHy`Bi|JYbw-KK*V1pQoLaNrU9uf7McauvPFLA&?jxO};~BNmWE zNeM+Cg4-kbCu)jGvl>ROG(m`qjoZK5Q@_ykH)WSc%8H1JB5lp||Y1Z0RyrMscupOQ~;V4iv1kNQ=O;sL|I3V&LA z%mL>2m7l)~0-BU15Aq#CV5s1HF4SAKDake0q6`E0GT-~iQVKGjqQ@ItXwo|M-#Zyq zlo5ni0;9cN*M{crHoE?x$=y2h2t9m=exT1GrmgPrcBG?(x{ zP^k%)%%1=WHD7;UUw?YJOQgponkB;h!o^91X?mt)%M1uLh7hrFwf0qpTHTfbVbBiU zzeW+QDlr@kCLk}jYR=U)kwE8ntiBV-)TUT4fPb(B2R-X!Tx%c-bkPbG<1`*3%ZyQQ z5HzpzN-44>{EYZU8dLliL|Ni|ygeyJHqDx+_bLrL_>1>YN9jWQACf~0`;OAF+Y5Y( zJN3^+>~sn=7%r?~w5G!$gcohIW}QPiJ1gFmHEL`A`kcW>$+AIUJVS*uvL?Q|RL>gz z)3Vtw)HJWxno4;>#q#X8dWzA(M%@y(NJ0;9d4Mn_6wVG=akmp)5>QT|Y@BMqU^#}T zgThFl-D{_afaPi*{S6rSR89sBEMc=$^n2$aP-LZ^%*@VJj0#mKa2j18%-M~Lu|L1F ze}e#0qJ*IOo@pX6SGSw9%M$mK?XmL?M3(-%1Wz~7Gx0P4GW%^k< zGzJZ6B5xCqa*5hJS~Rm(7xu33LK1> zJ?*ipfAzfjH>Kh4LPJKjoFwbU*bEN7E)|T_l!XIp|5LU|5;Sj=F-4ThWER{%&0_?HR_RD0~%F`*}OHvq^k|$8F~XvRwDD87GBXUifj89${)Z-lX@DVs?j6W z80Jm91_sH^ysCSByM{2zN~JGagFt1MSE3f%9IX8gIclrzCjzNLSbBrekRV5tKnf)W z;%%3^M{@eziDuos#gyMJgmqcHi4e^SJ;!RJh%uH3TIr3YeGU@vMpm49C0X*e`;|5? z8A;Bot9_cVz;&U3>}zBmh<<9t99>=qRS!i&H8Fdm&CmYyqM+}gqb{@)Pv7&A6cASf zLkEBXH+SlKC524Sl~S?WNtA&~`6WgvZ!ZtKtN+tq{`r$`9B49zrp8*Ui1n!1#q0fS zZ2?liBkkH0WYu~scWgTUIThvemssGR+Ut3*z^zcmA!7V-oq;7XRIqo?@+*ys9kefThq~jx0(f z%$}L=7c;oL0>N(OUy!rPViocOTV6L$q_7K@Tj8?TD9g_{%e3ZJ@`cCkHGLNxB)Jpk zqg{FX#K5OCzh8+_m>NjKtWmkrZ=DQe!9D3AOXL}FdQW-_WMULjV1r%&?tu)B13EXfGPw5O)gxU>#!2gRLE8FlGgQ297&&FAgf z7vI=hD}F;u$XbI`lVx=<$cU6cshJ}YLJaVrgm(HVF-1H!{aaOB2GsWZDx`POa@1lL zFQ~^T6*+L%d=PgNA}ga8`_w*3s4oCrmG`L+*yqrsLjpj@W;^667jSCuxt#0;I#uzi zw$}xiE^77m|NIqjGf-FcJHKqmm=rsNpmPrUMdd3o^k=EZm#7Of(#QJQK0!ESJbb@@ z4e@lz{tUuTsEZa6Fw5|M7aM{PIL+>c6Lb{vYu(+>{LC|M))|n7uuAwDZy&nOxnP9uYu?=z#<-+$h8p!JLs_pS&!;XbIUsZ=lbboFWu%4C=3CienwETnAu0YecM6qX7~7d1x>z;{WAO&79f`N=}c4HU>E-pU|n0$*XBMk zqEc$!R10NaH$XlC8xDP6`IjZs(duQ?kwnO2FB|waN;@A>IBF|K8HX3y(k8=|7u7FZy`8-!hK-JH`fG-KKk!eR9fU^YH|K@`$LY^sT&-j z$E*puA3)hx%jx)UVrlW7V%+81z}c18r#FwTO-h)vw1P6Zq-_F-Pqnqxm=cp(V`Ze` zgNP*6i>5D_v13nM;vfZM0a|g1X*uY6RqVS>uxlefpt5Xmmn7BFb!8RpEj{b4>8siM zA_v%LP%v21n<`JK@ZssX3C{7CallMv0tH`wlmXGO3SAa%<)hC(BHUhH7TqzDO1>*o z7I>~u79pM?iPtU-91q+z6>n$HVZR0JUfbtiIGZWa6S93fx4r)LNWB~AdHdyk9Y)q^*pMXBtPxxu@1GqMl=0gKB1`qhx^O5i)?>nn*VmsO z@8O_JxeT71NpUWeG~^CX1T0T8j!(DB994>Rf!a@J6RFimG1SijHG}}NP8STN6FV_6 za9!l9D{wp3DtoU>u?rCl&o5sJq4nmsdbI7Ip-Y-riE1P1`}CSZjrR!9K^h;l%*CJ>#Ex(_}9DZTQ2-?hX&9}Z=sWfYbz+zm)XhXzG#iLCS+S1u(QFn z@bWGTTAC~wr5+xdPYOsf`~UGiLN4wdLj&txB1Epn&e1ro3r`7=kh#r9_+*{bg&XlLEwB|68<>Szp1XldoBUbAJSI?&Nu2EZo5pMl>H;Mr$&hSXhGuRYiH zn5Mz6D&yiiZ9%nx)cTDpBWHFWp&!yuEijPdYYERUWUC5${Rt4CBe6@nzJeGcepd7) z`BUz02d@g!OYt?DlWE){EwVuSNkC~c6pg`#2>G{yi#dmdeG5&(7)uFa>0+rBsr@y! z92L#4>z|`gYJS~x)jju$WZFRWfN=#VO`b8zXsBsm!Wt=YWWkG>7HJUpn>FwyQ2!Ah zI~9+tB4zwdE_xcZH6b0_yfVZ|Art{VU~|u=Yvq2lEuO5Q#Ep=#hBxqeTI;2SAYPWh z5#Oq%g>!jXgZb^GYR)-Xk+`do{|avoz6SB@v>dAdev*h&MOoQB_~Ee=hN1F+(ZHh# zj3>O3xI-^hFyDtP*qDYAGwoYUQie=v2Q^IrkvT*1g=0XSHHjlVUH5hSvYQZTd)>mk z0y{;XNeO;F9-uSek}XeN6;^ym8Qu#4TrsEuq0DZXZn}%DjO{x$W(Qf+)AY}^oAl9r z+LWiR7ERYJN!GZaHKpiXTjKH-64qmiJrP7E@CVX^ zN&Lp2`;LJ@K7e8~3salM=U}joZ&@DmP!VGktKJS@2?3(I2q`3E+Av@EC<?aa3K3b#{YHM%h1 z>5cA7cNRRAZw3l0t2)9F98aV1i*WiR2icPo{xxM2`Q$T>)i~mP^T$swN&`y_y@g-U zV{BquSvi7jVg@0~S1E>0s6z}Pyu^+A#`Su)P7hzVG=z|IVL=L;tQ)IR09n*qr>xG; zc`EfUE&|EHU21$0v5h<|_o!xL-G?$!s69cO8{%5S9sA2Os$^qTt|= z8is!DIKroU{@O5HEs;%R3M@vR0P!ZQ;qFW!3;+Y!szRnD=oyCTKl^tY?~dHbN_km$ z^dI29|Lpq%HWJG2tY)n+N8LU)EiG4}OLg{r36uYTO_3YAluW2$ITBJ{q zk;DvI!!#TWQ~B+0nR2`28q`<40#NBBE5$2q!S#)*su zwkB7}@x=PMxu#s})dTlv+Qihf_5tbb`m)Gn~sWx85wC0MzH4>#K}i(U(JTW=~y$#||% ziL3kd1;wDO5)7h2zSkD?${BvA`8DT^IX{1PV(8SzrK}fsG=2n6QhUo z{mTUp9fKNY;-@9;aaZg)9>BAQ!#ldQh1$L&s1_d>+yP!|Xias3%i?jFTIw0OnzIB2 zrVQ~H(w1zXm-)w@z{LqKWl-Z$&s??0Q8m5>M(j+OU9|tAGcUHO>E(6tpa?tW@h}y? z=lLa2$h(shOV&-!a7Wi~x5g}n)#B_IiyyU*JORAmPi(oJO7eE&7*;FumHaRGt!tfk zPf{cX+1=Hc2123zXfFq-&EVRJK=w`{@bW7uMw$xE>>j9^;9k_#6TYyY^$N9_ATMC5AM35)pnHziER7K(rgtaRJBRTu8LW z7z88_8WD`0cy!`vh<1KJCRT#7vioe}2rDpz11>cFm?1rQ#}vhJ@Pvu)6>nBbTqy8% z@@u*}T_W5^6nK51^uIqI1t*mC^HmXYm6TUa%#_R1+ge#E-}w~-+^N3~;+TJ-fA!lz zXKIuXA(esK0UIjYv>7CsA4yZdIyoz^=vU;g9_~dEmn(IQvwPl;k9{yaqQ-d%`4pV3 z6MB3)*hwV`!whr*l%F<2NMWD;_yclG z%z&@82QOP_l)EFVWfC)AIq6=88t-`>F5^MZ_856az|Cu2_3!+H4&=L@EPT4yIFNDW zilNgO_yais@2`JY)L8>y1&C3uMY?}~o7(E%xa#3M;>=-Kwv6J13SiQ

_{!-ch zn45>ZQ}iDOc7jlje(u^NqznLjr-1Fz3ov?(Kl-`0V9~+v%>UL;O0FE}fL#_hO*7Vj zeb}V*d2An;oi9=A*94B!wLP;*I&>VT+@TUTWmXjRPGevt`3E%Qd4E|@=3XswLr|L@ zoiu(TP z?rYpP1~F96HTeNY<-q4eR{NaC^WMh1s?P>C7O=GJMTi-&8x|Cky1{pXbeP(s*0}kb z*ZNN(Fxu@F`)^kpRTUDZvrzpi17Lf2l8AJCNAfROmf0)FF)S`xq)AI09Gp@}AWfKR zTpkV$_!1R6<_A#Ed6)b=;u#GBySH#ZT2!`Y9QO7y5aiUc3R+dL_N7CDm08k zCZ-YK*cJx z9r4t9k7_Lz8NAM64M&42|kW;ClO#s4UodH9=N zOgJ?IKj_}@`Q_A|)&yMOpK$;(8^JOue?X8S_DkX;l((*k2(LYUQJIe~phE-ZZatya zv9weN*wGhARkiBCfr?vS2d2I`xth7M<*kF8O2fMPwSanbDVn`ukSUO{b2i|PC%L{_!dPWhFd?wz6FJz^i`>-_!T zz_?A*461C>tq=P?)|vU{NX_1!@ASk=@>4DP(>Mf=rZ?CWT9Lzk85`rEo8Br0c5aNz z6RL^6!@A!=%O|J2m-)7du{c-c`vS0|LP%v)1R0=9Ks8jvF^0$7N=?~~Y@%Se&#-nx z^CPjzfJX->GWV?>16h`+R@o!V{W;8y!QET_MbTyx-3EIzvql=rTn%%;Vd-P~Jt7=; zI>BxE&f?_hD>!dq=Zj=|+NR5TmEHV%Rh4ervbs9!qQ#7$dV}eDq~nAR3QED;TxNgH z`l6(Y*q~&)>+#n`w=lR+kr*nK-BS2W6u6yG5wNMRaHrrut+p}S8wReD_F7GTe_C9^ zv_-FRYrRdS{FlJ3`R-Hg^)YnKNQ0qH!`_80yc|B-o9ESQ>FeId8n5jXt}pNhW~w2& z$TcYrb|H>=Td@lQK<$|5a>e7NQqMMW=yFC(Gm3&>M|aB(8IF54Rdt^%D&q_P9Qo_KLr&MNWgxJZDJK z7T-YGQgbxVJMU@5sYE<@ILiL%)O#%1y`FmLj3HZ(?2i+z%4dLufdI^I>p#p;84Dvk zd+GId(H~1NWinL1C@nq%o7HDUw$SqoT$KI*v60*N)Wy=pz>2f12{D(UKOj|RzJY0r zt6;b^Mm>*wLN500fAuv%tEyHpDBDITGzH=sj)9aP#`0iC1pJ=p_ITMbiH2!N=Ni`-Gs;yvCB1D5O zYHfEQUfXx$9RMD^VH#850|r}@fZ!Ceb0}8lPM}F09+IpQre;0*v@s}`9=n%YRSV0j)aP_O2akTLHIMTILSNs@Y)+>Wns4-^7I5#2CwNXM~s7k z+osk8?gqd6S`Gr{*H~hMoMbj~p+GYqA4y5cviZydw=ywn>kQV$CReGSV+7yGd+Y1H zt{2&;74mqFPdbWYY8%(jgM{|sZUuK7@r|WivAAvbP$>(aO&*MGFTgMaY=5%vF*Vt4IH6MFX$vwyQHVF`}V5N7D&Rl)j8QLoQ6dA*oD zwYPshmRW1`QRp+rEoG6#vuQ193KwL13a@YT+3)Q@g^k*rbf&?zFxD~b1V02%v88-3 zua67*eMH~XxQP4YYvjgB-m$vA+i2?C2T}D=-2G!bbH6VCK^0yTjzWeLhcqu6+q_9b z^b`-AUid2S?ta9&@C{8i#V^wQGVFmts7pDf^ygfr;6g~HLqUngZTK8JPp+NYibg&-PZWX)_ zl|TclOOsPRI}CwTna=#os_;_IYO{DYI^|=UD{ZQEaNe#K;g%S9Zs)=DhY5G}$nW); zb?2fZ+F2L$@m-g?R9^YBJ&V1GRO@TK3oHIyPg-EORwTS^*tK0*9zZLFjPm2(?xDWO z=ocv}(hJO|{3l=r(`~*EX7|+X-}-@29nDvD}efqeS5f@Q!O4yP; zhtDZtf=U<6K`3(H2-7j&=ZYiZBcp)Y&ZUa}xv0K3U7%BV{^hJpTAhAqo$@}PulkCe z)3B;mFz|8vK6!M1fJRT+PypXJGUfSq5@rP#PK=5%{%1+z=O{doeOqQ}0`L&kyyVG+ zwWN_YY0~t<38B1t)56umwR{nm^GjO>)gsI)N{A^sos`&l302GxUoBg2r-7e)7tfbl zB-I6K9AQvWqG2|L?RC+I7+C+Y_1^H=@5a^U=z6jM5XY$M66ubDM8zrl5AiP%WU<=>bL4Jf*+M{UTimkdbRF<65786zp6>6x`+b zg$JNqmYpt$3}}tTYg3+~x`z}TA@r4*n<>yeVP+0qUipljU6kuh@gjZU&j{76Iqt3};!0Z3~82m<(FXYSJoou#PjP4;# zdqFF)lZY2H%x&02Q)z%Xm%Mn~EGOb2PMSR${YU^&Eg@?;_&7!mwh@3Q3D+9}-H?30&T`td1mnetMJ`|~Vlc4#kL94= z-ybQHBg()DVUSt)WIWJBOuB(+$0`kCX`CBA5*eCA8jST={Q#SN^miX3iNubgkOAmp zPOMq~t4;1qW$}HKHC_`)#WT6^&Wk6$aSN{s2QO5h zQJn^>yM+zA>5`dauPOcrtX%!$bTxl|sd4r~v#qq$t=)FY#q$`^47YU%iB{~@fV1N! zQ5kOMM%wTiyJ$ZI3>nMuh@>Sz2=cf~JXwNOO?klV=HfXg%a&N^Ys=sP@|sgXMhb3% z<}S$t0CgP~OC%qI%xFhqkBX|ZxT%F$W~5#-97lDXTkA#O(@ntxC^4Y-f7DKQdnWtTLt>|Yq%jp60hJeM?3OdC# zBhFG*XxDxuo}~k#xLll6xte&B|9KX^F;Wtijf2Cly1F+Ib0Dw3i;_S??s)jj|5u(ea1js-9k8`>Wr2%D~?!5umdBFJt~UWN0mxSPS+KGgAOD{nYa})sbFgi65S%n|{%e^9|A#xE^-NPZ=lhr$r>|5z{B))r(^Qj@ z-MvTq(EK7G3s#TRs#Q(hL`|FaO>Lm---fwGd+ib_e_Y(N@p zzkh(_NJt+V{}NBsg-UWgdc0DB0&VEH7*11(hf1AW*yuG^d!S1cxP+0T`7N)GAN<8$ zK7M+7U;cOl{RzKxNCnXmeXXik$#hU+w_9b=4B?YTXM)(1eG>h`uB8Z;-25WoPmKe) zp9a{k6x~K5e}Er*(7*moU)PNvpta!0fdCMp+rG3SP1_-;*nw4b9YT;1Wf^)zu0G;5 zI564lbg1j-nRKa|XuJ$N7B79$&s|xwMu`Bk$%7LklZb;@MzIeUPTH$K`7Q*B%cbsaM(_BM#6ue4eT4* zC9n(a9Vyalnijz@Z+#QrTf{k5s|%N6>$N6nV~--l)jnEZU-l1Aas z8h%b-m;FrTnq3)LE5J-e7W!oYVpm$kd|Og#`~m6kB|NNXv+CB5CdYvUY9*#N#^L)z zXb*9WU|i9JI=971uG}RN-+fh1j{beFkv76QYAZ6Hlbg@#Ug>Po?(A_x6hm0W%wbJs zY_b|I@)-I|RXpHHYT8?rm4A&VBhhp?6PRwf3ZN#Ns>C#^tUzKEDl`f~wheOHkQ zF8wbvx-W?qZB*t-91N*@H7UZhIiN{TdvVXO$x*wu_37~*AF}l-4SMjr4)`ahfvp<= zn`wpOZ3yHp$aU}8;2-1e*v7hg@bu(qIT-WM>Bcx>r_2dD76xixO%F>kQ~O=r3)Q!O zM)?$gIp0FFJP0%UqT|C0a1Il>IUPRRQ$%*!?~HF;;5cEd=}iv&&Pg3r`A))Rg-a&3 zH*{X!HNlV9$JTh@gZ+%TcDGk1eF zd{zdqpSHA6t1a7kG!w>~=s-aN{QT1DHW_e~o}O2Z0}WJpe+OOW$y@^3k-@T)1I}u5 zGecg+PS!fi7YIjA%)ef?D!E68J4O^r``42 zjhRc4Y=&x8U?o?xEDX=U$6L)MXtjVQ$feWqXG3}hGoSBP*n{yY&@(!PmfrGKp>0FJ zajOLd1=nJlE?G?@dOqUlYg0+aZF|(2l6t2ixyStCqVvf@0~heI?xc!F49n`r02e}C zoR^`AB1i!-oU&`v0^Kx&w-DnoI8&eewa!tzQwY2%X2oa{ZrrnXaFM-7987hA53UfP zv21tElzNumro#gUxv1Y|+p{DO8VddD%S>A%;AGPy5f$yk=IOnPstUjJ=@^5`d*} z8S&%Kt>!VSFWxO3gNr?`KLO#6R-h|S_27f45Ato_m-}A+mospn>(lV@{2>JOGbFwpGpS&~WKTOZXirE!(mo>$Hk^`~yD6bH(;yGkEJQ=hUnJYi)TUPJlJE z`t0o0sOAMK4Ii{gQWPWPapF2Wz!ehworO=0L-QoHO0dq!PARif1yRSB-Uj118AFu@ zi##1Lt{p~k^ZxcPdSMo6%lF@4^+#skQn{ugO(ytqihVv>!P_%mX;m3AlcZw%8Ubjv88V`t3b z`F&~b-1EWyJ!l#AJRupmN>?s-YdNP?i5c;FmmnSMVy`o)$?wvAZ^k%OE#Mn+5d974 z3R>V%dtgG0zeMu#> z+AU5Re&-AMzdn*lZd@}f@{fJ+f*`Z!UN+Fu%Ve!Z?Z0m+nLOBgok-G}ofjUdSECaS zB%|J#p%LOv2B$k zZs}%dq)WQ)*Y~&XU6(cg05eaVXP>=4=O0)hST>Uj1klG-P3~_!`G+@a>vBL)tkjf} zu&jhNKCU_D1H^#M@~Xtle|h!!cCr|~0c`%P=`!NdwsLwSyL12b3TS#cN=_7^YeWs% zANfwFX6p%nsGn+D&qK-0>sK0Z8M}P1cCF7l?^eEJg#!id;Zj|2X|MI{Pex`~<7|rU zkrmhe9csyv2Jzd^bo$zwuN2Pd6HV6#LLP37ci3Hd!-5F0;y+xzUIBT#W|a?Q(iezI zYvMJLHd~hjwm~xsIQJ&$+~kp+Kj<#1kgzxQ(A?drB8MX6LnPb2~O z2$ur|mu-#O%zXwb3REaRi3^XQwxcGrCz+*KHn#%o`eN!V`^Q0@f0UFfKV`IkIcQH1 zVE@k(DYOy_wvkx*=J4`f)PcE)j3JFKhM4j9VhZzH(N^|UMm-zjAsR*pIf|7BWv=3i zN99gU^+-YEq+uM;HQslBF}&S5tr(K0(5(uuxUB#VR=RY*(?+f+0`*c?KYExT)3%5G zn&HcDu3DM0Ts$dFWVnm+X8!pzds$%2N{!6Lo!4i-?!I*R(~Ib^K!Jn#x97(Yi*X$#Rn_JBY0^-Y25v5n z9ux?YG8SO>&x)=sccQwtpapguh5jp*V~dPFS+EpM{C{5tb;VMQBfqXH5R``H_>c3b zL?<(S7z{9~dwff*Xk{4&nRfD0fo5QG$h3Nto^VFe|GH1+XyEk1xaje_#}hY_!L zQzX1xaS+ktm^aE79Uw2YvIuZGZjiz3H~Q==z{xveH<9(l_VpVEJgD=gJ`0=i;tujW z!N}bGoKK{Q>{fACy7T|74=IJYFbU=1F+v`%tG^x3%I1jK;GwZnSTu%W>!S_@tK&R@@Rpe&-KegI+K!@Op{hO481;MoyG->g)B~(AC z^MPOr7XylyGX1Jyz$p~Q*8q7~Q1hI2xN*fErWFL+*uqcN{F%d2#X^MXiMBdVo!0>0 z#s+rwqADcRw`{#!iCnV~Sv+j@Tq}ZyrL(rQRM#WK*pWyrf=*TXu>ZlF3mY%>HTUgW zl}B39EE3Zc4UKhSfp5I!JL@4s4k>E~&9f9bBksF>`H3pLqmPb-OsA6w-{+EzjKwC7 z)gp6SPc6{=cj1_>!m0(UCD=na!dvquUIE4f4ds}_tfDUaas8u`idX2vrpVm0;&as-j8)5le?YXvJ0n%O{zqaRHQ_@g-PdppjB6WnQSmu-imiA}b8vcZ(NDqQPrgxLJiq-=JZ z+pJL2Ap>=7ul@e-XG0$k_BRn7+79XK;84j}73zspzEcerQdCP@(t=emmp>_E2lqnV zw|8}QRo%caewDatLXdNPzb<$GiGp(GT4g?R0y~DSh(8$Am6JzSW_7PojftWXfsG>Fx@_ILtoeJB zugzl?JzFMveC^tk9RZwAiS5bGOAHS~iH1WKqs@ow1f z!Uq0tQLrLTV*cQjHZfrlIkeO2cqtkyrW0biPpn8KC;esu(s>G#E!F6#h#$=#u~< z{$5#0jx-Wvd>-hxPC#!GrpXq*8&}`dweKsBpZ}G^UQ!`8ajNV!T0NN|!0K|Vo*wE| zKV>=-Lm@&{;%zu>s7q&JpNP(r-Z;3hgP7=acEko7Zp;b^mQ49v zVv8{a4fmhzodXZbavF=fzHYk54K>Zgk84dkR!HfAY|=ekl%-q$T8uzt4wRz(K!-yj zNjU4ha?du>wQF8im%;}Q#Nhmhy$>N4lLj0PYyBA+<)^D}3?RSB}lxGPHUvPVY!f>y&AjYu(SvM5Y1NvR)z zgCr>s=<9I$S}eDpcM6$5{!;2$UjYZ6f4MZXinDop&BkMzbDpF=DgM6B{JzutKIQba z?3yt0-j{v6h-l|RP^(R7nf3OJ<&vg<*VG_^JfHrvv~E&cTbl>O7xD*5krW6Jp_cwf zI(xd-Z+9Pa5(v!YC;32v0|$wyNG!?G2}foWr4cuXgO5W*bl@ZljsA++50g^8kjI_} zTQdHnfFQ)TGXMKX$a}-*zVa^Ew^zt_R{%V?a^}qGfi(BM^n{)jydzY~ySCaHLzs>P z{73f-nKg@xi!fc#dp)j{Qh3-= zG2!!<342E3U#F?BOS1|?k^`m=PXAZ|kh@yQYM>QeLh~|2#uykMUG$Fo7Lm-qXKsTE z07Hm3Ai=%GYD!Ynxt@6H$czp%(J|zxdEK^PyN*e(BMlrao0WcozjrW)jIoXH*G^bv zPAOmWPxhmuSW`IX^L9HuS)J8yQS$!W@{JGu#Z|5Ief$o{c$z?qu}A3t5ALOwM<5gYxvZpg24DgTeX3|Bncm~paJKAk?=CH8A> z=q?o8=BoCX*x}cUQ2xO0o0(3n)qCGJszae!BSZ0=8)z&P)Mj5M_+0 zg1ktlz=lJS0JT1Cdcr6%m0wvyd?D@xI%TiSKgJ+elSRhMK@H)x^Ip7AIR+SLHGLI{ zC2AcP4a8Cmb1huFmWOWQ$QnlYR8R{+Yp$+zu?`kh$0$tk-t64~ws^u5L2Zaz%p9S9F%036%C+dCyyW zUHj}*AJq0Y2vz-JSlqJGQYX+m>f|L$jfN?|aoWkFlPgh01Pw4K<`3t8rM#!k4f6(U z>;L>IJ`)EC)RtYytT{|&ql&g+;tXQub+aO+t{^mu<2v1&(4YvZ)v-=@JWq9AMK=5)jP^@` z%$SR$g4iP{=j|pB_WMaMLb~HmX$8#?9o7-Zqy=MkHOJx8CBY&d<=LveaK>l>XS7LEfrlo_YzEEPc2|AO4~Jk34{T zuZT}57~_7@v7ThlEi-M$J_s}l#X}UMja4P|;QpruWClBiw~NF<7IkRLm3iJe?YxM( z@NBn$`$NP?%mSg!DZT%;$oWeCyEICLo-U`VeOVB;+!D1!vc%WI9(KZ}tJkY9!1xU1 zQBrJyL1mw zl0dsv2>h{o$@)2Mv|orogIYCpXl@I4rA_W?*W{YX?0UxR7r-NL!_p}E{vn?1I7VWd zc(Kl}Jf7#*dZgIh8t=g>MBB7Z%aKou@k#``SC?HgD)Vv?3AT%V%3tBIPr+5XKQk;C z3Lxa1tMoNrwNVXelcIDb|tt?`86>5Eis1#xt}jzJM#VdAi!H>v|SO zh0~TcanHQs0tkO~VZ-9c#Xd*jm;RnH%L#g+c%isL3>q+{#>Po5F0stw_bSZW%J2BG zsIr_% zo8QgVUq0?!%l0a%-62MR8ox?E$5l`eJr%NU&m2#1%wd}`85n1iHlOZ%p2!t!sH{3d zOK7^ecyG}&A!dhwK13CW9uCqTC~#?D%L)L= z0iUa&vk>}3h%WDpykgv^qZ03ai@ma3cb1c+dk!ikeqC%OZju)1mHZQkp>ds7wWBWf zzjYZ2lqU@O-iqet$wZ4-t-QTrL7P4=#Rn;+;5R3*u_z&{Pr~Wh09oyq^=0M`Rsa0* zF}$QsUrmF*&t4#QbbhYLMwCMZEcA{t`6K5Y!J$lE0yzHY`wZhM+0m&VlItAwH#csZ z*5kRJC-Kb>wW%mB^i7*fcx>o*iQlG~=N9$RTpWQf{6WlAhB_rBW@>o&@$YPR{}!lH zw!#)>U5*tg2Ki9u-!lr+gk3#=F@M0XyQb}NEfBU{6dEsII9sAi9z)8B?B?3)ri24y7%(4k6G=}qxgW^7DD!KC zeh7BTS5^Pgw-SwxNo11rMPL1y= zaFk|PkPjfVEsimF-`~{u2MTBP8|fa9{m31D9gB71>7fc2%Tuznyly%o8qmm`0_db%#Ha_bmg|#GxLpr%&J0dVf7WZrHI342sya@s((`5he8yen_=U0k;84^@D^9=t9=vyOyJvLL6NM3D(87bB#1S? zoIZt-#fu$me2sNNWi1p;P=sJy2Lm?kCb%Ee^MY>=7UtQ7ZsaGu?k5hfp zv2k%saGseru_Df{%#7}@0g{&5E-t1%KABl7V#ds)F$n@sB%g{)x3{haRb`?l57AUD z2m&%$Ipl`}JS1)kd%Qc4$!CI~Aie0T)}-iGR%6f0*ZB6)Qj?#&9-7}8li6riZm0PW zz=mkkjo5rel^07_apSA}l>RQ?Nzb(7?y|hzdCmPjzVX+){;l{3*M+miqzVc8jzJXR z-z_OyhKXWT+<(LwoJW~-k{+QEmgq)4jKM_OGPZ|CH?~xBKiqSFCnq_58O((W_RC`#X$QPTg+0S%tDSkBpPFWjJfXhPxoscZPY3VqYLlu z&kX8NQy;Z@mcOZ>7&q77F=j5RZaUMPB{sCS=G9&1PaO>Gbbz{lsU7d78b(Pt3Un;U zo0T2$z;_sY*nIjGs`H9toiMZPsWqD4;#TynubGG%0~}oPq{kEsB>uEG#6HHGo#GFUr4BAlQ#%X4Lse{R99kbHd5cc`t#83@|;7uh!nGWjR1n{P~ zjBS@P$4Fc!zyX^z1#x~@!ghk|&0KvolfSgIwT634{SnB&VIG)e#@|%&0kA== zD)^R^_raEo)z5A*O{B|9&Ml%Np`0YVk0dAp5KClcT{A=>gwOV+pq~~KcZObj>fV_B zi9DfgTH!WUmYNCFv`*ED`K1-heR+JsCx^U2S`x2vG8FywGC zh&LwqTCP54xi%SBM3=MXQ=B488MrQj(%Tn$gpxPgIy7{^%Zox*X7H1cUuoV}P)AG6 zJmBfsOVw@;zfz{gF1GOv#T)Tjy7&N-xl`EO+)Tn#4}x?NYq$&>D`NWXoY642A!Ltd zJB;9clR*TpR{DN`cxFAo=CwPp_+Llv18j-9f(g~3dOnBS?c|}Dlc6no619vKd6mKE z?x(j`SYz0(@HP`bb$Zs+&LJKBWjdrN;GX2Gr>nw-dkuM6TqqyCo=?v8e+GJk)m^EN zoYDSc1O(o{mgR0j2CpN7gxLUg#Q)PceI*nK769Q+38b#o zcVA**6I4t~?*2+$M54&axgvsEUb+CuCdk`z5IQ3D$dtB<%jV2zq^bTHV|0QpER#Z#h z6da1tGuiN(cJ`p#{&KH!5TyfuQRTM*SIsB9_;D-1CLQ_V@3VlEGze~rP%GpgtKfBav@g9G!HM>t5C~E#@ zlPkF$&a_{oEjP**tFQGm5{H`9`stB1>mm1X6_0b^H!wBId?KDWzQFm}Gz!@e`1|_^ z@zW6%SnRvb4~NXpFb<;j<}rBh;k&-z(!MabIhjUIs(8LNYhzC+Sgxe8?o?{nN{@Jo z$C4x?)}DMG5OI{_Rj>T#Kt%|o@IF*|0h)yLbnd|4H__q4ZyzOxkRIGPSF^1ckDRcf z`k9!c%PHO!L3yoKdCt^YmB&{1U$N=RY#q%QEn~~JCEDwZXMr+b!i<#lw})ztgV?3*^DTg&OS^nz*L8_4s~7`*$F{s8BhxHZ zNkdm>b|4Y^OsK5pwyX0hyg*6hh&TTaY1Nmki6jM@<$U3zCXAZMG(g9&0Xop72met_ z9>EN-IVgX3l5QnqTI(R&lMR6-d+$Exoo!6;hD}(=>Sk7q*~b?KOc1E0WvZ?I@!iU9 zN`2iHx@v8%s2H=WLkRB0GhFk&TOV&T1=K^UOaT=xR7EyaEOesTQ`s~srkHnFH=$VI zYX;bYrFwD+=_J^G2%uP?U%+;;vp2A@)$dQV<36wZYtT^YyEr1nVd#72^c+|fh-_}g zE-dUH9X0seg1uj#we{RIB1fRnW9V-dRB&`tC6|z$2tQ-?Hb?s~2da3RP*I%Fe@tR( ze5}sKCD*(Q0O=H3xmx2JNF6b`?!_|j_}_ljt&lSc3(Mc`ZJxOnu-y2i3wk?x_06qQ zLxTVXJmbROj(EF{*|dt^YiCUD>Z6l# z6xcD!bO&;ZL|qhL5Vo$U5jRFjRNGh*Fqm%K-4T)8+h1}B3$G4&+6lTYtGegC{8xXz zLVy`>8I-rB>>T2N9eFCp=d@2D?}&(CDcS@&ba0cUJN z%^1odRxjHssrK6z+k5XKrO^fVK}dSKw&%gf@Gu-$F;~zMFzE8|cuB>Qfd5W+Ctlw) za0mHwZMXn9k!Q|KR_z{qKzq*OcG?A+aOGuXb|8>T`#L<2im(iOWZfr`+uM-C=vs

I%-_meMn?VbU?rxs4G)9QRvaysCbiAYdOI-BsS;Oi%g3wz*r)Q}jMOu_wS z?kzs{0pQM)HNrp&v83)^x9j$_wr?_V74SqUy2ARA{AG)e*kMN@noW-vlb_~1Q~3D@ zRa$5w+CPC$m>~hc6NUk`9gezl6ifqkNuH!bP-?TG!>z2^EhCY$zR8#BLW_ z_Kl_X)K+ShaF9jfVrijYTv&9nW!QlfPs6irRa4RbrQ*|QH9!4Zc za7vrPJ%)l3EjCe|W2QF8@4x4N_xc(?Ux9^-*d@h`B!{=d^Wc9ABdJ*u6C7c z@OFteT?QeG6VBXrmATI<^aM_cJSLGdeJ+F9V5zFe0~B}TMsZAx{IU|hLxb^A2_vx! zJu6N;GXsKbud>#%vh_p_UWeztw^{~vcHK!!D26{Xdk<67BGRB0&T#ERGC zRKqi0df?HARM=mB(c50+eDOyAT%ZLP{wLuKw-?m?vXGx&D%Eol2i(sI>Jfej>CISf zebbpKxxD4bz4jW=$`#tR7q}?wzhl?wpt{HkDS=dMlQlH>^9js(SHIYnQ;IW2-?KgJ zCXCB8_v6c}5esPq`4SqDfePChAw)Ktj}n$vwXZOP!Lj3&0^#O#E%CE{#js%=6>aLjOE^?E<$vJ8HlMhW!)ji`_r1A z(s7e>La99s3*2nHs`NSKSAx&c@6?kI-cAowZEPp=bpZE!J^%|BJ5ga6Z4xO2; z=ie}LbDRH*-w+3LztMF{!O&`KW1o`f=FI+jTPSPC?fsxBQ|Wa`eyxIo>K^tew!X;H zoX-(GjJ+?1eISQfok?q;PaZ|fBF|)eoL?95I)WzZd6C1N#E~vVc3x!!{UtOQmz3XX zw;Hf?bCg05B|UEOzpq$Qa97HQrz?UfSWDk>5KP@|b*=YEfJ z;z(Z1VZVcLMw(d~;xtq#ca~9=+?I@!XHrV{@ImDpX06xnH6qMmZipQnR|Ial^L^SM z{jH>AYdc$K8qV^8oeLWtf=!y^U{^Y@<}kH%xeVB*ricYYeBv0h4b;S**UzMDZ0UO* z^DaK~&eo9N{NY}ktG;ftDy^A+$&S_dQ++(3yZ_Eq>VMOzuvz3kF`JBzajyGzrfp#> z%x}8dlCXaJ>(VguF0XWiAKjGims4K;v?Qs46n74HpR+g#Ahx;HFzV(Qw%;DSn!UW2 z+4?ZOOURJ!!-fyt%Zh`G1KW#SfINy*t`Idh9EO9@qw~*MS0$T|8m3y>B8}5lgI49A zq_dT@=1?Pq&Jq8D>`7=({`xI{`S_+~oryAILd(dBJIiIi_A!J>zq~~F4H-$$cA;Zt z<}%=1xCgSfrlhIqc7O3|I)wJKu@NB{Zi5u`=^W+`T$Xjor6K2mvhyzV+0Iy;nqA!b zd?qc}gSm5yaap3ehfBI)pw#?@f(TAvTtQtnTric1V{8-Q%NPBA=K>1wSEMC<<+|A& zXx`%zV|8+2|t=N6kq*Q2bLg4(S!GpZ#EF80e05 z?G+&8MxdF@iugIrfP`e2x-M75Of`;}XWjxby}#KXFOB2v*vFM5`Y@+05Y?Uh3i{1? z{6@{?zp0~u%vxeQixk z`{5x^%x5Z#XL))W*UaQ1TF4U>&i@I#!OT>P=ln{&RpwqcFtsfoPVKYQ8`8O~`lfxDEjN3T#nFkK*qrc%2vZO!|CHscR4-Sp&tylaTVpa91FMx_ zeBu-0tEAeNbLx=m<*&mLss%Jff_p;R7G@~OV)*(_RL4H>p=WWjck^N-rXyx8!qA0rK{l- z57yCN5W~fZ?EgOEF&pT0fk_cZKav7vJWafco0}*X4v1j)sYHl0nL87`qqg*;vb?{0 z<$}GLg7S~{^C*H<3465Hd(&8>;E@j!%b&s*JY@15k19!dQio#0;qEhaGmR`@gIr$2 z#)Wm8+uudK!Xi)z*e? z3UGC9_ve+DH!!6}_Hl_n6GQnwy%^+9-4(&3eenmP_1++l3$rgiX#O=cPu%yeZTyRGL$!KpA=_ZPwN5hYtpCB`XC7e5-nagPf2v zEc@30j^Y6Am?A#>pxkN^G3Ky$K(Usb=?sb=XGlY;ga7DLDZozv zY3C0*(kLTLr2b$NpwBr0y>;-!;T#G#p(qIMY;x zJ}V)!HT4!rFxL>B(#RvNI~^HC%5e~azS-WH?R$c>0e=Y7AO9`O<$&q_wpnvLM?WQ3 zs6N$wi``=U<*EDaA+^hO$fK*lc|5JI^t8GcZ&a zgYj^tm~{gr`iEW~#|N2!PF{68h{ha49d?#AFD`9(AMX1S+PNSklBOtR_AdYaGR6pf z=c^5ssVM&8U-U94=;5x zUG?=8B*fx&R5@J`8HgdR6CT_u6;1az9ZT|Zm6{5eCdye&Wg;Snj2e0lo0?L9y<<6* z!|Qc53}jGOS9L`;T5h@B#n}84FOd&G5JP>6Yp%_w%>&M!=7Dj&z29A!k)7d=^n?+j z00?7XU2j~q#E?0yX%Z?~Vp*1(^o>jx8@|_v+K&CQaF=zi3IG=aJG3|Cf>^DO%XkOnJA)Vm=yN^TeO+5YzDyGFaLhkqQ^3XY1O7)V{mNQ4~f!JEIw>-iew zpLlhSj|i8Cvcni<6q7|ew|-*!Tk_~@MjIDX9~`Zno(XG&EnDF9W;uXL>%Oq~m;i>* z28F|`uQ(-?sU@pn?_?2g4rlFgF)z46_K9P$7D9WzFzBNb>=+Wvlmi4nKp%ELS1_Bz zcpnt;Y;*5tMCBqB)Mzz#H$k{)zf83FVWh|QV1vS$MrY19h7fwZ6Fgu;4w?z3KQC!U zB1S!HQh3b_Nva(0mhuF%0cTj1p|^MO?BUNgF&&MZKJ$_t} z6w-SVeSpciPX`$qqSfj^Jhez<2(c4V7@{j9iy`UE}Yr1!NpJZzm-O6=%)hD{bBk^e$ zl$uSN)n%N0iaHo(vm*yG_vCvn zW@n#;j0-mOT;v~~*)~rIE^M#%=U(Un+<=rk5%Tf!1&hG-KC@P{6TSHlHq(`QYk{ev zk|f=AXjK#{)%x-+LKL`XtIyC2Rxjgg56I`Y7B7&fB(DQ5D)jj+6DxcB{erG`u;2%l zkF-lj89Kt8&N>YF6Be|z_YmEdH-wt`8c7fwhpvY6s2kR>vX-C+p$n)}mJ( z7WU4~O?`g;U@}L*?e+Qa9o|u$xe_qN8neLh8-ww^q2w;nD6E3zBS45PmsPPhh4gWe zuiG(oeEd>4Ir3}0GQGZS4Vp8AB(dJQEB6mE*~)aUUwseX{HBxq@X_b**4(uC_k-%u zg;{IA3Zy=e#e3I`OmThlI{B92S`xSCc*-M$bJ&7aiwUD-=~FN@EBb{`gqQ@OKGEcMCU%v4cQLv^3kdAhq6EATPDXabcbM>*SW5<0iHQ_`m8 zStUkc62n(&*I(a+8n&Bo089p^)6Qv^+3*2M9955$~;Bsx%gSCwqzU zwILsx8Iga$lSkb?bQt}aoQwf9tfr=Y;N&bW4qI5jm61Z&wnOUaePsa!8*Ct-!Dg5a z@^$Oebg!OHjuA?P!+P)U)VebZ+*?$HzgUkRb*0=m)1WfyF1=8zD9N@@eL^xWK+iu> z zo1!q6bHKXs7gO|iu-S0-B~*YwhNd90 zuQxY*U#k`BtuBnFPpTABzsFgC6g&wRHWM?mZu8k9HVG%tj)-Fb81im}zy{D$go9Y2 z5pg0wj=2P4#f|=1HfEP9w8m$|K2&LU7C*5%G1a70Jm>cRx??A7#`G6zq3dECHBz=g z<=8u$vwh9TVB#g3{QKASf-6I)B=M4qonz~{s{Wnj^TZ{A+{Arm55Ze}R!T}34zMoS z*j?Xe%LUW`1*id5kio=cq)MF zje-z8i+3I4?8MHaJ#h2v`FVJV7cG5A4Kc(JVL$ZE5Z9wyB$d8*uZ zH|;{^Xs`qapE~@btVV>+9q&d`u$$Hl(^5Xp@A*bNx2x+x`_IJGlE=J25NO6oD7j-k z+Q${3^aQmLqVnGM{))Rf{y7xx}SxsKV5epw2>Iy zT?xv}UkM>teD6VkggX>6hHgTXpO%4c zzr)NV!o~+3eyzwja!+XTj0#v4(EahS#RV6(@T!Ow)EU6n81DH9@8nwj+y*jrZCrRz z?^Ld+nZE46hc)g+RW7Hb(+D@DLFw`$P4qHHBJAU*y$4TasdxE9O6-us&!0Qi#!rIE z*d6+5`)+DnBMvf!vbplS9zEml3AvDf5z3%Z$2yyHL=edHCY$E7f|s_P=XEIivkSGv z3(4OVK%PZfN_0V;^B{=xJ~zE_!qHd9PGhI#un{+!Ls~7>^U*I@w5fZ!q<~Cclb#Dc zu$m}oI-9(PWhu074N_R#Up5=R+0&Q{1(PmHeR{&9q(gvEW=`nv&+z6cS=l7kIh-3T zSn3&cL6Jt%N*hwak`lpqiR4)^fQ7I)5yJxxK_4;_hLlkh;mzRP+rf_)r_OF|diug< zr0h42*H9RoSTLm4l8*1I@NKSH$d_1NO$Zrej7iKty$|>RHAM2Er=_B^v$3-?dVdKI zvks1iQTjwyK8!r7eK{&L?PCx~c;d-Eg#*hq^+GR~9!0TqWnAG4qLu?EyVXTU+z- z>rH7yzv}rsF<91R-{7fT$j|#YpiXmKULTt-Ga-mEKMiLCCh zn^g}z!@?UhxdHhdw*v!5@Rudn$Ih~V7m-${CjRNn>6dwqw2YNyq=Vh(GnL4{y?%#P z#0djgOMUu6$Ua2(*|(CudMm<8B>@v|w-U`vZZT#is8*F_{YUD|~uDIGl)S zMBAsj*I*>0Nt1%#;ZI&rB>27+D9@i{7Dtn9f$?CBQrlm5EaUWm@+jAjcc$pnmDj?+ z+{?K&Dc2s*b-0?s^qxOEk#ZLo$)3YZn&=n4M-W3Bct<9&SZUVvQiiY9WO4&cwb>NW z_Ow^}jcOIsh%h2mWL&h+LGIDccc#f)RmB(>5X;A6T)%u$PU3(;i;dLBMS0Ej9i;%J z;d{6n4|Nc!47U!^Pjd+`$>+TGk5cTc|j;|wY@vkmta=@F5Uey{gCNd4q37M`-- z-gi|^U!Wdh8&bGeI@b~g9_=d4R9N9O5^Rnf7cA1whxL7_F7u+22`ny_O}m@dq*(-d_?__ zamSErE;8;o!Z(WNi2?7fuhyHxyD9AFY%I;4C!`)7rZBJpw8fnjRtv>JwMJJat=f>ehLJ+zvtJFrzR*8 zANyN4nS0d6N}rURoXew$Q*ChjS+7$$zd_jeMpESl%|N-XqWCkhFW;{Yk^5lz9L9p3fePxOfxj;Nl=a*6D`dO+318<>Si`o?(hz zr)|>X+Y(mqd|NskthD>;o-G0sq+4ZOb;HMj`$ zO|Zni*TFQgk4c9yNLx)Z;YQkPW6G!@>Efuch`}vIr@7b!LdL9QpkwGpFW8UwLxrHVYAc2DV-6 z^7jFY$O|q~pmF~eoaS;uO)Fv-41;c;&=Qh=q>mM>6p#l$^bQwM+GQ!ORaau;m}t-Tvisn zH?)U3*+>54gHjD1H;a#2=eD~gk=%3AI|^}Lv#yTvnE49hXiP9 zeTsfS_(LXH%lj>&=6M&)rk(?A({0`4w^3FmoS0#T`~@Da*U?c%bEoBb+K8U(r z^ztF?*a2gCXvoSfqQ2m(nM@I0yU~GbdN`wlCY`IF} z3IhyU?$~?J~KAD z*BCuGu{^uiZQr`3%~TSOOB=OeKTp=3f3sE%IDflu9_n&a?MqT|H{Oh5g}bX0)a($v z=CW#fG{VHOy1=&mt*&HfCfq;fKQVx3A=dJdA+F*A%0pvGL*lQVb5l4bPc*g7==8A9&y* zeI(wpp$Y@Fc{@#z15sEQm)Orrs`}~a$?_Md^33IAuY<_EetFm>u~%ZV)g(ApLY1tv zWwso#<1H+_$0o8a$91#O8ku|1kmuQEkWHG}?jSxec%109gTBwYqRosTX}9W|OxS}t z^Y&&{fq^ZHT1{pDb2PpB0Hh#=p*8zgpBRF_q4qzv&f^W?^aYT@qP@u8O46uI(9e#` z?OoAHPsX{=;nnDJD`)mnSZqPdJ^tg0XiLx`@o=?+f9jVZrj!{B+sjpHXlP(ypr!}r zegugc#_LtwCryTOx7lpW%@vM3|Z69t>6 zq@yDTmDhwY@9J$+QT+~2j*es$Els%-dmz7KvV8+a6lm*3%R`b_0?woHm_Y=YFM zf2ox8Gf@r5o(I;Joi*c*K;IkO_Rs}^#G%!#(QbdB!0kn#e!^H~vWX&(d!!upPbdHU zd4Y)N0_fq4ow}3B-PGLgQ4JK_(yIbt$G7CMkH!g$>nVmxCpV8DK2<8sbdoG4_3$;J$Us4#hk@c79lQek!k!l^a4kcS}6*aENp+o;KCox|zAaVotiH4n+nHeS3=I5G@pLB)E=_#Y}vEv5rMT z7fj_A7zm(!)`mI;nB4bKqx?Z$gl(t1H>Xvk8!m==O)%R5?S4SO4{*5}j8f)?>3GY$ zXZhJ?_-` zUj~75NF>$Z=XfkKUal+r?PU(=MqAM!P!>Yr^=$8C{KVjy1C@{&DL34Spx?97a}LP; zVKUvv-q#nWNGu)yP&*wT=&mgjA97O+3m-DY{%ZkM$X22Fn*u(M=CfoBGc{}Nk+1tl zy0aL5W$L3Y3mcua$_gmQQ$Au(igkp>=wQe61f`Y0|HIT-K1B6~TU)xjq*J;SWatj* z4yB|+VCaycK@_B$p+ibQK)Sm@>1Jr@p@)9=@0|1D{lFhE``JAEj3NS{38GvFTC5-mQ3X8?f>wpIz5oeD%lyr^mAq7a& zfJ#VkwZ1?y*-V#nKCX(UIGmVmF8gLiAO8xvOm5BQmVIZ%xvQAZyGEI%A)<2;C58GSj`6{x}Oo?E)3Yd(#|rp?nFV8q5(wUY!heeV~zuv_|TF-X*`ltK*rU zOdM~{!#kWmUhT#HBH?%>ai@y~h5n0>v)I11e(Mvs7>Z`YYnVn8$M@UkJH@3uOFn*l zkM>WVNDji-TFleSRJJ0zLAd`YUA$j+gwVjdk+}G?7?C#e!2L;Vc zbj5c&XTQoTCYcoKk{ig#Rjq@zUrhmm#!sIz6cA*uLQh>+hx9{4(BM>Iqvya=hpeB| zGj}-kuS>OW#DUfyiirU9tpIgKEqf~wWy*zusJ`>vXy82?h5(rIrUY$EV`g?v&rpA4 zv?<>IdQ)Fh+yi!EoKXQ*FgjaZZSe6arj?+$D`mPo?QDGb7UxQNda;>bSbDer>FRI* zqnUTP<`5sHq+)-%WFkYrI2IR&@bjYq6(8p%gzbSm|s%u;KjX+=I*>DzV&H(FN%h ztf?{NI#2(+wvB|f+utRqtpSOWaT<_r0yc@?pKnvgsdLPpkATnhu(F9kG$yL1hdg6b zR1aYFOyS%pJ($mmDaAcN`z^!nc-7KU4zze%-5`a(U7M4@zBBw=VqWtFg~VAk-$a(F zWI!8Yl->xOKAzK`a3KFFs~?gh9lS3Uz+{sii_-mk@AG`Sc&*89S_!TSygpeT0V3_S zi47k5!LszUzbgC(BRfhJ4n3|0g(6dVYNo)G4hfp-nY0_8qUF-}*yxKv?nIkus%BFd>d29lh_=x}U^L z-h!=^o;yQ1vJ##sG1;!0gSTUYm@sORSJ(BQ*Nh0RTu%9&UjL_GWEJUATOiOo1=nRNj3+|-4n`bEkS$IAA<-N*a|!Ty@-4S=v2!j&n5hzI9lAw1u@Opd z;#+XUnRR7c_ce3F@oAQ{4KC9rB_CPHyVoI)#UmpZhH02osBDXsVS|%C=4D_4yC%~l z392;sb8h zNcSaf;@a#|+!HaI+s;mp?271x)Q9y>XcwK(IZ8TZkX0)Geaty4*QmY)|0FHIyKwoDvzlE?i}{%$xg zuWe>+t=4X`p{0dA35)kgG{XV&-%9iJ*#@;CyCX{7M>#p3yxW`3fCL^GG6ej*U3lr) zoMfpMd+nhd6AW7>u%i>6`#joYh+GeS0^aH}K%mrtQV;FCh?s-!W>QQF@@3NLd)YTe zb}W9Yy4z-=d}Fxu!jXZqZ%-4uBR@10(gi}^8i*-OwqV}6AKfS$hc=2|jD5ZZ@_j52 zhsg{!{XirN`3)5f7DbYkF$^Uzl`n1>80p#Lk*d8nh@YeOJA5zg~awFx6!>6r1ED*)l?)!MexitQt^e<{56D+4%85E!z1 zRxhdKMKzROVKcomyH1CB#e>FLWuC zo-K?utO{3J>psfd;_ykD>zUvl1p*;#Ky>s6x6z7>?U`RQ%s!!$RGA;ho)nn~X_96g zbs;}x^BnnoK742y+>+(R2P)KyW`o~vF=dXZD;T~W|03kW*2H2Pis)77dmefGp@O~3 z9gzfr`eIuW7J?=1{1{BayBRKohEN#C0wm2XEWXW0S1iX&oga@fAy`=fD{qgIO*@gBaB-^hAimpQzRv43y1%HNNWono; zP_JHtqpI>ytW*bwtG(=(OZS(9}L3^S7*z)Gd$aXR+$l-QmVzoc$sM~ z|Leh;)$cm3OI|oprrr@xh7O-}WX`qWYl_akE&wFU`>H18d;oU~ho%UfI=R*K;_PtN~dbkc~Q4kM^~T7SM* z=0?G(dhcg06$e=yZ?EiZf~N3Rdt#@JX~)Y1S!ll&K98UZI9ByoK`FJVt+S?d?IPd1qkYqNvC^GUhHnYHLHX-|$K`X%8$pu)Spz!CJ&_f^#%b z7jCBF)(O+t@K}*q5JS#?I`x@Z3`9mXG$EN9?&5~%cs9trhkprcDZbl&JBjSwD(5$k zty&i`#Dx8#8}LR3!%+TZ#;5Q<&2aUHfz9NO-t?bUY*3F(j*gE28nofh-0>mA`6Cy( zP!_OT$Q2?Y5g1rTeYpZuXzQ*5sj<8~P|3QZu?>(Q=GuOPNPnsV34ys3^P3+0nH7h} zQv%nXZFVf}yQ?tsg7a`v6D<1!3A3bmK24Wg*qH@U1-+MT=0lVFLWL9fQ}ucg$4iCR zCCWVNGg{(TZVE&YT_dc2*f;pyAi>X<|0o515J)}I<#<~d{z$wK7&6JuyPEI1xdX_u zw-r~kyfxE2O>Lp`e4#xkGV!Qe-!uq5rOi5vrjNQb&dg;6-4=GGf|i;@gil^wS>FY9 zf+65EATVa=E)2Pf9uhPzM=%U%c{*-w?=*kDz$*Ixj@fCk&CD$ylQ8J29>ihF93vw9 zb#Cj-sB&&)<$>R)EP~tpT|#2$i-;7p15)frUH0fKyu_^y1)5d%kxg-$;VvDK&3L#< ze6AF>$=cl9h=9_zyVonknqUaxWs>%fi?4w#hYV}h4@lywT}HtP3m08xmSHkPeqI0E zKdis2<9m$RYTpE6tbyp7=)Furh6$t$XCB-U(iEnO=+iRdaCdW@^yS1_1NPBV1bZj=Z0AC zTPD5ECYtgwf1k#yf6ag1ZfWWO)1)FGwM$c6_iQ@ID7%DeskChTa*=3%e3IKpTjNcJ zhJoty(|z77Q~YY)hXv+za|uTEMASU*ua7Rwn(zA2oa@;4UaK_CxLLHeGyZDL68u*r z8I~!l(;^y{Z#`r8_Qw}6d$&K03lmz0GHBH^iH1rM2r!NO*5Ksla=bKXB_*aC4Wkah zWjn+%>D<441wq{SpSGXI1$|Z@$08TFUrLl`sOmsDyKGn-(}{O3uTd8@Wj>Z#bg5G@ zBpa2}$*uHw-t(`bRpMqGcHHfia5ZH6Zgn?3`|ZQosS|I8gy1wRC2%8AtzFApN$z(r zK%l0Mw0Z`O6p?94bk664;nAO;T{(zR2*4G2`G#YC=;LOt0 zz*dx1Mf0~}voV%!+yiH;75Sgx%nG?7_}*rHt#ob2=!{MYNom@Lc4I-~=!d6J zRhFlz2i(Xw*)?J#F6*7_RYA|Ka>C>c0N;9kEL#t}7bBn(ZMvW87xmJwU;(EVO-xBO zum^CF8v0o3bT{g}IwF`Q?hk5zdNreCp*`%Z+7WB-wSxteHA$+dO4oX*$#3&_2M+Gg z=Zg)J*z48ktSX&H`Dn$ee(NpIf-+;g%fQi_SN@Zxm~Cen&pUCbEmQn#k!)CNPg* zf8npdZcYYRMFj6k(%({AD=x%IUh~Nl2ZPnqL}31xn2h5g%1%DYfNjW9jww@J=c{v6 zpXktPY#C=I0vY_VB283N-#7qiSFzWT2m^p0e^~uZde_BYT5N8aJ%fl;ME#N! zxD^8m%?O4iSEVk|JZ$#gZEjBe{w?^iad68rZ@dpr%Nn5=Oqiw6Z1iGz18I!NmgHN> z#cH?$X=pQ(%9adei^Igmmv-qd_Y@hqBzNbDK@iH{%hTA{ih$@B5Q#b;kh0Zn1kq-U8p(pCH^XL_U5mBqyw5VFtT{lA zrt?%Vq>|iOQ+LtLMAH$}zVQk>=xo%7`3f#GPT+E2IaHF(w81Xts&;!@=(|ann1{1Y zXj+1ZySp7Od?xVtfIbfG9I_Om7ptX!2Y8jmXX|!-SJOMZhg40(vc`J`)Gcz(S}&K2 zE{QEkIJ96^eZmj?_uXikA*bvui8B|UKj|L@*P|=~(b6ocAJ#DAgh4)3*+ge}%iE&D z!d}YX5i}nT{N4`qfWjLDy`fEff^fWmo7Qz6uIZLj8g$?khdy2G@*K{CS){+Qo$QC- zQjV#BQc?u|ZzgW+a_jC~x$=xr}RaG@G z5FHp4EXk%1qh@+C@NocE7-nHbR2-|@*gv*dmzzBZ@WWx$9={OO)t#|oqmCAx9Djo| zo0J6qgc}r{B z{gF~>C7Z+`EtCuUIsf49Kr2;VQPJ}uBZIRrs+%X?hX#?lY(_JI2U>5wJOS(I{S85h zERJ0T`t98)eV$^fC&hk2kO4EWubr67K;!UzoSj{ZEthKZBE`(froEEu20z2+9;S3P zT8DRRZpk<-Onlj6-wcT}3iH0(MT-bh)+CuA=6$Dz4}EYzWo;$%LmjuS$0o;t{-WI} zM{m8L#WL$;!6vR9#zD_c4#is{#^=eW(ydZ9MO>q~;@Fe8=>no3si!TepC9UFV{!R_ zp~~<2&sR6kmnDX7t0VtAm;xUhMs)bQ{hRyLhc-R7g`=P*xb&*@ z(37VZn?bl#_2m7wMw+s3?2C!BqccR`oW_Qw!031C3W&@tAAl3s!69c@ngno8Dl^jd z!XH0|voS3(1ic{OX9VfGE~Llti??G2EO4oVqKyBQqAAl*+2gVy8{Ni$`Bi}T9&;wb zPg`3VD7;rshQ`J=*N@PJ{YWB43nak`?>>5s^`rdkaVR*CK#_m#H1Jd_34ZnSD~WIj z$PT~&fMhI2I?-b}7Tt-wp`!Fn*?bhb~e#w9?Llj^)_Y4L|5&~=!FN1}DO^k#G&43q@D z!$e!Vlm{7C8n!2L2Y`;X8z{Tq(%Xzsm(Y(hblp4>{HmFLiyS(cX&QJYdt4mdk}95g z{zrq|x_}@Eqmd_y+Z3^zRt$M-Dai!(v^Xo$Yz+EdI_3WeeTGz(pF`YSrYZLPly)(L zPnQgY%JD1FZrgY_!NeKKV|2^mW2eq`RahzNkDWpOPO^6;=9zoybz#tmAJ<=#Wa@vJ zO4V^ER_5@RVBP$9Lj{d6f6R|BmUS&cNPDFqY%r zo8<@c_G<9Zy92-&Y>?dWNf5D+wLK2DrTB05CDFn0GmJ$Y}qL5^_-HC3QR8 zn~a1E7(ne!YvfzpV&hL{TwD%}bklpr1$BNb_C)e0$j(4iA6)vTQD3?F+ob*%_PL4E zkFsH>RTw@S(!a`m>hFdS+OdniC^6bq7nbPSLf5oZqqr~#8 z-k`6?9oAhKCw@LONFQYKzU*1qM5dcPy5Fg8F$9*5(NtVNw#xaMb!SuNVQ?dlojU@o z$ZLRjIa_Q^D0|t{OWI#Si^BmQXA<<+uBvz5p^L>|g_(E_{dKKO z_ZK+MhlCRyR;Qn3%u)E#wZv-T@q%9<=HNa*db3##KB=h$!%Va7_F}+GexxOe>^!u< z)cm|i%3L4=3A;J#z#Ur7cSdFzZXBO!vyzxRW!QtR?ZQycbQIzpY8Rr|^yyzClF5gQ z-F0D~rx?l%5fZl7<`WcrxNy6s022bkHm%%M!!o4xZ#M9ocs(H7Pwcd{mhxezdQO+_E9^e^*?<#M3h5KIgz3r0G`58`vN5%!Ro}3l5W{fTLhY>MVBz3^ zj!6sQXR91;cw-Y{ue~vK$W01P0CSYXEI{;!5 zT37e4T0**4P!(2jczw!cF5C7Z7VwuZ5SBN28F4DwZAo*OYf)DnwsyEqe+SVf0Y(C7)nj2ri;bxv*P zoUTa6!`{nro zo+FY=)SUzfO9M(+-qu$rpvjROTd^gh@uP)~nV?eCeeMBRd>=KEq=vGH%h`%x*%Z;q zhDtc62dt=r$1ZiXN#BpRHbY2_N%7Y)>+Bapp}T1UP|(yr*||a~7$*J(WT;?B_-30S5=_}{9AhM4+`RdP})y^tq!fy=s8qrj;-WdD@Cr->A zdWZX%ZnEfL-kYmdGtZdcwEd>{6_GWSzgU&EiD5;3NDv zGM14-em4t`4Gkas^)BuXJVAaN00#`XE=}=`N#z2#9y#B_#3+Gcr0+Md;gPz34|EE< zuN8ZA4jyzLaEaA^nw_;bu0h5N&$lJ4LJ{>)N-7<>+rzYSzJ@y*p%A=AreC{P7gUA; zN#K)h?vdPF=ex_VFJV&3Vc~z)KHT1%v!e(2HMq})eVY4ab{ztwwkMd-ey%6xtMA;t z-Ynx*<0Y%kbv77kJt)|-R-Z2>HxEc^E05{mOxzaT+wN`28J1RZx0Lg~n!@QmyYG33jQyG1agDg{s0vuhM5gjtj^TL@dI z^A8dUmGwzS7J{G*Chmg0qtdpv6JLqOKq6}bt1doDO8%;ffo#YlI@SYOCscVt>Heo{?U;Y;(pZ-AXucI1agk#FWw`l0c2d*S zQ-G?vrCb;FMDChye5F{fK zp!P+_;P=0GcQ0|HP}URZ-@Y+o(RE#O?R(m*c0g z@fB|AZQ&LrC&!vz{E4geVEO{uUfWL0iR||DPg^A)+YH0*Y-m4(zXz}p+L7K|6$Z5z z1CoW+!gGd|ZdPbz*<%9~bC$8aG8#=EA0f;mA7*w3&DMrAtNQW*IDB6ZX#ae%;N^jF zO|(3|`+g6IS9YgdE1Y^eDgq2>67pHj1zuuOukTB&zT}s|wEr*EZ5VTTC&f_iUhINX z^;Rzf|M~t=RSdsz$2v0`zpfuQ-E!QX-?|)pNwzC??y+E(7UTRw6aP(G7X(Gxb(qrP zUDpkj8m5UE;>#r`tC?dE)~TQ`DNl~`dw%tkV+h!AnmSjg!3&*g83Lqp{1;2=o2n*+ zCW4$(n?fNc|0_A&`dfX5j=0*Nh1BseI%Q{k`~roj>0z3;sK`%%n7(4xu~E!fNQ}6y zwpON}*AU}_rljDH(6zrWCc^PxK`cF+uOHVfHWHKMEQYsf4gQ=G5c<37XcfrEv;P61m<)io7 z5S#{tJ^%JTHib8|5Z{%A8Sgg>n>Ep8wMrSgS>(u>8O26oE#%#P(}8cg45 zK{@2FINo4Lxnttt3#nmLuc6>f@9;Y>t%QdD5is>`leQ%nvBu(ZbH+hZAMZ3(be& z(|bw&>x>bd^UjbHZbCdC;4j2rcK^|6#4zbqr|(KujBZVecHS)Zrf;7KU4X) zcRO7A%H`4?G`Wypbk6O(Hg$ZRU1}-yc%j6hzN*Tmt8?g}Ac&5O2Mr4vI|iZt5xNp( z{@A!ItPq_C2dWd;uUW?}bjF`@nV2TKuHIfu;XG$~DjV$niXOt<&qMNUp&~*POe5wl zkWl9z#Wv*RvC5j0UC6nU%d@kK!&z(~AmJkz{6>rsq4=U_SwWnO=-_ssW?GDMJfXA; zn2Ol`BrvJI%k6`dXty+$w)0B2qdw_3~VqOui(}=f>=#U%CJIMrvVTW41jvyln zwX@l?+57&pTs)GeC<)Vg})aS3=K1R~6t>fNDm=(Q1ID>;#zoKT}5Nhq>H1AA~r@#8%!B}_j=^e*x&Na~e z`jJKpl1i5UK1y9S+)2OIH<(ZGCz&Bf{&@1mV7lgFH&gW|a*F8h_vvZUBE;k_a&P8s z+y4?Ds%dNbN*nPw;rOE3lUpccG833KE+D^dWSZmaRd=!PvlD?GEftegn93)7j^k=z&N&;1jCH#pinA_I$vQCCZ`0a|Jqk9PC9U3lNY!GSz_*0Ls8Va(RU%nZolO^pZcYoLi)JhqPz<8?CfD15s z{mKvRT2JFOwFlctEs#L$Y<@i689qNDk~%+9@4#uR3#qamFYkDS%}DlT3>{;V`_<`mFigs;;+F|D}0jDd~xn5op!K8|k|SuxFrW0tOS1;h3; z&?w)Jy~iMIt37}Cx#;1bod`6-S*A~WH|9GfX2!vk0=ons5Cb-YR!4lTxI6e}na~b+ zaqH z+_YjErV=F@bYe|goowGNeR2oL`;Vi`-*tiNw_BL74OjfRNMO`HoU9tlnaYZ;Ef)JN zUJEZ}|K{hp^^h;*pSk~8ONhbUOYTJjY{D@q%*yP{0(KMPb4P$~QqB+^Qoid0Nb&-)lzYCTtuyC!`_ntx=MHsO(-knR46CGp2vt13j{RV8 z3UXf^%UUMiwZca}BL`|0T6&%N@<_QAwK+4hrK0e|mmYQf!4JhB0J+g~OW#MmR z?rR)8(`AGGt^BPFeuyxu?}CA>6)V|+Z5`V!w=xA$Z!?vY&ijXVG9LlT++x@d>2VSDt!A?ggX@pB!Csg8M%*@ffjcBC!I@-_>D`rSl^0z5#A~4AgyK8Uj z%Y+{BEL7xYDgS3AqkgyQ$1S@Xy|*mVq*&7?{{|SaoUEvw*xai8mEDt|2eN|`_iNAh z9XGqIRSOe5!vX8}(drm!mzxW(tIpIdsejcVF_!PE2eX8Sw`fS+2ibP`?~X0jl^ndo zgwUnV0-=3JW5A!?9>nKMz%De`{GaD89+hBGku~Awz-aLN;lAa8lYQwYz^i!zxcZOy z8m9cP(UM0w3 z>rbAg%H@K8nWA0;5yxp8+hl*;$OW?)aRrq27>?K-fExye$*7hZSOd6$OPSc@nt=SSUZEjqWN zani(GUnEP1$_uTtsN}p0D_z^~Y1En^-{~QX1h4WWhn@C~ocVN;<9X>AQ)gs{u*l)^ z_fyzq$>@p^!tf+WA%UtT#@!cJU&@?Fw9P>EFDv&J4d|&)LW6?dzwIzuV3(VGnmX`S zlI-o=&7}M^*N%ztt95daGWV0B#; zRT}elW%`Q^-!OxAsfC$=z%=2whhqXGN6ona#C7=;@s7X8bC7-#cF_G`XYeP798yy3T_7!jHtG z_v{*44Sp*6ysH*aBpdIufanV~MOGvE8n^$0G1rZk>Cm!|9+{$vo$yU`3F${ZCw!OB zPPW8sjFeX7%gL=6%>ci<(zvy4!H!ncDY-Xe@aC{w!j0x|%t;%wTl-a2TWxKVFX8cl zR8$ChzJ%^4z1p0l#rF=(@I4@?liz^lANceVB<-G(JWrYPq!Gukd7S3}yV+`?9$3 zq)nF}uF25|9_vnc00ZKdm93mn7 z!AjX1bpO=f`4;sW*r4>Z)IC#)vLdHn7g4I%E?JWQ5*ZVS{MMI27NfDBC-l__q}mXJ z&v)E3sO#GqAzc!261PXkK5Job&FEedoUM5V_%JD8BlB*>@N)g_SR>}z%PU^4@M@Jv z8mKjYiH`ScGGk&OlY`I8;5)VJYD&U-wbTmH%5N^ryB;h3n@yGY>L$Mt!Mcx1Gf`NO zuGIX7yZ$=X_mEVRqM@N+<3yid z;K*$I`9);?rPS2j4&NeNx5UTHF|s1T{~C-u*kXdlYxoq;XoG^DOiD_MTzheWqcypD z!g~-m_^eyv2+f?pM$id)4hc+(t9xupmjM|j(9d$E{>F_iy`kYS8)DJvF17ZWKiuM< zn}iFH<;&pp{YT3xyC|rQiwlj-dN1Jx{S;k~L+p{EHu~=2+6kl7;jobS>)}-A;7-0t zt(Atd*UH+TfqKSqbd>8KnB)Y&;k&MPn6?SYe%@h8gEO9~j}9-Pgu@t4Nq$PF2f5|= zpJNJHz49zC{=J$s3AtsQpX@k;dH|!E5vTBO^3mU~$K_O#rNF|gkWEv-HflH65(`@J zrkT^^?DL&}K&$rY7lGQm(;##)UTI~g)I;#CU$1W1Wb}ftFmvh@nuCF>;XB#>*O4;w zZ(l@-Qt4#hK$5yaG!cGBH9TW_U#Q=@G`tz99*j(tZVoK>+O)s=5%o{rh&v`MH(kJPZd&u% zbFntbXh+?p~$1qx_RT@Jy`0`U^_z@ z?9b4pg6b6Z-QCI!CsyH#C6-OID`PgwQ1);*X%H9^G1Dyk(E|CM>!+DZ;@2dM-*kuF zx3nx=o(oREe&rX(Nj)_MpZa;w%RV+5UxhGiD${LSFE=>r>wj(pA?}~<_m-TUf-&t1 z4#|u8AxeE>9A2Qb*RMl@S@A=dyXXzQD-60mX9=`K4M(VulGSYpe$;3*N5L@zDP)Tq zP->anwN?sPCH9Cb#?X26WG~#;l{av83FGog|VqX5$)f!Djtei*o#L32kveeqB z1PGNLSt6SN>;(ah|GxeXGuxY>CkNIfTS`Mjq_Wk_sN#0Jj>Mtf=*PRSNbs220)|$h z%Ddib!;wM^*)2s*n=r8~1w+W5BGn0h!E-ye>yLidLxEu)Q7XKwNL#G~>Y4*8)8+iv zR)deLmFDxHo&zlNqlKr9392N&ZubMJk!~N&YHXM`fwag&NCzmVWwlD!)cfOlexw;MylL)#tUK}K3PjiVa(gn zW9GU%##oKixZT-QSgZ;typj()zwmkg!nGU{z$mvw0zMdF@BFsme~Bm6Y)Q-;`NnR- zt7~2A`IgVSl{WSx|B%ub+Y))x)pkI_O8<0qxu299*n)L8$Hz zt_Yt9gudttQ6o|xBNXgGu#!qJ_BiN3HvfkKpaW4?L)ja<<&;P=lcauI-B{#G1sC(U zI<&IUNBBSDdDu=iV}&^6%XHwi!(4q@Xi;cPg`m|=uG_`OC7oC~yFiBMyKnD`h;go& zGT=wqqE<`?to%hP^);#@p7xZ^iLUg+svkxc3obo&V6BlOS3x&omGA3Zc1C77dVDPC zC%ewceS#*Q8=(s)8;ck zg=2#3Cu2X{Y))2`b8h@&gvgzjav;~+ut(a_jHbT3+gVYxJ^{jQS%*h$t?)^A9Z<04 z(o&ZRa?e4HOX8BVE_ODb_{Bnqw_o@;t+emk(Hsf;28&w!7PX^-5}V)PRdiG`@LP8C zG(Kc^IM+ZB8-wO|QvqSccC4Bd9JZ9Ko zR65@dVg@k4o~cVqTSmSlmD!^D74)pb$0q=gr*EMqjX97|1X2LI*F5CnysA0`ZV&nF zKh}1k_34ltbg2*&c>CvBPGPtXc8>3UalL@;zZz2?FO|ZQzsu1bM9kZN_q9mc(DPh8 zYeRSotaURKGI)L%T;>2eB9)Xg=9IHS={4MrD_RqJ`i_S!<}{@e#q}18YxM#TP}#{{ zt3w;@)^qdWgLk-6FX+nOqvS*uyFRxP@pu{aX`|KUDyYi%Q5R|5N)ewDGJJ(eV%aHh zAVe8?6EL&*SJ0)%eVwLW4hkRsd-e>kJdK(Zv}wON^s5F;>LQ=d2i*#j?`R z6nMXfcO`;-Y7X2rlPN&4Qmhb7x7c<|62SZ+v~w64Shts|{3q7xya15R=x*U05CHlh zmaU;MEma1LNf=n%n20$s>G<%e4^7_R^r-3!eDBMuK@Bq3?Pm=q31#z6SU!?ZxTFMo z<~NB=#Q9bfHMfuTgh!>hh?!(V*fMmeQ`kS9xhx8L&|*6J+7fVRSLZs$DDV;^?vLB8 zT$*=A0cR|;lE(Et8PZCcsrPN}^MfsbQh@woo&1Rj4>*{?B27zA)a|;-_F1_D_-LAY za8uoO=i!3LcxKZ2dxwJzq>1K{ploZTO-f>*|HxT z1Z2%B{dJbExQKwA!Jy!S!(5){$4eFT^`iFHMv1H5X4l|f+6G>X*A+N>;KwSKrynnn zyQ^C*Cayr~YI1eD4GLHkBKS@&R+8$@nd4Mfwsci%tUWQ@tQ1Aykk9()2s+SIVwx1p z+9RQ3T*-T|09?e}LR0hKKQ`A6OpI$}G53<9pV}_o8W?d@p9_agN;DpsKfQW0kvHo| ztz+428|CbjQSTVq{#%|_V&wx&=TDv$_-hR3%Vy;)4Ggb9xhIDE8nWZ^4Z0p4L95*{ zyP$_H?jDfmefCXqN?b5X&9GHTJoL{4fEN9vtgh?HzlNJ`!tlGY6 zv?rn;xr%5&>1I~$*o^q^E6c+r0YQAWMqo2Quc#z~Ajpv!EyRAv!_( zKOra>f$%W;6+w?7|I<^M7X`bP58f3Eo+ zr-_UR^!+P0B;h6CK{YjMiIjN@|H`g~M}Iys?(h0*}@pu&Q|aWL3SB7{UF(tm^%Xu50h`>E zF?Zl(8B#3CeOw)stAPS?7`qkGq0UYm#uK$XN=}ORN>h*8J@2zTAGV9NpDj36hU&x1 z0I_9YXx`Rb-<*AXGGskuH(6W#P3IJiLN) z9D!?w?!`X``(j?>St1vEoxaTw)H=S-n<_p#@d<`_sxBUUiU)NPyAidxcsGPtqM#g; zSIwJ0*^gSA2^lZ?bygF61zx?5j()7q-;@5XKvC=8Q>ful$zjY_`4Hg8q%4Q_fyn?39%v%Z5{K(y^??^OumjdbHsLsem3F;rK9_1g@y*){|)~;TNHOUQ{N|M20f8Qdxv9bxo-5% z=^JI@Eq{4v*dZecH0=3~V$|o<8YIk1Z>;?3;pVo@%d38YoAV&rO`8QV=eze7e0%x! zKFrp8C0u2km@Y%?r}^V%ajHOW43%$GAm823K$bml0N=hz(%Sd1qPW@jk@%Ra;`@0e zkA1t@+5N9x_4j{9UpIPIfnOf@S6zIOO%;zUh6?!n^sTo5pZ-=>SGq(-%tx*e)t13! zBriEQ>)3UH3#z5%+4FC6Z0UYkFf1nK3dl~)2itMZV1F1H8N{WQ{83Ry2L5!{k#%Px zf|w|9e+YQ0cUg_r6hHedWt%0#C@66@K$*O;>{#DoQYA8-jOO#@heRG${_< zOF0#z^`*ZpLwMmO9itOpVmGsEIVWry&zqykgqky_^SRAxw-@OTbsYw31~l}m+t28< zj4!>X)iT26f2R^<<%yF#b-W-2rR*OEm%!uvtxf)xg!p#N=lq>$Fj7%9dbQ!Nre`o# zdI!#(o1pQ>e^Ad^mOLa5SPNfei7TNd)budwKFQ)P6>!K;4gsBY`DG?KCMUgfRaHfWaR=lTT;U}|t}H$K*D2}a zJLi?!(9I*=2PDZp|17IY-0nq;Y2O^igciO+uHAvk%mPAD4deorNTgxLz%F}TC|XMX z=rJWI(W`Bcw-CL?ty(ja(Kj?7D+u06kC|pf3YpF{(M$O3Z!e3qZm)ra1*n=e6xUWP z99%5NHGDvyQn9*`)`vd+Nenu+!5B7*Mo{C2z!Z3WLO$!9Op-I>il#L9fPOVn^j)(? zo*Hu*{}O3X>s|(@ExW%d?@+>;MQ8hVLx%LJx0r*oxsriP(=Te|=Ma3E!{HrPe4GE4 z9jlc2i_Ytl$`IzTSXbSRtD|$bql)iYA_%|#Zh{J$pj^AZT5L#iHwwR{=_GRrVtd4| z#p++$!9(s(pSLOm7sV-PntpJU{&?K)Hq%wv!o1^_Z4dmc<`9F^1VfR`uaTY zYh8E8%I$JZqp;CMgHE%rz@7c%nOJW^;Hc*q-9q1Z^+GE`em1oq*8;N@W)ddEHyEfkDG<{RSyDS1ip)l2I*&lOG~=xTX-+l#OH?>>KJ4+Fpf?GjNy7AsKlwW=_f zEUTz5^l-|+@{&>D-KrM!nY18mIIiPe3h&!8_lzmA!KYikz+;>U4SfiDZVaC`9w06F z2V)EA30aahK7iA`4n5LIPMfbJy*P5sZQ9h#W1(Q~cIisu>q<=jEd}-NXY%DQWz==d z3e?g`yv$IR3|Ff1Y9@2lFIg55j^)87gv{+khQJaSmejT-Vf4tcFe2H zxwCQGu4C80u$e%u-LYjDGi;@&wQ5+@{iAXJkm;7nr)s+D&b~za8OI<*umqaC>06RI za=GJTAAvafE14i=60&bJU*7%Nzfk&7dX!HX`F59kX!Xyg%k~E$q_kOT%-9`xe)gTW zM*B}1$jukv%3k|z|Cbr4%s$Py4kiVk_K2&_;s#{N1n(Ez-q4F_Qv`~01)oxvaIHVq z2C~uoJPzDH{v0P|-N<2}zyA;aMfVNeai*lkvt+=G*72mV{sHoyCLLKx9T4dS&DowBFyzuJVPV5)8vT7+)U0MMl4{|!*fV@(@AIaO2!xZ_BCCl!= zHO4)5Hf;Dpc%oz)19#{zBK2Gr^5Qf;`i}f}oH*;H*UzP9hRa%9i zXR4|MBX#F%N>wUmowHo{&uP_65$`$(?OCZ0_&_nNO?^ zy5>n0W&5}^?~gDs{$tP7?8fS&KiJ`S3^%w9?32x}eZHS>FboiX*-;;^9HptUHqN`li{@5bXnmBW zc{RIkG=oMn-OY|#R`rZXaSz`iv@pSLh>H8XFE6T{g=niq?CM$-qr!JI)U?a|uheGp zU8Lc`>tgQqOsMOvjkZ8DhK814q4T+*ry$XR%%j2ik^k(_UPHnVzr$Zy(J**0@#TF-3Obvt}ZAc#v%2vXYYf_i1W4=>eYfjSBY1w;;=nbqJT=y0a0{*=1 zdwZq(EbMD>t|8s0-@__GJX-9eZ@%lX$Bog_f1M^-$Yh{qh#kWFn|TfrPayu;Xb2{u zU1LY;YOHy_4|NDBB+e9{4M^t;DX+I%@Mv*t(_ueDqHZU?6DurIC0ry(0$=f8W0BEZHMT z=Hznw={sGk=$)wz7t+zP)b7H;@68t1F?WGgJ)7rTb}MLfZ)+4B>U|+=qe}e#L`dr_ zMd6$%opWPEW{21{Azf#n5fU3TM%D0napGORi`Vj2S3}4D53)f`zI;zapf6(?s{NT} zZ*iV4sKmX~j~{2#Ic2LO{P(|qDd?99H>X}u4!(O&IsWczB_3x`2=E;{)XADv%btEx zA7_w{ImP-s>^5x}AKrxcd*{KnK$<#`lOQBA`yZ^;gcwA{72@2 zqd+j4MFFk;@}(8<0emMlJBgiJUKVg?aEUT~oQef6EfYtpmkd+jgV$yTUJ8Fzj(Jwu ztZaUJhD|JqtnZWj4GII90K71RV!Qt`7vP8dnI zSXx^S4=qvZnwhCg>MSag#p1&KlNyK;Tr-sBMUeS(KZ~wYb>-0VXw^A_4V~~ z;I*q)n76eTObeW5^3PMg=+V6UNNCq#YyCM-Nl|cMQQU7RU*FjEevSIt+grc^l~pt5 z%whA4m?AiE$K!FgwzlBiva72z81%Qbo$KuE0GIO)a#VREanSUZx7}fwTV5BQ`nq9j z9C$T|U>%PW1TW%11q$y8e50UBIeE{XYQ1r~di5lAY?*>(%2;*gL=^}!Xn@ji&eG9s zOdi3v5ZBRjlXt`+#65Ht#~RI4#zPaLYVF&%3-Hamx>^0= zbxf~ja0AM}c+0*2_~8sHm3dq+PqLUqld<8|G0 zrn5en;e#Eoeb_Xh(3Lnfcdzmt|lP z%L~|47AIz8(B!&L7^Td+(>nbMW#mxh%1eVo20E-ZTU$3Pc^an$wTOPSj27-M_D9&F zP-SB^Srey7@&z!TTS`yWw2Il&D&{2q($N&b6WgMoN@Q${Lhua-;5*0Py(IRwhMGxt zU|2c$&aQI&-A77goI&=jrJpfzVV>ohYi2zD)Q<^L7tOyv)(D&bj7|>C7qB;Xs9(KN ze<)76v|z`f4yQxKV&%;`+S6+$mwai4Zln3?24&}AKaGDv`XAqq40Y1OaRyTnXd5TO z8u_Bd@OA+qJ&!&447ss)-D+knV4@4A`He~_HfS+X+#P)?uplZJh~?xNt);_OS{yYx z_~BFTorkS&f1;dhWHd=nL15pyH7loA%=pGP{(;QFAqo$HqJ*Mz$SSfJcbW9fZ+!K? z{=er0d_TPCAw-TOiB!p=U*54R6~%B)Tme}q=2%fAqlPJSrm0iH^Y+)C@$9edYHabH zZt|9wvYx*&!z~j>X`A;s#9Oxv-^j7okL>8DFzuMU>w5K}+jYo7`QuzT%I&kv{=(PB zjl2AX7k>W#{@?R^_Uv1^{AZPw)62@rvD|hCn^Y*$5st_bFC@bzoMF3j;l|e9W1$^~ z)iW)gK}Dft=HU9lc-^AMv&YlHO;B`y9=ULnBm7tQ=OHK@M{qcS;8;_za9|S=d~?8N zb%oXl&mG2b2D`git4q+lal;31y}>>eom6(}OO>oEq}`Jb{)QuL`@>vLrMay=GUg_5 zv$4f8DDU(Ym)JM&WSK>52M>JqqaQr-&1-iKD$+l=#A%z`H0kpIc(O$%X40M4sSn&{ zrJHVSnKEjab>e94hN+=@ZwOgc^>DpIRp1DxCt4`0SX&fSGsD9NXA5bljgga*s9GWt zRLF|T+0!fM(3g(bm0-v}oB|aa$I5BybO+ttY@`>vJv+82r%oOJ^Pm5OHErfOc?VNY z*%raK5UZo?M$W-^mX+i0zR;RA>sG8-m0+Af2v6uhATrM2iq$WX9mvure}uIjND`hU z6rb16ew4I3@>E5cIGXvC7Tdp2H3$Jl4$Z^5D9?6N#h@u;3)w!4Wy|5>x3-ovH?v8S zNe@4~c+p}VzGFGK_f%hBCl=i+EWo$i^Botyp$n$@jU+TllKV}LK(zeHZE0%NfES(J z-f^SYJ09Ts{q4aIcPLG5j3y0_@VEI8+V|e~Rf9P=p6Eh`Orioq`UZ#Zmw)japd{P` z-{cSBP~ulZM>uV!h~TNH)6J7Xz+Ob+UQ~I z_oyKymi;GG`qsh#-)6SF3T1(85&++KUmxkB)bgil1HN==$?it&*5M>61quj$&s2xkPElI`lMP-Oah`kg(Q$C-{H-yz{?eQYMyu`)G{v@% z_w=Cr+P0QbW(K+=ER*4ff&5A%08dpxT$F$2Eux-M>228drbCFrti z&26mrJ)U^adIYbj;t2$&IeKtre}EN=_yU-!B^7+;(Qz-$0 zr#MX}u=@{xc&WX;RWua@-#G-&t_<)^Ld}W&hy^t#2j4wWj=y_dixxfd>Z^aEhCiMJ ze8-M67|W(4w2-(-{A|uMc2@)ffrF=Qc@EFGk$R`p$f2(CQs=l!3dW5r7?7`f9<6h4 z-r2VMuqVU^UVsna`;kYo0N)kdnA`MKAr;Z#SR;mu8@{0=sqRmiLN#O0RE15@;|ti1 z)_G74YdzDY!WxSFyp3K^ep3ASK0keH0X2>%Jb;eg^z1y7I~i{L(gh`%%R zs00H+t-YJsgaA-DhZsekgNv10uZavg^pjuKmJG1wxmbrBV%UA8^O7MhvePIn);8?{ z;RJ-iSRDAaIP5G-JYUK^v!mfVZ))(8pX@zmIe5x;<&3}IxpUjwZ?kS%Do{wZIyY_l zSh4sk`81z8g4bl(9GqAODLmQ8%$LoFCR8lN`EGq^!gGVYUQb8+xwB`Evld6^ZwN`& z9r~ZhX(GG0Bg)_F^(G#gki++8R43lPQ6mSQ(CZ4tOuM)TQ+HSU;34H+kB z-b0sgvn!du0pH*L?gKQ!U|a1QCmp4MGQI}V@fZtn`x?Mlz7Ta2-VEvLzZ>xEZnUw zK20VZ1o{xlH2ejysFqBCZ!G$To?s;v1gDt8FMjdjefMQykZ&3# zkmxzy3qxYP_QrcSoE94M1X{A-!M9^aKSbvEQc*SIwma^Q{LbF5C0!={Z$hOMsP9CN zHxS9uI<=+Kwr#)K?PX7KQ}`y~x){vC@ucTs3{GL_Q5xnXt*9{nXaDt|OP?{D-ZDm} z2#%P8>6nAZ3h3OaBNIDCIHeH@pHahAmQir0_uKx*pN&Cpj|I>=E6MDP0GJ{^6idamb#)PfEGQ_*%PSl@Y?RBDF9&OD?>=&@j$SZMwhW?q<_W$jKw)wD zHD6pfZj|{5gH@NePaG9x@bTB}+Q)m??3D?nln?e^aY=}-JM{c3CyzC_{r*t5H&}bd zbL6yp%BAd=Or)yQ&4vmUUErwls6xmroq^dUa_c5P8+D%Dtt5w?m4+c1*hI}2)&KKvCs zPLb!ZoH!HJ)1Onu%E5OZE63lxrJ9-@cinYg(xFa#K40uOgDaLV``L5L!PbEw;|cl# zjGNf9DbO_fS}Vxr(vv=^vAA5$hBHlPTeRhW>}YOxpKG@?ob#PJ>#sfIfAeF{pEh=H zsIhjsZPZRx&6xS@vrA{r)W;c&wJ%Rmz-2LBA>g}*J?L1Au}}ct=Dq1W#}Cb0^w<;6 z5U-msdjC@78bMJTLhv>0Fb{X$LjJoAb#VBZUCR#sHZ`1&{g;jzaa zgU`l|8v#(nP!RvCGg4te{!jknUvXLao+R*10v}_+(c-C0O3NHv7H%s6-%u=n%bP9j z!E+t?H%w*EtFtZsorgLH6tY2w5DLj@>j+kiFPbo>0DI50g!UZ|HgjBI4>SJho2=+B zGTB~0RqYuz z6qN)0PuMHQ!PeZVdyp-PJTxKT8w(t~N>RPiBN2LFo<7uIP4#B1iwX;hiwcl1hckab zaVZa?3qCt{?{8|ew0C*Rh790?e2@Lsci7wuvf_;}2n0V;*EXa?8Bk#R^t0~m2d(Qr zVq^6%5{)*JHfY!&+hygpVf?-B*MB~9;AHoJLN=HzHhlr@c)e#tss6i4w}(wxFV2f% zvDtJB5WqC+$qttxY8@o%n7Egtr3X#`-$Iv@v~M{zc=i7vMFfSLrra(FQ^_lZQXk;RJ~u@x=-7-Upsix+TLX+ zSO281t+Dr?3q&A|~25y&@7JpKlJ)2pm%W#--!N3#=OHX?7<6lM-lKG->P z!hku`+0^AE@b{lKhSG&^5~!WbtgXT3cQxoJZLF*w-&j*hmb zrpCIule}>B-I9#(O)4uN`JD&8zkAm<&09BXiaK~;!C5yOhE}*Y7i()Ducrf5oaPuUzMe+H(Ir#1a>F~`&6`BdR zW-NT$Y&NgATOO+lwFvONU_lPPGf|Gev#fN-8JsyYGS1+4zH|R;uj!@~R;$(Ja$R+~ zeZ~Z}YJzR_a4VKcW7ryd!QxGD$lg6W&NZ`Njvt)6uqW_MGDUFQ0Juj|HwPyi5tNKS zvCnm|rnv9$9NJ&2UVdrG@L~`7l$ScO3@C_D1sL?rk3(l$*f>SHS6C8!W0!HS5YTql z;lRedB@PE0P(`|{4R^S{g+Gmr^;p~<&+#MsQSxQwY+OPtC~5@A!kr?e7bmszT!6o^ z>^;^BF8o`yij1T5&NbEHbU%7*Dd@i;dSG()i=CqKUT|ztblj!K9R8zki@X{f?7!RH z83?e}k5D^yefhX)U-;6!qsNTJhS0_jKd9dNsa0#fdQ$M_Y5vVe*hiMK&NiL|ZD<;5 z5&P1ysm(HN%(%^N-YZqXHv9mpgRh^nv%?G=v|)`1|!ubTkv-TduBf zyZAWwfF=3o)7YU2A*3x`_$Cz=m84>e5-Uv$dOh7ZZ-Q}AYHB{AL2~&;jKKHaW1+44 zY&rPOiX`|Jis`mvcNv54?(Pn`V-YvtKmT(MzB5;jzq6@~#~IwRW$O=q@FT1#i~~+y>+$%kn|8TZzo7u2aRVY|(H{vV z?fDi8hBVbasIYJV+>u*ab~5Rk_|wpEx}l*CjSNySth5Bh{?6O1RLKgZS8Y+i-zOWL zbdh<${@7zpm0r7Pn=OYyLHybd0loq z!_czh(XQkh8KrTS-fP){DsWEJd5z1_`^*Eqfaxj#0w^6FWMQsAckctUl4}o zfNwZ-;0}MU2?rK<;sM`pY*CQ2xX7Lb4av(R>WZ*w#KjJeYyrL-8yS2DgTXN)hdDqfd>56i zKyYlzUD26~&db+?;3#Uhmt~gVTZj@MI^cbNi#t4alfuWNln~sIJ8TL^#9t2U^?Lbl z;?(+Lt^dI~6k_8>H8-^}jZ*9HqirvRfdiES>JaPPR@bqfHH-#Yt=Vl?4K9S&vVtb$w zvrIf-9b5jWFG~;mwAA9ssQR4-C(@Z*~x+d?zQ{4^C-m<}weuA-ON^PTZ zydm<;vD+P1g(3>yRN=qNSG`C!(>;W52q`Dz1$-yy*p@LJ@NF7Wy7kSSq=)!WC*(%r zh1rQrN!7^QNer#AJ)h-1mY|+@vSX6AemD2+lV7-15X{Sy4RTNXr}?9FK7P z-inBi8>q`}w^>z9|KftpL2K*mW|q4r8`aiMM}SRJXti1u&0f3RfGa5Ma5n%X`4Oilv8QbI<|jlS|eqjmiM=ZK*s!FM=TsY! zcP#Yth@Dj|OGo>;!*!1Jo4WE{p#oQ^(;WnVpKkKhHiSOhX?f>U>nUmE??6CfGqLj; zYbtg{V#ZxT0U|pUm05sqQYzDA$^tzj_rVaGCUfNA4%`cJM>ycy=kub}1$;NQXvpa>)eg4J~X}?ceR2cMi19JMMe*^Y(J#7 zcjad&l!0>=~SCNLkD;X5AjNAfH?q3A6L&xzZ)i2~xG zaZU)n`A(h4!QAkqgys0VuVhR;wv%UwhX9IU!DYh5rMcz#zO2a% z7Z<(&n^F-^ChQisA2#`k06F$RAc%XD6pj|~ZMp7Bb<{8xygB9rwveU{8eC?x>D|aI zx@bp~)1sX^b)vcXtbp%fLn0r50=}PHzE;5ZBa7#fe=kW&l~Fi*^|ozz6L@mz((3AM zXByabM*+DUT0x#_x2brO5d|L3p2)cFjx7q_y0T_ahHvT-XS*#Hr^8-4c%aYg9z28w zInfV<{(Iv=`iQp8lXt3RFnI#LXV19_frbt(yYc4RfgpSLY!7#YM{H3B7u0=ex<0+7 z&^w=MCmW4*&rHm$9Fl(?VT0GGsup6b1FA-?*>Onya7SpHk*>CzoR7*)j&hSx;^Y%sm}nPRB73w-~v*r&bC?x7I<&CO2u0T-@|^>fMm0i zcR$g7{a4&athmBgJ|e(3{k$VYn>hrJRci3fl!NbHRgS-Vq|}Ex!6P9SzQKoNq&SxFB+IQklQuf1X%8 zDko;yisyR)$(VuU8InSPxj|!Oj?x>VURcluzd0fT?SXp)4JVc%5}Cj8WU^ZPtSe4s z&oi(f9!_!zU^fAxqS_F^>kHa!!s1q$I9i!{xjK2QGISubHHTybSFMiXlA+eHk%|CK z;gFrU@oQ_3wY9aNAqoWiLrVw5!Z*450KOB;AF$M(tb5}PcF~_&s+)s5?cig!mkozu zRoSdDVOx}NCdsWkxI4<>cC%5X4e%}I+9ddf!{N-2mYxJJ#AWo?s|YHrS4KxFApY$!~)6;VBQpgT@yUkJ^a#U(`nW zMTHK;s|eP}UofP4eAdoxyFY;9K_NvF&)}O`8|s@$g(&4z4IAtXTJq1HWyU#ukKo7# zEmT|`-Io2wyyHhIEnTb^yrZM-E3+*EzF*xC+Hsg2#6Dn+6o9S==Psae?x7dfu0*9G z_|74Cta9+(f5g58(VaP^DH`e|m9H(~D9mGx?26Sdfe5il@C}E@#}>$@TCTjz`qi84 zlgH}6t9|qF&qkFw2A9~13aspqFH(^GkL6erDD}o8WuBEe^vs zoWO2yF!#-Z5GQ5fnyM+}BTMXsgnTZNEjU}ix2Y#iM1AB) z1KErBt)enxp0gD4+mDq|p3X;>!Fgx3SebCU-;&|{4F3G0ZN&50IYl29z%wMo@!NP@WSFe2O1xgi2 zRO@8D$x0{`2!(=_Nz?4J|B`QY%u0PF8;Tsw^QYk1SN)u684(;32+S(M-tWKx% zTVLpGSLY}LD!&~w&kh9se&UCVy?oqQlB%+gXeW$PreEPb+32b{=+-QeZ*ZfTCa%!_ zQ`d|T9q9H3f!fF=r4?BNI-_3kiP)GB2Ccnd_oVVir)Tg0%O%5$YMXT zo{;cAFVbJ7EDG8Nxdhk%Krz|rRV9P($SxVa#hsUf@9e5?FaAZObm5zZIw1^QH2;2r zZ;0wW;9E4KsOq#ZgT@e^udLy~>OU>fP6~AJJ*C?L z{kMSnImfLQA-p>9>S zJX=QC-uv-0Pj2KNXv&&ArQ((KpH$A61vDX_P)PClEuS6Ne)l)$$9pul&*k=NK3*Rn zL<_2p?W~nW^#Taq)};}pL3E(tY$05CGOU6?qD8z1=_pB*V@$cQc{dd1x+t|qZ z!n38nyZw7)5l%{261q?z%zD1Ny(pjcOC^PGNPsmQJGO7bS+Kxy!!^@IosYFn=>xGU z?F*rX;DsLx8{9oSBL^+;;T>=qCt&^R_nvwP-~Z!(d_M=@*;UT|BonP!v+nulm-ANM zSeu0izR^AoDA0#GAv=(zPyR@NDTF%^4K!;;6*j83qS_{hjlX~OZsWjWYo1GWI@ny_ z@Wn0a@rJ%MbI`bv`q$zcb}4md{o;9pcmN9EQ9@GiXio63rKM@VBA65 z=QY0ub8t2b3HyuZA8xBu$3;OTc-6%rw27O}YO`x0M8SMys{j(V5pz(p2iSD$I+NM$ z_KI=Zl<;p{TK?3~$e)I6L*IP!_t(w7ySn<5zx?IR6ye+BaUVZ^*z5KD*MGfy>eLBE z^A`^&5(e(#6EvtF!Z+l!TXxj2FF|j+{jMK9wiFORb^_Ez$S3l&iEeC&G9J!9h0z@- z3g*Y)J46(Y|3!rb154PTjS#{2P1DsD_uzK7K9~$&vp?sWY5{h*fc}8Cj}>IYwUezM z?dZVX(b2PAzVZ4i1Kh71JjM7sd`+1-IQ|eCB6*ZkL5g8>f4&hTWI@o6&(HE~RrR0_ zJIf#5@$`g3Z0cDSFWULk$s00-@5y78lg&lvIuK#x49AZj!aD1=C}&b0nvn8!w$)PC zWIa}=RUgy<-?%i1M>_#qm+=wqUtGIN_u|^YYZQ?;_P+bp8vvg5YlUU3G z4T0$z1w$eE*RyP?=kSe1-^eLT%JFyFTD0ilS6}@TcgDR*1bi3fF&d_!P5`Eh=HG7s z)5wjcSkAVoHoJZHRNX_hT27qtg^DAMd zL_7MaD9LdXE-7w+$PN)r(#U#WvL$zzznKC-)=M4x8b+_+&a;f_lK zf@8xMv|Ch%xI;l#S6*fvJ=8sJr2bXq2dBP0V#Jt@8{ez0{^-!5{oA&El#sb2eqCLi zCr%vk`+b1#s;XIE_`+>(z4;s31%913f8j&(&JTREvS1{k1z2w%Ur^dH4}QS6z^T{& zv>pd7SQwcbNQCE;?W1r(y38k>|EK~91lZT@xEv7oWNX0p06w=oB;b4KKxJ>;B?kWX zdAq^iY@7FkfT~Y7IrbktGv$(FdylcpBoO>R|6^&1_qDsOWvm~K;H+K&`~^0J>jU2i zJIFIuh(qi_S%H3}(Q;UX;zw4y4f$n0zCZ{`rEdw63h{%#WsMwanKW808|-^yi!fD+ zMAaMS;KR#CccnZ{CcQ0pdDxss&F$9Yzmty&Y}z- zfxIxTbX9Lmt{y+f=ndIKxB84fPF3MT?0VNECg%=x~13) z4$tsOyMz*ZWbr@glJ=<%}!?d`1_ zHvDDJo*kv7!@@nj;_)5pu(Y?gojiFo7!3T^fBn3o;+p2>v(?ofA3U%JEf4n2U$77h zh3rfC2Iu*hl|1{r6%TtLh`vN~Cty_W%LJ?-e04RuB?W@xGJ!(qIK$}R;Zlec3wF^5 z?!17Rmki&7i!IZyP``e&mF7}tbLWQ#Inj@IIP(Xn2gF1+NEj|enXPb5Tp?u4+ zk9TyGl$5Mp{jDX zS{5=Q{8>G;yZruuqG*KIcB_H~vDtuQBG0PbAGC!ueK3&3qJw1mM`ml!Xs4U}t?r1m zk|+=e2#%$opa_fZ)ia4{GE?jbXTLS^$w85L!$9(;0$YQ#O@~o>VD19y{}%jBN?vej zioJ8PH*;L2sJH>#(=S&>4ppXIp^P8N99ZC>rF4Lj$3Gd6i5xM|E2y|ldZJ|T9gz&* zLOJ;EJ+WR@-I-HD@o@$h(T_4*#tIGL5sUz6lmXvZWcW@%!yX?WYKjl7V71~o5qk8y z+W1kC`3O#*^-v=&kN6cqn>Ql-}ruprC#Y>r?iAbJ-NQi!! zSukI>H0Y;|e?^Cu5MXVM3pDVLDhF=3sRy>(ZFai@x4%UTsurKa&K{d0BDeU)I&3yD zew6Z+IVxG9oH$!>{A}Sr{p91~;*tRaiiZsw!A79do8<^`i6>%PTg%Cl#{r#zfd9uo zUUt=0Gq!E}XvdDN`IaMR8cr4ttz5lExA|VVa>dK*R>sd!HsxU*(8*5(o{(@#0inu6 z%2ZZWA@SAQwyj#V5^L~**o*uIgTMl|87>R`uZPKv(^H}4^nqJx`&kg$h)@#^d;p_9Q@7_Op^q4>YdfsbqZxut(a5`aK(SLulI=uX{cef3? z_OgQn-$Ls*g?|5jh_0+Gag|9{l?~3VZ$!8!O59dKcjM~2T&_^iXI10$NE7$*>lK41-OB2I)Fc{?X1(=UB$O7=b5?TyD9Rj|oW#rEg z$EeG%Jz2X~^m7j=V3VK8^Pl}?tM~0qZM!}@sahR4FR=S>e|vAl2xbt{6Zi&ziowEZ zopDqUI9`~YWF5XCG^SXnGk)317b52}!)t1JDO2@zr(+x9&0BZhe#hMi5VlQEMNz3w zH7h;Ha&O9*ENs&fv&$ILRFOa_1@BXlwFv-=Z?TR^a3N?8Pf*;XW_^m}6Xj2sMdsjm z2j(x{%n~IKV)Tq%BD6hBV*<;-d5x`>&Tfyx78o;38#AQq<+nTW?(OsWIy>8(OfED8 z;YK0?-z_c8r%s&!=m!FU;e)LO)`nAO+((Zd^mw|*4Cx%0-(FW&*VM*N{p1smzxl=+ z#IN*&elIBy)bN54J@g_|X)*f&5KDKsV=o%MEzCeA8d>V=>VV5-<>g{%LaYhvQ3QOZ zdbE77`F=Oe{rSN#>smHNC*=T8OVIAS1pLTcN-nvUzP>V8Z z^q4#DzK6_9F2C}wkwcY++G^?u*So8O+Gi&eYv|1EE8B0LDoyncRI1fpe4818Kn9+s zmR$5)8agt`Vc=loMeYJ;KWQo|n|)Qa3R@IhMD}n{U5uo|Pa>Qeo~iH|PC==aPmRnD zEq0dEQ$S2u>o6Nf*&^CO4+SCh5n zgKsE#*(DRMf}tjZyz$mIakM&fqB`YLTt)A(`mWE8w;w#&b?{X8hdWz#9Bywo=k0U{ zgCXCLfyyT7rcdHrngGM`@wq3UZ&0BtCsn|-W< z=1`G4QPAk_*?+p*V@ErD=3Lh$Ln8xP)irsy?RWp;UGM7~11%j$2D3oD`s%A+et8}C z0y^)#>&wKW83^bJVwSDCGe&S6C^#O6KmF9BHIYcdrH8*J1(~*RmPem>hRy}ybYylC zD})hAifxOr3wg(a7bomZtr#O2NGU5>%5pErm@Ijlr&>+C7J(T z%D2hlRkPwN0Okg(zHv&_z%BrfTo?7ZCD1Y<4np0;3 zc3W`75PQXV*V`Y{xJFuMX9pgK1qEb5p@SwI&CQK$cx6O zprGgrxBt&sSDe(mXFl7rZTZ^uU|BkhPTG42&gTS;6brC>`Z%RxoLV(r1%F@x*TQqm zaJ8|8CxuH43P}gci@_F!m0K8YxGf4I(UFvj#_RR)-vG5Rd{@2r;u^e%%$qwe&#BPc z)Y(>s;5!esTwdSXZ5 zD-a?}#auY{)W~cg;KMbF*9#5=Z)~i;^wM!WJCP-0?cP(b!-E; z0pFsN8|^lH1eb%wvHa`PPsD?75^|HuB8LZ&U z%@x+MWeP1wXTHmF`?Ua7<-kdno!AlC<&?p_J&fRR*Hmw#-z&l$;p|eOhzM=5?(XhF zkrfpd6c!d#R?Pr>Z{4~L@Qv1(M8r=dHwW`L21_2 z)z!IY&vrQEk1~;9!;*?NZ+`!iPd>7<$1GlHePHu;K+PJQyC9WYx-*t5@k?Mv^)B*%r%Bf8E;A*=@yH zRV$i;qN3tq!^&(nM?=HuGiOc*0)b#KaM{SB2k#s-w%j{rID1b2_)pUxe)!Si;z6NM z@X(=shd2M=wi#V}j)nFf)ArYD2WlfJL{o3IYEEvOo-MU@>RAI9P9Cewo~nX8$j4Mj z&yRl*Fbu~*imfA+RaNsBEW~=jyt&oY%p9EP0WB>qR(qEpEhNgMv$M0PFn>T%L1kst zsx@m3@GZnYk7JH;BUx#;2giSW7l{^EK1M(@k*jaZ36fbZGUl*wb&H#ar? zwfdaXp}HJw_+W>F{SJeLA-I*nHyuPzcJ^Av-jGqv*b^U)nG*(FT3-A?O~_yoj=L-s zTcZ@=8z&bw-?|r94!-+Lx&H6CN(H_>9yZhoTD_utMzJ)`Ah7#8-?{(v>Bu`b9;i20 z+AbYot(ssjEm21gw-&gRrdGXi!i^Dbrf_qjk;fg$UVd>h+=}cD4Fh=O^qS@2N0#&+ zd_(p1b#MbosYe-(1ZP2D5t4+!G!UUwWaiF{_3HXRlLO~^X6a+pV@(W=HI|0@IwT2; zFi-(oBc#E$1iM5hdQ$jC!ui54i?o=?+_zuJB#B8=Ee9Ys*0O`#Mw$Ee3*r6^X$-Ig zY_oe%0Z8FNnYi0Hl3hfC1t#Uc!hz0-{Wz+-Cd214S|3!7z`B;D01c%*PhWlzJNc#3|B@C?tE{Hd+O9G0pB=q z=s;y?iPGst%#mJjo*35CueT;W7JKCgKhY8M@KXEze;0}RWTR()ZP%F=#);zF738q3 zOXI!ECNiX}zOL>~K2!aZk~w(33mn7tIvrLZHCkYY!&z96KV!xWz&8qZ@xr-zPLmv} zDgz)Spb4ejV!3`|{lG%IKFIeNHtoF7!2_S|-2A)YCF~~%VT-~qE{fgeV_$)q*9u&B z1Oq6`2#%^1J2auFY2+YJ5=BCiymeLfUm;zxx+4aCJ&*_R9~ynt`MMpVp+%K^uUGv4tdU9+xqpt^Q>G|>xA zJP`gx#aub~zJQeDZxhwj?6~W$drzE*wNZvY4FaU=X!mGAq-A3yRm z{E6V3bgV(!xXVbo$Vjrhq#=(_H++ZiEWf#enP<@E@>fsoINWir)7Nm$xASnP+Y=gF z#(Ja+@|0us+QHfwKnN?=pP7RzY*0nG_wK4DTNKFS)BHgz%ExYZR#weeyKe33RV$x< z>TwW{9>PpC8cbWKGO)=0rD-ie-|3HcGk<~LfbaFc{Fj@r>YO+-z$e3x*Z>eVA6>toZ6JqfBL%?4$+JVDh5CY*`$SLB%5i9^-5IpIDV7SO7Mkre1 z2r)o%bwy^+G_$t{lq&Zy9t;HEvu8UHJguP#1$;wnM8$0IH{cr!8hqLQ1a89=JiVtb zcToI3Mnj$4G0XbF!UO@mpA+H4HI(E_km1s9J$({U94_Jox`{;)N( z`)7_|P}^~+W7IHLd8xg#n>7wJIw3zw5w}3Ba`1g&DaYSN#f&p36sf^MHq?oa;5*M5 z1>es(f@cpctaoZ4Gm9)O!D4M})u^E-xg2O=HQw^F&MLe& zQ+w*L0TI}5*)P5Pa@CBP@L9azfmAHB<4GQ$ghZR*RN5rLllT?qO2FR`9Y_d{bxnlV zS*yVvaw+yyXn8^2)GH>0Gr|*Rr!)%@eCr!wJtWPPDRX>0rICm1WwY00Ok%o8PA~ig zP$0~bI~Zc$Mu$777z5$y#m&JJXCSgyFqSO#Obuyg8tQh|RF{>rVHqI$#E?EWl$D?7 zEGlsL{Q;lf?{GL()!Nq9S~{q(bWn+iwz8_~+SzxFx~%H>;caM4t{UBP#fYdT>$Q!c z>I2b)KSy0G)5*Ar_SHT`pwG`Ae@D}xpBNo&CYzVu=!Z(cv8W5aCKzn)kq(V}~yi`Jg zfY0OZgafZPI0<>mI(96LX)*!dn>R-$^XD%QTF-~Y+_AkHsEzsn$8c$=lfL0^KdS&b zd_$@dm^sNZYMAvTokc(#Tf0Sr6D(M8ch}(V?oMzgNMpg>CAdRyClK7Bad!zG8h7`g zukQZ_3>YxzqU+SD@9e!+l-95T%jXx=$D#f#J%97MN;>PXE1q9IZZI6j`@55iWT1_| zIA(}bG^_pUe))da8J*6QXRTo9UW{DBuMK?)D3GnE{xqPOjRm|h%d_vGAW2nnZDyDH zkUio^M{#Opj{-%yYqzUfY};aweryY>^{5+a9}2JxZ&cpDzeyj zqArJXRtT)o69s{{-X85$>|7=yo#PkOC>VSM8UFne%*d~JD+_?p42@-2pQ+BCIUX?= z%~yhcw?L(Sg;R>UZfV{J3L6n?<9pQa$Yh|J9TJgONfi!%S|}9&9;!_VwsAJ@d_bcd zIZ8b(yQySoPQxH7b6xEfYKD^XvcdFy%ZFSrGt_<>%=X56v-xRHB(NV{>G58FwwYLj z=96E{c0G7_k{ukdHkCh-0H3o_|D}n<32G1yc3AFG(%3USE~xwYLK<5_E$EMV`zv*+e9R>?g z9u?%TI2`8_{!+m0cgj~bcYlx26k+EN_qZtG)CDf+|JD@4;)IBccr@yvzuVhpE(OP$ zE;5Gn`2(g_%!biny?F8vT}aG|3KC^R{Ve8QG65AS;?KUYgc?pCM#SOF!t$75)vw~@ zq%T^(_=3x9V$1?TKr?=^lsnh|=NC1MQU+63@xNPs<^jR=n1fukBXg?`&u=>R-Tn^~ z1@q^9zJK;Ki8~LnpSr!Kc{rcp{dbOcxPJtL+{IR&`4%Gq%Cm%%^j4n#qW|=1Z!9y@ z@@Rt_Hx6$zvY^ys_a8=n{V-xD8Wr!r7Dw$O&}}g8fqfsm=Il@9D|vqz#Q~ zT)-^y_27a#q?6~|tU_{g`M1(YpkJMf&s`K@nb!KUYJkB*EXLpuPxPE`O-cj~fOz}5 zVCoEkAL&}}oo6a+S)V_+WtxGQI}+-;K;zB)4k<)|NLr}llnhJFE;=RB$RYo;uImQ0 z-*$BvGA;{Je+wh=V|aol`isw{D5gv)*S3_aP?UvR zCHb5i;1){!38!-~De$-SgOXnUz_y4n_5j^X6R$6tu8TpOI*px8yahP$Dx9~}{BCMPtJowbKOrP=wJPI9bF2|+>#OOtQ^J1%R)K1X_ z=&7}sGUeSOPS(1Z@|iz>CUVSs1@kRN6*UI-4P|| zBqRndS+|xLwz>#pxrdH(UmO3`PUHelRO97hPm?M-27ZHZ(EO;ktZaKLkC`jB&glIE z=V+`ef6^y~)ldUjOH4VtvakIOn9~ZY14S6qoDn&GCh6^u5}F>ab<0j3Yt?G~1)89> z`@Ypw0lsuvbb-)mLFiG+a?u@`x-A**QzYVY%W8y?uXOIk$Rp^|BRhkXLDbjanst%R zACpQN8n3-^XKL6|*H3zx2|ZgHEZ<)a*Su-_A_Vl^iO-z)G%dQj7p;{)0Bs+3n zOB|L=TMGO_%t$3=VH2dd=?nUbKi;dEoq7anF)sZ!qDIBZ%thyl6@{MYa*TEvqy|Sj zPbj}$(mz0&5eTQ+%(m9(m2yE01N*3lFdX7^6rs2h>6fFbbuosN46r}jw~;QCJ}=Jp z>z1KJ2c22@Ebm78#MOz}qs&tzN&Y+)mo15qKXH>pVrC|9ij3X-nnnq75=4qn9F~d- zyD0gza#ad7eDQ`;thiD|k9ufYSnQz88Z(sF+a#U6>BbM{kP%q&eX5SnQh?V*z}6pq zTeHKYss!6G^8F_w;;g2o~EHdIrNr+X|sbaua_v66VdH!!#DiJ zKu|9PIHP_QFERYlfA<8>{qmNN`PDS{GpPUa%2VQC^#xA(`TgHL9a6*f_q{G=qh1IL z0^zO}pzs2wXN$k5&_(5B+wkaSu=DpmQ0=1iqFkbm!n0{gm&?sQbbzV*dFY|;kVaFO zQusRv8@(9cC!(zpyr?`nE%00l^dxU^x`s9BVUKv`=CkCI%;V)|5)1+@#ru>{_mfRA zK5>V#aWP;Sg(pQyI|*UGdxw7iA=F}4?Kuh?Y)Zssi)Z^ z*#Vt$+RQJ)Kaf{uY(&@(MlKaeDAN?mL5VJDF?IDxs7ktqlScaXLbX(-l!Ih}J2Lv` z*+u&TT>;f-i#*oQ5E4@SQY@pBkLF9_WA=Ex_Euleib(rE!tV?iZ_mf$VGqZ09%k z3XL+u_a@NmP3R~}2Noitzs>tF2z-s@=qjE{bV&?N^$bm3qvPr${(h2O1poQq^(qAD zdLC>(2QMD{eJd`t8ctSWc?D$dcMe6j4E8`jaK>Tw<$1KZcM_#f&*TeTKYRrzjh>Xx z)9&$3D>?Ct171A;<2D!WwJk>z;%=7bX9`j-+a6rDouL!>zprRb+8BE#Z7 zhx1G``7z=9o@6Hblc&39F|54#m&&@#E413$cn;lkn^-6^I(i9iTnb_>z{!kE5E%&1 zp(EerD+s07WBth%E;iral(!JZs8agX0tK$aLxCq_Um$}G5S)dBreI6M^T~(=zz|PH z_cm5rsF$dzsSQdY%t)&od8B$KXhe%=v+&sYK{s)9ma$8LzF+^D97K};-WDgWzt2(C z{;d=BLA8=j6ozu->#SidlNX0sp_KPc?45vz{R!}~tDG`y(S3aQ)(X$~&4m1ia0Fz{ z)E|e|5QDh3X&A&kr88$i1UZhc6Nno6g&Xd%9Lr zivCtIE&4sIyJ5hnji3jCcCuZ)P6}VZooL+;34$K2VdQOG&hQqv|LIs~(y`^QkKbX> z)j4I^U$TqJOdj9&0M_SYp7%Dl@{R5^(GYnVBX(09A|1t6N61FJ(=^eh?|(qXuA-Xj*+B*O*I?=Y7w?Z~ zDR)qw+O$Xsup1+ihgOGDj$ZM(5cnaGRdsdyN!NN1$Be=D5F&i$N2D}?8rG8jcOM07 zjSi*Dmj2&r$vHsN2#UWBT@FUt8Oa_A+4d2utWPGN&ld$^XO>e{fPA5|{J_p3SGF7x z3rm)vyD9OphX8pS+g4d>;0rbkwnG642DLYT-uxTT%r7mevWFEB)Qc;?4!)(8N+L{k zs)LF+N)oN}!HT$$;ZUI?_cU{LnpYgpojB(lBQk(gWQQ!(lHX&Jc{2GX3*ht?4elGD zgdG@2j)%Y_1)=_(NP*|>{!y3`k9U)E@j49!L(x!=4Aoob=HBS;?lN!4f(?g3TLL@L z{-8TUdfDXBF-XgzdWJt;CZiD0?X2p0!}m8vLb2*I7v|`kZR|@Y+CP{f9t1>c2-aix zZiutGd%?fM&B?R&f@<^=M@4wZCKW-F6yhIvX95(y^||~bRas}|PK|C7kl(`X;=Ywr zI)DRQIs9k$UBRou)dWKT++)c%-xsZe^E`#gew9wz=1a%gMNa0~bJ4_ieRpOv`z2E* z?iA9bkoT6e&~Zu3XhicgCm{ak>|R>=!yEYGX$HJwi14lBfc0(m{i!#)pg$?OrOFwr zhEU{)-{fxNuc*`1j9B=ijeFpxXGm9ti-|e%dC`afUiV2XAAm~c=>y8~-G2_!yLaL_ z@zmJxpndJO3Y0A#xpf`$H;R-@tI6}o3rqTqxPsco<%xabf%af;r{J&g0{!Z$7CB^g ztQ6KsBDa6k-V)8<{LtAEzmhEq>M@V&bW5g8Y!Q}mZs_16??xj+6)oT^TKCd$(0R9t zl?U2i$G;kJ>ZupMA_)+C7J|>e6v|_O&BO3&Q&LkYsqN_*dEgFVDN4yG}oExK+Ji5jBczTAqfBP z&O*(ocfh|5PnkaB({0Ux=Dyadivp$Bm3gW8skj<0G}DX6e8?4%qLIo&C?npz&@WT8hK=%;}+3e1n; zaY|)OfI!ew0qz&x1ftxC(EDVNoYo&kRxMCQCGLpENnAQ=UB^#`dK^T(_P@PFWnD|k z^h3W{K0Parn0zVVihU zAXzspt<;9!?Lzd z7TE`OPqjuVarnb1E(8@MNIlB_COGhOY%cXc?v=llRfuzZrpe3h}z7-8hcrZEA1TNfk z)X~nV$P3Q1P1C;U!77h(Jc9=guD+Hdnp^2;K;hK$oH^D}53ucMeJd)DXnLH&q}^+l zXjgp;yF%zXD=6O&wXWpJ3fYNTS+9DSgXw^R>{^+lbdsFfJt|j{)T$_y8TGk$oW%(^ zzRzXw&`f3-^E(TB-AnqoJ3OTabS4XfPu(Ndb7w3mul+lB=eR(R4&ofsPjN z&y0V`LGlG^UzJT#|Efk4hVj3M63R6Ofj*gE%KPjF2Sj+gAt+oDY+BfL{V4I)Z zmAio)*X_<}OaQ(A&T9jO5Mc0o9Aw42-j=k}X^0nS^H@Ej$3&SK(C=xiKtY^R`F7n@ z5=o`UU-(d#bG&;@9x#lBgk-~FLr8sj*%vW_`W~_0Kt7${inxKyccvsoy+n0}tLyGv z{>8;Edb1bZM8S2nNEZ|DbsfnszXx}b%?(G%0k1dqph=%ALMc(8GmJz}Fx|gLj;t1= zSBc3;!WWz|vXsWr82iB&f(r+cBSnUX{RI0*H1Mu>>?M|yJQw{Ui1tmpilt_WwY?|P zFha8Br{8y;-K#JrUngfhWdXwB>WJtrpi54ZDair!&I@1>peHMqow3o^kKA6K)LtL8 zYVyu+VUex_A@YE1eU;>=yWVUU&oKlMKpn_ePXW@F3Cox5STiP^JFfvk07eVS3 z;9uqE$0J926m}}~c{zN!BMsYlj5NGowu@NX4T``?Amn-({OM!Y2fc&QWe#g>7V*O!FZ0=I-BEyui@-=WvysDu(~`>jf#v&?-I}!wKU1{aptw9R zK_x$S9fo`y#$O0yKz@@x!4a4;$p}{p)&6r}tzw3W{_@rMcHN7ZaFQWt&UW2mauFA&=b0nKm6(s!?C zL9S;>sUN$u{%w&OJtcLMt9AS@JXYfH*Sm}MEp6-hHA_{&dSjN~b>f59F!-B)z-XtN zozJ~x?na~yI$=)>pqBP%GUD%ihNP#&wVPVLCCCd&PB)rA4@tR#U;;ec5iUBMM_@cq z-#5BfgdAJePZNND*4FWj<$IUSY<~^-scfKz2pSx7&8)?_%o}3qJC^Np-nqAMG+&Sq zT!x(6RDK(YfJ*laox_OT7lIIQr*ul}wbFF2YSkiG7dcbRGQrQ-0Xj}_R zua8H=oaM)*?pwg$32+fG{ghV~1Nn(L>4B^z>ng8u{`wv|25#gVinYb;vC=WMYh`EL}RoAWU|SnTJIwggtK zkHo@zZB>G7HXmSqDTKFGiC6WZX%~XMIOyGbk{dEHlPu-z2glsB26Y>8hA4_ z8YPt*R_CO#YI_dFtD`Nk!y@4Kv?@PC5Jr2peOSdeGT0m=_r;k^TDmHx?FTuf3+3vrD z17_I10aRgD8$Y9`Zo6;pRR(QO^C~TeYtFk@p0?#!|Ln%Azcvd#_B_0Zz0OM2-xMgz zwo*IcdixcK(#`R2H{r$ZgsK&=cs!rl!u2CO%b=L%eEv&fXV_qU0^YoT4Z3%<&P^r- zMyEI;^-kmsBrv`;hLjUhKU%ca2MakfKJPL-CkW*3;+Y}*Q>Md#J$$7l2L@@i{e>72F!fJ!+PXU&yqCs+KQ#OGy5Vo+ioPtCv-yDf&w@9RbgTE=G*d? zb`>`*Vdy+5BJ9gN>xK92TY=swG^E+GzvX>vy!tHYK}X5QA^9odf$OL2n+5b|dNf~; zr`N>k(R|?bO2v=msapfjI$;zWK>IkZh`evA8I4nZHVg;J?&Rn;;<&UK=mR;hO0K3A z4-&LfL3^(NpUsf0&C;B=cn>=nm9KvOgu(Nt#>lwry}g@+zC=+5{7OhkvwHd5sFbp& zvUWiWb>bgpJ>pC_s%RCF-0NR?4SIMa%M@mOB6R*OivfiwIdS(~y{8Ot4yqa$SW~_X zA(I}2&N1Pxo_QP}S-e7Ami)cb4?D**3~qLfO)}-lcBy)k3Jzs^wCSweE(I>yeTGo( zp{M}?B0z^te=NpqKa1;d>TIR2deN15XFNx4B)UsQ(M@| zb0wo6!Q*(%8TRoWPV=9HD|UK63Avgh4(Kr2DxDq$(rBydy+;`_bb@81jA)&DnL#eA zQq#v1+8LO-_sz8)>@#lN8{BE~HNB(rOXbdMm`7vv^Y_Q_FQ_2P-51u%acRc>Ko|KcS^{H(0h{;Z<1XtS*v zpnCPB6`#)RSVMpqzxIi~a&HjV82n5kJY{kZoSFn93>^MNhiXwwzC!=`Lz?c#RFR-X zU-6*;X;$}P9c>;tPh4R?eWfQNOCDOE+QZ*hkCS54ZdBxD9;iuc8u_kG(8@mS^R9SE zf_QKxvbLJe+)F)8=Q3`JHzO^DQQRglJGs>=s&2huxrgDuo%(u`$sB!4+2I%i-S;7Q zNfMn%rs#_81rNXZb3yflW%Opc5x3W)llE3aVPPTWu{_W_7ZZl}dW|mS4YB!F;=k&v z6G{dJ=|tc^PAcfK%pq2zM)y%N_nV-O*tzeZ!`i3amRZ|igw- z6gHg+R-Fssc;A>qhW;8l*4*^SIlRggbPZRLE0HuNrhXKPSN#gRO7KVs@q%dqi;n0?Mc8i0}0_ zrOVFn7n|lLgqwh5Cl2qp(=YA&obK8oNAnPeMSj+WdX_#{s8|sbf#~|j4^A;dtG0so z;=TzSl9XQ^O#$n2=KFokyFOP)-QVqh51eLkr#u^mQB4L}KQW<~2oSTm;grl0p$xU{ zM=U5E8j7L8d%r!73zexcw{4L=LMv~%>0xzHm>#Tweh-r-nw*lsBHT96ial!WZb?1m z)8Ur>NFD1;`VV*#<<>8zK!b@uSjcu4`oV}L;(BI1?AH%={bBJgCsXS*XEHLS`DbRa)qMD|CDMmH%_^BUpDq_;<&ZjpR zmlsk`lWMII2!n}1^xE;$tE)%6zWM@g(UY*DziP_wMIWmWL!>&{5Zed0TqeZ=!Mh-; zD0P?SR3$R+!r8PB;Ez=mI)skvxOJr)m*o61wf^G}^o=aQ>kh$@LWL(Tn`%}eZvXUE zPwetnL_nwc^p@Y5@oLLOVEB@=wrd7)l^`AMf3Kv4ELP7K3q$y!csa078Ho* z_S1IRL`El2=@j~}%eWAr&WHeBSOYIaRoQQS$1hPq@p+#zDWZVwbg1l8tGvFnQNV)a zD-~AuMMm=X);i*UyNTFvkgF-;>_aEn_I3L#bpQlsPB`YVC20>6wu4%3@4x4CRA6yB z;g&dR^=Bk_R@I>gA}4U|BSC>*dg*|72Ae998^+^UlE?g2;+*hzj&j@^y+zx2EDx`{ zk~6gd+Qoz%SO(0|>ekmuf`(w!VQT83aaZ&!8zJuHdVexc8bYcz*82cg8PoPoc%Ib3pCUrZ`O>u82K@um(sWkaJsdF@ce>k{lz|G<h6WZ_rK%c(m8N~{LAp%4&aqKSs2I!?fxyo9VNY@f${be|NF*23uz z(`+oDSoHQfj>3+G&zR~(&G~Q!I|#S-NFbgQZ$HgMxka~H~TDyVCpGt;m1Qtxrui**h>$>KK({kv)xb+n_h89B< zt^aT9`VWmQX>U(l-q29zWRGU3=>+)oxJ#bCNU(#T{2_W(0xP*E!3NfobP8LFiuz-? zlMJ3WxWevbaqawN%Uod;;X&5^!m}H*euDPZWa)zrIeLALL(`X^Cs_t#-n~#WncqWU zz#fbCFGn?N`usO4i!IcTs6c}k_czP_+eMozuKgO$!(!?du>9cz%~l1cK<$h7jo0lm zxnF;>^71?&_5ci^NWKER@|BzSm@%_!Se*2{_Qf*W*sbND?NmA2(QWGMNTld5*ET=C zULG%L1P&ro7L&rmLYzy~x<@|rknpHxPMoc2t8{qO3#a@0>EKRiF8YViGQv}(_Y74 zM$JHD8@!n$tf>;`E$cOq6^(r^LWI#7ne~ye#&eT z{x3RurQ25J3wvk1(^K61cY#i$5hyJAzy$a25o$~&4Tr6)#iGnmbPQtd+5K)6cq*v> zxrkB-^9|zuY?#PUc}Qw7r>&)>WoT#!&{3QcKG6ei)57<;8H~6|fXT9wu&a)&sb8h} zLx(nAi^%=CS3?ab1SuLWPWHFZk1r1C5^Qhw-0>CoCrw6Tn4VAeiX{xK-wa|gve?TfWmQt44D z)CkK%fO$jN=y;`*M#>dy{Ktyf_95MJb^77{Z6=%f(?bn~ma_;%J3nE|R z!}g5lZbrtMIIcG|cnSXi3up^~6%)@!VAMZM;_O2S*-QCUr_wdizH5~FM8EOW`mgA3 zH8o7tKNiLwe(bsS^#a%Gpl1*xA&-2Xwf~A8c^fhi2huyiOGAOE3C$;px?D;^7i78n zTdTRKlWf!M^Um@Mb9+hcDVqL9ogU~~EmX+yq{@!CFl>bgv zDP|60x(8KhsQ`5+AaqSZRQ^Vfb@s6SYr3F7w+5@~v$1l3&VdoLaB z;_4$YSsmmXaTWm~R5I1>bo2r#6kGqj9N)hNqGLi4Ak3nFwH5GG)2Ye2vhZo;Uj{~~ z=mFi!CgHJ=PZBn@B?C>sQK}z79~NAgXgZ1bM+*>oYHQRK6;GEobXRFr32#WGlV0A} zg0-|jJYXcM6ApSz@Hv-owao1)`hsV+^E2tY7z4mo96>5fwMvSo-K0eOIjt<9z#c-1Z?3Qpf`Y^xKu8Dk)tD_-C#kn#{~|TRsMD5y zAF!NHYu)h5=CP)>y?V(CkmJIv>w&~sk;>vr@hM}qiLOyc? zN^bjYN0Tmx#Fn&!_`|_5jOYf4>33mGjHD>>f~_{a>q?{!pAEawXKC$-=8g)!C_2d| zb%>WsNSQFA^9ewOmoJ6D#2l=r=sR3 z?pA#ZTs#U_fEpZYjGa3NF29rWQJGGdA7N#kSd0DBowU4UlwQdcNOs5#CZOLqqv95U zn(YFd@t8e8x6X>v{R8#Kc+mLhF?}yCOT%=Tv1Zr3%YQS~Dp1+49+Q`xkc${;+=kbO z<3DzTYhk2Ke{i|rrvKfKo|F1>5)QzD$S6mBT*hvkPnDOoM(bkoFhm#9^b3{my-BgXf_ z+MnY;#!jl$K}i$O)-`h&n4HJBvSi`Mkg{Agqv$D85tQgnATcF=o9UE_cMk9h3LyQ` zp$?wN(F1DhBX2tAZJ&i#@HPjjW-kk=CGM>FZc8~7d59N_Fn35lChUEjg*nP;Sxiq& zh2S(>yxs_$e9bz!5=67zBzNal#n6Y(GZqs_Y)@oS(SRdI&+rY9A7r5WJO5~*LpqwYN+j#PFhJ5H63|N1XhWW(s+Bi|) zme&HP0$k;qH!Tp+Sa5m91wh@-rv9Gh*ng9BU5k8oED>Q>hlHp64qmm9{nHiwxj-XnL_&! zQ{0nDD9;@sDj7%6uMo$!toX2+2?<2t2}Aw>SYmSburRw`wQre3Rzxo|m@JEp7$d%< zit(%Shsw(_?I!=`_G=HZ2UF@W3nq7pI`N|Lq7^%>rmE6?EA>tw;+|!Kszi)Sj)wP$ z+0qG%B_V!8V+9vt{ERre*C&|%$HMxlxlO5kyQ7`o{d^r-MmwBF@cZ#2V@;=`UP72O zhwGy>%dVn=BkxK}*%MCGnN?RGFEKG*htuOZV!wy3{pB#U&V@Vej!@+q)_^MmI^woS zuEBP{>h^{1V>ongq?VAX%06f@Dz^_8+K--$H!VEe`)LZ(Zk-+)e8sSqSGFprL+8t+ z>}W+3Kw$T~{CMb?nJ{qfSXHxQ8dvNLc(7ZvXZ-USM7m!~qxYSls*V5f;r&)lQcN@1 z0=A|qOV8MYppXXTEJwsfV5#8sRmuBcrnWbZIj`vxUHys!())FkU$EEfLQ*y(f?A-6 zqpCXzCaH1#^AYL$Frb2(lhKa)FEih^x0}r>f#HN)+fU(P4^v;4;KNMH1ZNjI`)tOC zrGY{t7j-?ygMt_bmmrpa+OmG60MBsw#VtbQW}zrweLzB}_m(D5X@^msKM9z8B$nbZ zzyKMWgtg1bl7hofm8`ks+#I4?eZFFPc^Ul*_Kzqv%OwY9RXs9~xlRQ@#+1VYCsBWg-+q6K{8eYPUFZkz*H(3=P&{_xD5jBl@0x?` z&`>Ym#FPSM#5ZZ_T3dH#=1NR_nAskPr)(yP%Z8NDx?6*)3@??v8jCPS*pAEQEAIEv zpMymw3=yDT-@Zc|N*;IsH!PX zz2PMt@L(me4pE?tY-d}Fs9l>gHq`IGEc=dk;IMk;({Sq_MdiPzhBjsr@FY7?Y%B9+ zkh$nBD^PuF=lLF%oKY@FDbK74pR`5Damh1^ZnZd3(axxKR57hg<6TWRr)E!~Zkwf; zwBgf+VV)~Guy_O(2ukf6&GO?VC0OUaWLnh4ex$dpS; zc$}HPv@I3eW(>|S(a+@!yXIH%-YkII_WQh>bMEJcF*5Eju!Z<;-DmtEyi%VlMhJTj z8mdcrfAhIeGp_sl>pjoYLn32Z!!-M#0t5QXn(_5I-}p2Km6x zty9_WILE5Or_NWXK~t4ay-Ib8YUoi0ADodXae5VEQr%TZ=nNoni?ybdftyF}p#j&U z2zkDRD!njN%^{4fPe|bJeD-RKluwTIDNtZJ@=0|QVOjHoFSNg=S={7T zIVA-7hDOMHK<8gvxtyAO^zHTqyM#`wQ4HXM{+#9u_Lw*O1kP~(a*KU+=ZwB{%u zqwqz}#VNK!nui}{r^3s*Om^_8<=(njnEQwyiA5)O5Zo;rNamt(7usEfl}=S5_wXPY zTt-gDwO(kUN>-dT;T|849ffHMMu#PK?+`r zrqvrH`P*2$l0O(M{XA4R9(34!KH~E8M`gaufNNB_yfig3;;z2NJXYpTsGGol9^E8| zB7iU$pmU1E^z*#c%a0~}wJep~M1Y4NoeW}G(Ux8cSx^1MH8v;%?Yi{>9>#W?7qOl~ zsNS3F>n2ek@x4flAkgjBoQo!}j#AN`|dS zU>bZ*Np+5fpJTZYcR%ga3MRlO~X;A9s!~=e~VK#s4uq4NKLT_ z1O>C1;Ex5p%=2(WX=%c9OeleH#GmAaxayd-fJ>GnW$I8kT}!F3<Z<=At~LOY~$#Q&7&@c_mM^`)A@n~N>5N$l!T0B;WI-=-no9nV%A zmMdRDpUbnqRuji{T1OYaSv6j7&*<(pXmjB*q8RkCFiZSQEcVUv^D_n3_(@HTbvK4x zZ>e@?*)m#Q^SKbgdOIMQfCS$KVSSTHCwAb`|K6eWU(e;p+TVaHL@1o{GPZ-skr2-V zp;hk(R=sC0%yoJSHuDwH;_{D&UW$KMMYNCQ7?Fx~oj2+m)St|J@edrSjz;!#}wpz>sW7XdDh&n(Fj~1N>ia?$1S!|kzegh$8B>0FCCrT*u@$*34b&KD1 zStj2dY2B@I+_Ac&EE;V*hZig#~81c|TB zTAIoxqHPvyJ~@@$v1H67sgJJJWc$-#`mHnk(r-x2m;Dy(TT$7c@S!230uXq zmo39j#>yD|+fo_zbh=Mb)TezKr*qPqjn@<JA&y9Xeg)*t8|_7fMtH0dWxZdLu-xV5AVQ#jn& ztp>@;56o;4EYxfgau|qdM!oR5ejPI_!QDT76NK|qP8cqO6GvktRg4Iik6Dt+2)URJ zae0M!BSgKF!$_I7g*=Et{CG|l)|(ydWE(<*nb?q(Pijg0Ek@(txj3dwiW^pzo5wj; z5CXAoc52IU1kr0C1g3}%5bv8iSiiL>>W6w(y~_{Z{V7+0mJEWb|1+ve@gN^l%*6n&;sXBv#T3ZYqz}Gp8D&VFMdpd6}#gREi}au*w0qf*mD#&6NJG9nny=z8Ug5= zYdacHRAivY&4EUkF9?u4ti7l1I~@7*cN~3;+%Nuv*OrVrOb<^IIKtSBS)eLaC!0+Y z|HrMc7+veOE4y(?)VzPf_5I<9;86#LSx}A`P}PZ56rutaVC0ATehs$>WK$h0bLi-| z3(ZrNId!)yYKFr|b>u(8z-~lJQYXlec$Cw?4ftkp@w{>@9np-V^WVY$l4&aoX)0G? zzT&?f*=}q6xVmvWigpcnW05TfiHNo=DNUU53Y(~#8{=4sa5S%pr*`)@>n?@7eq1kv zc&BYZNLFiOzWdM9jN%J%M5$dRqde}@a7&lW1vxx@4O&n1HL_@RcacUZ-Kxig4GAc$ zpRD*Kby*Ff(nJG`h&*-Pv>cMK?ST*l<(uj3`aFp@U*#4QsP6BHz;No6x#i_%R6kV6 z*hf6f@Ri&2p#82U_c-YF5j%F3$arT>kNdVNeh6m#F1$%9&;M`ZMLPZgGRGKw4G=rb zaHHea8YQn2q#d6uhZ>SXG_$I2l|%4$h}gOcktUeIwNy|8qX??GS0G7vD5MS{HEg`O z3}*SEqL6X?F_d0gRSYey9!L}h@D(5h4Dj7FjSsCF+yX)W?R99oN-tx}3&G7lidrv~ zYChVgt1en>g8spb5d|2}T>s;$A+0Jgp3ESvpitNPH9VgR+&57y`ftB0R<3$rT(NFi zUe*i*-@;)nLPBxm=5?)LAqoE+dm$g&8^szCC3JtV@!EDKz>k(;=dAN`qd>;$wG#22 zBxRVW;?H8|<$h!&eMod;!A!-ZC~iowZcn;SD$dVTM|3f=;MSGb)bDj4*FJVQugcU( z3`vpBeX_gPP{|}hvxlO?Fsck5)>`*W`bqZZMuzHZwkUlZXGT!H9U6L!JkM~BJKT_|Jex6o z0F`N=ivYDb1h`24{^zR<^2`!~ID3Q)A&zWkx|xHb7q{T?m7|o1BJpy)j@7Q0I~`gg zahT|27=QE)@-y$}{}$seMTpP4M&wz%RAGOuFYX**9;GY6sf1{VMTgbEKqv$X`H z@F&arezU0l0QsU*vX7+PJyN1K2#xtxKzh=dZ+Y%W`x4~_LA*5vSTP3_=w`vKg;}iL zy$~-uzilW74sG|z-Xe*zZ)nQbk528fpT4mjlIm`Y#hjj$0te#azei#7Qqod34}Dq}!HqLzLQu#~r?FGl2-kk{QM|<*>6jsllIi zhA=vq;nNrtwJj2)@pU#W=LMws?m@6}oK8&^Rl=J3T}FS!8yqzq1GqGPyWEgy?3gTKE#Qoww?Uec+dhw8EXfqoWI)Fl)q>!he* zzNJsT{fc)k?=68BLpWzmsD|*5@YCbk6x)8KrTkMde!Q7MWD=Rn=PB6LOiBG7tKaFK zIZ#X}>aDUo3p_Puc60|4f_Jl$$)@YzEL5Av7>}Y@P%`^G(0Nj3Ie~Rk!*Jr|^?IDO zMz`*Gy$$D!B;b*Of0Sl4$gm0i7YTsj0?S5tL&T$2^Qat>6_?T3bliT8+ps(jN6*n{ zn#<;@c_&47C#J(HGJW9Zd^>L|-d0dgQly9FV-;sN3xX+Oj@86VHCXjj<$&sT+}D!J zi={cP2}4iI1s9KYKEt2vQR+aTu$@@4SUF=+nzWsvC zlp4p^`m>~5J7)ruqN9zm1CizN8F(qJ>w$U%mXh1q^8_d`9ER}a4D?Da!qZ!l*DWPb zRdG&4=9V#OtcQn~24&jF=Wkh>6CB4sI15D$L$-y+G_Tl%gafR9{?gSy41qpwi4^zZ zQ85Cb?CX4wZ|lcE;3Yg9zKnA^Vf@EGLg;Yd{xV>~4?f}8u!E;wQA+Br#&%-$1?Hm& zqii$H6=?%aG@r_3W)E@|Cm>Y(=06dA6xiX?tEe;>j&3MTy)c2rj$-sPz<9oDz6rJn zNUD5tCU?r*T_vj_jZMD4V_m*zBX4u)eaLn2@X0aj+)Z(TKw@NdXlv7y=t<>%XYzU4 zTNP#rQgGtPB9-g9xn2%X2Su7;bT(#WhP3zqzu({Ai}tW?`pp0Sog?!z+!>73&vOJ! zVvP-2TiRYO1UCD6RYb?8Rt zX);B7u5~gh=>KT27+nS)Zorq%if2QE<@!YGO3QFi#6!(mlK|@4!DdGboHXv`E0BIh z1efV(_U5I|ggktZz0JtDo1DxustSzc%7y-Dst* zC>lR5LCX6CxgDc^bh~H6=bpQ8j(eV)X4!g5znpO|j`xTw490HXIrn?}3B;kt{2dcc zPl2obZFfqdHYZps3NjSiFz$|8NyYLFXcVA+gm(%E7!_pqrhKVOUoR#BcIYM}9b(bJ zoeifaYd`%e2BZx*(l!aRjJ$RlqX|dkPSt z8qE)NQ05jMzbfQ?osqVM*hXaOyasfCF0{C^hi0fh<=?_EqQU<+4GWcE@x$a7;QNOx zk1JsvE7S+)+=qdp*9rB-N{zB)0I}n?OIvtS$s*e292KPm0-x-k7{xhDMt&U;IO&j9 zF9x17+iM^7@8JP%4~-9)>WrI&edAP_ei|U2^DttrKfA2=;G26wrwDNz6%^lweg31K zu-U>+N~Lg8@j=+f!X2-n3BvA6DL-uvbv?e5Vbf;1F4j)%QA|?R!VkN+Y$3Jj!Q>w7 z8Z)$QRYDpy(z%5R@cK`RQB!+25lKK)ZvvR+|75Xxb98Ws-MctUGr+Z*nco7L6InTj zr`i|`1{I5~U1N^7UJhiDp-?=6U#ENqQqlk$6CPR&Udisgz;a4nsY%4V(9-~?iCZWJ z^2;QB?QqfczO)Dp6sMt)^4k2?6+2ZO`SLQk*T;gL51y4G`SGOoOB zktKF1R;;6BEY5fB{i$Pin39l`N;QfIROX*26U?Xv1bs2Y%j2Iq=E$%WBh7BHS^16s zHM`s9^`UxawEB-HvVcG_MH(^zl;hUI;d9z)XbZjE@S1&S7EV2n({RIl?iJc3^x)>A19R=0b9Q)2hGqq%w zD4XJGhM${m`x1t)hDfLoZNcV=WGq+;;*P zfbt5Jk&@m7ML~&3QgmQg%@-cjQ=@YP_&?9kNOeSflE14e6-5(bzOa7TtTaR3rdXU# zul^6B^R$-Nhe@1OPR%HXlK=@ku7d1T0bji3yzL|B$`&6=|4^t8ocPh~^%N|2hPQ48Fjxm?pA#gkzuvXrKC&ELcA;6RElK> zFQGT-QL#~1jPK4RKH^BjCy=$`5SQT1XQGPF#yjWE{H{yn7|wUFh+!&`Mq#_@5l8la zT2>33xoU8I>BF*blS3wlIHVoVaq1**p|$O85$VATWO6m5!&Zj@Z!eVy*GcxS;jlQ0U&0$Y4R!ws}>yA$7Pc zj*Bu!qKUO4)phOs7pP?nw7T+iB31JBBsp0%9``_CSQs2Xp-34wtzRkj;V1BBl#9^6 ze%VR2jCJ51G=-NSk{9{X@N_@Tj~!*B^Ut&jea_H@b4~G>(6BcG79w#1v zz*+{@RhQ4g*zf4$g*BaXv73oxiMU|XQ3Lv(mYV;%&I~5%gV|hZXD@d2 zbV)4Ra@Gd4)NMi{B1d}o<91UkCoM}q71cGK_=I9wNV?tV`5)v*de(HsvIk3V8!JRT zrfR!Tw)hxp^!Tt8yfSBwQx%lxq)8J*QR1&Miv(I~sE!7#{zud$r6ohtqA6_J84}2# zVy)U)c!~)WpylA7F9<04N+dwbuG<57-Ae@NF@X)$`-T#g+SVQ98J%nTqx%d*k0qI2 zuOZ*k;@fdMu{G8zL&t;7ir+Eo zA28YMzkZilSvxvb1089aF6$p?M~SK{Fh)bH4Syc8`k#$jkD_wmfgK+1Z@vg5I^S@} z9h`5g3hba_7-^NE5BJ8Z`B(*0P-7@r`dBW2N6d;zA!h};FFJ}`jU5~j&kP7{4J)jJSofoy-m;2^OMvd7 z1Hyz*aVqm5EM`9clC7_!xXK)kHPpqx=zy3U;KiRg-A$?#ZLq&ip&&JXjhu=Ho@YMxXD3{!@Jg)&A0plA!on1d9J!bI<}lsOu#nOaz2 zLQT`0;I{ISv=oP4)wvz5GY`f3#&pmp)F=EcGPGZ$^GjpcWdbp{AD3(9e*G9A&Zu2u z1O${W5ecTnQsbwHfdWXcgl3|Db>rrKI1YucTf5@#jYsp5eJbG894RX zSiaG@ua9h%uuB0yESx;$BOYEK)!~|ABvh#nuXUjy7aykw9s@-o_rWX{NYckR83&?O zzeXcxyv5%qx1xlwA`+OJ&`8&}$Je{PkB=D>{WLDg>z}9vwsTo|qndNeEC>jiB>6E$ z@ywNA1)vHYjw>I9B}etn&~X|;UyI5j?a}cK8D$a_t8*ByKBKV6>EWWEdFtUj`ZauU z4dv%C8J4~lxYvKp4LdaGi$lz{)`FSz7-aEe)M%&a0I3On78%z;;GlVWyn-R<)a-9k z+qX9f47cE~-{N;BT2PF}%@asAP3%@ZX7JHQ2={&0QGr83rA>^MOXcu+Do3xfmFaUI!)NY3SG_j zzNl$h)jmWHy6<&7J{^_>TSWGz4~C5!%ZI2GONL#P(18A+i3~jb3!qURTQn}XuScuF z0MlbslAFBxll^Iky7;F_?JE!>CIMzx(cqT95-4wL858VhJFa(_^SMV9y7MTgy=A7rk2_kut3@V z@gYIB%TWi#6j{s20c03_?Witf*d4v1yEqs%bz=_4V0+PR=eaPrNa&y2*oU{nXLNYL zBJlRYX^loiIvv>b23Ghf0TvP_c=!8P?w`k3B&y(BZA_v7{{t;7`998q#iJWm+~GUi z1Es_F+n43ksT;BF2D*QTT$<`N)!E5dmr`5^SqRpU`YA*Pt=^|UOnC7AIcx9;4!gkw ziZCO{2GOHLC5Qa&9EdjS&nC99!z2gwcl6^+#tko_Q(KO42Dsp$#k>s>P8kJqbax)7 zB2Z!#F84rc{VSTA!ejh5R)n+92(HI$2Y@l!QPHRa;j>#9g*?2uBR6nBa*{{4K49p%?H#2+#8H?F3RtdPDXatk1 z{8N~t6;}0B7L*MNCimc(EwR)w@3m)Nm9N@|^?gn>lA|lJyngJpzzln|-VF^jWI7|F z|JbG^BZ_%KQ0w7Qd9A0-4-#Q+%4l~*%%Ep(0wch>Mkz zK1vzT7gxSG9Rqump<6f#bIay3S{}n9nE2O=V1eY!Ul+SOxKTgCf0 zCb0b6v>FVF8Pn-97)qyqW*IMpWO|)+oPftoFv$}h3#Hs>lI(A(VFO5m_bvFS7Y=t` z$6=B2oHpNNXD?aR?MnNCyoNmncv-oQgXVmC22!>MOt`kHoKyNW%xb|JC>Wgd>aLbs z)t*WsqfKi5gTZ5+a(AyM94g!(+ok_jh>wCw1tqO7cbQ+{GkEb!398GB1ajA@?DVH8 z+rm@8G{I|J5)6ajn;D)y0@1R>M`Y97UWqoPHi)|13oQgfBFHXf(7UmdeaU#3I1eOn2rOJfc=0OJ-3 znXq)?oWZ6z{HH2kr&4sm%bCbeLv1kmNXjL~Y+Z@VYw*#st-4AImUtK|MfHj(?H4D1 z+_VEUikZp{h?6<^4vIBaVIi4Jeuc<0A?KIP^xn=AkPstGJ##TYMi;jcXBiN+P3KVc zd+I5g4PE)|a^72?!XK{*!d-bX1wUT(W?r|_4S<|6jBfFikE@aJh|0wS{VtjvdkUw(xgD1a72guEy6w8QL5Er3}i-d~0uvVWjYRcSW zBjcd2-gF@VDn^h=yuopVD{K+TX??lg65vKI0g7I6a+s*}Z3W`CttVohAYWR`CGT^} zOQ;=48(ECik@0U-c}r7L!kE?RrsY%euCkPGBnL4g{aC1+W4Pu}>59WlD5Qhtr`2N8 z5fA?Yt`j!4pQg2u+*xVT!@#E3;3WrN8-aSY024Wcd?|YJ$-EyM)ePBln2`3Ju3qmn zsw*0kQ*Z?{p6qI=U%9$^K^QB_bB`G?wNOCFl`C2m;Pxs~)jrG5o6+xC;4K9AP;lc- zqM5EF?axvP2d61G6`Y{%KjqM;36qO-thn(+)#YUR+C*`9Gj-rbpvAV6Umt8NkI8-U z6kaSKK?ZmTGT?;{nfIsPgbaIi5K*5i<7q4&RCl;%P+hURYtyD}IjP%~hqC=h-^5sy z6e~+QD7lK`ob!dP(+ssJ1dWH>g<Mfm^#s`N z{W}^sYcEMvi@d)=hP4@va&^ks2mHf{h#cPNO5MKal%cKqnH64?%1`$(x2y{RT0a)# zqUGM+94bUUrgB(atbdn=aw30(t8ke8K+0ajg4|n~l10l&znm2UD;C%yFJU1vs5~RE zM}Dk#=5dRzaR6dWx8}|flre$m`DY(@jf+EC#`)@97Lk8C=XJS&nI58Gt;F3IpcCMF z@b8P15})jg!PR4@H?qjPo4oQ<&g45|S_+v{-w(FO%EtUTYayGHlN=$0Lbiw&*L8?g z7VwA_=4xOvf$JhbbbIGPk)$`y6Oh^`fDI?d07in^1~iKv-*{Sq8%OhCnycI%mA7^+ zg%{0!zS8o??^f>-r3035iZKPjZFP6DNsiWvJgD{cqg=q#ERQOK4djP z6t_eD27iwN#NE98uiH0~w(C?j@OFOvE0KbSsLprFErRS4%>D%19l$#NX$7sY6$Uyr zf2Y%H3L%gC8(x&?abJ>rTEkSNebrc9gl=E#FSl1+auH9vOX8&A70}>ZDbxHVis!r( zgDvBUDAWFkqr8a?hdT&7;kUONEeqGlG#&8IrbiBPu^U6cS|l1Gvb7FO1qX{EMbLs- zA7A{LO7qf6EuLiH-~P;blr1_TwK19Q5;T;Q2&sZVpE@V}B_E*N?A8&ZVbq9->T4Ky z(Y_seu-Y)3Rp>smF=neI`vkqt**ZB`OwFa#q7%>LJma7_v_Ei*LWj%;Nnx^hpU=1J z6KrE^s3?f)c^1(O_k<^B=bP8QGRhcW|7N3n`cL!$Z29>^{d)P~g)@OwMq0fEcKtFNo|88{}H&<=kH7eW8Nae46`a@k((z^KS z!(to!?>9EZg6%E;psT{TZ0VmRxYFQGSw_#)U!mT^IS;Fj5d_X6=12;4n{7xJT%=|& zp|R&ralHw~j8!hlk7Eds{cZhTe^ZYj3*pkk!@Z%}oi1NYS4`QUud4x96n6GtV-&!- zCw1D{!xQSje?G(s-Ff5aXddBly4HTD1vs3l4*0k&7|CN+ti_pgl*-2~6AMn#v$wb* z3E$W&ympio+*MT_%(0<}q1+t8u6qSnX0%5W>Dxq(H>gWmk?8~_N>Y1e9AQqK!da^T zr?sW+CTS^}1x{`wu@>5`VM=~sHN)~oTbNOoEF}z zUx+UPzQ3IvKOh9(A~vDCbBeKF6X9$YFd48SmH@d0MW+pfrORYSZoxSCE7UStxw32c zd&>_BJJWCKC#;CN_&1rdZ3X4_Fi-K!)~Nwn7=q*8{K}H4n&jwZ^2T(VwoiBI;IU#| zpv$tuDH1GdI<+g#3?h%Dv!tpRIc}mOL*cD=kP|t~w-N#bqorkB^xo;*%Gc-V3~SH$ zd~xaclNzvIoBS_S?;!qXtH(zmMffAP^Irsy&EY{>e_W0p9s;is?8krQx%JUt+XnB2 zEq99;yqJ9h=@AH!%JKJ{ey~&4i#dV4hFt+G4vG#6Ys9OvTb|>L@G42A#_a(s8FniE zQjL%8219_|Rh&8maN`F75R(j?KTAu91BTPKGqgy6jPuPbk7FWv{94lvcgxj7_{pZ< zC~lBi+CRJgdJo!{D`4b;wvQPBVky{eAK~ z5m$=Ql2>Ki<2B-jzu@HiP1&{$eE0&p8^gA`Ki`q>-EShdwu`y3{bZu&`Oozn$Rql! zXxV)yaBGb_oxo-;B?ChsC}4ND#pV==s)+f8@NY1a+WjNoh3Cv+rmOWL@0-S)PJoEJ z{p(xyH0cd&)8d24ekcVJSiTGb%SyC!mey-tN3P;DwtGy#Q6-{<1KKvF{P!v~;CpqV zQKyu7w$|-=EU9nKDf?4Ra&c(HckKGxgB!is?(p_%J1oclR!o0%v$GACR|0H-#VVwz zlF(w;6mElamD=9sy5-m?H-m8|gtxA;i(gIeTO%`#Xpmo#laF)Fv6A&YDoIa;J~WZS zS?$${oER$qTdt)*!7u5a7D1$FCITdN{1`Trf8fI79P2~o3-yAtiJ4@E7t(&gCiMw! z)RYr=DgS9?FYjYy$7iS^rQ2UcZsp(ev=jq9ghJ?K@BNm|FN%Y$s9zY$D1+<2CAi_? z0plX%$+KeC59huUwZXQ7WXP&n*&zaX&%=bb_l{*U*=>AJ3VtE<=d?6iuY04rbSZ-6 zMRXI$+1CZBV!}w|;;uOEc_TICY=J-W3A?oHS*8~ zf9$@+Nm}l1aeS0L{*bjHUP%?g3fO&s3-Ei4)HwKxKH>BGY;GK0$#p7rSy@#8x*pjiX>!8eg0~j^` zUOKre&JOFSrKp+uUzopI`rVAux*rby;o0=M1&e5UO(xVSm>y&zKWx>2qgng1VeVr( z?x5?7{_=H{)@q0PkhW?E6vMQQIHZhvF4Us>`DMatD&jjx)P9!-?%H$yc`kpqkG=Z% zZ_MDysZUHy=GAwL_oK4tr+!@4#3%@m<^D0MBXXi)!&NVM>e~vQdu@ZC+M-lCKe~5+ zhS8(jU)T7H`Qa<#OW}Ba!TrR&<)B-gsjW0vkm- z?$}*v(>2!VGXR7c75MIJB%a_spZ=f*yDfYT8!ufxToM+}Gz%n-1BQNshlIY-<|*r% zS$-bE`oy7$Uf8L=AjKAKao@~hg8DR4M!Lk%vc!PqAF<@_Pg1u>=nN}?PIBP##%ykV z-Rk)0rr)%2REXW@sir2LQu?7k38Qzv@hB$HX{7fnF)#ZYD#y!}bofPhFu9@v+2wV8 zgCu)$@ENK!e*axv_x5?PNWPn=G14Sc5~rTdcdqUEjTiBQ zi7fe=kXfYt+emO0c1(FJbFRPS%$Av7Y7QGow}fIi}l{K7R7LjC;5z0Ug2UB2~k(HYoyc+#)mXp&bU-<|kGQqwDCI`g5~@uO$Pbk4BQVsD&L#rn## z)3f_40Kn}Ept6;{Nh`3qcQr#1n_DHZb)wK+d3Gy=uAS-eGd@TTPwy0tcg16usZpn{Me z8?0Y6N8v+!w&Prxwj~@$3=r)P2l|aQFLqXqIIaF?_PWRMLEj3kkPQwJC{mgCaq$}Q z)_P(PgEwj1$?NzOZnl;4UmwJ>kT{_6b+`v~zCkXKnQcG&Wo_w4vogV-&G&9kbh^5B z0|t!s)b3&Bb|qEj4CPGs!BAZ{rgf+82ldpepf1w$wOjT^6KDWDXSYab$Hp$IyGH~I z^R%zs$8vc<4LFk^!BO0@d^t1CEGCSoh?}RTY&|yMgM;jFLFncAXYj9W;u>ttl*!2z z+>QCMEr~t~qaf^jm)I=}cM+TB00=%qzEd#3*+wbTJtHtGWjgw$>}kfFlR6;o>}951 zW&Or+CaS&q%$UfD%UVR=oUR&?Gn5wD{bH~c+j_7i)GSGU&kQJ6EjCjlBJWt(amKCS zHjTl;)sOz~%C}kFUxfZ!m6$RW-j8I=v6cSZF*hlp!D!gt*4gwI6&Wc@pd8- zms4Tx3Dxzo_W88I`muqJ@XQzB*&$A1*gJd}@6L-{08qX4X_pkpN$jSqL7}4Lo%z;g z4y%MKG!~wC!(yYAjLw;MoaS@bROm?1OD@4eafTQ`n~nnFr6ji!TeJYDf&Jvm8S0Zt zg(N~O!;QpFBkd@zNUWY7$J%`LgiwZ`~UiZz3#bi)dlVT-5l9iKWfE8s3w99c zS=!j3UW)jy5~`m9$-8tX`r}Im>a(|vmK*%uIk38`*vXM5?$4};(} zTEzaxpNxx`0CB75qgwCr_{0tkj!d&UWNASjmd2UhnVr8L4VRj3wH6J-D7P8>fL}AG zkN|6c)n)5D!ATut`BRlbBIGu6Q0vFrp~(4qn3dq6 ze7Y3!VXcx`b5#lO6u9r-sc(B1o7SBj!vdXzb)qqW&qN5XXhq|bMtuD3xJ(rhhF>8( zOBk-u>oY^p@%uSeHusn7=I&YlO#j#u$A$t1JZjg1zmtn~c=IhHOom<+s#S1==XvC+ z4Lf;p+hUx%>-}LLkQ6-|YRIWiK2lhnv$ z=V{~5DRkg{7is9Fll=WhyzDP#Ek=8pz%3Vj{r5mOy$jxGOJnF@=qVTs=tVFMjq0gG z>|{AIJ^v`%j{A(W4U?~zw8s;?KSqI-4DPUs!dw)AshLhI3?Wp%p@_q&nMSj|&kW~! z60k6W+cM&6K3UjT%r6yRbwkT>@`YbMCK}V8ll-cvz}PFDxn$0_unIw1a~0@deNB1a zmXrI^)f9QWAXBC0yim%OHVUR^`pzYKW@UDuw{D#<2v zTKe7kiabppf`Xxw2!s`RVr%E+p~9uyP2?d^H56y0)^#GKWM6UN-Z_F(f?!|>X#%LE z+~lp1JIpOd&=@~$BC>WaG3C78p0QX?L)ho^v+o}pOGLoN^(Y{UOwKRLpW~*BsdVo}``k$Ki8zLU*xS|jWW)=%j z^BCWcOOLk;Cs8No#JQq?-b6gWuTaT9_~B0TK_dkJ^|Yt&+r9)i-=F;LHDSY9Ks0g4 zb#B~-gR>atJVVwQk61o5uzbFb`HKesx;neBQLeplmGIdK7}H!j4dPh1YM9}jD=%=! zWaB42e7C8cJG{LPt!Hr-^ePE;KF)yyeLV)#HkU}8s>@yA)WJTLV+0Nw0)$d^KK3XJ zVRNG#B?9y)?qfUOA$a1#-~)0IYzq|&`B0@1RH2*^n61t-laHKv6D_?Vgxfet_x>d) z%y8sdD%w`mE_u>wakI)ROA?g4sSOP##`m~b#I3WQ_-!NAy{3tDDMI6b%V(iUHYxIH zBXrm00wh|gsD^ajwe7BOG8$>B$UVVvCd)06jF5Lccw+Lm(gVz#4+xVmcsbD_JSH#& zoO`|yh>159!_5|tp~K`y&b%j`Q>8~Qs!Dr)a%1}`H5I7RVXPjSR%o1Pj0;@Fh0V0j}fnE@*|&l8>W)A{%TTAr+(eNi~myT z^j{DXQXQFcub63}>@O~+B|}va7aXG6_x?NwLIKr$3yNu165&45CNR6vPc4@PfGqp} zL&s?00+6v>i?+^_F5d(q#zo_14tubnCfoBams2p@mH z(UI|dFI54LvrL(_p1z|~EZGLxokqG|knFa8Ga7yfKpv_58%B?lMGnCC=TGZPp{-rsi;l}R4_F99 z52!>POI)=$GP)S8j5EP{%Td=T`I~`yi6jWyHtK>$7qelHvwC@jdjNXfK32mwT>*5>{9$&beau=4og0nM`~D7RK>n7Ogz+s~Md%c;q! zD>Q{f6l;Wui4BG{7B-l&KV$1`)k77O2h^fi&y}%J6!c|(-`GTN@sOBr{yfK*i_PU! zcR#lZms4McfgH3N-u6YxCsdd$Xx6(dXweHB`m_Z;FS zoZ4p=n0KxpYm>tGd7zQ(!cegmmQMj+%LN_pVNmza^(cRlCri` z0A*Vi&TDC|UB~Ty4xl~~0L|-$S_bhTpy@w=L9Rpx*(XJNkjUju!6+`Zu5-gJF_0=eC^j5rqU>T9|v(nn(a%$9U<+eja zhSM3zM{f%J$31Na@Dbz-{QM(S+vzduSAu-NDdWYUN`%^R`5h^#ZvIOWWtF`N_Yp?% z{)p#Hwv)tk%4Jiclju1wj+Q?WUG5$-^-my<3h9&WlW z{Rld-zr5|{=k-gAAFnCpM$4N`mnP9)aa~_1r)6sccK#sLeun>k0eZ9nBt0CSU;R!- z4C$F@>oG)I=6pSnquivOmrS(-1q_#&8x(F(Z--o-Peq+oesjRJc2vK((rz#AdKrAHcg@7(@@U_`!K80nhK+jr+vQ+}W6TY^}LlFMO$5`pzkn%jtn zxmOb@L)w6i{0R3O$Me^7*T0PuCneJb%wd$M0_a@)j1EeMj7qc=?}V}-lcqyK7BtYD)rQViE*vdZx9l5f9wcV->&Jv zK0j>C@&uIZ#78wOSX}-=(qd9vDELqfsj3wiW!m)o-oFqappfY8)yhoe5KBwu-&AzOs*S3q~a8#>s z_t~8iM-?Q9K!4m#8Gnr5=&!xt^gN3Ko_ohpKu^3jcaqzF?R2__&N6zAe&y)_%ck1* zADkqcX*hXj1V2c$ar{wGD0PGCm4kiO2>yyCDvANn zn`czu5A+YN$6rZ4$1Tb;2vFIkX2ru-WnN>Sta3-uC;#7n`^Q9))=gm~`X`_^W@B~# zOlX~z7VRz$@lZ}XME}?rw41zj8Rz*J zdm<&oW9jIM0a71~)zrokH6!a~m@oWDY6_@wj=)NdXXl6>X<@bh?C7o(UDWZVO=li& zLfIfx$|N!-UB4+aA40au$sY1y7~#u1%PmX{8EG*^dd7<-0C(;2q48Va^r6^L#PhsH zuPw%DLB_3q4+u}-pnmQ>y6BpA(=Z^t@}EVc=I9w?B0~(jGd{)CIuxmB0FxFKT*sBU zAHto7$1J@&s%ao+ae0sT59|F~H@J|>Y5~}9y&>A68IxX&r8i6sbR#cE`}t@GM8D-U zvqSKcotVp&+jcYr%=aN+(e0C|B0gSM_TFrL4=2AUm8%!Dif-S$4}bl+@n;dUW3t65 z?OVnr{H6Z;vj9IPo2Y!?Wqja|=+`L0HYf(aML=D02KA7A z^%lR&Ww&gz8h%IGC;q~@hD0Hx)$Y^v-jPOmNUA4`k9<$c1lNu3g_HdjcbG|StNiGKO#Z@ zvy0^wc_gAHCtkle_t=ZQR2*2{^dpbA)RQUGL>e(Kpjp@)tHX)k`WK1%NQ+6Qv((cg z*OCF>PpiUJdpa)$W^evq=clKi*G>`scYE|lu77cI_g;;^3UlUWkNo(a6=TzU<69Mk z(S6zwW4e9jIKl-g?=b>QkkoL%U&2-!(IvCw=ee^wjny8xKmP3_MK8=bU39wXoac@A z+5#>V82%+LiUjOd_UDLpU^FUI{uO%|Y3D&a|9GAY>D?#ts^PAiwcq@^ zY>26Z9cuiF&2+;u$-2o-Yck0bEuUUGs#uh<*@K$oGNoHD(gi^J5sTrx{MU2~#{9hd z(|Z9B4PmrlE1MiOi}uIkQ~dcRuK~+;5lgyWSrt!wq^0l&FXd)8;AuPJ^R+wRulKE% zCUZv+`3KXlnTksELF|x%_WEmc9!^ERfWdj>-1g`(vgeP%xe$>LM~2GAlOLLRjG0qi7|JB*RbBXNTNfkyLp! zL1~mrkRe(Skjf&_Q#jHf;9+juHv2DOODXZr)CNh?bIRz`fIf|7!3Z@E-6@v-!}c%= zXtP)G8%|87DRa3M{7ovi7~UxjON81Ds#GN}gRnxjH+c?kK)Rb7nT8B73x8D(72eUw zIM}v=8zyP7-TPtiYj$guIlCgpTWO(JbQkiU5j@;HTe%DJl%hHqcZj~Ak$C^xmxfgU z?c5pr?y5XC4^#Sd-okg}B`1-n)b6JHfu;i)K~p2YV=CauKbO;Tp+KtM<~{_qHTpmco6+%>na05}=2&dX(a^wQE1gQ8|~H% z^QKLbvHUiJ<6a!s7LY*=>S2*uL>|-rjE)O9W?~)#0kkhgh6p7f$w9#`!vyRff?nWR z!RzZQs(6A#Uqe;u{d|#awq@4YBdhvGGb0IN&QHP?V&6DJUBa?9y<=S11HZaQ(u6J# z(Bjg=+o^K=`7*BJF?j9MjopND&7Qnu+?@x(4e~chDO$ok4#&@X=|CplMA<|1cXe>K zvtQGlV!N+)bk~Q^eML=UNGQHRO_bhC4X+#?AUFq!g6*(0-njQKycL4Ji&qtes5shH zFpe`F@!Jm$XWt$t+a|=D1vF?%usze*=}>5{aNShXW8JB$mh9Z1zP!G0KfGkpIpAtz zu~eaNw!EaF^36P9+&zsD1PiCmy~2|Qf1ME&|M%0F6jtzNqsvr$M2w#~7p@F;VF<>) zPXZHREH5AJTm-BA#_aj8(6R002feV{x?QZS=g0DQgV zeFN4%#Rj|9gL6i$wtWH8Md#8f0B1^nAxP2X8LnLWy+yemhPkrv8cF3QTA=Se0T$R5 za(Eg~(WtlPx<@o$!YfrBd-<|SI9=L5cQZhF1d)+94VodC?h>sxmUgU{>dkizFKp4S zo9b&s9iVLuFH~+{Ee&*NY32$ae+);ht!ndhS5|JhJxYvVBHvK+9~4yBVB5Xq^*u7g zS8DeXK7AwlL>)?NK_8&pE_3Xt!f$3UrH+IDD)BJl$>4}e8wNlgf&_nIA*J%QN0-*( zR2bQ1lE300aft&;lOnAMMkQu@EQvC(-bi=`XD6{^b82l`pNPE|W9bG%V|Ks!&sVkt z{@ncu+LjQk6nroP-0HvdBxWm&zrjs>{1sC~O%6YmdDz(ss3hc)Bia1xAFHmH$k6~1 zJv7vn!UIDqsJZcWpr?(LKdMdu!XW*5=$3IAY>8D-H%2$p*UH-7)c;1k8%Kr||97TN z_dw>1k~yB8RcYDO=@QQFK~a7k>7s@KjtZ1n`0y_`@PouMB)Ne&AuZtc%+1qDXJwQ_ zjhO1I>&85WR;j~b$b)an8Gee*K%^aO9yyq!x$L44i?H5{#FY#bv1hbrX2MvL|ln(wf%qCCxkbi5?|E z^+6`3^B$f4ZygP+h*^?>bY5TCdX6bT)JP?6-f7y!lG{sAKxL-NosVGzI^Mu*3zkW*1Tn{l1=aC=fIqW}q@*XNG z@^r#_pVMgrA+bo4mq`{m!V^U|=_J868Hy{Yr^noJf(#C!8oJ|x(KyLYJmAvDeLQOi zRPZ!V(0w=SV?7jBY$M7q8MT$Q#!-@(-+)V;@$(RURnw6qZaH8du!%HyZrm%#JLtGA zMo(U63q+)}F7wcE%bbwMGJ+iBd0@>2% zgWrtx>^Y|c0vFpVFIFJ0mjcVd z2Y&mKv$3PIlDEql-$`@4IhK5P^*JI%>!(Q}V=T83%v6<_gK)mGL3l(RY8 z$`38ArO3W8Po;h+vvfF&4n$3|cHOA~t%<^GZ1s|qRH=O5^cCo$8N!wiGJk$l-M$n3 zqW~P#nB#u=J&%*}lZ9nvbba}6$s46*b5HlLjQ=~EX^^fnAWw)@)LplUG1?g9PFBe+v#I4Pw`k_~p#WrI1?Z-+r}p7k91oA9NHfC3T5d4HB~m*eE=)rN-V;D$xX-Sb+*~9T@9pJy6HMR@xpanXQ1EXkI?ArOS4!up~69h(Yf^Z zpaE!f!MnW6buKpN*(^`hqc{am-yaXL@w$|w*=4E$dJlS+#%=aSe@}@h2=(`Vo{zJP z=xdsf@#QmK*wB8XE1ga202=*Nh4j#3m{guQUv~tWZUS)f0fm@2DX%d3`cj|xAqqe2 z-p&`j9<9Gf%B6rZrSx|0Z{qe#%~gG+eP6Lg7`vR0dvBpiJ3d}Da_{-RXfgkumQoOg zLH}{2PQxqBFdJMN?fg8XS^QHn9$?I--)>rec03_q%zN?t_w9^ERuyMlfzl*OS<}yo z^l##&WDJYT0c^19-o%a5zqO8Q^@8^5#9+qg0~Yia0Je&=0X(WukgdV}a?A>Bb|EKE z>PsbShwi4SRG5jh`ygSCMLOB{V%J~umMjdEDQVFSI3|=&cinyAO5k#4E?h0%YjtK5Xmfk8Xva$UVvuRW5JaIWcJTzPyh)T9}o=i_P+ zU|DzcP2XN>pUfJCi(Zi*cil7>lkE6+Usc+|$DWGWw`ngP%3)?uJ_EpKA$k1qj}z*~ z`)wC|JarNrmD%U^UOO|b{}q+Jt2q6IPr%FX7`J36MyhgDWOQ5khY~j)Lso)NYQ1 zz5;vWo)^1;>l|Eb%ln7QBuKi+zhxTw7@CujUKL3c53?jP zPdL@ez5Bs<3xNWVS|6zX-|as_Z~}t(cy9@Km9(bGu;3sUuS^Se+%Md^eq#Gr?N5@L zQ`2OQwGS&BGmY!g&qDNy%&2&sCARZcM2QT*s^jeF!!1R_%2lqE*tf6(h|01OAl6e*f8PTx*TbG?B?U;wTvWN zM*TRE0@K1o3K|c*)Q>^UuImjZ`N~D7KW+}s%@wA z`0iOrfMDvz;Pf`A;5XWGzNyKHis0V)*#_t8T7SPdyEk*&`m98+i-b`zc zk4>0nBQfjj+r-#SjmR^p!eL1wl<&9=exSc;(R!Zf?}qOQkZ;+uH;k219vmG!&W5R=`m;8 zF!Sbjqez-3@Qh7QR9F;f5PeMgO7~*XdAa-YRJrC0Ya%1{+AdW5IWDRs)prrS^B0d-qjiEaV^V+ zRt_If)@Xu;usj=`j9{lST6<{(#jevC%)d+SGb0Rn(dqI-Mu)xxb_X06ZTWsu{%Qq4 z3*uh6{50vY&RcjmnR1Z(uZeuA$9r7$KP-J^K$PwCwIYpRP!Ay8jUZi0Nq476=hC@= zw1CvoEg&ErOUF{u-5{|`OT&^22>;vP`+ndvd)?PHGiT16nX%KDsXyJ~v9Z2*MCC!b zB}x+KA2tkxbLN+tr7|L;t)AM$@TpPOz@{e7|46f4{|1qk-0)mNwC`Q}{5=s=N~^LO zPGNMBJy$Mbh2QQH%x=rEtBk?uyyNAdEd4s?m@~794Nd*>?rF9{ZB65Y1D3g97J7&7 z(g517eBU{K=b`q8<&Krrci~#RQW|c&y4%L{u*q@x5E2JU;-CNq#!Bd|3BfVV673(g zS_Zk^@gs^Un(BA>IJuJu4jbvyX49EpJE)Y64=k*3bcm~cI%8oztu=Yn`9vd02R*90 zoWj z3&_Z0pi(kd1#!VLb4w+S*2a;IWBr-U8{Ghl?v&7c=IPb+wp%4kk7rqW63Rx^3jLHR zXNl>oVk14dd;EbF-U({!I2bWQVKT|X4BAMQrjNK0k@WhY*IXChCLQo>yJU1{AdB>KbfqE-kWDZ1W@n*fD0 z;5Y9_ziC{d@Y3@BUbu0=VK+nGt}A*a*@rsJ)fU>HH*w*-8*seJ%N3bnuKCtGs(tzo zHOoKBw+oFb)bQ^Jg6%8}l8)l;zmz;I!%l=|p00!5J1^Fl>nym9K#R&;nfqg-6C2J)%BtF2&m2MVp<=ye6h(@-Ea+-1~~1 z+Ry9GJ5Ls=)7u_1($r>_JQ3&@4%)g0>zmHG|7RCB(E3X*9FZYI8*ddgyU?T|SQ^Fb z4kP{QsI~KP(7waw2y#o3l;vi+B$Y7eP+IIl2hPQO+e+M<7W1-^2wKO zyDal3AY;OCPl?&FBD^mgcu`kUJ^JiFw~G-Qf|&~dMqDWHqK(C&F%C~*Ij;X^@pcw_ zKUCzg8`+gi)*&Z`*q`{720@yzP+!F^KP>cpbu<1WZ}ZMVm(KIrX;#Hv42i!|NrLzM zgP982u(w2NO2@8-ldw_~k%%ynoDi7T3o#g$FO$R|9FLZoK@i!%yS==`{t|FUCD@N# za*5{qq2AGG7;3~{Z4D|qJIgw&RP~AvFNdlq&uY#tKd7V-h4a%{ruoiusry~x@4k+} zw^1gbl=vWtGyhUegx&JTay(T=@^mM?syC%g_ObvA7kp6W3~WgR{*^4IDJ~UN#j(eq z3{8A5T*{%;5TdCih*Ou9i<~f!XqRuH4sduYA`8$h+4nC79t!K(XyW*De?MoDf zJHyyql`N#L6Xo~1zh*+wd+lW>)ZMoVY*e(h`~k>9@9FN_&}Ab^7d%(%M(KKI-IbL- z7lxqbbP#BnWH-ekKHP>FHTujIsj*OWJ>(;5En_kJ%H@yH-9?L^Zu}R8vCxvYHg)5r zZi)w@n7Xq2W!NdyVFAHOi64?6TCan|RcHE#N<;*d!aCG%-rHAkhmnnxwE z;1%l(_6(Qp-LpN!7`GmWS>xwEUgZQZv*zKL>I=X+N~jASlctTmmLO4tS!RBFMJuWr zi#lCA9>(6d-q9O!1-Xg=vGZ$&WzAJRDpwm@XwI<*X+)5n`r&g!gXBiLiuKjp&>?;8 ze$SWjn5|T;JJSk4D5o3&N?sP+`;lt;@|s7j_NBI+EfjNXb~;Q+%C}AAQB^13q??CY z&X#`vj=(X3rCncNE*($~kD+hGv%oJ+Y{^1)>nun8hIkn3O*N%w_3Z1=6HmIEwX*9N z&Tgq^=A^0PK?~5u7{`~LTX$))TX!K#%FW!F+=Bi3Y6e8si+>jbx5%X-KNha1)|Rk^ zXxoT!oyBXv63zdxO=r~CS&Xl``30#NW@^>-T7}UWo#UhWa|YehEXRbFR%eFzX}64c z)?PhOe!aSqjg3_Scx%3#0?TT&Jr8o+D!cW2F1+)6t^zP|wr;F?H*{$D*}_GB*xbvM z-6qA0*ApQvvFZ*6sm03bSrl^=aQ@hM%=^WdUNw*<;j6m>1J9b7=&P(Y4Hby4m9cP9 zPZ|>fc zWNa!irTxTKWnBX#zJ6Qxw;&3x$Numfu`GL2x7uj!QXpf^b4kkspTnR?1EB#!p#kG2 z9VmxVD)G#_A1}*?KAS`U6w7{x(HB6^KGDoQW{%p*JQh7hWlyE!9kc!Izm?SCm_p}i-X3f>K|9vSsAYYS+)7^Aj}FlUQ){DZ?9 z#zFfQ)ptZ`n!7~-opQM{Zp_L-z_Z5yB31Q;obIY$ghsnovJY4v*Gt9QGdcv{t+AE^ zM{gZ>ZIHv)QWuBT;92iZKzyC*cdx5HyOu1IzplpmL8yv{@?B5kx8+>$wG~}C&nw+AgacFK(FEsTT?Y7D1+w9%5vAT;+Ypm?f3qpgaCI@rieVnlW(Sb(D0I#n>mYv;l_U;#dGn;0IANfeE@~TsTPe7N+ z;;S_f))j(wJ7gkAl)#tmZGJb3mA}%$SGTRUrh@j5I5HN;yAp-ro_s(uw7})&bu-27 zlq1MKz4AlZ_RDjn2)jPQouLmFOLxn*H`rxp)Ku0wVwuHtI~i^vv0pQSskzKxtfDvb z>EK;)*_&bScjSN1;vY=_@4iBN-zIh3VsqKl8BoHPq$Dj(Pb4Pq?qY1+(@akCQ((d6 z?XbUIzofl_an>GYn|`PzIjIaQ$y-;jtss~0Rm&&-{zZxm4!O&p9^SsoI>IJ%11Vkh zKN^nDDV{uvakvi&GEfKxW@6?lx?+3767{71l334aMRacQUipe-TTzJ_xWTvgS(`p= zQCz)IGZZ7Z264f=;*uysO1=hJr0f!pf>D@T@M62YVj_Z%omYDOJ;IKWfFhv%pu~UK zIwFe#NH*on4Xyvo*0_S-=Lyi>d*@~L3gCsqQ1lJg{PUrLV{*Mrpb$-YSfb<#KF<81 z%)hLSSzV=)CQqll6?WB7Ek~Cj=S7x2(jUn&@;uT2i@qp9({8A#0jEm*klZqccfkJx z8^z(5j++oA+Nz#cu>njFUNokcndCnd2$OFUK&jd`Zuba9SHv%^U-y6XU;9vBDt3$2 zbDIMHv^(^=66R+oYL-q9_pWfc+9#kAbMXC7@}~HAM}pMdMx0fXH|=Ca%!;t2ZBjeF z8Xgj=oz{ZS0)J_%_Qtq;6`7-UO7abcR6$JIN!K05Jr!yWc;Ch^3vuTo~m3k5hC_}~_!-Dk2|K-+4@Icp%U)DBju*sL|r!t>e(nFvQv2C@K zSKZa(&KTFG31}N@Ie7A39CU(xTRTj?p9@$1OQEo+ImLaU85Vt&-uB8WSc-B}(F75u zDRaHMCtZ8*INHpAd`pGedEc;FPSt#3$^?fY)Hjj3P!2c<(e z@$+6Od4{o=2|Evgn)RrBVe~*D$VoFNT%HO^w`JslNq6rr^S+xp@aCze%K~wHu)}<* z7C8O(^&%;yKq58eNK)wv+gHUd0=f2hWa*!T7K+#pW$fK4qg|}y@$yQiWIoiM3f<2q zqu*yFrN24V<21-Rxl?LDaao*rN|6m+#tw|2;|4BV&riNPs{dw^r}`~POpgPuzxzj6JjS1mdBq;WxL0yv&8npoRK;L771j;;=wfGt98U9rYq%U;htdVw8 zY>mB69GH2@XW})%dZ6QJ3Wx?cPAgqMyp(|Y9>IBI+!-i7)|&rze^nB@HQ($HOBd90 zriXDT>e~xkj!a9#L#w6lg&I4*a2pj;zBA}~$S=sH9DlwTV&HR$9#DX>^)Q2Ehr`R7 z_GZL);_m*A%&5X*lCcUGMI_g}H?eN2(GdYBk5427udMN)H)q4*#wL7Jyjt`q%u_w` z&lw0W2ll!SmR=+=d)l(JDhUMi#mT&PRv!bl+!Umj9?O|0o8*~+&z=aZ1Oo? z=U(()8fUtY6C|lQPn`dL#1p?%8yAkH`RvYYDuWWZxGc;pcP$y%rt82R4#N(!B*3l; zQNDaI;ZNl0)*L@?xcPkE=H;pf^IaZBck;wPPJG&kE`EDFuId@5`$YcaRnAa-6?b}8K(*ax3so~V?vAPZt$t`6mAIU@h|g7- zjtTo=uMQJDN@iS$m;s(<$_8Aj2+e(4=Kn{_3)NH8)dtgfNR2(km9Q$tmq*FRKboV1&ytj5c;PO3y4H=n={;(0j*Ka6;I#|tZ ziIT(sHPA`F5y(W~e+8STPviT@kKj9s(ww{CM5*w|Qg0GcebHzl)u;1_ zigP2$t5Pl%XYywyK4O-YLd4eXLywx$y14DvnlnbByw)*0 zEHsp9TQP!~G%UTzLW7L=`ow2ihTybby!I`l()5qw*>(X8%uXj8#T5Fod6z9qc}=>~ zWamt#E&sVP`{C>OpnLj%U?__2@@ELH9mworQu+lEd2!$;8lMst;lHn2Yo#>lQm*Bg zyeJ$e3JDlvrUy#g*B$nsdl$IP{3q1cO-EiV+nrI($1D7O6n#+b)Ay*ny9-?GCcdD| zLGLI{HtjeV9x3PX7bmUn*NZC`SJwV^9%^k_vkN4-WK{NwmDgrYKXsSs;SBS0fMpJr zLEJCDGMjHPtund%2C^P77z-lG|3+AtXf2>-Z*Oh!Jj>!EW@h~JUo`ONG5i9gNY0nZ zGWC+BIF*&0vTK7ss5C4EzIM}&Qnx8$XcuKf~E-5N2orr!qDFi(}Wo6L#D;TuE4ontIrCWcH61TkGCQ7xHits1F&6D6a(x)+R|#$h~&&*!gM zLpU5_8d+ez`w-UKV%Gevmj$7F?JTfO+>}+krLhk-{ z?YcW@ri45rST5Ls4yCK}P{MFcxl6rRQnKA36g0=vcqv1Ki+@ixd^rS|2q>EfsJw^& zj0NljiR;}ut^Q6-3w5ib&i;MqNyM5HJY4rD^<-kTHYAYFg*z++%9vq5#|{tt*m1T4 zEGAvP93Ba>d~w7`c5ODMuSo%T=@bUd3-Y4Nr3p*3=CGIN%fC4FhV+aFi(SX^8Jz>q zD(+);^{Lm?U4Q_V%uuV#_)10U_j`zer+lP0^ie8$G_XR8c&~9;bkzi33bwwKyPTQ; z3jXpExY}{6G|pg~JFn;vyzGAL-6~{f&$OD42kQL2BopQld3!36O0bE-L}qpZ^5ZbS7^a}yS;E#+N{7@W}Vr}pb%k~*uCi%_T^)9O+Ok5TXemnFEeOc3YjB6G#Gc6 zyUh-7{;zeL0tyf|HfTMaA436RLeJE9dox}#!wfI3Jj;$;u`$ZKmfg`6L-4s0<&5E} z=0M}Zxx7V&Cim0n*BmWhb=W=|HchwA@-q6)5YHz^8Ri?&)CMfLz+EqA6T-8yp+8gA zkw^4a50$U@*Z%%gr+Y>}L3a&894k*2B5uOm>3ay{C3|#Hl*Gt@&9RZ}4D~-1(B1Xu zTAK;gD`P#eeEQK|G6goLqH_+u8t}|@BK5F^tj%upcm;SyO6a1+M(JpmX(BgQW!UI$ z(`b$AFfafyn*cj;**M%Ae{x-OdgKq32J6hzqc>QDrq`EW^V;~Ju;v*6MxvtaSt{@? zRCfmj0SZxw@a2QJVtr#{h2dNSpz2+1^A?TaO>eH*tDqAblx@7B$Y9OEM;ZMr@=;;+ z92~uUD{uHVA^Qm{Zt9;;wZNdk+xFc$mMwqlodI}>U;N(z>f1Im3ZK9coYk70`d_v! z&SjxzlWWq=I!1-+7`ejlV_#^WgTE0xEOlw(61xN83XCd;cgX-ECcmb-IV$}D@gD@m zs}2SrcswcCZjK&~PIO-Z-Juls0=t}|w|yp3Jd<~GlS4!8{JnM^PCQ}ja=LkFC_gc3 z`@K5oVF<1NLrD(uLJppP3`8B~(=#Xa;%s(JZRJYi^wwKXcvMLOtu4EaEUl|~O~r4y z1(oSLD+__90o|2UkdAq;Fd^_L&|UzKB4s0|V6k`hPRDuobNC|r5yWyS<(2R!oWnPI zMu$TN+Wsy-G_gi1s5@jZ=-#`bSrVYf$o`nlw@dmlLc*d%DgwWxKZv_OPO(tI=Y39L z4-2?fr?blS_j;!LVG@1}Z9EZRTw4BC7p;!u!zB@7PSMz0ji+17UbGU@^r>FEIXpR7 zUYr@T0U51f?Dk8Ee#R!8q%^$zW#Ki}L=9wY%GpA`-93HH>4(d0NhWW>d^|{w9EI5w za1#DV#VU5CxiQbjjy>Gn;qz0_ZP4BD)DDi~J35C7Zq6&`?F0XarW0~gw{97kbP3ja zr+Bc(d({#H3v$^xml%!h?DfN#LBUST?GeGa?Nm@E#y>+L0KQ2UqIZ_`Y55*x*nxCq za-QFbAkO4mJz6>WiN?nyUQN?%-t%yysq74-DCwX!Y87g63J+`rxj}IsQ?0}#44T6w zX9AG)3lraOB2~k@E{&wm$gjd7Lr)(#`S`57!q&r9y^?7nTaR%J-2}- zvCxTqLSF4YCV8oT0yE{1F=ElW-se|KVTe}bJc4P7 zZPX{~3#$z94si+z?*Ux!blGyMx6|Ps6JCh{FIB|B-3aqnFyTr2{cWF8)r9HW=wn@k zk~yk)+A>&|BZVECI;h(ZgR}!Y!oz?+PL!`eP{siGAp2e)SD{Bi_CUhYxyS z(ov!Qb=uD&W>$oz@%dRnB*WZ$y*83ziMvO1&oFIoo3MJdsKw`?f4L$q4C6Yg~3s?dC z*_i0Y?k?5cdIX|^Dyccz!|g{qB+<}-rexI;*S{K8cu$qy^?igT*$Gz|PPudo!0)~K zx3lPhvs%;bcMd@4atgk5_0FEFY8a>0b3n{%9P+eEbO@|K2*mHIX%lTqhOo#UbS38+ z{qU~qPwDynEU=`T72WwsTYKnL?nv=?=BqYa)0uGhtSW~*skhz7p?d=h039JqPcK@A zZv}5CWILQu!uK+$wuFlGC^s!1wTmNF)ET`Se=k$zb#~@;_(rLb(8mvNWj(`-jH5hU z-X6t^)~p5hYL(BG+P*?Dxp>?P6Cp;N%-U^r-6h9VbHA%({Jf-8k?Qii+fFjzvuIjd zRE+I>dVe>UGdjwjvaO_3M4Tgxj8$=YrkPw}{)`rm_Cev-O`2!7H_Uy(#C!EU}Ebu`GtnDaJsaqNRLUM2g^pPCDSrlgf{wD{h~McjOpQzeg4TWOtdy~hJ#QV zeluB2R8^lPxbc#M+1L3WbnV;k$Tw9367Vbp0x?iKW2#i`FMe-nJKoWRlQirKsH48= z%?Q&cgH$IXO8naL+^o?JZmvgF;}ZwH1GxiJG&BMEDUYr9*~iVHyakd+=)qRZu4rc< zJ@efQ<|`^igvg8lKX23A9{A<`h5^cELVi}Bx5BWw<xN^tqAHqU4{sG9&x@FP;n^x=x3ap-nJ?tw@S+o+m_rJ)u{z&Vw z+o-4=?ej@`J#(;EI22A_MC#V|=->t)+tyq+eDnQ)EA(Rv_s{b@5G-=5Cmx=^yy`uT-s#4yD_EhFiO#R z4RDO$<2d4X5HJRYkqK(&9=ZGC%^_S^q_=urP?%92gbaB6&ClAF(qyHeaHpftiosGx z)Ib4Y&~)VCZk+Up=!<8L+-brOytpl9=gO2(5)!@JFk0h%L8fxx|Mtu8g>Tq^8ZN*8|!v*^@N#J@!}Mo`wr)5lCcVaRY)#Ngw$B z+8VyTlvCT%Yu!YHW=_SY_6+b}BL{i=OQ+fidE=@Mb#NC9qze0@Rm*Q=z=`cXi_a{%i{4%SwL z{$^qltx_E1U+;$VIp#mmWEK{*KnWE0PFfF+ZE}74GbS)_sZJ@_3lKNc=j^&2dNc1W z1rCASSDE5Ngo2tD8QO>oLzQhk2F>N zlVIBP%MCWYfB*GCZ9i^)KJ`W5X{x4aQ+9|7B*j$j9YpzW`vR}XSzT=4HJ;F?Yb2?Hho)J!&?c?ZFL zV|m%(iw4DfAfV%>ukCssf9HL)7&#LEr}wE|(^cI4kc-%R-}=sU|{LU#zljwTbUOm(#j@KDgm8__^4zw5=G=jIC zM%v_?^B3a4yT_x2h?w8`hge`yGN2HurOs8_vDrGZ<{JvF?*~9DDklwI9dTBt@Q&wgiU}t;gi#*KGTz=>DxzG)) z4h(%f?cf->Kw~@y8Q>UH_zF=t4Y=%gx|>&@EccE;iP=TE-IM|7hFunC8>G3QU9Lq` zDPO`;Hsiv>Q}y@e#O*mtN&=G5P|(1gkVd0H!P_KNu0^}IbHrk5gJAJBD}VEjNsL{A zywnPiIs3^k0Rt>X>Mq7dsz17<#*s|i9|v^b_?g-G(dc(Ah8|#75w}Wk2p|x2A@*;Q_q^l_F!AKvdO8!O!QS?1gF66F-p& z|CN9U)!B$AIllS?O2RGJ;eg)lTClwBjG@!wg@cn=E^&MN%ojmc*8}Uy?PX|&5$x6X znJsvt{8oYQ^v9~VB;%|;?9BhvlbOW^skD*bH+3y$@9@~hxxkt#_>ynZPJ9&OBHRgp z@&nC(I6a*MPXTuT>hLtM$|-0LBJ?0y*$s)Z>JyP2LPV?c9@}cL(FOzeAdD=sU*br+ z)pB0)Mj+yRldb85fE39J|0d1y!S zp(P)4d?~6BiSo0&TD0t(O1d)VpkII3;a7vN>vRA2>uG^skFS2}CMrARlrUiJGKLQo z2$o1sCDzCpjz_c9C63}XM3CXpbY*dhGRY#+Z&-t>(jUWTJCgL-1>+GrMSUsvSl4ShN0R4Q1kZ?`{ zQ6h+=sNA#5qs__ZD05DGMD>9(rjG{RzH@h$7Wc1OT#T9V>ox~3b2Y&KapuLGp0{Cy zd7Yt)QMW~4yc!G{YtR&g2N-~y>Yn!vx@V8{3-MFbM9_G~5F-_J9mfeM4^WybEA>?N zc0+5Q-~L`!_i| zAh2;qVZLl`O$3P;IQYQaYWp>4+8AH}CjV2MEDyzXi{4ayqjJs&E?^KA06&u3HsL!I zRF;*sEe%aP`ux$Gpz6=x>(akHEZ#H=I;|AE7MA)pc-59JCz8`B70oECGQ$3(s<+bj zPjJIvCcs&JmjnE9KcP|@SFBv&!F;9rj>&%!R0NS$2Km(Q+_ov2cNts#HV86bbj((7 zRSY{GtnTV-vT=4#8>$H-U((op)tq}i>uUEcL0LhEKC-_09ueYA2^35*=+eTxMc(Qn z#d%ypte4@5Vqi@QQIuC24SPZ+MBXqru3kk6*8#FaZpoYykt;Go#-L(FZ*wM3uTcIG z_BPR4JhtX<1{2rCue4hoG|K>FxLth@AB=T1;<%sQPT%0rJ|IAS%WyCZiw#D?1F>cH*_|I zwq-(G`tMs3#^r!W;Lnlg9GDbd!(t56;dDDqP%{f_2;ExFs5Q#1S9W?Miz?Q1kNho# zg~%H$#{J;=3O{ls_S$1L1U*s*^v1jGG%Q$p5a0`ulYX%kk^ zq$i(~zNpu(?c0@Xrca}-xpqQas1ZSHt0gjja zlwG@S3PgG?Z4PB2%k%7;T-~NN15OuOyFKS874KIVWZQ4#kTY^PnI-3qg1-f@$P77%1G=sHzetNKcL%$AW(Z-($#KVXll3Z`DAXAX* zHlM4lf#RO7seUif7%Q;N6{7#wN8OwNQe>*WpVw}4Hnn>C;1mwX;8Teeiz?^`pdcHr z^rXt8ai9va!wrviv@4UvhmSx`xC75({`uaGuUE{Q5P&XJN;7@9*#tbHf{g~|%sa@C zj9j|kj-IW7Xlnq_aYe`j7;bT8PJCGkrSfXe1Eed%IQ9HCePG%>=^$o z+Up#49rPq`oF|nc2H(OUtUk9;w61{e;_|51!{LC#P@i55`S-YQ_<=qj?#<^3H7Y*a zxJ)MC+;xaS#3|$te{)$#0QCy!v{yFc%L-tk`<;!u;keL@74zyETFgL_nU zLmL{p0ttF1&$h=u*3ZXnTsMrj+#XzJN&hW@4vBB6P{-a$b_%M@cRH?r*h@;kF$*+5 zf9M^`52IzTFoGsKGeUNTwED5CG9}#0&MjR|=oQ&grfKGJDHJ~HNRQ}k{c8u^FaE)L z_#vjrf`bMQ0o>3h2JA;FI1y#>8n%eCc-0Tgs>4HOCE)gNUlA@gtxaJ@J_pZgz8auG z1!JcUAhpb@QI#SYXruQ=oN_hL*p5|z>-kC2-p~-sbfc8PIFxo$&Yc*CAF-*hNSa0Y z=FOiy-`WPx`7j)b*hx7l7?_#@yJP2Dqn2ybjkA6ZH=cj~`9<4Ijiy4K zfVBPI!1p{WVrXq8`DYIXGKXw^IuYd4xXYxj|G%D>kVKk${}rt=Eg}_-*(V+Cqz6Rd zt?X~CFt{H-VKjDaXsGy*p)2WS0D<9Nmr}Hlf6yi4uI-@B0kM>hxLi3lbjkdZh*gSl zopKWHzO4rD*|%sq=_cgoB-@B`OUbe>dHTOYY!3FaUZLT z*1|AiGix`NpOIm{3n-_!vX?#j zWRnmZN?hqel}mP&kI<5cAQbqUoV|3WE9VKI>7D{a-J;GU|JZ<|mk$9VHI_q=ogD@4 zj(Vz|BaYz&)e;?@x%wJA>p(S5<-{FCVFiMivL6I!l0l5<^5g}{Nx{5@@!p5+^Bldw z-t9j-ES8WdJdWPtg5R>Og%eI7ItU<`Hne&rB995K1Y15e>UEbdzPS%4eYp8W*y&*{ zm9MWK$1L4DgxsPyTUqbV0y)@b)`L#QM?FI&aIWhm>j}O8Q}G~bJop)YPw}g4>JX@2 zI{s2on#RXVb82-na&Z>Lcoob4MT6)EHv4EHvor-~h=N$5>?+p)JwZQE|rI_`T$=D*8B!7;72N zRgdM~rL|R50nND4nr7A)XBgbC+PwLhX9XsLukmXmLbU!0>i9_i@EH^Ih*pz4Tcm%d zf$g^%o9l`5->JIT>|K8?SyB-zVM7nDgg-;kQm%6$XY$UK) zN!-cNQh)s7xy%H*b#E2_>ppf9taNKFQ~QFRnittRaVcNJC%7-nasK6$S(8ODugwBO z;^bk?5L{QwBS~n>p$s=X1-U+Lzj->+ljYt?JrYFrzWi+e z%DMSItCwV{fkAbITETRxrJ&qFn28UW!`Di<&J2J4&uz`UdI<2_*eB}q4{s2a#p&${ z^@xVp5yYwC8vNw74#PcOwNpnnmfLa{%9YM;Ta_?e=D>%)i)k1%8~V&_XarN&Oj}5G zQ@024Gp!J>e{ZsRmWs9ai2nWra+t=({fe{xgy*i@h^GV>*Ax#0I|CXVn3TskKjISL zku=ix-CZ9Q9LNF7bv(qsglu1qJt?8T1~p|$chka&jWJum)utV{um%GZ?334@vX~-9 z(m~Sk6fQHG2~Y}GCi7SZt4bb+(;BfXdfT%PO4c;Q9JI3na)JTFJO#q6q2Oo#6VD4* zI$#4Q?Y5=+9h5gNc7y1JKU_U3FcFTo$3#TP>C8>rb>4xgnqj2&2$p|@*?J{(TGV;X zE9Kah2=H9UB-4S6%Kx@-(r86(ERs7~S#``%){tGlp_3J;be>;zqN34mcAuQp3hd*< zyjpsOD*`UKdT~aV=G6r3{%oaXyPHQ~auY*9HpN60!amnpgBs#VUJXr{EJdSTcZYax zBjuHy;~wvu!EpD9eg9*FUhWzmAiNdD>?-i_{>5osYBZ9%K|vLHGc<_|bgV``Re!RN zK6hrR$b3lsqoU-WKzZd@2L*K!>m*&$Leg}2tcC<@gC57t{vw~=m1)|* zKVa&PR|R64*Q;a%!o(krbkAvgwz6=IQY$Hb7afo&kWO%Gq&=M5SZTT#cUcY9jMfLC z@oxJa@KU29THC636F}nr8&;jbg13LM^+-+C-O$JgP^|ri2k``@`^~&d8VW1M*zX{@ zrkJrTBms&lr|35SS+yrd$p>$s5Wk(#{mCd5i>gMS&w5+4(`%tyBsPuK4!m3&fL3iz zd{it_89}zDeT32evAf%rtl9nU`KOuR2_gfs)LaNdIcfa}CWU;ExPjzbj# ziI2<*U7$Fu+p!Oc4_QxHVPR_uYRfA2$)EPX;DWzc>%4`-+U8A%)rp*jWez5)#&Vy4 zj^ZV6HxeoRBUSMa{9iCykGTYH=nF+sQkZ#&RL;yT*C`wOEeT@X)H;Fz$$HE`;-P+*Dg2UnoB7q3?rfks5U-b zAvOeg4NCsPywxLT)p};F{2r!PZJIO>eM^@($e$*^HIGR21ghhs`C-n#lKNrvLmiQX zpks>S_3ftxe>a5Zc%GXGen&)@E7TPXu3;j=w~SIa*HRS#3Xw+_fE8MU2Ski`T$}1H zI&*06ZIB*bskNQE;Qrd2 zy7n7d2pE17oSg~c+6b4DaIzWewF&ym>H`b1AS*Zf^tfFyjnDq3F^vQR+3~aE8DRow zktgTLMb2+vxUMuPAcb>kj6Gc2ba5u)Zz13+5Y`Po*5B5lqB^wp*rkos#G^t z#N1|RnH`h$*krMw5jBjh!=f6z_2b-INJ!`uIWhseoOgJqg#3HIlihidIO6@X`D>f> zfx)@U+){_XO-DV(N45l>jJ;9{TXs!6F?+6&qM+OJK|!VjtN(;_vW;j_5ce$yZcne< z6SX(WS=L&iuW^*3d;EkyD85#3w=r`Iba3pqoZqp$WjNSVsWY!(*eJ+Rq$vA*2Im4K zS0LX43WyR6`j11E!&-;ikSL{kyb}$D05lE9T062D>BPqO&{Qj*7 zv9MSdVtPR)1}8OMTIl?6miK@J00i4ebpeE7BD=ulG0=Ht$Y(lxk|C0R-d~WwM)Hfn zfEqdet8IvTR>EK}bCHc;`9;p_#2WVx1WfQ|#hD-Mz5jE^09!!@%&{n72X=U#4df{^ z8NhX%KLH{ugYiac&Jd$+SDf8$ImJDaW1TA+rxwzi_gl^y4_AfKUpzF9S<&fTe))aR zKE#OOcSB>geW$Ra`^mz-`wbJ^-KdBHC=-t*t$EUB00!nZqUm&? zJ#egIWupBgEU`X@jkhyM-DlBtJc8Q^3^_id;sG+tehznPD z`T83JIx2>;?o9`ZN=HgnojbQLMEQXIjnLf>mJUA=gXPRbnDK(gb$tx{q#uT6(1iuD zpe|O2kWMOKYFCsD+ra_p_{>g&V(eAMBrj+CUS+p!`sG@zF9Us%QK)o(cE;4><X)Ny$6D9kHXuP3bD=Q-T50F90>uqt7xj1^cV)W^Fvx zrD25K>MMS>R=geglc2OZk9_4i9c-WJ+oP61n>%V@!N`Z^6*_DTwc^ibKXMfhpw>JX zkEc3zCW3J;s1~tv zShY2Z5k#-iC%~20w@ndFtyVX<_!b->M3yO{kqPgI2sIdpmT(Fr^I#E*c*P5qCi9mt z-u887TY!dd){}ryLE-o_U97<-v=x6Yh6Qsml9hABySK6^r;J|yGmWXpIdzew5I%_i ziOKo@Mg}3mTud@3$jKQM^7X)CTSJZB@390?(}<79R2_HKcxVh|(;f>}f#PSVJHhh)hh@2kX%-~oaQY9+ZIw~?(=gPFnwPGDwM5Zvhj zNp?OsbcoS92~Q+~Ot)@Jpu5g7A}_C=h#Rdn23{rCTEs)M%@+`uWDT#7Im*%}KY+nq zX2|i(5kZ?rSk8gj?dH04+pMyQn_XFeM0%h_q8|(cjw$tN?DuD+%C96^`wYr?^{##$ zQYFe=#_Hzg;Q0_>{6BWF-TJTeh2ee?pa<_8a;AjQ{{7FoZte_lHSlekCTQpz1IEt@!_wWb9XHUV}D&io2LPAd;}%7CeR%s~wCHCf6`A zYRyM!-6FHbML;BcHK7BQkN1TNW3qq9Rq(;*!9kldsj{MUN6WeGpBg>J=uk_ssWacj zwETccEu!3=RNV$5hV3^S)NN+IhKZa+anM0`=rBhWCCraAyuy~j-!U2d`%_-Fzi##3 z9~N5puQM%2NqqdbS~i%^G4fV~?$b^@Z&6p<;R{R;7fU-iqEK;xz$?Cg6JpUf38o%o zy4D6A9UTvkR+ANd;e$U^H43JFeyH|aUrTbwpU7ZcLDQmD=+E5p@=RQGQXk7b!tP1wl#a?(XjH zk}m0#9Hc>z?nY|p?ixzEL1`GeVd#$g@VocE?|;B&IL|qIuf5iHpDh?a)ozw(Wa`tE zQbJdU4WGPU`W@;o`yGfF_+0iamow(@@D*^UU;mgya;pJvuv8NL%y1%9cDlv{&*u9+ zDOc7rqtwSNga=~;X~kQbia>rOa&6fHOT)t)8u!5XR!C#WNV;EIbP*2d0b5tF?Fk=` zoMz2ecN>ia0`%p+_qULlJzcdxv{41}(LAb48T19ArLmBFxaX6YHXqBYSZxi$aThTl z=5N=unCmecg?nqzc#H|t$!(BVX@FTIUat^O>{f8-T1w|j8^L@sIeHQ9&$V>xii(e85yD@JD1Hc8qK--9FtoUC^d0}lMj8huR^68ism9ms0gZx7 zuRiR>q-vQX05hxoL;WA#jP6vuZaka`vWlrR;1}tl0YSPrK6@n#om~lC@l7Kr5b)J? z4P>USPP~6jUXYc8tOynXn|)UCa=a|oFj%moHAkJ#tZpA`9P`r)?l%)rh@is zaAyl1tp-6_z%uVNQC}>`)TA$eLgGAsPhMm`ed!p9s9@;#kZ_HUp?a@7>drRkc}4ha zl%z1(9LC4lQh`B1s^_lYb2Ip^J5A~@6f#w}cG;&Eh6MayUyA4oz+jKSgZ&x2a*Qp( zutFn?ga=+>!Ng2eRAF^Td^m6k{Dl9SDnA2zRt*XM!M%sIPYsRG7<1c0CxgH>9r0!hyxzJO zGuMqZcA`1iLc_c%(?^i?UDz8F1tDQ4M5fL4i+*#V*Op`m2@c;Fv$Fev%$BpatFV_n z+i-}|qWg2%ENZJKX8MUbz0ph+el9RlIqq<{^s&iY+u{Kt|L7`IXjCp4+U7?}tI#VX z96H~th~Uc)SM;?;RZ3+THj3}1YlhM?T^afTB)Y#*2I)ff8&K2r3Wxhj>JfIY0>GxE zFNI|0Zi>OS?@bo{d>l@iMIz9A5hxBp~M(GQv<-)`5_042XA0ZZ-7fwCzWuj zY2PbzFr!RL7o7%vynME8-*1B-15wu<|HB$M)tM%B(XCPVA#^%=a#BSmWBf0`r!Ty{ z>oD-#;J1%ICL>g)Rn&cC>pso}NZ!ke+!FDD7IQZ{9AzedFXN8Hf;noL?E5w+ayIB$ zJ-qV%`u;5*j}|AbvDFEgo}f;&fPPx^gV^04Ad?v90p5^D!ialL%r zO=35Vo!Q95pqnwiOhpxbAdD9@z1LRJ{6L+%>c;i@yOZH%vw|ne{}fZhCbuP={P@{f zTST`{ON4YqHVIP^rMYjrjWWEvEQ(4NAXQrexE+rbZ)*icJ)54dZCL4YCKH53gt&9&16}wh1RAh%bMCUW z+7rFvJ&cf<>OI$?BLjK5RxY14e0LQ#cq|Hmab?b!>qJSCd09&*WfIL}(F|AJf3=)j zG!imSL{AEOL&wYK(D*z-RAU3#pn02h)Z7PTDcgu4J2kUf-(m4kucKUG6v zIQ(1L$1*k{90YE+)It2=C3R69icV<5#l&Lm+PS-{Xpb#tIl@ z>Y#DYLZH7YrtApxu=CJ>RESYjosnjnUC5840>x11AApOnAQg&%kzH%)kc~n%#>}%w z-$v+&ttQdq~ziHoRVFuS}KVKK{0xgXoCixj`4nd=lIC% zD2?OL9jP^SsK?N`J!P+dJX@pTD5;^1P?j=2R+`*wPxTFB*7U^J#`_3Tv#`PI^5GWy z*3A0b?UzWw#rd26zG}vIPYl$O#fmBcvTz631t-$pO~V$gH-!4HiR|d6-=T+^*y@x^7clhv^Yeee$NGh9I63Kr$WTT&F7zDw{osev zbaF=CNLF!MUHOInUh4P5hyY*TC$CH1v!gj-=z3+CaWk%{((%2Mwak{D#u}Vj*}*ua-;gUUH6*TSN5wt#+q^v6wP5l zHwcI5@71^|qj|D&KaZgVik(DRzqc$Eec=&82o2J4d4uW;?4v444xNwqe|5VA&dQ6! zl^gl(Elnng$kjv4^dsmO{ zYyH(PRkzpe&+zQ%KF>2kwKmvCz^D)1#(3@VvFlEym}*rf4l&Q|N!9gR4g99BQq>7Xf5-&RZp3p-%16ho3`IORKF zed(t>X{cjc_*A!#*X4ttf(S&H{8C1Y@r*;WRlr*Dv>amkULh)IJ~{GWGyQ)3W`Cy< zu;VU6q$a-$WX@2?X#OpttMOaB3{2WQ#us~4!bs@1zykRZkg@m8E)}>D5@0BSV1klu&`{+_N{d%sUlLl z!AGG(YAn@VrGrlNyBoX!}dhm%v_z! zSl&MuJ#|1M+5JE(2W~|`9pqY#yc zOG*TRssL}vE?2*VD&u{MB|o2I3bMkf%x$}V=T+1Ve^HwD18*A{OS`~WS-cS-TT0%= z(`O3Hr1NkXNBSAyB2D!A9D?t#{e(Um5aoMI2Nfn2dWuc2iiwhw`ixt@>gF&;|2$Us z2YboNjI_F9i@WNmiZ)aO6r#?vQ_vEiJl`V5j5>Io-JzGYXrk}KaqAFbqVe8-xbeKZ06f%^GcmvlOj72KSe)+`2YEBy3Ha1!dOp2h~E}BEIgL`*5gA^=@v-ZL#pjS-fv3kcMEK+EeEj+#E@G&4sq~ zl$rX~2s+44dQ(~cX(_u{I^!o zE+$*iY~p0DP-o0Zl-F|aZ6olu+EHyz<8Rx3 z$US3ShN)D{8IhCwVRZwnp`k4@KE3zmMB^^BV#MmrKx`@xLL$lW(Jg*)vw`NLwmY?pFAjS$; zz0-2>Xc(0AG8O6qj+0TCRZU2oY~me7nJZI4L#g7v_1md$RPj#**nHDpA#2mnJMeU0 z3vg@5>VtmE8jOz$Ng3?DdGS|LTpHQwf|X@xj5?l zTF7HA+M36#|0V`Ww5TtFUQIj{$C-Z{cMUb z{6HYg#AseJvf?aLXuPuB`P*rWBA!uTc28(OOG=$^Q7(yeqo$wtT(W5t7A#kCwLLq_ zx^@4bb>>dwrt!D!?^TJ=Vy;!F2*6S&Oj%I4Yv3G2Q&V#J7@&W1$omeiq11IYFOUv) z98|L>@r&<8QHkmO0l2g`TVqhZan(!EOm;5(`x_)^Jl>Y$X5ML9g;isB_|ChB%b{Zj@GEHM2v=$o~3d?Kx3F$2UCUF!9e*%WpRo;aS#c{_9bH@n8B7Pz=@QI zJ=|V>di)TFqh7Wu=#7TZ@V3FK0J(^x0_|oK@yrJ>N5$=V@gf6hvA}KBw+_yRm8&gR zp&IQ1QI%v*1A36dONw6&MIFAW%jktMhS9Vzc#KBjZ6EVEDLc z952miwuJu?PRhDIaj|iAj<29aNbZN1{pGW3i~Zb0&s$}U#M@fR@l>x8mcH-8Hg3$|0U80W{27C=QA^t*#+S3Pj#Uf2+o|lSOJXoY=`FNGQkJ_# z65L9{OqBXv^ii$19aq5y5`al1=8X~Zdv%&JxQI?*Cvrq~F}KOE35^ljmX$6RvJ7?i z%O<~CpYXQhE40eM-|XiI&MtlPi;tJcb5n)72E0~7m5s;k=K6)DSS5R5gqJ#X`a|nk zu8h`KcB`?GxzLI%r`ztsdp03o&D*_cRf{ji-X6CVV~bi<5lvf*2I&O^x8Mq-7mfCN z=qFz(W>q542{MrRu>3C{k-#J0es1F-$Sv1{H-p3Z2G^hTcC}Hz;2w|e@B&A^P7fkf zYu!s%Y3oRrj4xA@RH;2bU;kmcz5er=g^D*P%Y`fj3ObmCeW`%?ZDuY7zi$0jdh)06 zygyokUY37$2?ybn4B5dg>2EDwR5FL=h0hAx$>XKZmmtN^O%bHs+d-w7 zz0>lq^UcQQ1 zAQQ#$&eM&Z`ec-3WOp%LlKnT-$aMH4gZa;9yXck_eWMg~Q9A8o&GI0zv8S<1b$I%im_p$M}wR(XX_L9({@%|$q02cN>B&`do$oVlm zaMJop<;nYt(NXFTEaDl0JsC#&=G%F8?P zQ_TbZfPgyb_cdQN9l`3SKbeHEV&`^FsVaFpF#%srMuPPEVA;%=&rv zxo#%Az9|q1J+{Wk5)zKqgDiq+T4E#R(X-DC%R}VVgs1>P(ZZ{zrUT}8pO7~lsOwMm zn$oCLiT?@THemHGi3Yo?om2YZgEFZTtGjE}d2?awB4GC8NmOg$WyYTWSK03QrR_R~ zHzR^_dQE(x!n89qzf9Yy6=)?^<$*T;cba;!8a8k>rR2QY9Xry|p!C$6Fc^YP?rzAM z{uXcD@}93zoHo->fn$Af#d(&WweoHL+OB0bt#MuB=fR1sYG4_<>-s|E6Vx6%Url}; zIdWzk=A_{ayyK3DEm(Oa&h+|zI?}hMBpD&cb5lr zN7%vkdHctNPFWUX1MFwbhK|{3!v%-2ApWim=s`QLPgos01+3v*}ef zika;O1|59Y?X?43UQzWlKHVN1d)Z_6_pK1^{4x(1%fL_eLxvfu9q+};H6%EhKrfg7 zNDF*@Nsdc z<0cBlai23aTWF6(xF%`@^)%#Y-UJ;x?u1N;eU*j?pc=q!{A;86#~;B6P&?2$Y0HtL z=^VU<7v?K5s4mrYvpIS`|K1spNxjCvK!m}Bgr{R*riJ-6o9SP6`eaCDR3(4b9<`y! z_jF59LUp7ez=Eab{mwi}q1=1DQv@byO!>5uo#d~5W1CuB*I!JwsSxS#lAIL8AiS-- z$uH5CocD|>-1h%n`E&4a42;^+8=M?ror;Q3dB(hW{;xM~i_7nT=4RlsP3WZp_ zEh2C@dkGMQKmi=j6kc8}jkc(qk`|20)-~3jKK^rqFA?7vi_|AMnXh>uQr1zS))Bl6 z;F~m!HG}un$9ejB5^6!AroE~V)Sp=FMzGVf=u-kNL07pd0*WMOF64eTH`?AS4S&$a z(oMHz>&el%>@KkR;jbWF3hEA>$IIS;p^7mm{}Ao0OqWAzX8SAMiY>KEe$LQTyMZ9p`PQPd7T4x5m&Sh~CPjE)#AGcYCpSElmgCR!YUgK`W&~_MzU&q1{Bq0d=qhBZ_;@C5+&0vf=rqKB;vleiXSV!ceGtF z>+>JE-{cMX5k+4N`Ss5zNJ*Zzz_ZsM7UGp9dfvc_JXq9F=-Wc*t^;z=oP zt)07f6!M6xP8z6V9Q0@91{+<<^pdw8 zm`!~5J|t`1{gDaiw0s}HbptkW3k3likfxU-zuky8?ODvk1ueuQ@Qg2;joBp`#oYux z`Xs#KcW#nuBERjko%>hc0^Dm6AXCcL|AdWWK#wb8kl>YIK_lcXD#3eXJ)nbrE>gqp zXrL}jMZKT>kzG8;Nbp+xvkR*gT2kKEr8D##k+mvE@elpwKxUEBhw!LIAmPjajcR3+n6R4%A>Ir zs=L}CZXP_^m8g=lkIjs$E4`I@=Ciu$Wz@}^eAw6Zw}XwXXMBDjOMof%E<)<%Fe#oYs;FxO z2U{8{(8?>iILfP5`J2=j@5^Dt=vezGtjRFOg^w((SED)ubdH$qI3QB_kerco(En~<3xQejV0icKh-!5##`eIT7 zm}oC0DIY;faYvw1YKS7HWPryeVV*q$a2x<>wNZ78nmY*CZgz{|PeujxyZQc%JQ?7DyJ%|H_(K3@0iK zbPLRA!T{Wd|A86l`|-o^m$>ME%HSu8g+(Si>oXX3FFQKk?|v8e)8O{l)V)6o@E4+u zbl#be?>s4V?HelH@$b?`=?Qd1DGDQzcVR-Wbh^Z4lMff05%L0jnKI~Ho`0+dn@SGY z{v3+^iPqJfxx$>{+mE%Kk@V>rmMuU=b*Kdl`g@~UA6o_gE6QsAHPH+@Sp}b#WO?(N*BFa+;cjRUnRks_YlbK=|Gy1y^Q_l`R zPvyExSHd+vGAhBx;@Fh;#qVk5ZtsYAF(E z9ViGp83q{IQw07%^t#@AxHxWFsxjFVt5R=@c?Jb&(Lyh}&0oRh1iPz*&5$chj zd;q!tE*=4pa{%mGdUuc={dmL|$%8WYrwbgPs)#y{t-hD@#-?}S|`|>DTk%-8m!>cqr zSimC<(dGE=81I7(FC)W6Fl}3ADq0L|+_%q(b*!m)4e5J^>bS=l?nn~ONGxO4IIovG zjybo-QW}rW0%Y-SrsF_jGhOi&KN8jSRc<$SvICdljl5Q+UEM>-pTbgux?Z618v!mL z1_!-y2hQf;K)@8Bv(%OKSvt?kxVdQ&l=l-DskUY%{`X{4k+iIO@}>+hu;qwPJsf6_rY#)0{;9IJv7Jum<^01gxQcqrh_{5`OIF*_ z5si>(5&*g-QW}*L_9;wId=;>Hzf4%;0D~#8B*pK==f`}6`H0bwLSI2+z%{kG%7lte zx0JpGeG{*+euhsYWn;g}E+PfAQsoZDN#^@a)UotHCfY_G4@#;Sm^z+P8;)!=F8Ke~ z_C{#bQ#9cf2WjB0Zn{t4mB_qRMB0IVgpPc54$ryN%{d10ynn~U?}E?Q<)TQnNvy`Z zTv-z{SO)WF=>QzcO%{dPJU{?eu>Nb`Vse+QF9dA%C2mFLB8Gsj?KyLEA`x!4|9!uW z`4tmD2G?ttCvH|kBjwm%$EG3$)x~gI2Z<8K&t!HWu3PJ|G=n0b~Fm$tZ&r2^jH z-M@|)m!%*Hj^kytjq7f~uSuSJsn*AYfw!SA1R#T~R$v*Wc!jQ`jsZ#CL_Zcd8tROn z*5pjES6K_Y==cQV%73M87TX5VQC3h1s%BQsslLct4{6$WG+5q5K28D+wZFgGgN}5p zPNL=erT}D5vgyFgu(pi9D3@s!ah*pu@rQ`DfFZ7jHM1khP{{peM~PT=-vTDl(Bs_cs`#Tc^fN&G0*34CXs*2_9!#M{4`FW+q6huSeGs zwZzrQufpi-w#kXdwC}qEeq}-EfgHpk>Kqm}(r*JckbKGF)e5)u>w@|bt!AM~qz5~7 zYfi(byS_~hJAY+p4<02gVC3Tia z9_U`zP#uN%e)O4t99z4j2$a{h1h}Fo&!B2A;nEC6V2Bq%@e4=a>z{^};Hmf%^X0qO zwVlkDg4jpc5*W<#J_>If+uoDYbb`Njjq{cs0nJR6aZgB|RJ4xd*}&k09&&9NvVPfP#Gk-^FC)od?JA44!$ zcT&_7w`Bz%NCB}9DB?#L8vhn2Gvk3A(ocni73*oY5bQF4-E?}{gJBYstt(stKqw$vG-}iU<1qv4*;y% zdgA8Bo8bAWpSTZcW3JD0x4SX>)Iqr_g*trE{j~iV=KF-CfEx-lFHt#%U3!cksgxj@ z=MxpTNxI-&Ia~{X#C{O%F4TB?<2Xbh`w8&HudZ7yr$M)=JrrF|;0n>ayyh@uy547O zuU6E&Ftc`xuU;S^0c;3>SliNhDG9!ol+X`Mo~H?Sr}8^a%gb983?0w;dnantddBsA zRuWKICYfYJTmw1K6!EQT%gNP-90L?SmDOYLp{Y=Kltny}mT&%-Yxo+YyvLGfE%~?W;B&K9e7-$>+#0RB zFBA&Z?{E||sp}OJuZW!>G!?7BYN)=fDN|&eotZ_x4q#?7fw4?jsO}$|=;-tMR&npj zLG)1T%fTGYR<38xURk93ZkrDJjfI9z+TVN*$;9Yo=JOJ{qmNg=<6cVw84Pv#MHjy>u|6G^LTh8YiuUdKxJNvrqn<{@*u1>lR?G?^@I=s{*d84>|mce zT5kIeWyhsJpMwFqK1g}3asq4gfV=LtTkt9^8X`=4>h#8es359+{+Law3mH{%+AP69 z`*QDW9VS%#14xBjl_O)^dno}R3W>~ zt?KI+XpBeN51^5vU5SR@N(-HSpW?1NzKu>P7?Z{AvhK9MV`dLNNWXHSQcT@t@41;L z#(cb(N4fb`yEE6o{h8E_Yworw*(7bH;g9Pw&|A$9_6nZ08{ZeNa4B*qDdU+QUUTZi zp-l$}WA=_>QC+%>*?&te2umphX=7^LC7u`(@;$Y?o{w1f`{AbJbM-}+X<4JF zMAF^;JyDCVf;ZnmCAw69H|pPc2I%kgM{cNO7eR*RoKnse3Nh*$3XY)-FHef}-aQ7o zA#;D>b@~n`y4{?B<+#6y<;s)Dpdc}75-yY6T~NSmA_!VtQpyK(MckkFg(&;gwl#2f zTnpwo1nycvgkf zb8(_7uf=J^3l={j+y8+MfSwhI{j}O!n(?!Z6Lp$K(j3+P5PX5AffendmL`tPP}a&H zdpf+H049T2bfu7qPEMxJsVBn-cJMg{QW2 zHqEG#rKk6lBcJ5A!*#I$-_&D2GBQ@*q7RKm{av&UlLIm6pW>L+h_WUh?Pa8BMdI(wAiBvrhQX=SuD3*;88B5yg5i>=o((*8PxMv ztP8!hVyUry@C~2D>3m-DE0u7zb;6tVA7pGlyZhp+kY!Xh$A3(uS-Hc({kU9OBYr+M znqo%UKnlM;g5216hpN$>FV*5xzg`ysve|W0A)jY5RKf7E0ga7JG^KD{8o3UKdr#2k zkqX^}vk!Yxr2K0U2%^R5HDDT&U*7`*c2t+u-LIuM+fmjUp5{yiZ)@t;I6Sqoy&kZ0 z^=is?)h&roIrtoilD22eGkvcUE1}ky&N^K^8X6}9Toi#%eQVRqrd~pS*hkfMJ+0N~ zaiRdLV(}XxUqv!hYv>wz1>@fv{3ih$ud)L%OBIAyw@<*Z?DbCjpd0OQ?`HZKHv<3g z<{+0IfVum^Z3@_0iVOvBL^P#Zf3!~KAbOCg)xesRQO6&nMe0q=X}DYM z7IK*3auM?J?y1F37Iwu^%|G46Q=B1JILca2;|G@de*aBEDMeOeF`K4Gd7fz38Ulb# z!Ad4V%AJ3qf<}abT`SLds1gBm9&!>uHq8uzb$3w$x`g;Uy=8ih^E)hUC`)4g`cD>r zP9TX4>gS|5+0wx}>onE?dLG!aENhZ>xGjfdF`}H+7pU3F?>P_l`afC_l!wT4O1_Vo zo|{jE{e=oINwQ`PtGiV9ITMIw$~!}u%`E9;)?$-TczYwv<( z;Hf?>*TcGAE8+EwoY;<|q+u688#Q*{hDRJ9DZxu3;B{V~a5~sDdI;cAENzfcSUCJ# zEw`e!z)x>rOxpJcc)8Yj-GMW>Xzry@TPMK6MPB-7+36T4`>r|h4tK9;^`hKu#N z3MP_9W1z~Y(^hVrh@d&)wN$x|Qj>34zOoSNn=_kIiakw$%?=QGxgLEata6kW%k=zb zh4L*s_0`_(gJlhV+p!%!F+Q#35$tyB5wfV+~ryKLhJE2=+gwttEe>`7tleiVc5113IghjUn77l>B# zjcy(F&>uQo(F_jh9o}o5uxu}i4@n%6^;-U*N?i?UNG1yK$ol_&_tKbSXxHsd0gkp5 z%7cQY-B+niYdnp@wR6mu+8QU3BZrI+H1&dCG!_(^g@bSLQ!ko}8yDk~w1d!RMh`j` z!BPe*ZZ*{+QQ~Iz<${{osJ&rSBkqjfwwX%X>qeJ+CS>!qdubU?m0Qr!3IapjOb^FNjmzU0E*Q1aJC96W)&7f})*~YGw3NV`_u-?>4%tR#FF?^k8i2?e@NHm-(kI9ZO zBIMF#{7P_t=fcgTx>P|+i|PU2g&Z1|&yiua6(*HDl58S$0UK+nIMu0)5>t=OE z?|Huq8D?Ye)`#pAuUHroTDx4(>}c;{|9f>pB!0nX$2g@)hHshx#@LpiOB_Rc1ZFjo zp8Z4wd&>p9i?=1@e~kk}{Z}LB>{8 zp;V8%?q?1Lb;yk)CmYbryK5*V04!Viac`HI*=QOt?9Shdih;at7-_HVH3mZ-bACA+ zegG06z)36>h|R;gJWq`GtvHdd@ly|@MxPkOi!b4dr|cyaa~8hopi>jVUqPq~$ae#{%2@=+F;eXF>7q#gw?sK8LTf+fpMCzCr#D>~-n@j8L#w zWe0lC50}$QkfYi>=c5Xao1vmDE=Wxhj^^Shen9P*^|VlO9B?{6dg@J)_R% zHx09y4v>on$6l$Qm~xQj{ZtD9+&Zr0wi)i6e38DlBNLd}5tx*vC7E^~(wzUsYi4=^YH13MwQPTjE`%vi?xS#s5@Q*p08Ohb`YU zdk4YMVUgJM)^*tpm@oSjjaF27WNKiW1~yK)m}&r9C8b`e`%|ellq{MH<&b#J-_lIi z7%WgyOk>rL49`n!@*OfkL833`cmQxu8GUtzwc8xGoj-H4H4ArfFvNWpXhk4G9A9CW z&rB)L1y?ij*A`H-c?tNDyC5QGcLdh&`hohV_t#yvDt%~oKW-TQD7tRzBJFn$m17-M zR^>96;rv?ehdpzS^i&V=h3QV!vnh8S)Q0fAAwuj&f&bTspk=n+LN^bi)yRnf^|S%X z;t3BhvOWbB@<*c$EV{|)xeo(=!M!?+K}tkRoGiE%+fQYPDDO2dzj1q-6tR@m9CK6y zJCT5J2WjqOn92)xb6lm z_Z9=cG=iMhXW-S}#H=fLKEm6t%$3vRY{1_|EzhjQC)w|^QQbedRhNK8vO=Bd9M$j4xMl)O?fEv|S^E zkmp$tTQ;x-EB>Bw_m|I(dAY)k!rxy(dh|1-24VW^SLTn9Y?#yL_|owe9#bIa9lB4o%mMyDt*F1@FrsWYFJP;e`0#PR?FkuAGE_S zOJe70CJ6UXyS@c9kb8EDhgHLZGCu*(PAQYc_m#HfEK$%S@;(4uF=H*TDq{$bRiqC8 zJSl3$PjL5LWgp<_yLOJ~pDAD_i8rXf7(-qg0=rX<2&Si|YJk%H@e%oLdu*7J#3`4} zlAsL4|6`mZEW!MjbvFUC)wnsZD6O1Uv`RZqo|3LNN1NyUIdp(s0W33ESCYQA!j%x| z5Mto7=;f6M`H|l8{4--Jk3^pPc+b+B@#H0g-O@q_6Qaeu^#}2W4@Hb87pZW8dihQ97XiqxL38 zoEJdM9DBuC(b!SPePH`EfAc2BHv3)Nbcn5R*Xc-4U_0t62u#sJLZN1>Vn9~fd7>5) zfFAxgb!ZiEDTZZaz5)pa2kJp!+W#bYNS`iPD?uGTU!Dfuh8iw&yr@pRDJg8zo{;|w51%_W$JM^4!)=3z!lh}s$=oi;t8gJwhQ3MGh`si$w~2#_k@T*o`ONzQRV6-91- z^a{UxjMRYNqRT3vPz}3rk)54g6yPA)yML7>40jDD4W`Gd|07rI6GdqbrugPsvFZo( z;Z~wt%HITAW$|Z>GSHg_eqnF78%6P(I`6LE0<|(vx~=Ep5)hZU2|`2^a-Pz8bF9-2 z&I{BiUTI7c=aD1fLE;fI-|Sj!e7C&3T-uUik%)-JM7BfiDu0EYJbl$SJ5JAEv6*dU zKIDFEFMu4&-q83Ju`&A{egVC`S_FL z?qG8CSV~DR>4^isL)9sh68dLgsn%^$X`xz1<+JdSkAQ+hSd}QounL2orm`bJMGDAt zi1uRZC82{r0kAp{3Q+)r9Z{G#m+dYK+DwOkx+||8uo<{PR+HEQc*U9Dg(XZeEcv)x z6bK#$VR7^P)Rvr*X)6AR+8(>7c>>BdmCosEia-WoQzq{GOCCsOh)Fh})@L=e5BKEq zk22&pw2!E%<}_YwlNfR!0_uXVOI=Yb%ggaHZPO$0aJrjaD}RXrMo>coC%u30b>exz z7xQq%PXQPQJi%vq^U}ALx-_?aB}=P1tGx;46y!9`Or&Z%*NPPFZ)wVFSA^Pzecbqv z0GEWY)B9p}=g+NKH?*4DZm z5Y)`vFPdG(`*v%lqg_rr<(Pb@%CssU!T9^N)rGC~_2s}=UVMlA>b4)?yOlL=Q(14vBZj4SNH@RY^h+lCre-|03o`<(5cH zI^6cGY)rEk4{;|mv0K0l-l$ZEfj51u@#1=2!oYmVkwtdIdG>0~AK8;3y8@^ru^7u}3*NOKB$S->4 zI|QH(S*|;yg z;HVW5v>Ng}v#=6=m6ATNU^S0ZP_#)(${4qX028fhhZ|faVz0vjGA3JrQveG}tttq@ z#C}+H!mg>?F`9YT9H6DCHM)jABm=3&n&ankJ|xbTz$Wk{!QAlo`mOe{FclrMW+cSL zvNE?uBMvOB64@K^P0@(su>p0l@=+#bV8Dr!I!>fqhk8}}7H*FQJKPW5U#d%F+s-r% zf9+Nk5%{^jxHrJ@DRG>@!eZ5uvxd{E#VUOtA7aB4!oh=oU1E)Ot;pE9Z87>sJD$#U zt}syV+_OM>VJ~q;VP*4|qr#=DtJ~7T%VkH)E#FR0$2wBP4w&4pn~|d#DiDmP2uqN7 zxM)1Q?>|^9^jAD@O^5nknE5U+uVtR74_qI3hc+G&cKBxt`LN9ry{Jr|K z!A_2AM%BnGGgUImXe$5jv9Lg<_v<8Y)$VwI=51!5Sokg9R%3=SYmKeLXu0EU}Ja}ABaHqfD!bj+kY&Nqz)a219T$`FZzNa8B0 zL6NWU93=bNczT_vY^GN=CVO;s)P8mi2Xoz^$_EPZej_O#2uG-P8X3&KrbrWC{jRINVqXgSVFA4oU(@Z zCK-p_0L`))tySRHU=Eb~Q!`Y)oC>1{y{l+cfUH2SMqi6C^zFD=4rh!7|F6i10dwK| zam;%Rs?(qd4d!jLp$rbPmNPL+HPA^U@wZ~^gIsluvZ}tZctFcJ%QTs<)P@LMH;=D4 z_0w8PetGxiD0up3vW7maVd*WnDvt*%6Ps_c?s*2lK*| z)(Na*nD33gcAefr@Y@~CMAe$`yWT>%zf`vL#zK&Z_q^>KKqm2czXsB1;lOb%92v}^ z>)V%v@ichY54$o4_3eiR!tSpq7CNyD3JMY%*3+@FpXGOeT}0t1x^JYUJl0tnf=uZ= z6g}^TSiTRVqx1#wP3ZZ_ug-aUmw7vIvm|eDms*>@_53~70RVU6@{kV1m+FM(pJ?V9 zj!@JOrD+<%$<=rd5SI)Jg7f}n4b>%hbpPonv9_cRD#X3Qe1@<}yJ4Bc(< zoeY??vaIE-Z7TD-KB$A%z812bH#1bvvzaDmuo)ZJ*be=%#l2X(*ZpzYop0J7HA&C9 zJpV7u&uZYh=l0C*MI(Ku{*tVi&XD-UXlHA?P-n$v9}nE+e`&%$l;zOHle6)ygyL%! zeyhoD_L-f*fCk38b|3wIYi5|A6)fqEg1}i2BjxK$oPdb56t_r&y523WViMypVx89D z7$vc+_J!ntGy7Z3V|u+%tWK~!t6d+~wp2y7$dOX#jQ$keV(2wN0=i~{{Dh3B=kD=w z*ICrar__U4hq>Bo;k0@bi>#nGsS76VM#cLp6Tpj!w~|26S&MlH(_5LBAUpE|%28;e z8~R7W*WR)N!MV2qi6sG8eSDjRJJ`;-^BZ9}$as-h|A@eoak8`?EVq=}Ta7qTIX~a^ zm#@wVwfpXcul%^*ND~cBFlU(L(>iKsn4xTaBjWkI;4<;>&jp#1 zJn(5=J5SBIa4udB`X$I10-%#z?@lp_v3 zhorF|stf8styRdov7$8Y(J{O>oING`0@A8$a9$BW2MS{aaPc{rQVRvGxNo7 z^Boq64XpWbD@`$S7Ms4}gGH)rF1cSJ=u6w{GMBjH1Tel5yczLtE&1YcGK2*Pw+8jV znyyeH?Q~f^kEA|&2scO}=n?UjTyyee12BJGP|!! z_brBt(q;@c0^7su;U(|Xtgvb+rUo&w(3ApW0w0mxj*e^p4^v;k6=mCnt8_?%NOyM$ zN-3$dG}7G+-7s`YcPj`;cgHYvBOo0^cXx9h-tU~X&JUP1GkflN?!B*l#ZbiS*Acu~ zZ5w2T7FWfx3{)S0UG<+(Y#{4vB<$%nr==r#PH7v8KIUMBv(}MZYt? z4Y?Wmba#hoP@=A}&0x@dCXd*cu0Dw>X&#Jz#nz}u<;E*OVa621Hz;r){^~UrmAfix zNp*4Mo?b+kr&ipYx)5VEU~;thk9+_HXO^`sR|YGz{Gt*dmws?pZipG02vn4-aq$=k znP1ah87Ti~2NVK#%(1`uxyrtH{a>f0V)ze<&gA?B^N2?;IPDU0(W#r>Bbg+%7PQWq{hvk0KJzfJ=ARnxtYuL8bPJ^;BzK)O1{!L($*6u}fg9&HZ=Z{6BQ+=Inr-7XWt@(8$cKGaVXAyawj8jEr zgmRb^7HPwYXsducO9v)`SW@2PJeYr+dIAua3i)cj8DiHTlM-hx*7-gHtlvu3s}LQW zn|EnY0#fAMQOKbs>ST<_9m?=Mf6P{^(=HNBKsg81PLqpU)@;O5lNT*^y>iKi>Ub<8 zR8ydENX#p|;T$wCBxsFZ%PO8OPa2Jwoodthv;QCz6G4Ax-<3tc8cbJoO1ls{Gq^2j zOqo+>ZJxvc>!EyhH9MG=UxZZsGpO5Q{q4+`q&`H`~6j^qbOLdjqbx?_|z&j@9b8alb|3@f3&}`P>my zP$V#@Mo7fZn#_@=f53?xqb=%VwPSHcM$&M3{1yY*ZlfL#y%M+@wO5;E?CFk^1f7)?vH* z^;P$iFrxP>G)spPA#3hE6XGA2rvbg*5 z=0-5cQQgv?hq#WVk~Ys?4!iESTMR8spI3z3M-w-XX8$$O>V?lXsj5mpNa!}2y1hxs z{x&yY2ZeN987QV|wZk!>3R0(lbVJi?8cF}#d=$L&QojK6iT3*=oYuJA(%^uS2(Xhq zC$9YI!T5EL05@pDPGC?j#r0U^UCIeEIoe1XQ9fM;%nW>BPpFSxVV5QBr#eoOb^_RV zJW<{9f5}%#&mFTBcJaB#M^TpGalPt`$$A6w5cGIZHD=wLr2vaZn|%`H>OAW2&A#(lt?Kowo)gx$I8xoU;; z7!7fD!dGY!+Tvf8sI>8u zN&F520qKXLq?stD>LR@$gbl4`%(=OUYJrsWrd|?Sl;5vTOS%$@D%$7`IU5Wa^Y)}; zL!gBnAN6}=Uu^DUm1HcN)U8yrO6TE-D>7E&oIa0-v$eXU#dsUP-@AA>%18@KHpRrm z6yO0;W`O76Ai$vznDh_$A3nw&_eJj8;*riUl2E`-Z{Er*`qN&-Aq!zkPC{%8JSg=# zpoyFR7}oB1fwk1fs}>N%b#5kX#tH4A7r=h%OFfoS3R)P^OQBNU^Us1q$7?QSH1bO}JQjAV4qTb5 zxP&V!(h%GAi%%K^1{x^5QuI-7lM7u)NyDed!;n&R9NHzR_&QZ)?d_O=HjC`q4Q~&< zlG+O~fV?z#zCeq1f$g{|0`@Ami z7Lqw$A^{eld;I4><%(Hyw0l&=1BF9N3wR{h@HiuC-#i?$~YTO`^?U%UC%L5fM`Z2Ft+J0JmVRgASwVSKo`g9q&dQKjcfG~V^ zmmBmJ1O-xoQK|PR@Kn@BAbFz9Y1GJ^BUNO;)7M&aCM!oq^#Lk_^vK--!I1;vyHOBa zf=@vHl(hi5J#JyM)a(LS6+3@a8|Az_*g7m(iGB4YP}%o-0Gle6B6Q>R0nDSp+=CVUUVg%0Ls+mG^b7}oRn)&=b0Rk~Qe>S$}#a=R1@ z0KJ@H*B8R!chZK^E(A!`*weqm2JhNJ&gmu#TDXud?s7cW4YYl27`d z+XEWv>R$ZskB&s_f5t=vBqapunhggqZTv3A{wGhxnhCzTNIbg0?z?p78B8Oa1F6Lo zQrZO6mGXZwfBn8;mWWwWEcqMMEmR(xl?jLr^ov>herVB}?OAGFCzP7@ zu$3}FA;^u>ZHTq+y>ts~mj8z?7qD2@b+X|X{G~V>dI&?{J28mvoBu$mX|{9OCSGwE z4r$3FVu?NIVi4;pg-1nlMq`)M(`3tb|8ZH1fgXw>?pbfU>rV^yjtjO(O>+|uDk2xP zh`*dWz;7%l;;#*rd5==hwsK*N(4)k+edl%})D2+#J z=J}&`JgZw?p7#!Ko;2pG*L)}a)I~O&Ohp$>d#^*4H=VhAn$cE+)LciE#ECtfC3uT* z+@#@CduZ@VGC1yncH=;Dvqa`4a+5Oq$`ck3HP)$W#vHogDh&VIrrDxQe@O=6Kx+u}wBc^J8iipoXo64-R@To`)fG ztjD|Ht{2>Iv0%M_d@=c5nNNj1f|+zee`DZ8oPSS(agMtj*T306y>EGfTQ zRUGSGGlQyn7g9L1o&_G2};1EZhOwKdBmz{Mx>CFq7v*?|glO zh&78X2yNIc7i2(`M$wWwowv}BedTu;i-f5_KbA)$|99Y^;4fZ5g*W`!aV;AxRZVTP z(_{Kgixr9a&7Cd0e3T6Bu!3Xhw3gf!>@oBL(p(iRi56Uclso{5Gm}ve4?5ge@ja8D zT7Dp8{;$x0AvYWL#w$b!;NAd$8FLy?c|0+il47J7m$w8VR&-6>1|i7Wsb_$D-Q^E= z?u7@yb|SV;C=Ptl4Hb3GL9vc6`0!N5_ys3=jj@r&YBt2D(^B)J?XB7K+`R351KA4f zBxVGJsmIyipl5ya&t8EA-v*Vb^rOAqyIHS8er`Z^vM4XKDJ1kt@|#_|Set#h%8J{w zv%Zk+`)-qISmc`_38_+viFq$hz{FG`5HK)TRuQ+D%=iL%3^NL?d^=wqPG&J~RIrkw zJAE3;Kry9bmPtVwC-gVu#zuc}+z#Rm=(Yt26@Nn@5G+OfRNu8zX)gI8>8Q%G10_xK z?4)p1niLZ@lPc)m5F%Ri*_fO4_fEGjbnA9)^6t6*I=6b^H3_3C2$?nE`0pJQbk)=t z`V@2>G52xow-Qel?$^7%2HrM2>aOo{rBx$^{=m}bUypa=ox2~sbE6&pIAHiWNeGY= z)Eu41aoqEn&i{vYyyF3&Zv>G~PylkXeD@Lmb20$$V&a@O4J?36=IefFex;KA-Zy$k zca;v*M|O+k{Cg5mMB4>Ee1EXYW&`y?5=;Og;TVxn&!fjBM*y^%#Q!|^>^Z}i^OMu% zj+GUvfJreQNh_EH(|WF-2$^!D^*L8d$XO_*5MnodTyQKFlg1qTl|=`ba!9(e35ZnD zYC!XYO2psDPqL>IQa}5eE)?ZFo}P3|(Y-ab#f>$k#eG6%@N!ao$gCmxUieY?LtnzL z?S{(fHX&?h%2ZxVpZ!A{zhS@TVg7Cg*?Qq-hRWb-bSzxc+XlnR$v(1J>*+ULM*6}) z6v43}SpFaiZdn)|tMaRm`$;nSMaQd*4F)>QpZoOZ3$dH(tA4W#1YSrrlgWro&Y~Z4 z4IJVP4C5^9Zl3_}`R?4|hSk`KtfR5l@njjEr*-Jj69)u@{KtEWZ+bB{@Ew#b-`8(O z$rkz^Eb%bH-SlGBncyngTv4Pyn(b9@j^Z?VC%{^&BF7W3LteHJoM^ykfb#JF`=pq< zLp0#tno%G`$t-BkzEGO6zr zz7*9azR&bCS$Xpr$(BDqU>HfzFx3Et^SSpx-QJH(K;;)M$Z1QQ9lep%JocdX+r>^l zBd+b-Vb)M`%``nNthN*Wy$KlQeMIhXX0C#*Ko6|$PykFVvRx|?w}~3H*9S`V=#d=7 zB3m&ZW6W6Y{yJ104)+=LQ#%gle)9i~9`ZM^dASDg5zv-r1%BBVGSch3j$dVUe9h;8 zy!d4JZZTo;Q)TKhm&f27)^GornXlEZ7x-RGW!H7kGQm(|SAFbsYRh78%X>AqhmmV_ z-=`LI_U3qMLgevskLw&`qoIOr`N@FQd`;VuBn554QR~*5%#*R~r~()9QAX1Em5c*Q z%1aT+gh;mb3BaSQKG;p@^qqBXlz9?@wdL`v=j?aFF1v!Mnho+X58D)&0FT`W=Sqw` z2sgiQf7*T#P$Z7|Uf9f=?Az^zr{J~RlSNLQrmmvJETUKM*6V0!Sybz9{_3mpn}T9J{i|TtBL{1f?(_r-8l>i<^jv^PiH@Ec)|Eg7uat*aMU07Q}qjwcm?|5gOvqvijL+cDTDU5P-*Fj zty}HlzH0wW1Tvr{Iu$~l!@|1(g)Fdr(*}aO)`V)l-j2vxahv7>Z9Dt9%_l<@`?k1& zkCMBGRX{F`U&}d&A7BhtI++)|B7g36xNY$}dTM=L|Z2Kq0oMRUT)U#eV@}w64 z4l3ZMW+0FNuu?gLLyJ;!$5UBLeDw|knF+}Y^e`;b=DXboZ@c7v|NcS?_xv4oZ z9K~h2XM%X;;Wd*Y;<1pzsL=Cp0tJ<|UF*kx-KtqlamupdGV8*cP#BneF3R{!WG}s4pV4QBAp0?CTrZely_~k z%?%jF(ymLDlL885L>l91s=Y{W+~c!^jvn_5a4~uK-LR_jiqv^CZO3#GzBo@ZAvb$wJlM8rQ<4vGNFY1Xlu1Ynfoz+ghKnvm%s$#m0v(BJb{4$zFlp)O1 z+#)KHsY(vs-O;|MQAy7LyzNd{_kjQtMg29@-f1k+< zHD2i--5x>SF#N!S?~TM_1xWR0G2k&IoJ6|F+9YO`$aQ00Jva%};GZiOdNjWeVeKhN z^>a1m&$stxI>Mkl9uPc1q{3ks#o<;K81H$?X*q%8&A~#$SlXB~mNEj+cB7F?BCRr@k)PG`6(B& zf^yo)h=P#AW~Z;p)F;QIqYMA5SC9pm8XF=1g!5AQW0txaA1S7goUlvz0S$b-A^%jq z%LOs@)x+sNn{bx*L(lqn*u(DF!(;U*M-9Q$&$jiwBaE@bsZ>B}#T0tF zJG}7lu=^`&0oj$}%e#;TMK%pVwJ=+BjCMdVywcR0p>lnAoem5OlpO;^eurydiTZ+ENFe}~KOJ>?lD zGN_;8B_YjyC23_L_ftIP@;Hq%*(M_%ix99)4R*TqU1{gDo=LQb3S62sZwV~0q>5~d zm#Ya0Hf5k;x z0bu<+J+MZ*r68DuBx7Z*_K!eozz3{8TpMEpJRm$cCt2%s)qm`1pCp04xT1Ya6h#U`)>qHfu6PX-o4$S_c#Yg0ul24tb_} zf^$p4aVHCXBS!Do`QgB9NV_Nslv;5-1Nc7DrcH&Z;bU$|4H_l?D2pI z@ihZ;cg8>+MyAM`Rl72&`iDb}*RZ*y$?Gt|`C7ANTJzqmlkmUM!s?xu^^6KG12PL} zqn;XayY+s?h%ueZR;C<2Ru?F^Xl%y-INx)a`jciJqoK8_@;R{;-T%L4O&#E+`~MUI ztj=qz96Af+GtLMWd7~t#$uYNEf!Ppny>LzSbhBUaIVmds=v2+y#C5wN+Xp$B(f8Qi zoDpCtmR`_u%D!C!FFH^CBdq7Upa^W_#tZ7VaP6@bnNz)sO^8HW0h!bT#H8<2O_q~e z?eJc4q+w^Pc!MQ^DuCuGe{h22e!>fretAB}dm|X?1$J4R87oxmCAlUw@rtEQ`Z!Ck z)bT(j{pz;ekc(va4;OO}HEWR$^fof--4lLKHTj@iCsi0QX0rE`5vpJA5Iz)u$z7vn}ceQ!6L zfJGVT1n`p^dm4B+%IPV`aCtje{RXdXQ+Hsb0_zb1GY`;o85QvwjV6S^sth_a!mk1U zx+N`Qqjf~26VPyzIKc{9^w>4z*~gxan0=YIto9eZ@;IB|h&<@4_VW7~(4^~SN#UBj zIwRb!2?>vh(DDiWTP1^nC{n|9ON>weL8qi4Sz2b1rMvyTOTkh5vLS5XPvOe&PsC50J zVPF+mQ~utt2(o{RjQQge1E)R2zR7jODtk+`Mg3_bXYjw&nO{PXC>N$#eB&IH)E>e( zxsnPBgOP|?;~Yz?@7=s_B&!atJ}7IN7DTnJCe#fWjzG1ZMFn^?oXhNI>Rv+CH5`|o z*#2vg7+$I=V_|8zyJw_U14tH^Nm?z%C=VP~W#LhcGrZQgA03INJ`mPIoQ|?%o~H=& zR0stli{;NW700%g;3p&nU0b(UjiQrO5F>+>?N>*<>ihy|YHRDMloY|7#-wkg&YNV4VSW~ArrSC zL+z+Wq&A2Y`j3zX+n+EhnI!Otpw0z#!J?Yz;}Syin(DQRi`aKNbqYf<`oeDRmlapX zvt3dOkH*JbT___UV^C>l;OU2VSmQBBuMjhev@j8jl*brO3^YIt)>R?Bu8;k7XQAbB z4wN60IWA%=jrHr*nu{e_9}uf@LT0HbVJO%RZx7=1<6zpLF(SR}4U(Fp_qzXWA(sIA z0m?s_+IF|EL}n_$X=Y11&E=NFtU~=PZ#Tf%o`UT}K|2pl1!L*XuW%>bukN$*)iyUs zuK5_i6pEqxzAk@`|1xE7p<-NsrVk$&TMHN?=gFWwK@}@k*Vm`~++U$yUS65Mp~DAY zqAT1e;bVaz6F#e%{Etr81+ndrU zRaK=OvVmoTIyEG5g7B8&wcSWSTWqvgtsLrzWgNg`q~~RpMxG5MQEY0lYY7X;i77a$YsvtywDnZ8xMvMz77k>TH# z$uHY{K{hbQ!z1-$N#;d!83oFocT0V==d}!wLMKCn4S8bc5}Fh61xPZY)*F&P5GclY zm&g>r?%>X%O8>*%Fa3bN$3Oz`(wCSi^Ma1 zH%e}V3fgT9@kk^nT!7eGn{=JdwuPlq$;T(EG7ARLZ`?P#f^X?h3zC)c&8(@E6X80j z?X%a23KT<&hJ&Jt8;E`DqG%Z-}y5Fd?no z!1btT(Se=LW^l0!3j^P`ovXTPxBdd|hZpGZv-M6pg&`Z4nJ2;!U1)L5>!6n^6=HO%R(S4%YgHjBwUPdPTvpg*@`=`AP>8tzC3^#M&>`Y zFtq&lxmv-n=e!LM0tSH-ORHu1n}&;yqeGg%Vm5FDM+bZJS5{-=G(OeC>2#D5G`QA` znY%+A`PPf8ubi*8Sj7JB%Wm;Vj~;NN>$@vt{8PG#lJi3al#;lOVC!_^@F0joiLbbq zg)fQqFTm!_a>pfdI7V-1p5t(~L@d>k#cvY6sYW;_f5t9-H7K^nYVNZP7SUUB$$$HV zS{pEdtoH}+EW!qHM!4owx_Yf!*1%7qX7f(JC>|6RmSUo^`ho=5sI`$#ms+56Yh2MG=hjDelO9hP3hf$FDP=dm95v$M`z!NdAFd5;)sU z#ONwhiwrKLNpaD6o~6ID>S{#@QNkl$V?KAJ+2(JYFnNU2C*@@AY*J`{n9A{d!oo=H z?PX1V1z#;w9M7t?Oy?0N<5iTbW90Qr!q3gk?N}7As#YBT1i_Q(iE1Pwa^Ok2>lr!r zbvw;1C@3f|KU6C$5}o_a7=9Ck34b#1>XmTSSBcN6l!-bXk6E1y!jBEC_;6g+-&T;H zZ-S2q_3uF>3KqQ{#l^@CuRFI!S&(uP1Dz5I`7bvAy_SjE+y#5>bv!)^;69L$7;fn5 z8a>@kMB<0zlg3co-;l)~6E=X7o}yf4lW5J?qd%KWCrI|Yea!mqt+m<}DNB8`w-6}0 z=zLPNjrHu>S0#L3Bds`lz8%DK^A8I-6%>bK5?nhl&%F+9WJ&&3(+GWL z`_4u~M*IgK;oG4tGcyH(!ia*KCn>U=HpT~3e)!YGu(}Nr{Ma7))ZdlvSBP~XI3Z*fL0Tg%ZglEzX%jb2E5z~p)rTq{db<=JB zT6)X(g@JNx)NG_%Yy>)XaRj(uOjDLNl)Lfx(Cr2R%=1)G&z)0_o zIJ~MoG`_D?iI`t6L&cyiYq=+OdF=sXX@VL^!F__A4sJo>YV1n0#j=CS?T#_N=hQgV z)ME#i4ane&g}}$aqvhbH!I#k=rLC%l!2df%-XRD?d(#%5w_5sa(!rjeY`0=7o#W2_9y>fF^^mT_qO5P8{&c- z4eP;%Uy*>MB|+vk86=^08{(nTj!I>YcE?Xe(|a&iGrzD9@%3AL|8K?+Ly0A?E(r;Q zNG^})ZS9t2(tmuxFkK)~KM>|4}7NWygk)=va9r~tU zJdJKIxNYaC)p|qyz)Q|M;O9Mq(W_;VM6dOw14S^{WVv+sVn9rYgl910`0n0Qri|kb zQqo4?(E{YOQE=9*2FP;Q2!WMF_Y_3O9{MLN&&~1)_1;_VCT%Z0L5U38{I>NkJnw%U z=W^BljL~5~vk+L2DIVmH4SX9QzDhgwVe+yc0$%bcUGXd^%2#PD#7N^4^=Q#4_gz-|``;z>4=Rp`92w_&U_rN`I-@T}5-L(Y z$3j)4AATA5*ABFM6s@@2?dGv0$kJ)(Q&(pNAxhqkk%1KKCMKCO(WP49PrbNLr=xJYH zjfvQ=O}Rj~R^hfoJl4Y(>Yr9Q$h`~C35GNzE^3M*H=H%U5|uOQl^q}`~0v^kna#hEi z14|Gh8o4_2_VYupS5YcZkuvE`PqFq*K1q#`&oq-588821sCK#LN`nBmu(S8?||uj*A@?HsoI=dXq}M;QIFul`v> z^PZ)m?X)b1Z29Depr*yyL*ima{Rwq)kp~mrp2{Y#0;0!fsN=$+o2rz1U)0-@b+Vpwag8M^1p{@oS-gTC|C;o*Soa@M1y`BNN4*3EK7T?1x* zOs0}g*|-DR_-oVJuRq&Ozm(`Le^+dOT~4D099_1^Ua9cxyJ(f zu#6CtlXTMFTz>a)r*883LY!Jpkk6LsZ56K5=>tyOf_5qC(p_)MT*}qk_WP2DaDS;j zf_0W2$g{ygR_Y`PM;_hrTZNRhq|d*9%f8;hPnNljX8!WDwS4vQi7lLBV>J}8_}3-b zr77Ry0F58%sJkZAJXp6B$Z^y2S(;I1%?0pt?vM!?fwx(X69_tFy^x-UkZ3Y^R_(b< zoUIok>J5CQ`>(e(>W8ctB6%fCEz;{R(DtD%odr+#pyLno`W9azS^1;)*G)uPP3E(} zxOdk%;HhD=niCMqJIu(Bl^fsDFdgd~!OB87$j6?(Q2&<581!sPm~~OTW4V%=>?V4> zse76c>_f*RyaL~6Yi$zZ*DQ4#+5rq#raeuo=MkZUQo><*2oGQ_myLVc>u>Bim%m-)8x}Z`uBW2@lpAXGb0qu^g8H5EzyzU&~L9f7H3fR&Q-^_;czdP~3xd&fH|lR^zhQBgHLZleoO}y&D znmfq)+=3nv5WoX2L(VD%I}LJLnhqPD%hOICG$3ol1x5iwchC)>_XhUUA9qw#%)$hW z88sT!X`9i%9HAv5lQ_%<(W^5HloCf1#FQk{MQXIK&#Kl{V zrZD(Nj+zY8Mtb!PIaHRydc2=I3_#;6jyEFSdKg zruo=EhllEH7mwI4?K5QC z|GTrgC;xLf=xEFpqHbZ8dZCj7@yf~F!@uH+cxfCm`rZ7=oX{cesh z-ArDaW28=n#F5yebp^pt%kfbk96IUFv9RlnpJ6J)T@B$F+P!-rZ<_qwsz(iv3PX~w zx1aZO?xfe%jJ9Kae{86F^oG|^^5`bpVY+&cAdP*Rz0zuP68cq$?o2Md-EYS^|K&W; zSSoG-Nkz|0`yu%;A&Xdn8kal1bOI<-NVU~=-Jqq`NmoVpbn!$SE&v+27LAVV2Ob)} zcm*O|wy=r$SmO}8$!5#8d4^H^9?qoAZ$T)|TS>KpkJ&dB9XCgKMz-yy0Ct&v7dhH) zuD`R;)TjLn@=+8%embQqxp$$FvoE*0F=%LL$S(GdJo@eLzpPw?ti}inigiGF%!uV$ zO9wndRpyggXlHi7e$9($qi($M&dw=j?q9exBD*N`&X#Tt;xD z$!3=}*=vqwYd6Q*N)qpT^bubEW!!YF|2CRm{$#P0%AR_w*msrZO{f?>L_AY)YrqWy;B$0{&3ZC7NZSzRe85ZcKWDKalg)9 z#xa8}?@ol#*ewg*T~2ab-%Vf(dqYM2eje4Br`ltTcTsLIxLm=iAH(GGsr2YJ#I!(_ z4n-h*JcWQQt;415Q-$KDE!t?|MRzTo2+6C8iFx%w;j>xKKb4C#sa#DLjB{;@K|h8@ zL8#?8Wo#`Izito(Qz=BIF=C!QPK^HeX%jZ(yYvu#*FJ{I_}sewRUH_4c~&9>KEi^2 zFcp4~Z>u#~!uH8eXP#zJrEU7`XIpg`OZ^4wy@k~GsUP!aY}xcP3V4h3{f2p`X*#rj zH@~!hP6R7`7YMr|7pSC&acuGKW*4H5l7fhrbo_ zd*#`D{S+jcAm}cH*V7jh?;ZG)PzMiVHPol8G5m~R$rWRP>#lm&8+zugGI`OVBe`b# zK*pDz`9s&$OWFX$Ijh`gQ@KjZcvTw7u;w!pp}RYzy^!1xa)v?BD~;Ho=)SbO%`~DB zF%VeZB9pL8GzneETMlj%@{&D+ zk1`!@B{2Z#<^h=my$v2C-E1Iwc0A!2r4Qpg!O!Ni^EOfd@e`-NG!8#?9=9sqgr!xm zyR`e%gWsozex-3i5rm#RGvk~9iw;xizC1;5YugKtn}1RBUhLQ`H3h}tm6zGZ?WvR7 zeOpg7*>5T)ct?2u{`9z=4Ba7Xcx=_ZJ4PDgcgVxhq0@8lz}~?fa4Y{QnROa(Wyp~G z<(583PGS~#@~8cJ;=Saw(dD;VBKOKRUx+T>Pp0GE_sF&;5;HY$;I!%2x!~364rs$> zVl6HxY0lqGUT>@?i)2PYu)EkG`NZR+zj!_b4NLlzl4l1}Qmd%KiK(7H_~3MkZxg4x zj+&bupCdwNRwf-e&rUo&e`f_N7jBYYvI4(fXDKj^SYEFmPXYb3Y!B=G)|G8D$E9P1 zqyJT_Ct6=kIxB$9MA*@qC^KsZ5!o?vQ5&mOxfVZe{Ih_V(89o-%f1kYH-r)fcFm(7 zX<@?iGJ92TaQ`qjI4<(Ia%$jLc}x=G&vWLZ@iYrZ(x)p?``Qz{3==h-l7TR=Y12|3(1yLUyKmBia%A@$D;5&20)$m#BED{8MGMVf5T&LKsBWZ$! zMoUw5F3(SoCrbgw8)W-`9Ui+4;Jr16g^4b_8=~92rNb2L(jp`l1;VM9WipYwd6kXT z6baFCt-rgv_YsgbaN6}q!%KHCPEW}-D5mT;hZwHXsZEvr5R9iSNJ%-1qMoNcJ4U<3I zM@eh^3qk#mpu=;)dwCh3Yd~0OD?RB#0Cwg|#eG}YQNt%b^#+B1+Jz?ArJu-Ztx^qh z=l-%w3^(jZUWn){KY?t@b*5tt z2-02;8P=x3TU%y~?lbjeJ^Dxz!HwQCX*xc`9a^718I~iGfFfrpMPC*CN|Z7|TKHW! zc%O!H5Va=NDK8$UWZ3F}1GLtyR|-#~8D0N&VYeP*A%)lG=;TL4xxcprVFwLln-K;f zG>kXp!t<+m#3CT0iklmca05Ff*>-=m1Lc?jenwsN7wmTY7x0wa`T#s7QCost{6BRf zR-<$-)uG;1MxsYRm3c*3?P;1El~HK=^iMUH-wiyFzv{%$eF9DaoJI)O5Sx1<&az|V zg$VDX_N?(NAXi@XqZZ`V`l4klkpLM@ZU!JNv=nAEk&~q##$_Lt@I)-&@?2A z($M0QuK08tZ^pbyqE&sD!x&b9kn>ZVp)>}}S!bYk0|)bMX3(}LnMgl5Hoye;T{?L@ z2kZKP>kquO%(w8LXLO4%Kz<(^ox;FKRs;MZC70``2K>r7! zHn%h!FSYP5;&+|v=+5x6J*bff;Iic@raflDok$9)tJxbS@OfJ0i?8DhP5OTn@2<*@ z1vRmUzY+A5V{BwKBE%;hQq1wRS{!VUK=Kxcu2T_Fu1?qC>(~`lte_GkljMWf$6fil zIG6eL!yoSVpC6`wOSMtaJdp4!%pk=o`ps;bEb_`_ zV}V=t>@abo1p)Xy99=&FunZ}ei84M{nVV_%@t;@6aYHCdfOm(fV%foYGA71qNV(yV zZ37GkOR%VTD9&(5npJs_CKt_VYc$wnsQu)W35J`N_Pcr)*Di{H^|TQOwOFn9Rzfui z#DOAwCPZ--m20^3ylVFRz~oqXHa2!8XUCmR>`e2eDR2<6Z)o$e-S@gzQe}G>0m%L4uMFsv(8>KI^@lCFkGCp62gUyZG<8MZq&l6r! z2sk)LN%A@5h1G@iUfK*gT1ZZTH-1BR&7>Okjb5hms$mo!ivw;Z**({<(V`LM6H#bn z8taIM*Um7MCLNMm$=ZcP+>xW-JbZO}m-u+sG8eF3 zpqx(H!2BSX+Wpk;aQ*xg8EKN$55ZVUfi9kaNZ(Vz+^ILT(;E)1dg1k&8DXX`ZGk!7 zS_;fQ37gx_{o$11sqa}cX=u|xbhUuGz>@F%dpc#e80>)=Vnpwu6Flm7RAxGg!7V1L z{5N;$($wcjUH?plOvmH%Pi*Fr^paYV8&*$;hpsENms~shV+FF0yX@9KAeX4aH>(di z!rvyBrN@E>K4GepP5flHDgpr8>6J2HUM8iJsS=94|8OAxfSjO4 zj1d%aD+}E5VF&7r9}gs-5@ii>*NZFe5}`c<70U@WH>-_&f7CEW?1;tt`TMt$bbdM4 zf}f9%8`mRpMwv%FZilzJAPWwQ-9zDWd&>sX5RZX>f_AA)*8!r>#c5-N8x_3J!{lm5 zI^c+k$pH5Y5yaUIq~GQ_(i@f0>G%Q4dpVVmoB8JJ5)sKBqX1{^2Jhtr;l8t3jI~s4 z)P9SLM445L&_@7K6{-Sp3RzC_nklNh)$v|SHajeqCEk>ZO|Qp~X>oh9d&>N=NIh5U zH7Y9PL5cP>t-6V>Z()nE^{Mc>m z`RPYL9v8IhW6m9#9a;wIEf1-R)ZxW=$F0?=G%BJr-vU7l4$S=~ZX$M)_>3*Qxr2n5 zJDW$qxVrjeVzF$-B1NAu-h0OAo@Dv_KK=P{u58@gU~}+2t0s|5dsVs($IE-$yu3Gp z0f0`FXo%v!9rO>-R<}xBU73g}iTFiM@$k;iSlupBq9|)!AX)&~J1=z$8xKj+!b(7- zf_YsG%AyZ>(%5>J&4J%~rXa1>qbomUfATW_A8Ia)`}b<_jkt8}$5CMDs^mk5*zMyS zr8T@2TWgd~8m=f>_Knj7MJH&j5+^UMo=#BDo7h3u+UXUVx2>t~A<^E1V~Q?1Il{oy zDhE?7Q10(j^H!nJVTe@;1@nNLk>@Q!6CD0x1KBu& z!!y!ct2xnJNbSA<_1(FdxpHz~OB@*pU*U~~mshQG@h)eO7RI9>JB)-}JL3hO_=5BD z!9w~dp0A44sF`Fmqj5GENC`*Z?KIq|`v+v0S*2DnnjLB;{uI{$Y}==)*kL&1f8?9o z!airN=MpFee0Nw@tI2x91fvu=tDb=Lbj%vql$w4_Ufr@44s+xRh(13FPai*N8uL*f zEFrVK%^Buh4F9X{zH(U|Mm$R!zBjQY1(q6C6*knV4Tl5a?-27?SE zZjzj+jI-`65_pJFwAwPQ3$yBHAT?|4s_Ohr@>2SZmf6}h(97Y`2>}jIcb=of*3AV- zX;@uP7m8P?BMtS}i^Hc=&}qjbTLu!+u^(XuI=mYLt5fgd()wL-FVrFj?T<=0aArO@ zIVy3iC{;M#G{PP|2Oxa%fdM7HJ1`?&yG6-<__*P=&@2n^Ui=4=(JhleV=p3&>;Ck_RpK);qXmbG82M z-{_>`7X2dVW7nsrw2-SYiXH|DJ@m)t)7|!>6|Z7$7yO^@uEVLRuIa0YAc%mpho%$@ zy`vya5CrKh^eRP=5_%2rfT2he=^#Y}g7n@YF?2yhKt!a39;pE$CDiZUyx+|G{SBYP zj5C+v+4Cz&s^ z6x^J*TjWD;+4_4glM+715^5G+*HW8g_T8%aN@w%hkHw9e$a>NVzG8b?odR%)BwP%V zb1uC<*=|3CUL2g)h#+gXx;{U#E}%ImFp>n)EdxsJ;X5mA#yw^~9=K0m=c1A`zm5>1 zm|U9Dz8%_9Xj2Fo-Coa70IqB;`D8?L}|wiePaj&J{f}RaQFWZ_pue{t@^< za+?ca4X3TH7N60xb4rb)M0!WiLqiIm3(ZKkFG(F;HPTnjMxI{Ee<4QT6s3s}v0^wsK&S&8D=gkS3k@Za~xO z2?vAbuTj5)B;1^jHZ8w0mXVIw zy*aHo#2nBzuIoC?8%LeEK)w}`e3(z*)iFpp)CRf&J&{b@sEq?yJ`F0chnPDC0l8z6 zUct|t+%mr8j}j7^EVQKkLUh4#=Tx^SLLUzLe`%sq-V=oU@`JT!W_TP2#v)4Y5cGLr z=NHHA?Da3Rv65@N8WR!|z9FI(V%X3H113wkYQ3Lt{KH9};zwKrf>+G;s5me$?g}nX zzYa5&wg$zK6S)h%cHwxVTBk%Dbux>$l@@_Ab1wzD%jZW%Qa^C)!>dfXRRD3WRSEQcnxn z44`Q8(xO4?2sn)xSB1&w@n;h1qVY9d)*)uLP4C&qmh%A-7Vrox1s9=V=G`T)tf7pp z_20m4t0zV;(CRJD5u8G@PW5A4%|ActBg6Uied7+^UF)#1;`OoL&^U{#%0~Zr&c;4W z_Qj907YU8iy1M?WM(!e8E8hLItqYu~uG=e;u4hafNCTnutb-?1_G+yBB~b5)%A zO_pb@or%L8|AKjxf9O9jF4~ucF&z2HCdMha2*EvAN#WI)B;3ct2RwuR%wP^7O?n38 zNNoaU4IXF5iSOOb7}LSI`&;&l*qe~}RL0h-e8#@wZ9$YZ6<#x~dhm}5HvMDp*pFnW z&3cRT^|$MRRtQ_KN&d6CUwdDqoi*w;X)nWBlAzRa<$t2cuV(mu{wBwg7xOrq4{<-u zJvRy0u~n!}za@z2wjJyy4%k96sXZWoXKF|zxF+iIVI9w7tzvfH9C#BT6SFE1zNgZdmI%JWgExGn~YcXv)Bg@1nAUZ!X_9Al&3?f=us^ za@f9)2|ch;q0`WF3H$9TQ5tR$UhgmR(MzDmdY8I8e4t5`W@iru3?x{+g-`1!~+id9 z>%sbDK-i%1ecW8hryxFSj~$__a+noc;Hoz-00Yp7!9XV`evKYBj!3XAU;_>wK(M_u zDdgSYk@_rDpD6{s`^mB0PUS8}1h?<9!COJI`0Grg3uQZBgGcxXIkfVQ*WSRIgq7*; zkWumusgcs{@x(eVatI3ggVZH^d!VGC^zANi0+DGwVo+lLgOt`;i|$S>4qIh^v_~at z&D&$9eboHk09LSEg=J!+J{J_?Z4q{c9J^AsToL!xXqqZJ3J2h&=AE$Bb z&zGhjVt(9=B?R{OucV#I1l&G<^nFyl?f#>th9)$s7Jx_QPm1kRz|3%&9-y%)eUk-P zUPa?nZSobH^E}h*7Qn`1j!X{!AUs6W)mLR97d!`Y5wgr8K zE;?I`oyW8&?9O)lV&VxvQ?=CCFwZbVGP5!Z(Hn<#K&+GO3^v`Y4HsBFk&qthUv-(#ihz z0RFgifzFM*rn0@WQr3dmLBYu%abF1&4;d)jr=7${ouX_r5o_&J@erH~$~9^TS~{09KyE1>`iyTY^0d(>gS_$DtepR8;A7@0A96`pZOb$%MjO_sPSNN2q^ z2n2d7G5(M#(uErt`sn&8ktX>}^6`;O$hNJ`+zzw?RIt6_!f6H|dEn5EFus zE8}K2rkzi~?JDBC3=Bwe%8b&3TLJQhV|St{@{(|Fx#lYs>9-(_3N@eGd=g{w(0iTM ze_aEPpUnAra*9C@%c0cn>yJaHNVAwz1nEceKW_d8xP9wGbLk(rXLM}e!a_Yu?_oIF zqCr?Y5F=6{e^-f|*-joj4m0fHEad@Npd4S#R>#I~vxHLYkRD~?HO~r)tDOp1bXWJD z6bC0}b~+*t_wk-go>$9-Y}S@?-GTL?Ms51;rb&MYDceafO4bCHTxXL9?MoImYKkJ4 zDZP)`2^=D41sxqHH!*%`hevcTyy6WIdL-pa%Cu<0n>(iE3u$C8ws}iQ3UJ;=XBCSt zLjy}kL=3eId@YY2=|X5D7K7yd+(KG~KNSnK+|7D)e~x8;dHSyd3DLx_616WJ$0#^c zw?h4Bwn0E3LtN??HR+>xTdi_#28+kd7K<%;YJE(M-)JU+k#Rj#0qBk$Ltv*ei{ucT zKbrPo9=5#-`loE^2-07A->c9#4WQsr5z>8$9;yx~F>o%iAI)?ghKdTLl91kE+hj#X zOiNzT<5+%ytGQJkPvN_4ZmbgKXa6}5yEQ{sCEV$iTvZ-*^NdjrW95015Ru7a)#{GE zYwCub+bN&>9tkNCv^EO>$Y)If49;_-I0|sNF?)i>c>Qz8;cW25*ENr6 z|4HAtlJ<3)OZM?kY9Xdp<1cSafA(h|%VBgE;FqDWK=&2|PnaK`koVwz3RwUgC<)@5 z{13P4U!QThi@?Y6T}$(sX?qEsQ9^zy#Kk88dYAjx_>CImcRrJ>`8*cLC>S(JtubU8 zcr_PpWOV3?F)o<5ljf>Nz`BFu;xt{kYTd9A{PJx}`=O>Ccy27lv-<{fDAzNqYp;bB zLhyu(-Jhm)SB~bMSvn@a3wHV9uiFfk5S5-?Uj+b@=H0=PQk~znPoLW5I~@1+T1w(4P%XvJ-QQ^j=}_Ko55s>i z_8vscPqhSZgY}rfW%87ZQ>?l9G_V0*!WLcX1yVN1r9(g=z5%W{8%Jn?0VUu?_A%VA zUsOVr)={vAKfMvU{Cv>g*!0))2)mF)F$pb=Vtu4cz<%#w?xP1KpDXN7HqKG5$QqZ) z^G}Mur_GJ4ia>kG0 z@rvSZqkx^Z#Kh!l?PH|kJJh|*&RbjpTy7ucgAY)?lWr;QosN%VuQzojD|mIms;0x% z1c!|)VDfJhxP>qV2+irbl|$Qb8l{09qMrDGiq?g=fZ_LFQl*)xQ1S@pb(f#?6jtWn zqg8rqm-agALR2Q3+gWd{%miJif19ZI~Pr}M@6JE23j3f%DVB zO7o4#+`Dk81&pqDfQ;WG2QL%!WGl9Nl4^1vG8~Ke869>pVI8vSv)qolfae@2M1YQ> z(Zr6SN)A)S z-aTVA7ZBGJo*w(nIO3N)Oi4(5K)43v3K9uOdE)Ct{(_Z%C7=);9x<77CZ-)i%Cs82YkgzBV0Fs&PiLWqo7U$0q)wna%#9SD!;6B$Pdx>O*Y$v~|17dY$9(nZOg7NnG20Vt@5DUP3A}Jv zuPBAwZNX-uyx$%q+<8xcDLxy05+|vJpLMmn-@!OdTRU%p4uwD@v?h8|Qgx@>wbiN+B729!9giqRGGoUj#Y4eEA$%jWi()jMYi|ScL@F;8*B^sh1D_ z+GG0>wH6{eK2TJHj=$x?j6Pb{q(LI*a2hYhvDwbf z#>TUw-E3|#s_wFM`eKR_aV~KojCC7y1(%0QO?{yYEokHPDJKnH2Rd6y>aHC>Q%2X8>!bNsWag$5OV~CgLlhX& z863KGs6Tf=)SBb3?DksxMdB`SFRA@dzwa38F@D82*h|EFxMzjZgl)H#G&+tnXIiSs za&lr8zYwFFIcR%EM=9CDBwDJ9?fL_u%y`l&G~MP73+Tnf1DN~B4^YV5RJ z>peGnv`+s@Fg9<8p*jRtw850~vR9wGtJQKc`W^M^={@6zUlL>v;q5DG>M@OmJ8&4* zO;lOjj^LOSqbpBl&PC`eC#voSQFU}r(7;~2hV+QHKVmes7)&YMR6o@idhF~^y#4&P z;IKB3ulLWF?$#+=MZNQGL2P%KFD*%8@}IrFJ0r&D>vr|_q?fGw>uVymcAP&rzmg_iR{fxMPr_!Mv#*87flXFcSjrz!?IH`n8 zSTrlRqe$r+2k2;}`$7Jq%4Bq+3T^%Jk6gr@XUMp2e&BHlPZugf$PKxgy_$cjOh3N% zrZM2d`rJ#E+7~6D22A_5{@OEC&9rk!NC^Dkdbk& z&h+`K6a}!MZutMP$+#c+h&f+NQH?V-O@n-(B!C(1q$1@xnrZd^FfSKD5{tXJnue?( zY*LyI{bl;vyzIT`gG$HjMjiBL#Lu4C5VAK2z%g514gf3kE9=!g!Nzu1CgO~w;z65l zk6)13S05BeNV~c*S!sXy3TJ8l>kIy8w!#UPH%?E|b-C z()xR(3rDYLdS5UvHtuw?-Q}045p;;M+}Odj<62pP4QinG)3o>}48U;USmRA@lfL6? zUp<1*{Hpd{5ry}RbwjMBy;>x=yq&$p*IlREv=A(*0L)=wq>dB5dDVsK`E?Sr-$o5h zbFUeAF;fw^{#z{S;2IV?2U7$!DK0z#n@>F?Dhu)~5X|q{OCEYDBdU(gRNPE_zV%rt zIP?Jw2a37bd-OBZ5^^^aZ5d=x=4R%=PtC0_%}a*M1O$i$mB9&fMgS#u0IXF?a?$OT zIUm=k+Eb(?ei2nK!^LgoRV(Fc6-odCK^CSS{gXvUGKPDZ zBD+BK4Jj$;9J6@9B;&6A=*LJct&}Dx=H1XrmzF47|HB&wlL@vr-s`|8a_NT{V zg=5hC@2jV&kX}qHx8aVo_i95!<)U)V6&HnVyN_y;Jx@9^713u`20q!>ZFMEtG7`9J?Lmal*U zIU!DNZkQHNI}@Igb&365-6W|fqn~=>z!;@84l`-A5H@f_)4UQQItMsdL*aZtMGphMBq-P=aR44c?XA4J_5@Vu8-S%u zqof@Pls(i`G+&Gk{U|CN$hvCzYDA*rmu@&+)EmNF`S+K zT<;P+>=(CKG)N#)x-UWeHp`z?l?qxREE*V6F_ z3rc!KU`@vkx&a!%Q0>U@)VF~Df#u={${T#hECY@OK8$Avv?tc-TM@a?B>ws>hD^_x}_fal}ed{-**N{;LF?>wiuDtLltFE@b|H zGFZ8@2>)C9y^5PMspbF5|C9QzhWCGdjQlrTKK=iogi0qx)4}|r zhivUGnCw|(^?mS#VhI`;t%q;#qf%kjU!g3qo91mZ?Ta*e-t?c1iI+2Ha2>q%K6`0z zVWY%i$`B!^Lqw=!%G1O~hUcxdnJdF$o(HRx9+`Vl#;f?kBIIr%z>2atR@!65B#E$o zyLj*^Q#Sb?bt9*K=#@?yCHbW~t%U*;nYgGMl{dac(e&6^m$3r zyHd;`z`Cnjw-xTcA_UdsTx)WbHxR;9NawQQnr5o;${7s01m*;ld{aN*L({y<%jL_ z(qZ^-Kwc#xmWMtYsMZ^(6W!@HQ2}FuOa&!pywGR+z)x9p6qHm?GTku-dH)F`TW)i~ zK1h2MMBH4eAO09|>6qAJIXievR$gTH_KZQ7^jo#Da?w-lO#GR+?T~M08J?Mx=rTg? zhwvkJW~aJ6pQPBokD;bn zzlTt-_+ZnIzO6D?x!lB;?`V6BWF;nO*_`~i_rWgXcsQc=e-X02u+FC%sn``^6OR7AXG%zyES3rtZN;C!-iTm!^kMg zId_3#euLMqRqt)HbbXINv*Hn@lj&qP_SD}?wuix0oE&p;t2*o~M4kKC>B^qy-z=Ia z0r{hs)^Gcjl(*Njv#qKY`)*{cBlG;(FwG)7u|lnQBDv&V!&u>W-@$6=@l`C!P+(fsGL!8}rr&-V73 zzCksj;jUVMbiWzJg)*YuX!vSFQn@xebFVdAVfDYnPYT_tH-=w6@K!>LfPq4O&+wnA zUmU%+Ejy0l1li~IF^?wKEg21cZ}2*J&!BU|rA3^t8&7&hkILCve7QJT;hTTi#n2l2d)MP5*Ee_VI zjkx_p&!(bHu%_-G)45|bYCpUf$POB4S3^o>nzxVmVFJ(o^0Xcn`Aw-Pkr&l7`MNuB zsoUTqXRbY8Dt2tKxff^U@b$$O?LU^}1Ba8tmDXC8AAZ^q{d-@Zch^^+^efp(piRf8 z&Ma-V7ki}ZPWx1!Es+|G8khfAj7ho(5@ZF2AF>V1$qwTv55{XdW!em>-uH&UtXbdY zOoaDSyEJMP3Q9tREfP3JQ>U~ZX(9mw&OsKE~ps|LcJJeGLD>TqeF(z?c4OUegrHa()&5abR&k^|U z@|snjDhCS~>FhsV%+AeCH6NTi_!c{ijJLyo4`+{hIrBST5q>Loh!=TK^IslD`Ffx2 zyU|RG_yzMQHIw^g_ostuY@td9#hio0#Z0fNjFyIiC60?m#&^XNwkCKtw&K9`V5J}f zOs!9197@D)H7nw|d2ZGIbaL=?uwQ1{14N9k>yv&#jfGEKmIQn9o$P466b%Je8exy+ zmGwPY^V)$4<)GtgYXs0oG58J9B2XI5DlhSK+?2$h0ReHW&D;-xwZ|yPe=(9ne~ayq z5Lf2JqTF7wqgbM0>3ms;Q%qYmm}Ai>8Ru~z zbDDL?EW6(++}siJ7o@)?oIfO_K*7>dOOOgWgalpD_ME<%ZLXxc7hM2Y22CHHCLHt; zPaf?K!5BV`9jY&H$tLajx;rrhAkBpOM-PF{**z1LztP zPEn19S6Z>tm?4t$^cPQ23_lQHf9D)zs1B)tBY~R>a`Pg_mn&7)gN21yrTJ7~`a{6T zBI_lgAQ#sM9g2jYL`N@7fNwLE==`1oLQU|CiZSvK;STLRaYaEkFb=mQz{kHTOaPVq z370}i>P8KNcb=TJY9Wfd$&m28Ge4Z8-fu}E5LwmrAj8ViF;m}2^%tupcjf_8VMRgW zD(bh7F3zVAZO>j(PMX8e53@kf{%u9vaG#E7*X~btK^{JlZR<+Nv=@ox5`lhLL>F>I zy#Y8fVb}I|rfz`tzYoG%V3)*kMX_U*uIhs(?J9hIKIJxCc7uOkyRod863ne~Roc3e z=+&2kqGN@9?Z|%-M^e2W%M%H?k8lr}NFOZU7~fSQDN`N({G|1^O)Jdn_)q*Mpu5C| z4_qBBr_qwZqSF#NuKsor+i|x=R(>^mpvyO#&HY%__M@CbkfmtfRLBvPUT8p}EeGiB(<%QNK}-aAG=cJ|d;pfUfTqw|a^;20yM3`n}rl0jPTm{JEoXXlGL zq5}s1IWS6@O5OpqKito$hlBdm?*(o`P-d=X2V#h-9)UT>ifYy^`Rqv+v`Bx=Dw1k{fIp`d42(1MHzv<4PKQ8k0@WchSnTxK^N{mY z8p3C)LdJ@mwhHzIB46=-2!OeAf-p1rI$7Lr3HlKgGp6#93ttyzG%f+p8VrLAXt#3` zF%h>U61zh1pR+HF-l$pwe&@&j-X_vybus)zHtdXRtBf4?s(Y5c|SRkJzc1)-vg5$m-IO#yWeR8wT2Ah zxN?r~SMaf6k{%Hbk%hesGI%^49Z#hzw_!s6L3|WAjRZTp7#V-cS=*hLUk$76f?APA zZOmh1j^LMK`VfH&|^K(p<|51W=_IUXs0+@x{e8N`Np=0RC+Ee_*`B5 zb48jUHvX`SIQV`9J7$8gFEV3Bj%jkWjy>ZmU5*Jtr+6)C4i)*GDk7l5Y81#azw`+l zo30SX*T@WD&8-&eTW{K2geh-{$9V7wY0(3Hd^|_{&G##O_Lk z>{B{UoAWqNbq+MtE?^6$i&p3~$99;u7B{^U`)Z=T#Fvm#%bxvC;Dc?Qt}v9`#;TN4 zL(zPj?tt}At$)eE^I5mI0t9&1W zfS}-jHPgAbY^d6GeSpl0i-GF9BPSWw7H zn3vX+9Z5wgtn7225WFif#3MIr3CL5Rqau)&o}bc345o0gD~^sA62K=Qmh0cVl+5n1 z9bb}sp0voR^egf8W?h?Ko8$Ic_Wa{^vQ1`7ft%Do%56Q<98#)o`Mi{z9cH=GAjKKt zQarI&URl|^QFEYa=-Mq?=|O9RTk^BveT6*)n3AsRG3?n+RxK3><^)w-`_#^~UZc&* zzp0>n=hEaLbAg}I%jZ%NGTxbraVnpj4(je<2U1&(rd98=o_6$vl@kzlzj8$l`e}C= z8LoEIxdc-U8EPwb6**c#e+iDnHchIPk^Upc_`snFjw}A%O=@l2heUKga&sg@eH`06 zZI1pz2K~oES~3bXrscZc^)@ssSpy0Xg5wUTm=DomNf8~HN$u<`&|YgK)VIVSCi0dz zb)QhJp_o_&&vLs-pa59Rp=0JGD1kT%;2W>)e1M}z_-PnE^-|@pYP%(dN1b)y)^juO z6|9;OQjPWCw^xUo(x#S{$9X-6kUppO&n>iCL9R1dE7K!M%$+z0q`FpWsE7T{6jS#S zX=drjWZxo0u2ArbNex$T!|EZ9A944VYJH4eITCE=WzoQc8QRfF$`%NN><)Po$I=}yo)~9AVJ<%>Zan(w2RExP$_MHna2*pFE0AR~3&)s@0#^+1W8hHGW zyCG-~UQ)Xj8qtT->|3INB*6wiJ+B1G zPJvu}Sv6uS+WJ?s1RO%HJFe%A4Wthz4irl!fB&g{%;C?kHG)*?H=FhWTWX;jHfxTb z-nV41nLguH8(ZBcvPKC+L~OYpDuY|edK5;|>$z#qE#2ZDcQckQp%w+|j+dQR)vw27 zp1Ez_B`uZQx=%}2&l+Jm!K{uM99G-&kw^%>hyIWm;qfbV0R>zrCyu1!Z~`v{KLj&CHy7^w(6Fv# z7@<~&0?y&uL}b+*U7m9dSkaK-E_4I2%G)sunINcc?W>nqO1(u za|WfyZaySwT|Z8OPZSSB^F`37y)7msnvRwa7_n5mMuC{v8(E_gopV-!CJr#LZJ+@4 zulj$8i&shzrq$O)So6paNG&AQh0qF5To(+yC-&OPEzLd0yX^m2R8mui;aVS?K;i&8 z6@MLj@J_U0!qMx+@_TgHWT>+|uXekJ7b-Jf4`yoc5I=!!eux~^w2IDKrE%HL<8_qi z5*&?8OZ4QXo(t2@a$Mz!~}SS+p`-EgFiq22MibN6Aijie& z7v4S%Zo49cfsL2q+g=z5gzvjBG_r%@4nC#09Ho?H)v1RS`;$k|ItT+m~?yXKY?YSnVk1t8orvgw2dl)Y3pMVejiO zW{OS-KAa_7fdKdn%Ccwe5d^-oidx~~<$ZQEg%I@SWROm&HV&2GS9depT7}SL_=3ZE zU}q$9$UjCVyX-{{=&nU#-wD))$}t1L)uRJMZ9c@pem+VNOe}`^QU#bu(6fWPYOBe2 zp_2V#K}OxW{r>vBLr}2};wP*UZOaHuRV|evl}18xKH;aOiAB|4(YDFDounVsAk*n3 zc$vR1D;#`her%f2Y0|vNVD12g`$mCkj9TEj1k*&Fji{JiPe9uc8uwoSxE6M0&R}UW z+_ewLCSnWYtg0o+H9=80z~5=16P6)U1Lm3k?yn#17&o=Nyq zZ~+zwrkP}ARp{7ll>q<(DQR5hjF(HJw;S-_BhuH@UqFD_gU*4g5oxYScS{&akCjC*FT^0dTyVLqtDl~(l{n{=<7 zXqt#!p=9|g_&WV#>ks;En|ncrFm`NjBF^FTR@dzC_?>Q8=qx=ZAhmakf-l-k4I)ID zF9&?bUfhHHW6EvHtv<(vMO*yBl#ts-4Du+Fz9>vU*<5NT?w+Ka})filZ-DAF{N*AUIvb z$2uj{O^<>C|IN#<^qj<}Hjw!@r{e<5(C7hc(XhWQ;;+r}qh~E55WzwPX{I5A0}3%} z1_r)6w8~G@4{(PKV)EW*TMb)P#{#e8xv#zzaCBd2T@j3xqxS9tVs*M+W*!6v3EMzs zV~2C)XZL1a?A$8Q>(=SNSL3PhZ;V zAPYyMBl1#&bOb;>0K(@jm=2-hvklkHb%T*xmc%pQ+)EmyrD-cWRkPy%==)`FNbw9C zT!O%wI|~~O8-N={i*4qp&`bjayadq;cOgQQgnds#l;&W75g zA5{TyT!in@ph?6?opgxsR$2MbF`h=9@bf9XL8+4D1Ths$fb^&zJ*8MttYe9SrSgeO zQcxMvbkbA!tjdq1phNl*jrH*D2w|7kiL)OhHZeI^$%1A#Js8VK4gM~d`Co!OZ-z8#t6S_apUUp=P9?%B7k25XmOK*U=Dg!^c@gPk^Mcvgb#XD4ec{`v;CC~ zTk#?)WtF#^w?e0cVp*hhstb-`vgR)y@5c6AvSRZ%TcYq+4{(R2=6>y=&&4R6ciC1DZ=ek{RxqKeWBNJzmU0}J$+XHgzbW$<2p zml*#Y%bQt2J2Y`J_Y8So{}xq#q0OJ0Q`1aN)%7%2zKeMGufdGWcHaT!)^ zW2K(_K{E8X@~|}Gga^9{6|4-binE&a080@@f#tLB=^Tf`3XaD=ih`NG@hbJjUy~Xe z`uXwYF~I}u6?8Gh7TTHG1aTYtGzbtH#8{HmHyZ5pDK|#MbU&!@v>;}A#V2}5ITazW zGeXpUejn+KiC)&;h2X2kAp*H(?hO`u+vrdn2C?tU2fqE9=fkS9Kam)jFYMNJ0&KHG zS+ml}{CDVeZaJFNm)F-Jh^Y2bwKt|R z%+-XUp!?Ke$E&pI4vyAWp1bKk#vu;#1CP4zz(apu;GWAinaccfh}2aaEAxIt@8C4z zY?*_OR>1HXG;%EM4|eR! z?`}MRO~{aRr|?hEhlJU)YbNdXONZC9TDo7U&kqYMO@~KTc5%63>^NPRR{C^eXmJgL zxQdhlPjYw9=H=~={{B}B>wdS>6Ifu6e(_LBtQ@B~kroLN6pVFsUu409mVH|!$bq)yriJ3ol6+WHis*%qqBThUHyZgT^+zEIuaT&dB zClj4x?r8bxh#AZzDbJ;j4Zoj!@uqgA62E=j{T-~PQaheTTl}B7p!$w;p>dbS(UuE6 z>81ulgqo}0Anb=kmnaa6@n0XnT(8mG3hTn2{h8~&k3ak$Z_F34!Qm*81lVW@##$C| zAuBTlX@&|ta+LAf-@N7yB@b}n+Hz}!uIi1}UX>?0heNa+O3*!JBOhd7COK6&ZOQM_ zK}2bs%*jzimL23%G^aKl=n+Y)N_J?NM_zJs+qg!HD_^}_(9q%Vzu_323 z+M>KGf4pbX4gpV0{EV@e(S}XF-u>FR%T#oq4eKfyNEU^ZCB&`b~eCCJyHD}RUy}Tz(@vMShwOIB#kSaXFuKNZDNuef*o$c zaAwpH01)i@tM%3Ot_ec+x|;VqQ1&n9XrtTh9YtD}rdwNXb6p*e)B4}jUgs5EGC?dB zGSx+^VXlzDBq~z6Txw@A^_PQW&Bl(Ij`M^YZr`gg9GVGYVQa+NpfWVDfp4`F*8w!Q zHuV00dSt?&-p3QmvV-_g&+%m8^=iid0xbbHaj-4dG0S^twW+Z^E2T>&K^gw#7*Bk6 z?5F!~!Iv4EX<6UD&hsJu4`h+a1g)TL3kPL+ZtUF8naINh@h+6)A@Q?T&zua_ug{*& zN)b>#F8jg(=i7?6i(Q}^`wiqr&SLaVLQCz!)$&*N)Zi3l4)ENZ8K&21)BN&mYP<2y za8*amW*#b-L&<2)e^bV20_*aNJi7sk62T|IIl3PBOn`WW)iA0^%tmKP%VTT*@GFV(7A7?Al2<5`>lq#&1&kw}>0I2aT&2w7o#3mH78x$KPsoGd1IYOsXp+em6_ha?sP$d=d}%Xg(6 zf6v{8pJQ60@?Yzc@t$|yN{DVn&`30y1n)5Bo>kl(j3{x>{ccknd~RuiF~+)wXL1BCM`fgWqg=EMwXe>z}9pRJNada1}TC z)#$ohXI)oe8Am~85SCj#y^!6y$)X6=7lXRo75XEP9esiXv{d9YiiOo5I22L|fyQyW#Al=ng0qny zQA3gmI0ic_S}K0uvu}Z*ATW5-$x2Gpjs@%KtZ{PNTmiUYHUYDEz z{U_#(%TjvYNA?~yMq-Nffx=mZ&uK5n;G@@8Bx^-#BL?5jnu>{pP9hoJPjfKyW%j zfLJZfoo>q22lL3MWIlWDG>-Sp5E&@T+&--)$jOR(=Ow7VoAQX2t`q=sGc0{34cu18 zGo*8MRUfFELG>EeKOhQ63YrFSr|G5FetZ0NHH#KfYhmpi*uK~q?B@T_yjMo_4%XZL zPRqG6q{4taF_BzmPz5j;jj|eGyW@M!jav0qCt<)>ki9E{AI{B90k2)X)cz*secVDM zc##$vF{B0f(DMnneF)2Ix4~g3x^_C>QR{71U6CrOz;yNor#KFtcJujF3dACt);ZQ> ztJU5OI{J%OJYSV@O;l?ufxh`z+X*<|jbC$|@P`uXq}B@3YIrt#;ipKcEdrHDJQ1{^ z%#k|asw2&wh#JnT&cn+@wJ~?3`^0Xw2KSeH@1|4k-t6!x<#XqjB4>tx52FFkNdT?$ zBhxm)uh7bL(+sY-EX+w0=BZBDRrP8_8*>{AEz^4e5$mRV+u!WCN{0irOsMn_(;J-N z>ZS^bfMhEL(nvEZ-Fesm{lr8w{2g3H7*@~LK#+hdsw6gC3#`bHyn8Hi^{GL-xQN+K+Xe6B^ znyc^vRqJ1OvWM8eL@EStgx@rh@+S09Aq`6!v4SR(F4D`@;<&dh%%>(ZngX0_+lnui zCj8}Z3e$L;5)Ny(B`BGcQ;lA@%O<{qQrEf6^+W%aETEO!<_N2!X7b2zcU^PT2zXRA z9aqA0XDlTCDtkok_l5sX^4ic~Vf5jr)2X@pl3#Ac>?n^fb%8x;W7zauI@`q}P&?2s z(h2A7j$wUt0thW>#|=IqnCbTjPwpy^Dyfbg{TXQ5a!QMu zRF{X#%8&UU1q3m{7cPQ+>l;2z0c6?EoqEr}k9!kVe0%jmfibUV6Z?FH(0~$xhz$ov z0Pb9bciPBaWJ=@nrcOYCgem|<+B@`{>vs9Vp9W?TKB35}ZiaF-H1vo0c@7`+u%0l= zEmXOt5)zsl3Q`FS(O*HKfZGCi$J45{=xKSj))ou9 z`XdWUeg5;vn#z<1>3l-s_61pdH3BuZxCO3G zA;}Tx7^)tJzi~*U2Q!dyETL&BTNqx0PE_?R@!fn_O6kq8c`BB;I! z2D!2}BE_+mA>6a|N1}6LuMBD7}iw?!!D#$lT6 z3cNS1IKChJ4u%AmqqzVO-9L5irmBGRdwB5k1c|quK-my`MAU?3xnmYztblWOWZzZ5 zk{9+;r_MvBHt9Rd(eaayeT>xH-c1XkQ4le`bx48YN<6bY667Mf@+P*dKEYjQCnU6> zCi3qHf4;Zww88A+azH&u(LdVxCx(P0$^dr2@45X&0)zECE?(+7v?l=HsYf?N!`1CDifv!{cTTDcI`J);g zn%KwmcIz3Mv1mP^of`!bykA1}FNVgugTC~?mA*Ugtz`9ePc4&-(PI@wqxfz@s}DnW zs6J*DTt-_Oi4T}&C8Nx+*pWsq)l6qJGtjBDU)ksi<*Vul7iEETl-_6h_8VGKeX@*( zkfl;Tc8N0AuugIdm28E0h>oV=>BZQYwvXM+34&l$Y` z$rC)F+&dJJfVVJ}g!w3lj`*D(YG$*a`BAV^YWY-%p+48ADO~c?6Q7m8HWcETguG&Q5e0#2VIAu}xoz-TgF7ER13v55Fn;R$ zH^c~786*9$%%4B9Yn{!<_#R3!2V}Bu=J~g>)qaD58#be(2b3P408gqRuO)_nWcv9K zHM}O0WhzlBFk8C1EKjBq>c%kh>@`6 zo)=AdZyq!>@RMJI#=5+T@<{*699l?&P|aWMt3WHY%b6;CcFq(2VN{pBR~!O$bw@7W zVtHt*2hpkMDnx?T!+Q_L9IU7r$Ak7eFC7q^#CE)FBAICAL0UpomAPndg>cwVtF`H^ z&jEgf27=lGqzr~sdo=(gU15%X&XS31OM zzV)L2XgCE}-z`lWFT(&qx1|xlr^(QP@p!pG1ygrgP%cVedg=Z7bc?f5_jsMKi1Y;pgISbaMg3M$w$c1NnE!GPJ1d!$tEOO znbNUs+Y{gylYHmj054ncwKyP|rE09?33u!&ARQFbf)K{NR)p8&@OmqJ_I!m3zV;M( zo9(hhgL=G}i91LR5mqFJ`QKN$`xL!8<0)x0g3>D=*-L?#1Lu!}QZs%%usQXYgBWi& zIF_-^-)`Vt^AEFLC6GCq;^}bJ4WxC@W;OwU6VgB!UTpKCsQea zPCEMft14;S4r@35enZe+j;kV@Jqcauy;3IZdUn=0Lpf9fas#6F;`Pqqxb3+4cvKw9daae3euO7@+vd;lm4Le2i z%fy5tOQ*s{#lNb4%=#b+?~6XXIRoIV93zLVvAJeXYi-djIWsQ^AQM=zipDR5+;P7t z<(dkcd=Lq8#V9EQDrVz8UPr2;6cuZw7;DompP^%eiMTDaA1+h5pKpv3>x1X3^j2EM zUx0xmpY1ilv)v(OYh|US4~L4WqnF$V4$-E*-v1=>UgysmU0mwQSEM}J45@CCsxOnl z1AFnvRp@IMWkK(5ev@n!lEtMs`pj+b&#Tjd6=zIu~NZ?fFl2|GV9;tgNlW23XD(T|hUL zRBoIpwQQDsr9Q98f&SUy!*Ws2GEfaw?q!j!p30k=oo;^e_hnaDb~g>fvesE^1Iw=| zg(VmrSuLEFcW&Bz)r4g;Q{%=s3z=y3-sd3-Tzu=E%w$vsf3b%_Slig(uE`6(^$bZh zZ{=+X%aKj_8mQa``AN*3-O|r}H1D@_x6}nZxdNe)kd$f#%Z|mjORO&?`4KIP0S8`$ zIvqanK8Ey!cRtS-1I`mX(myapiGP});5D*d_Y3*Yw6BpoA)PrLSY1+2M=cs1Jp1y{A2TJ`Nwvu98fLS0;L6f^&wq0vsHrA*mu4YyLb zIz+CYowu%heofXg+^Gnd8W#Dz_P&%UiTl6fO?k}~U8d)RUk;SHAVSSva|xl8eh=XT zo40hKMnXZ6L3Giya}pxJPL(r}zn^GfyHu1S99icbDRtiNw_?jzfGVo4rEKm6pP6`n z!=f>bL^M+$`M}r(OvKPQlU>~3*yr*tY}^(Ift`{ zkdV4@-&taL(&soX6&W_0LZgSrZ=5=s!W59?X0J?1m$lf+ho!35#g+2bt-SYK8(9k1 zC{Ra?&72w&Di&!C3R1EXx&})B?o82f91!Pw@oohpK<_5zG~L7sf!kso2%6;Cf#*h4Fu{`+ zyAa0i9_|W8asn!i&JF*0LNEQJ#tM!@A_V7HzX7oS7QII}e%HLad9JBgt>}Rto_#ke zaL5{I{c9CHFUa2!XiW_lbaJU0m9JZR<7NA2_RzFs46nmd(AX>< z=PM(b4wJ}NHLz8rk=3zS*Z5rIZfR&EtQrJ40S|+ely9cUiR_Ntc05Aj#Wwipv%?y+ zQOuk#MAr=RZ@s#ss)GOWF)KR4-lB7O{CtjRov*AqXfIv&)IePvJV>Zroo@Ae`o7w& z1~Y+fUs?J+V!-gJc6y$~etF$e*cM$XmBJPiPl&JX2%||Zr3EgY3YJ?;3X){$PAae; zTY+*e&xuRKx8r{GXFHi*)^m;oE%6&XTHfs~yqic%ZnCiBzs@${#{=)oL_;rHD<*PB zTwTWn>G-|RWWfQqo~A-W+JCod>fVe+90YIvmb<|-dktr|6H`Dwlh~fgiV2?U#;`=P zcA>Zj#5tS^7|#GVgN#}14*IVG`XhI19-COfO@r;9XK0DFA9@;)gSbx47W6g{fRnge z9*lpzpl=UjnLID0Opqz-19F@kC)!YmaRH`RmR-F!sjt(kwf^|G?YE`Qjj zu+OtOelGT}E@|nje=y+5(hlz<#^rn)P z=X#(y^bn{_T-FoEy4%0NYS8gu(i|v zVDvJ*B5gt~E+X$(u)3QYTh$x6eI-*W9h9Wq$N-=f9NQ?*wn;MbX4?7yT%d(~r{NMC z^}}kylBE>(s9v(xAah4me4f>L`C#0B=Hj)m{hLTnD$a*=cmc|Ezf~2KJ4i9&NA~w?81|puYNnYhxYdY2K;1G&&(WA zCa2U1+N7o3lghH2$l-DFt2|7*I;+7?rbhz%`J!4^P97 z_Ava)x3s1gBYs9q{5?4^jU|0lTMH&qB5?up^qCkR2V8*40e*^=xUG*DCnJsNl+(k= ztE$hF1wVRpmH}#~mq`wINN*l&TOLi}Ovr?TgJ=k$lOF`0VtW(5g@Te+TFOwtLWN5O z5XU6K6EZpSv5gP#T{u+@@PFOU_y}oJ11t6W7}a__`Ls*2Yvv<;QlMcZ_Z0BlCHRKpPEc;`t~sDT%`|C zF~eoN!m|<2pY>>0lr|9skd`+m9Bhsb52v*QDZ9*5Ie7%0%=de94~=1EGh7=Hxd4IqN_~I`5!&Mhw|FB*ZAz=*z4EcP3fiIEhV4yhzt@#71ANwpY)QH~kMyhq zHlpn5IgsU+(75HT{#jxHDRxA>JDIHZu0fSi46x&h@U;q_H=Cy^5-295_Y@0if4OVO)<}#n0z_6nHwW z;+i99Btf-0BBTeHB{0+{{6Hc7CUhtxh0SH~QvJ$mt@0R}M^`7VN``u3S0((b1{>Y- zxhz~8J~={pKUc`LFzqEFuzZb9F!Qyh)FHl>a*eJ+pnEDhRZdjAr{+D~=j&$dt?X~t zzk{LpbE|XVcq~An81C@xx%S+cy+J(PJ@7UvMWL;d;S=K;-OFWahtE6R>@gO7dE1P9 zgs4zJT$PssT;)h@isoESv>Thnx!kjsRBC3oY7)6S4T=uuZt${eG2!l0peh*KZ^n$Xc=1a z>B;n4t>MT}{Xgu!M2u5uAR!ijZ=X8GC1r}p!cR|)%ebVMU(A?bzGn7I*LV_JC zVy6nm{Hx*2eU_c3jOA`Pm*Efo?aGx#CFZ#J?RRt#iVq z>nZd5Wc9j?6zAa&4^4JrxYq(e3_Tu)Wp(VCqDD+1phZ>a_k#tqVkP7}DRsT$5DuH2 zF>W;IzXD^CJmF_lvUnKn6=rsreiA#wo+uxmCv=BSTN!8EqrmpFaH| z{+hiY|N-O-3!KgK^XIh3H~fS_HV1_4uaWSE|j zMoQqUNleT8wR6|x$>^zzW0`kRO9@aQmD_9tCKvn)FdUL$bAfv5u;Ct^zq7^5Lw{`5 z7z*UmLyRRHByWx=Ov6#o!2r^2R{~a1LHR}g*Hh9mKCY=srErRr-^D1hCsMkK->6Q0 zZqEpp017{r_zB8AXuJqz;~k)aw;xGk13}sEeJq(Pl3500eQv@Np`2ZTq{O` zxWXJ$>MfWA(~DV{#ZNGm*)`bakhnps{E}P)q@C{rvvT%yUvxVVY37}Lmme=6K0*W& zqqD>OVc1U1!=rMOEDIK|68-s&l(d7NNAPe9A0w!2SCpvYS*p_-nAL;)NE+_}t3Jm5MKB5w0{w?OdX#zm^ZiPTJIw*LCJK!Q`kdTlrv}Cgxp8J%n zTzEXlXG*cBwJ9P}5)OXMd@HEfDqs;_SQCdtN#~U=u!|-l$NdX8RtvR2zn7tz_h_Z~ zR*&PcTh?96t46Msj(!h_kicH(`~q?T4NV%O$wdv|iB($*)8{U#fW6X{Sh^##DYg!0 z4=wB@r}iDs3!wNidfL^@yvT7iVv+FJI=A;!Mw58Z8$=sbh+{aR9F-GMKg1CMB^~`g z2=@6b&1~=6EUzB0f+m2V;1`ZSyUeq;yY`k zB?>#Lo6}8-)0wI!k_p(Y0@Ed;pR-^hc~#5rCYEcn=M5i8H{(Pbl5aSItw=eEV@=ta zFJlPu1p*3v%KT6qeQEMx>cu#c_76OkBZatO>bv)n2o$_vZ9)t+KCw+9UQj2BIk01Z zXW>OQl)t5hd=LloCQWE8+x#!4-YP7vrfJ(waQEOE+}+*X-QC@SySux)dyq_!;O+y2 zV8LM^Kyc5$?&sTh|1I|BV0CwOmt1vL<5iCKs?MUp#~#T79lb_w9TY=RA^c%>HRMNL zff@3)W(_iA^C%MxvCjQ=Fghk#oLvK{v>$#d$}uG({%1d!3s~h)n+vA=TwT+kLp3LY zk>^MC!LTvbGf@&<1SkJz^b!&$Va)g6C!q(_H=j?`e-QqShxy|ahJVjE426_pA_Kj2 zN54FBx&?I?8osplOQR44h9&7!VO7`wQ*%|DM3|Cp5KpLH%M|fFTn|$c0y+DlzPN7z zuz(}hfg}n2{sDxjH91}i<#}^CE0RNJV4mCB_bI|s{_}~_UiFN2Hn5|01PzpE4_Ye1 z?dK~sFf{#%{%d%OzIeR7!^fpOgRmHZJ29mEGJa}qsC_25J|?BwjUzUFCwOHeyS#2o zY0rSwg%i$m!@<78OuN>h^5Mo05M6Yua@mNTa(=zo(1R*qGoNV5rCy)JW<@P_(d)<-@I*1Xv zkk+VjW`41Wn$?6i?B>x>O>1pwh({u#np2?QHF9E%UOQ&Z;ucf+nWz$`KVw*iyr{+n zVsT}3r_`Tofyv?i5YhaW{vdScyb-Ur)@wx~yy6;du7oNtEBdfH_nx`;3UV4gyUCd% z{6X`4X2+7w9ZGVGmqxWderUb=;htTIK=OK;FrHFpL4LO-w`LAQ!T9$V3wPBJJwt^$ zy%JnMmu7^HX>(9!93#It*K(=OS&4I2$@u9B*osI1NpI{|9iA^_gt>(L~VB5c%%w*&i0D$0vxZfTPW#PEr| znuQLX3t3U~Xoml7jL4Pv{HMtDKv7egkT`)+H>pL8SWFMuxmpg_`)|9~hmFrgeFqzi z@X2UP@~o++yI@0?De#YY2c^^bgm4b1!;%s>8C$#?PkBoB_Mhd^i{EAznuIZBklbfvU5|SVBs^gT!LWogUEV^Y5s(>=W^zx(I+w(J0kJtpgP!W(e2T>`JUo$qG6tukvhw z-zdOU%6W3l7i;&qm6|*|=R^Kiwe4Jz>YHPKi*C3d@{{zblv@NtWn@pjUC8KY(@V{d z!&og@iZe&3#)|GP*OsoniPFYYkdOl9)E{er*K##r^#hb{ocFN7kAV;Qz}}Oi-a#-t zN|@FEI|vJPe|NO17w*7yqK=_Uza!gTTYz12E6|`#$?lbFN6ZBEJ9{gRz@UXe>YtEM zqO_*Wu3m5EYy5+j?B**Mujwl)GRAUw=7Df1#3`BBB?XW}mRY|4o+y3xBRt$7mZ(NH ziY2KcO`gp6VUN;SBhU1o>#2i5tTOShLMv>|Ip&VkfCs#@DU@M*wou4j2j0xJtl$aW zmiWJg-}IIee|`CgZz_aJTgmKFmeahy*1j0RVMec=cv%P-es{?1J8XsxFAry7v8hD) z&;o`Z@{n3<0eYjv>FxsElqs+jg7h*4=zdxi<6$U}05wTE(c6-Qn$j>Bg32z@!YJ@JCKfd#?Gl6ec za`;xLRG%bOPhUmmT)kAdcJcwL&qBxFos)N`Yd3p?r3Hs$pw`xq)9KQp821dGOYU8%1@b2F-5_;`Bh zl@e`7e5Y%tTM!#L6@~<$UQ*~tpaxrqx9OZ+9KPo6wP(JtXsq|C=bwED>)_b33DB$4 zoA3gnn6d+dc9N=0*GvZ(0V_BMTx+`eW)rc8D_FPyJvPVoem20miRjLC+Dn+X>0l{U z>Nq#CoWslx23y`NGCb5FPj`kA)q=56N)HOfsit?Dz{$-s*N&@Fhp6phZg~S;o6_k* z;upG1FqRa|7z$f+>k@U)cyA){?IsFlNx;XcSzPOZM~gU$c*xIPga5>(o}#5^D9M_M z&z*R=MSc8)R+ICRDcuq7hU1NwE_E-pce)n|DQxH=uG8{2_dxh7Q}=7&Xloh?CfsP! zTRjIj2)cLQ;8rcJLTp(RI)OV8n)Nkk(R4oY{J0=K_#S)f%5SBGgMCbtqf9gkvmvsTc$+e)ba zcDYf?fB$HMQp!luxN-w@y{uV$gg3ctyub@=R-3Eb-Hlj6L_l*6?%YJ|Q!%dJy!pIl zl1E6$zaL_vTa#;2XRZ`+>#RunEaWx=q1QSPr=giz1`Xl(FhdPl@>=rJMb~f6&;f>A zj42|4mzFH}IzC+iI2>Ezh3Tgj=^*36CX_DvdJSG;HPf$li#4MB0Xk;iWvV%gH<=_G zCA)8LiE9GXwrj;?*OBu@9}%mHhaiL!brJ2aMd(mPAgm9RU_^yDxvQxoS#%*w(`x7m z{}o;(zHNj9mSt^G=?O2=8Y=+|O;Z^T|GeO*!<>+tgqon|uQZ%_Xw8Pq!gr{b>HLGh z!YvEanRy|A8*>qzC^b^mcxJIQkE<|G{OxpwmBtv!vU@+L$wJKv62^2397payqv#t2n^k0jH}9Ng%BV+3#aFuuD<`HpOyG#^;q(Cmh#e z|CDDLx{n+|v-#W|GM(G48b$tS+uK{+`@{Xe1nR1PA>&;sij;W$qUY|Q(Qcp+Dh?=? zbMZg+zJPClO%AiE^^0gDDN`e*K+2rOaO3F}WrVSMQUSDSY>>##B|w@sqmUzkdCquF>6c zGq)Q=@kYO5e)_xFA$M*d@^k6SNfSxS>xXwK2@?*-+ed-BK6SdgBWOrNRV6XQ_lV$i zN3JFXx;rJ5mP&01d4nFFLSHOjB{(gnId<`CJJLN(_n!~xF{GZ|g}x&Eb19hue2R#d zD}`gNtut)AvBe!9%kn-Ve>PiEjAG1&=0kzDigcoguqKIyFm7g!(!f&}svDr?t97R7 z(Vw^jrQBV|lrGkhNrb!=tCx`i;Zv%P53sBE;KxS zOQM`)YSPW)nm30;#R#bVMiBCf8K3$Jw9GS1a$!sX7vT;gJY-{DnXv;?RaHf!di;$<}%CNKX?e&HuA$$WWrZpZN{bn6MD(=UOQmlADxZT zobZzP+fg%QB>=p>1qT#^P27E&Jw}a=iW2GIpI=nMiNf=LE)$U<)$C;d^vn&!kl9j$ z8-gm~9lXY^5b#aD<4|LDdolkRBatgu-Xy5W_^v5wJbwwv5pu82{a%k<7zjIH_^SIbu zJ^5yvsMGz)w@M{VQFu?NFjKEF1)~ozf>M-HhncvGehc~*swI>vTWRcmqtA?10u(!e z?V=y6Ib@a#e4NbDpw`?*mpmv)(quVST{r@Fz^J9oe@lOV^|nR00D5tazmux*Y80L; z7Iu?MR*SCKsT~EN2aofJ4nfEKAl zizC|2;IWiYddt>UEJsDv@?QaNZg8T1^>z;z_~l4FGACWpNSOJPxe}8$i8mH{Uk^@t zPiW}VLsE6>tqwa``boyQCt9u18h2~PJCD<4SpJAcYZogE+@Kt)*xf&Evn`E=FDH^a zn*D)asShV~Q)h^Wh)fnbGsUVYXKEeh9|cxcbkd?|jENRrdsi#%N z9VT^vvtLVGs{!T<9?07nLdA>Plxg1e96As7;6~zy;#YaYpq2qe<{B)uf)YnSsi(uz zpDA))>;ziCPmtf&Wp*#*CiU}83;BmpL-*AUf0N&WT>lXK@}~PB-TX0t=OR|3TJ)tR zh_(N*9K;)?ap0j_|Eb0qlVZcYzGp%(67c_#VsiLxf{~rz7>V)siZYLU&e=Ve}cJ&Y^)CYlBS>Y4^DJ)0dd8UBNzMcCH4-F@H>yorDnHqaUXMWO}AVUnW|&U(|Jqq z%~V56e?6&Om?HgLl=HXJS70~D@!@i>tmpK(@M5O3pj5kMD3`enU;<7UYam^xrQZ`m zO_=(WYCeDZVtkO^WyA+T9RJEv^P!h>`9y5u)|@hnJ`l&~y8~##4YiS?t z(}-hG$+wz2vfw4yhmIWo;DOG6VKoo$w>6?$0560vQ!=Ee@poN84-$zEZpC2~Il#G0 zg*9n)C=9w5S)}LUOfpQ=+CDq6AS>ijSqs2wqd_!JP+kP!t(fwWAY#!a0>qf%Ha&l9e3=DT#cIh+ z$$VK&QK;W_M9J_U%?u=gO0rh$UGIMs%?YwZcPfFt;5@!)xGI)} zxCr0n4#Ka7Mn`oqrL1R>rUzu_pc`z=-@A+htgfYCdqOFVkYL%_z_pc$U`$Dk1xJo8Vm#rZ|SdQrfGCf z8I^i?dTHs3##omrrE#* zue!v+GG?Bgb6r_rTblxJNBp%w3ujgff zHrkNdf&A)F4MRhCcf^Yxt}m1P6d+I4gur?1O2XTR2hP4ZUJ`Mk%@S}sOnnlPM zJl2z4czQXko?oACnvJQOimTp#PTT-qRhV{2L_E^h7+lFH29;3B9YIT z0;5GKmJ>BYNT%5xr+3Jl6!_+P(?+2c&n(Pm`cak?%O96V^e;!A1?IwKp@K1G93z$B zflN^}td{WEFZjHRdWb%i+VpRH5iJ4Hy2@Jrd)ZD@>*vE9(|6YppJCyW2f`^Yw=IX$ zI#=HTUvssB}rA=DoF;$Mm&5*XX8+=M2paKA9GPe=N`Y%i2Za5k$#rL0&(t|a?Lb(PQ+!cWW3lRnygb+JBJI`Eu zeX~Pe!U-Ux3XZy!e|))c(s7FnfQPztd9@5&q3+>%Fl#?*r1RZntdb9*syGb8Ux(1IwvccLFb5V4zEC3g5v4`ljoz^5y@j`6*wCl+aLBglS;VKI?9);0q)phW1Yc@T*zY7pc~;J%OsLVx2d%Hcdtsje zwO&opcf0T%GP7<@`@~~KycB~kV<+^Q)#YPj8O86h_kPA~Mq(cgQ>yn*n4f}Q=f%kv zCX1}L87g}r*lv6@%bMCiGDmz;j%sBdEO^3I#Y<+yx)4vh{87M#AG1h+f~%gP{32YV zWXWyxc)?!?9KnM6)*06da{DAD{bX5u*ifh_!&Q zWP8}4qfBUQDD0m3dZ;S@U{o?!Cto3qY~$OkPycUxr!e5@P%N9X7~?D>MYQ!b@mGGnLCYF%=0-Yyc=^@O;fH1uku0BAH*TIS zw#mqCs-Rh|t*S=8x@Q>RE{aEQCraun8>Wap!nnkWnj;|7QSiR}8>t1=*4*+t8W1V# zt9*caJuB zoVHitj=R`T0hbx&0;wBbG{`U0S>pZEhe7#zISZJ(*eRQmuV)x4VQAZRCG~E z84_yvPK)kWwUeMzjQ)IX40dycVKt@F5iSP0au(Cz>hoh|3{frK5;v<18RT* zmRH01y;t4te!W!HO(LSDnzUH{XH6)siE0A}-B|~_MkQwL9rluE1+yGVm(2GS_3i4Q zKINB}TC!BAQ(nT#sqfHVg}0+XHhskcQc~bRcCG={`wck`$-yT5u1&YyFGvO-f>;xg zm!gM`Z_>;=fBwj7peYs>^cozx)uv(Tk0@z+e@q$JSbY6qE6Ojvb?*yg<3v~Je7wFc zEB^xH=Q9c>dPrlP)d4wDRyaQclK8ZC|CRbU)Q+GAysG`1odG8z6k2~uch?^`e_o1Z zE!kZcArCvfssgt?ghTsJTU{d=uD4w!saS1p%538v%&i|;180AKVpFxx6o{Jrx_gN$ z!~NijKXd*ri!+*fiZIq9$_OyCh8Vr?1tAGBqJBqt$l#=1Xoa9IrT(IC53$ZwXxA5> z9cQ-TWg2UCCqtv4-A}h<_*3$YoK97j z!(ab$&Mz;?@YO@DngzKRe!q+vu1ZRO2W)2 z^I$Wm?8BjQ5vXYs|J~ujlng~SN{KaH=@=6rlury1)O#YPrl4)3<1icVrj=N=oTqVr z8X=UFudfqXSXNuHIS@vbF_n+_s3D0eZl>&OqDqV9`{e=Xthz$@+ASRr2Xs+s)TEuN zx@7z1p`BpInCEAb40ARb(DW$O9WyyQhcy@o3ggCj42K~{QC^Rn%_ z;k8_3G90i+x*n5gG@SOjm!?Rn{{r)~vxh0f689nH&0;$NAepcI7JJx-s}-v$7fPd& z7S5weCQ+W!5R!-b`5IhO9k1?2qD5%`6r5*We`t3K@_ZASNbmM??ZH4^Sm9NPa@Kj>4zoF_i-?yHv}4^%_TMQ9Q&=$%D(Vt!{T8tQ@3cy*C?ZpRyoyB7~F4{KR;g{jocSZ%-%4WSz0jr)$8vwPVfGq8900 z-tt5QT105`Zrqs`{+lat`Rw1SbTqvhL;ccely*u&T}nH$5-1@?-DaaU3s}IX?{O%8 z-n2@;HBgz;^dYv@n0{oa{b@GbnSon^YlXe`47X24N?Iroa0uJ|ZnTwUu`{1jFLIbw zVftEkIr`^dmU37fK1|FEuD&?W;)_%@w4E35>=DWl$jxdFe5nH6ycGP;2v<;JK!rm1 zm#)U_`7@d!4vHc-;1~;?voBbU=Pp@4tG+$WKj&${>nAB%}ynV@#$!K7kRLS~rA(z|xYSaTRR1?1;yNwm zYX&ap+ovLo$2(z-n=m>RT^~dkr~o}Wo7=$uTUVsq}e@Rk3_fPbp-E#D4Xwp5D!uz*s6Yp0<^Ldv-u@vV^9iSE3scKip5bQP zA*?hKa4_A3?e?b;gEw_0+3*{in)ZwQ#ljqvrJLpb>1XyIXl^yKBv^+uWA%7DEGSk{ z9lK>3Ih9MOhCM|l@vh(;g!ZF!)4T{b?dX?Q{&9elxd4~ z-4cGhINZe>s9_=@@4X=}8Y{~?S3$@Atef5qeOJTA-3s9*vL6K6@D~)-(Z4prR-(Z{ zZHqN+Q}=Zu@=J1Kw~^j1Ry>;)$9%3<wy=GrV>zECkL`C3G@!5fEob7f>lt!LkUi#l6dr#G}TMk}>9S;tR7Q0xk zzvs`N-6>{^5(uCt)a326iGIe&#K)Vu6};dgA&+6PwJ4hOno6%Sux72b+uZO)iW9#u_Sa1+tdYp=Y}#fxCfu7U&s<-zHZUBqsL`-GG}&+{Us%ndzT4sh;bfwbF8RyQ6v% z;L#Dt22v8vmbYy=re&2CIY}*cJul}3M~I9!(0mWzv`wZVH$pqW1=W^PbnWA}Utsvd zNa`ZwE9&z_+YICpA@(R&SFDxblpb9$E#p#O$ zJJ_HI2FoskI^6TY5Pr5-m<91qY2*Sxyo3kJ2ju(5Uu>_#3Fk@$|7psvzF*P zipJ4;rl5Min7=U%Fq9~~+-XSp3}W9N_Y!iLa(M(xvre0~(vq>=OarY%{IO_*P6sEr?h9#47K#zso>(_ zSp*$WtZI_!%q){;i4tena|08699NCFc;)(Cpns|Q=A%n3{#>+oF_|Q~&ZE{{B)qkF zz-gw>mQ+|;Rh_tgTdUib3qX2?!|F?8vc~k2CEDqwm}1?{%m33HXyRd+Sux&0#76b7HHaQ_Cw0#d+~oL7>BF+H5^4{1B`IZ{H2X}DR8noJOKSPR#Xo}=6e7C6NCQUUB~@496Qk)v5M~H+OUq9j*vKbNG}KN% z=Jku0E?cWLn?zDjc@O&9ppedky(0w-QPOcN+MoHlbMbs>&}l35Hpg zH5c-ank`t}gr!;8)|zjbL{>CO76fXQj!tG!_Z+l+{LPSAmmO(%8{e1aFP<-4Sq6@X zN_sqo*ZOxn03wHYJ=qDq&~^z$>H2534=dy4N02hs+$lupm;}3K%i4MZ{hC4iZTx$? zd^E8f7x1)KX$jnLC`PxQzJ^i+fqIWxT?#mPN@#oG45-{Ljc1sS6e`miCHb&~G41oc zCN!#+uy5!ZhX{$x8XCJEC67bCTOP0yLlyAf#V3>d1#;i%lk`!0=z=6?Mk~QJ4U9Mm zbEH89f>t0iE49qA8DZrw`O+PnM@QPKi!4d4uj${b=L|68Xi|!l99PbCY)7ck$DS*er2PcnmmWK97Jx_qx_uD>tRHPFcNbl&6C4kyQ~nMv_p! zQxEGZ!~i6R29|KmZe%k%yV8df$G&k9FPnSCCC@*{u6gX1U7&^!$z+#TUT>$P%J2*x z_lo)xUe@=>;(2fF+0U~W9i~&CeqGt{*vPNnL?O!>cR6vr3^I?ev!cWh$@9FxzFs!; z{d>v(a-ZNXnhr_`>9gO{?^v=30;WO$fv4n_ocm)0bIRNJF|JYz;K|`^-5eYpWF&dW z$_j2(f+G*q$h%dhC2}E$OcH33ogJq5xXWg@ocsEoVGhmzkkW%c!#ld(`HbS{Et}~X zFVY(5jGW_%{}o4E=^1i=4G-_dznaquVxa_BLXgqy({w7CWmwp-&mWIRdiiv_&n1C8 z1=;w_H^zVf>mOY5bj?wRrOlJaTudN8* z7&Ef#p=4Hbn2hb0>u3=;>gcLW+ORUG9FKmIk_MyS-Kdb``yEg%V{*{usnl3&!^X2L z=cLY)3QOvSVj?inD|imnj4lVK<2WT%w4*1pV9b5*A@=pNg`wqu^EO?p{^~uZ!y<={ z{TruGBd0Pjn57k?5mA*qe}d1ZDf&;Wx1chTnMF~~DNcTFbY_d*z|-n?-oBvQ{+E)j zQw%*}%^&Lg3PoM2loFZka!WRO0!WuFbPSw2;d|nlF#fC+;T4yfm_4kG@viaa0|{n0 zgpDv9Bv2$ABo=Sk8v`sO{)gh(FloX?eHykcpm9WE7v=}jzg~spu!d(iv+(ftq&6%^ zaWuWDLxQ6513UTb^_$mw&h@OLs+a#R@L2L2UFgp3*)c}^66-XXU>vzFMxAePKCe1T z{yKtM;>V(mv!q*fj|axQ*!dG`bXf==_f}AzJqZ35WVv7=48Lt3=b%LHGLNC;g9E)SQmQ+VtPI2v+XK#CzT8I5Om%^ zjJOW?o!?#M;>VI;tuVG=Y@?>Ukn+*`^jaho9n+<8IY7jt{-k7%*q&y$T608I`P+E0 zw(ap2k4TXAPk79t^Le}q8^1(AW_u;?@9x*u>qAd7zYHNYf;Td!oB7TIerjrMwgP_3MN`BY zC>u{hC$VL{YPacyPoccsVUo-e6;c&w)U4@DiVw6+RqNc=eO#zKsTsNt&;C_gD~ml}wy{@y|K=xU^=0P`_QHCr#7#1@lW+JCTG~9P=yi~9>XaO* z(D9X@ZOl|a1^E9T|BLWYVIeZC|G`E|)gFTlxA?#a%soHG9W5@54J{JK0R?yYNH z*k*QGyIAL%iu-|-f(FK5M|2_hTuMG#KR)h;!}uFHm;YZY0XtVp%M?XTQ__`G6AYR3 z_w%WF#+MH+a(y*jtCS~CwWhyK?7mbXVU>26LTDo)w9!Aig}T2M3fM2vLuAC=vOQ}4 zFY<>^+yHqmkFWfbUsH90Nz$SSO%bJs0E77hK+62r5|#;81yXYIDhn ztI1DUwH@5iW^iN?+|E5^e_RyrRIYU3VqF$zVtMLq-;E@8fK6M4Uhavt@gpcnnXr>= zQgO{PQHwab=Q0yb{ya0=?ILE#?hQ$N_ScN5NbaFVZOHfG>gpy@cm0fgP75-!F9p8o z>|_pr@>3n~ZME=^+%Hhk41B_`PU9DW_5DBiJm$5I8Ve5i>;N_Y)TjW_@t!ozO}R(n z2lFlx%`(kR*-a(5te5M^$x0FBV#hD9I8Sr5px_-y1&cf{JOBWf;4PU)Z*wY+QfgcW zFVW%U&_M@!6vs$LDK{qEo9Fuc`-eAo!%I!WSPWk17?X{CaW(-b)dmXhsFZ5X6Ij%? zTsTRG?&c;^gaVa_FvMVPe9{uDRzfAVQe}bY{=ep}8=R3U5&BDNOZ-%d*@P(^I1>C1 z(rA=60|-;`Ue(!j0Y%2DeNBHVq+S?Vj8uhx^}Veq3xe;!F|rys3V{rPf)Pna}O<*cNTe_^u7~#>%=WyiejG~%Eb=qM-7m-|aTPU}RuEh&T z?;8vYCLjCY;IjmxbR2+Z5%xjf(0T#tq$XDrqg^0(Sm3PESbI#`Ty9_vw7+cTcCss5 z;-V)5<|N%ewQ|p05M{uDvhaE#A0}Z^!X1wpZf9B*?hHyr4%_FrZn-AR4pSKGc#LzXEGX;$s(Nft zbkY%V^^sFUvGj7=p=+ic`(ilhZ@W7r0gn&HZYi&2$9Xy18v`MtBpcOPENN8xgKo9o zZ1y_E++u`WSOIEt{6^5*nq1;Eij<0A*hs6c>rCX~0zz?YGu zKDEa>R;YMDal#?Hauyy=URUcs9cN?>I_hH=PDKTBKn(dBT3$(d@V6wIa-MK4i+(cN z_KrsE2+vs2;h#DK$jhDSYW3Epy++8fy8Q=n_6#{OeoQc|x(-+l-yiAl`L^bD>m48a zvF3m3eIHWiHI^}Qb~X-9R{1!ea_3_*oZu~tQ2Go*45;`S!at)m=TwA~U>-0m-?{c$ z1Nu~PYK`7ijv#ZbLibLCJ{MHX5zv}I0=!?L+=|Or^x9u(xeN|>4THa%9VF{Z02;!m zKX57kfb--Ct7o;DY)dF8(pd`09N9ov%5*I5EUgyF*a`!6_`~=Ct)gW~>eUkzlSW52>@%QA z&RwbzI3IAsYm6iq0M^V=Uf~Cp^{%v(?AF{tn{5BQVA*05AW2bk$7s6HLqB+!a@s4U z6jOk#ST#RpCgd_56`J>B*J&lxYU@!tHH0YNEX{rVj*z>9;8ImwOl4h#BE1y6@@ zrgAH;7CaZPYt(w>xOWTH*$?M0Zrh@d!k|&T6TIT(`0%(^Bm6+J_j{3esfSTlS%Z}U zhb8fQe%bu;V%dq$AB90iHA=8!}^D16(QJdZ_5W2r~j9>QM+&lWVZMP~J z`)nFCIvTJQ`=HqbG;LGp87aJWg5xXCvji3`=j1rV56f`S#H-Yx@NWy4UYhGiYp>B?c zp6E)u_InS51bMGa@f`HJrjq|lsf{f*Pk1I76ZsH_SnJLQFhh^OcrPEr4#!YUQy2DF zO&0Qdp0+D5+GPeK4Wjfta}*pNW%nRP<8?@=AY-8oN&Z`!RmyJav3v5vt0RJCDJ55 z?EaO{(utQMc)j85M##gFmwImW7bQ)9Vd*sKFlNvbxa^9BTT zw+dVI^h#OJx-PFyZhIWovSsJ4udHRjFqoZ?s(d_yR-hMLysqK9h7!TPKAR-!!<0+J z96CYLfOyHdWN<-6i=b|Ee(kf<^6Do73I!6jwq%>IPQ+X0B?jwsVRR`gE*tV?dj7b( z*Gz#@=3KZJg||dj?*I6)6ETLr(E3+yYseNdOSs$oS1WH_fz~B-JetF4?%E8)>!MLM z;uWLc!FJz%m{P`wzKRdJ?Pn@=|B$FY!xYd<<;-T5H}rvNH{1`twm23Q+LkUl!tjPn ze!G#NWXUbqxAq^c03vNRBik(|wh324rREdqfuR3_#yff?(V)X?#Y=-PlWSIaLWO}p zMQTYgP#6LDyI-9rMI8*<&?j2;_UKPQ4dYXys=o8&!e2YIzba}d9$054H-|c6!4_|2 z@E3q7cAi~okrZ{gh;Lg2?d^Hjr&#_cNY3m0jHNtgG1+XAQLUyXVN?meA>uy%@l?Kr zg@eW{UCxIpN}UQ!^fduShGn7{l%tTC_HxJg+6v!Er}En2ruIf>iZ$|bbGvMG9scR= z=DJif(!4($LnhE)TXy?vtOkMJwHlA}cm~TaV9`*> zQyE>YWQW-77II6D!E(n@Vjx_T*9MkNrY3}*K7ST0fX)2-Uh8T+-fE{dkc zN)-m(h^3-u)quk=bfDldNA2yNf{c>^(X9N zy^|7IiuBNPSN|G~KAXLKS*fXL5p^%;#Z1oU8VSeJNK+sw1yT|UdnrQqN2jRiHSw3aoNq<_oUZt>BSb_+NnC(e-@pRG$?{R8~HfoD~F10{Nw;a+6J>B>>?$Y<^d={cmfZc8_sx z=AWa3)z%m=SlDE(ahq-;VoDc+QomM*jld*FGs#*ov+i{5#DSB+m3-c*OGoMcE*0UL ze}L-6z%udOTs?pd!jmUbuW*M4{WI!JsLlmfupj0ZASqMKKAgu&=4>B$`1ZijA6Th7Hd+nCVH{FKArwcw3~dv*if332 zErj{;?_tH1EM*Nt#XkFTEZSJJ83BaJ%A5{pujQg?JPnnll;C;;TDS(x6vS7e1=cW< z?8)X9vqi2?mZx(zp06>ZSQrJoorR zr28P67^WgnS;E!Dec6;S-caK7n6RqDZj)XeStbhPfOtmS@1wK9d75`A-Wv*65PzSU zLkUp49wOQHCE5hPmjHvyCow3`{ACu-@f;&PurlG)XKoXLqL+s;Ib8^YUL#%vH7ft~ z1-0U&>PINjGH|CF1+~BSAlnb5lDOfLDNC57>W)Sn1Q_cCjI$^49rhKaPTo!W1wdF! z->CbEq~V7+;Zcf4ke_-b$2wbx*IQ&NNL^x+W_htG+hQrfP7@~FLnii4$oCwRBd4fj zPDM95%u-PR2?bMO3s*W_HXL(8D+b0LHdAJ8(yJ~OnZsb=*PovcAb_=5F9LLdDUq+< zvHECiGOY%{NvgW0d3dvue18@-aqKxp+%LevAu0oVO3Hl^$Hb3=b@@1_D8UgTW26nOwA{E<$hIkQv4w%rdu za;}vC7eOP_^)JzXmThxil(?II+Uh9$A)E0wd=9W|j9hbyiWv3AH64P;oWQ{&^q726 zl;d51u64T`LxzTOJ6xB;_(6c(I1p!2;HZG==QMmZf|-rO=PV-R$CS^A=f6Fw zR6ap_HdhN>XsGeDLTOJ~WOY%qPeagb-3pXsk97r6T$hkwsG*|BvL^In9FcrCSyy4L zlLWK;F<~SS&3#OpF)@15uyE+^p5d~IIW8pfSVUZ@YJJtRh<%_?B^r_AW%cJZS)pr( z+$9bWV5)x9H~wOsWun5vkLOS05;6SWjQEQl&Bl~^9#mIs2ldPIUi4vHg>Dn}KEH9? z`~14x-sT#OOi&UQaGf@`875(sPK9Xirr63gqIAI2fr0Lc0euxZ$H8eq0t4IkHJpKm=$v~^82L=ektNm zVd-mYQPfF^M#brA>8&X63Q-b(6MQu|yyW?f>$qZkYoh6dhi%sn^(IbsKb@@%f*H@( z54d3m?R+}|S|@`ZM1z2V=vTZAlC1@V6xFoL)1UMIcU8HK;+&`y z{Ptt7n6Md{WX81WxrmMzBX#Z!NQZSc%3Mx3ZZhcbSdoUve2g51c6Nr}cMkC{Yg62+ zGP~Dy5MIQ$4<}d)em^?pv}quMU07bm{ImTIDVTlr@dS!1jYO@g3e`kn%_aP5zjKvz zWtL~-msq2T6MU05%os4;k!`rJ0wff zhDC=rI%UM{Ol{h=ZouBub@^Qc0&iumdFFqhcvIZ)aGuGtM7NU zTSJuH6mAP_W`R$oC>u_)|L457SXilbMN-rHveg})NWQP!LRN8J6;I4ep+Q_Z5F!p` z8P5MGnsT6(@0b1mA5(7`7S;bodkZR^(w&kDNO!k%cbB5{5JL$_cX#K|9YcvUNSAci zP!dDOvw#2Roa;KT-~}%>d-k619cz7-{nI_%%~oGCUy-7ya5n`7=6sgD8%8$<@z#)< zv6IBCX}e_sO5l(Xq^)y5!ghdEEFv5)unGpDN*V>gvE ztM|4#K!bH&OG0${_u3{{;r6=a-re1IiMBayardF|=g;#5h2a|hUx9|t%YvaWzyw~f zE^tK7nYA)0j^7+INO@+S>@ z2A{Opyo#v4qNvf=Bb_SsBthmpk9FS`H5e9`MY7=JdagN$yxK0Qq{&T{;V}6gfS($2 z7@P1*t^UbexR!4hjo>evy~7f96!adB7U^yqWd<&pY@nE7yM82Eh;0U;X>8g$&027h z5h?Wxoi3!oC$Mx<<5&mdNP?wa5@OrK0UyEajI#M>A#x-gpVcR*3G-NKZvOH>=*!-V z@AUmU1-Bsk4D-{|)2$GP__M}j1UNaJgXvYoyKy-P@E*M@wL_Zys6qs6yjIAHcTvAm zg63<@Y{qf97k;v0zUQK6Vo?k=&q@cwO@-63%4~0~!3>^Q7;?q=X`uq{`@y}YDNs)F z*+;ZO4JznGaOyTG_r($^(;1c6Kc#B+w1V&C5$`%H%(a?qd(tmYTeoA#9B#Kfc#UrU ztf8HD zNodvMc(H6c9`W=d>&ch%Gy$NIUjtp2o0Cgh26}V|-15i??CUk}v&?)nDd6liD6#+7 zrc{FdCJ>4+?q2QPgb5fATg5Y{h2 zcOIIPR{|>POBf;vx(Rbi&QkGP??MKQ_Z;kZ%OlD4k??(9yqCOSz0EAvI#W zY@!`mO0EPNruQI1nXxus^m6nXdyh_6oQ_Ulaa_i=!Eots(*k*y0&(Y(`p0TRzx3t9ssEBw zI+4`X0`BE(4@%Zk;DwCw`(9do_w&ksQOsiB2nrCb1bK_|nbNBqKF&<>*;xrjWdNF2 zTSmiA@^2gPICUeOm4N~(q)1jAL%esWRsXJRKbFep9+C_J#3L@zA-v8<`3%dR^-z+%>KhW>)mj%O9$#j z8W}Cw8kI9JDxOsc)%oqnKkcA@RZtx?@h)EE^cM>iTKr+%Px5eEs=x{~aJdwT2X1uc zxU#Ml^fZG%RlxrEXI+r8E2XM0!g}WHB*#P^HX#OfOcJd`zd6l3iCW8_bI$DC2CNT# z&>V5TR(H)EkMjgx9Fuz~XaX5pvt^ zhvF5d_aKStR(mDiG|?uNcFn0uD2k|<^g!$D3`T(+S)Fvsa1x(i@ju;LR`Pu+4`LaE~?_qTle@&GCKfS)Z9fC3_Z4ojJTH z>m2>Z+oQ9Ny-)Ru;6mln7ZpvK4*0xbdCeb^fCkeKLv=v}_$2Wp)%1lKd7ZrEYAswD z)#<04evfZpI#~i}r+cHaGu`Yj%Z=R|HriM+b9@MS7d)N8AJfOp&dn%AuHqKeL$W!3 zy73$KybW~et9QbSXG|RYrVOY0vcm`rT6@iUKtdKGIMg4v6J{#@c_7@F$Aw3pm8I7! zt*Yty9UAYOfQei_F^^JFjOwx5^k8sSsytmUr1&1=*8hrRSuubxST+FLC^$Q^7xr$RFGHjP}fEvC&%d43sh24U6$c z_)Xbo?xx%tpK%Uu9~@25M4m9uJgON_p>yw^B43&60l{^A%0EMg-O$oktKEr#_tGWq zuuZbiK5WrXa~97tjY-LxRHK1IP=oWi0j7l)}B;YIGqi^L_9nKMOo?LfW!}n{b z9f0y_eb$0ccY3Og?XhG!xeCu3 zbvZKz^nB}3bKqnJ=2O7JD4zX234p}*H^4OJ0LX`=+K%megtL*Vf>vag@DVa#cPb z12$S5cZjh>8O9(%UHkKko0bN@GC@Bj)0AEoKZ`>CLa^R`zD2g5pXqAyBJ?XTdKRS; zkV_dpi~T-$Sjr{;pv@&>k||# z=w~5bLMp;)rDuHimxS`+a09$jf>DVNj0gap`Qq9N+ReN>=NIYKirNaV&yzmmR`cE9*(HT4}#_rlv$C@^HCX5&PWpAd#87Rojkf#_>BVP4E z*W%fck8;v&$1*@O%6z`Iy`c5Gj+<-M#-7c)N9bH1AZ9%SG_8{L_5%xtnT%H%bP{k%NQ^MxbyNprXd);S)E!Xz+| zlC06>18wZvX6KwU0}u&6aS<^<*gzr$eB0i01gmucj|rSMpnx4}7C?;-Bq9Jq@Y3pe z57_Tx$0zIoU*xqJKRQ7(sV($3GK@Dmxl!bdcaYxQ2tRHS9F(kXpXbJ*%ZAs=FgCoT za}e$PA~$iyhbzZjI@Xw8+`8(34pbN>fDoAJ5>0C9{0Mul%#xqgOdm&@b#8AQ=4n?5 zv3c()B{P2ZZEfoIFWn+h>_jFf!BN7uR>}(}r~AXp1jS-$uYw8xYZC46CKe$Aehvz2 zXusYokj!`9R{OZi!GkIhA_BVZknFk^9h3B5@5p^nA=IBy>-WtGYl*xc>t@o?)xAk( zH+I|2a$`4XhYil`5r@H_#7xWYg>zcgK0i8~0f|Lx`-b7pOMEj%VJus5DC(RDeA!qF zM#A0?G`924di-th-~knoR6f87Sk9pBEUWr4FkPad+Rq)b6o1A2hYT<zpLrMFM^?fo;H09-ReGr$6nN9FDH1V<)|lq{9k;v zymIowQ6k~kpR$&9KiWkf>ZKXrq5aZu$m+K(@ObdKE1@eSnpcK>R}(XGBnVqdlQB)6V7HySkqH@O;1*n8m&1Dgn(S(e0M1vljD&4fO!ZN0{g*XcJASBBJ|tB5zZJuj9Tb8#EpA_6wH;zqFtd=b>GkKC-GEm{U!>s z{7o>jpCgk9#RxrT*!vwE79x4^%d$MS(AshUUG*d5V*oU&A&RLK%-6+x-89-x+0~>L z8d;|M0khyc8OevVYVe0idx(JR-iK_%;`qa{?9wx;tXyL6@%-xiLJ_HDtSl{TCZBz< zqgsH&v;vIodpR`XoqZ>{?SV{3c064EXXW$(`fTG3Jr(%*pgJhNv?ZD0FW`*k`;jtikb2?eU;b55;f7u*OKF1yh7F z&b^u7QlVHBQ6=ky6fnD`m&@YSc1i#%s6t^S=w2Q=T*^0;@GFz|yP^}_9j_1u0z%VJ zPXs-TUNyJ`Y4&;tP{pOEzt+;^Btr9?$a4FZB4#-~`m^7|sC#o*=;eGdvm5@0?^KA> z{<-|wuH$Yy%1f-40OepIfFxeLa+I<=wWyTlE*##|BXOWLO!nhp)sPVwyLNT3UM%Ho z%or9e+{pVc5%jMQ#2%Rny2An3Jhn*Pm+b+fHU;)KU@?KGNd%DJa|HMR^wcUOWW_L3 zWut^I?iCK4pPz#cCbJL@<+JlR|F$@;_x$A?8~V?HLAmHD1nN*?bY+c||1P4?ST}41 zjb)J)GO+*x)1c#Z10>U4(|-d#Xa`Za*P?|3^o%r4S**L^>9ao)WuJ5j=v^W_czSkb zr#|_KQ*Z)HB_SaCufp+VE=hAj$enX~HTBbCvgtcCMQ)46oIhcR7OVR_IhhH$dZF^x z7M+K^2k3?>UH|5XDX1_y>m66}|F%&*h{8v@&b#l&a-R=#pTFFku4bH(=hqcqnq2() z#!aC|j>x1=XY}8J%PAeoz{HrKp!$KWkW5@tmg0nfn?kBOZ(&ow?O+1{U;uVahs@WD z&{CPN_hxp3$mWf;Fq7abtz(Q42$aUX=7a|QhusQgVM|vWR)*Q^$#)uc-tTtY-r35O zwlxe){)A)WdO>q>A(7qlVsXd(@y|{SFBIGeL1C77btR68JQmqq_YeeSCJG}}`h@zy z<+a3>bMw}^!yv|-ry0vwk!FCs_4FX77UbgjUb`gK&j}z?!Eyh|GCQqG^DV5ZEq;n( zP8%dE&ih-HnIE!eN<2pTBfuam4o0uOTe|=ALvOF-J$?89kr1YBd`71_np4E{QBbOp z%dki;Sap>HF%Wcy3;FW$D+YUt->MP2wirN5Hh5^uXr7@l=Xn**Zm~^?90@JSuYA3z zX1HL8{ltu>KqIAW{StUTgWi^IKFGoIN4~!ifTO>CdH8zv(v<>`=2C7)a{jM!)mW@V z<*vOu!)5*tG^7niHU}8+a=#@B2`(Kl^q0lx5?(8ce*7q&dwu`B3kWhxB9qpgmzP@B z80_na!luWDX}bG7NWKNgMDhVcLt@8N#G7ujuNP?yOl)O#v-)O?e};;Wr)B8$R#ByQ z)TB#t*~9yG^2;!^F+-K*rAXhpFtOcW#upNTr!X2X+$>lpfMWQuyQT#6DjV+HC{z$t znAl@OJ0nIsJ?dt*7@R8iDIcCCh+GG1+N@(CcE)IO)b&kwql&%3wo#HpJN8F~JG4C4@%8tlr z{Ud+otD7hczLPezC#QOq$%wq`6y=%M-%#%4hJg}3TE5(jdW&&!l3D{dhM(vhfLfnK z;Hux_NpEx|3cEYF?r$Rpsh)jPIS*x6XQrHVi5s5ETu+&HlRpT5V zE@PAz4cDZMAK`NTF*+TvY$v|;nbBCv7)+v z^au7bJ-%516!3JIpT6lXWmQ_e`} z`%v#%JH_7-KPVY06UrUsd9xZ53Cb4|+bSnEcudD$fhkT+DHq|Bu5u9X{JJAM4^G0* z(zHv5huRYE6r?=8C>gR|t;2qn^r9ioEJ$qz!=zo@Ehq0-MC!8{hb_B<3pwMV^7yf5 zCX3t4-hHkeV#c9QdnL zR$r(dl|!c}V*mXRnWkJo;W%i=&5)a3Bv=4yORq6vceIS+`*5IBhoz@ZGl}ag|K0at zJdc%JbJkdp_Iw3t;kD>+0c7s+kpc@ZI!E4Wh4zVA2an?ISV?A`Z^eg#hz4JS7=Axv za4%^D=qAuy>V=NvtG%IWeG@={8YGFllc@AK0mng8h#WJQUc_JsZ-=g+uU=@B5Whmj zgZjS_`r1nGrMj}GZAtSNmBViZRW?H;jRxiMj_5qE(NAQI7QW;Asa8iO;BsfEtd;ks zj^cLSy4UF;fBm|t0=|!yo5>#?jLqe+9?^QV#>xbNKp_bft3g2)s~PHZ3A8h#1kx*K zi3D;_8(H;nPP24A;WKjP1K9!bEE z+TQ9R_}V`n)OBT{pM?FKcay^CgHBCH&vT6*PI)H$sc>TipkJ|O#p8LaA?@H8#50?} zbiLEFe+VLJO$38CS)=So9zwLldRHwd()QlY?S9^S10+JKUHI*mW`gwqX~kw+=s4o~PO$OX3hSA`!$$z7z(1?-&jBIqO3Mk69Rb z{e=w4?;=JtmRvF554o&9fITSCtg>eS%@<;C4RZ@Y7wj{Fo|coZW+ms<`O6Ie1Ar?vU0`xl5bj6W!00F? z;`9w%_18Nw^mpz)#39dX-hFO}VB4Bf0UtOrV+oDkj33<4v@*JCWLGMU4kty;{f8d* zUATBCTC_p+720HWe&}ygmPO-=1-UTbeLI2>1sWzWie0onyt^suSKQjNrXZ~esD&;3 zaM3d?z9&IZS{4$S>xpXmdx=yPVREyrqSwiR5r?W!D{~2BH?li=pcDG7`*Io`1R$p5 zKteJ@>~l`czm~vUAq9P>t1k! z@5KV8{U&*qQkNj)J*UOZk=%}9I%W;$pI1{grO!9rA~TprkX*j)N#JBaJkT^8vg1pf z!hfRU-I6r@xQiMrDVpmz!hbgFY|`iaKh`gOMrl-ldnzJGvoNt*)brm4yWhE3j#bil zt63f<^-(l_VNqN3ux|+wu~~g+%Kiun3E?0hj)Neu0a?-ap^` znaSjn-pu0B;wLvad+ws=#xDdQC#pcKgx7eWe(7VI266~)AN;$FF#8o>P1CMyvC5~< zRa@#EK2BMW(=-GUCV(tRI41{T+UG+WjnsmM$-1T4-rdLS+oPKi(R#@^=1;5p!_@`? z3UGbSYTi|J`y|1s$-QlK(#1DzudM_&;}gRUXHl)*$&OiF=x?=nP>P#Qkm7W8BF@c9 ztAEb;JXG_`mATN-CSBv@0@~D`F{4O9U6ihejTCebKMue~6yfm-Av$7Hhvn7xgLj!g z_}TCJ`#z%TDB$xcN4kN0w}+TI_4qo{jsD*i&l@TV%x?JF@ci~>_%`CGJUdy2T58PS z=bZb2YgbDD$2#e~-yb^4$G>{;18ji_jOVR>CieTx1p{U^h$|{mZTx#e0ToRaeC0k61Zz8Jk+kK`^_P+Rs3s|vQ!PlL!JO)(pSS;o-bB);udT*ZWNG=+0tcgIAHZd( zltb2Ywwd#%@`fJZbXVd=HCWjhkfo_6Y*MqZulbqF0ORVSad6*UIc0$^6j8C`;`8PO zZTCo8I%h^o3NsvN@|RZ{Wlmx>LgXon0a>Tl_m5s@VWupvI5F(zH_h9m)6;y?9HpC0F<=k%NJ!KGkRGsz-9mPww61PGkF3Yu<-rLP zzvq3&yX8CEnt_~;{*TXYXWmjP1(@tUjmHb@oh|+^ejvkqZs72{Ky7%#Lz6jRjWE60 zkz$$hwvaT?Sbv_hzGjxI2UP!a$R&;Lq3K&*cv_PNvd@q5ACYjdp9~!V53m(0qf14T z+IupmRP1!BOcoSRUWf!`=FLgEmu@GSqNNha5_|(Fx-|9PgP z$;0)sVfj#fGf4=J%kLz8`}xWMaZ`RN(j$9{qwhjXV7Cc#o=MHv z;zOp#j&_;&VS!14L+_YIH}O9(ehXPh93RCOU|W0u#= zhczD%l%^J}2vc?*v#&|=Ky^xDwXQfR>_Yxx)*Zy&&J9q{bl2K&zquFCp2!^j4?1-w zvXDsdYap6Tb$=jF(=vOO<64Ih|FEk6Z*4V_W`H6EhNTCslUNKoR^&ikN8dfOr51LW z^zP?wrxs{DsxMiTq^^tEjA|q@lmz-U?UzKo&KuuXgB7v9TWrr*k-u=l;Lc6bHHPx; z+&Nl>L{etS%uC^HXiM1)+XRG9>im1*qX;ZBbHns6`FN(4InS(D z4PM_lu+3xo?^Twg$>6Q^my(TM&7T6BD%CF6TGiFPR`(`+45UHeHu1Fy>isUrLMLFD zXVrmVld*klIkhEzhs8kAXnZ+k)F`qIWkk-@G}qNsUC;U%|FycDEU{ocR-MZJuiDgv1N*1b zqJ%yufKwA6N){%``5B}gJxUgNI{0LfZ5oUj1+W%Wcq_=rSKFsKDF9c+Qp{x}I$_#R zI+6^xMNRDf5*E9Yourv#RUxCFZEsNg z*FweB45;gOtt!n;P8i3_Hx1K)U5_5TKi79xsJrdXaN@D|sfx(|`beARY;ZNG=Hx{1 zQ`%`G_56A2cmNHk){3d`wum{1a&@)^x-%QR zPKj;-h@4mGo9T+3Zq%!Bvl9MTSX+)-O-0Ug62pS8rkYk{IJ5rr?=E=}ZfKSVTbJe4TvWj0CPO7JF>+3swdV za?UUP)GM`w{W^aej3M4(H=D-j0nEd7qcr&J&O=SlH?cxq7)G+q<$Dm7p_-MM>1IHr zTE;c}0?+J~+ud_6d-3Ve!17)4EOv_w;Mj5Z5zlbpHgvQ7B5o8GhZzUlZ&z1t5AJcn zSN>Z2Lx?dWrZDHf(XZ^hxY)9BjtZj)U(-l|@2*$I%sL#@9+fB5&Y zn8B5XeWd>LX$Ggg3^zl|jWqOO`ujsu#mufBvB~>l@ape$H3W;!1Sn!lb9RC9MEa&G z=ZXXkp9Db;4S;48>gKW`*oyO2Yncazyhq2{aw82ui@=%m6ocJc*~CK9q}^|_AEZ!DJ}1baSiycl^$V+Qr}DDE;^!m=*0< zCQY^_vTc!YG_po#`_%AB&LzfRq#X&}XL2hSEXH7=K8J}!&x0qgyO)3?jTMcryHv_IM4sOfHBI4Og)OCdwspnZ;Xp4@7 zE+l8EL>4Be3Qq&N`E*zHPIo9!S?15VYdog-?@sHG1kEZ@6|#BUc*FMa`Jda}@PAff zeGU4ug4gZ8Klc6M`9?b^7_=^e@8vfdzV~`c?*j>zy+83=nJ0&WBk9aM`h&~P-vhJB z&R0?FYKlg#K~f!hr3b<6%dgKd#oF_lr1vHYC`*4O=TFUH3JVDTi-KpPL`3ful9<){ zw!>zoK*E0Y?4O+7?&bc7gep`;%5r%pZ6Z<3i%Z9EOXc*0!46U{@^bY{b+jTr&W{>G zF2CzD+zppcOP)=gFOye$HXLy1hVS5tMZW(q>2uHzW{N9C3ZRj?vY>#LHnT(~@0+gP zj4s?)-@6~Ji>>u%)i16tQDBGmh9sK&OlVdPp2rDrC5`|wxPR>WSR-JCTki?T7i7ZV z<}~@0{%oTzhJ5-Pk#Y?%w(Zgz|CR@7pMDZcm5Lf24{Ofj6QVoyjxxYvh8apFzNn15$?2S59+Jt5 z$C=4v1=^+d$a^417*xE8eSnq4%5Cje#9|q5A6R|4382|H1e=9<_bO1A3A=ND4-nr6 zpf&2>$|w2(FS1n0rTQz$O50%ic(xjJg+{#(4F6|u^!-SEElhC==-$IXexw*y_uBia zx7Qy_0YQ+e0|TdA~sNN#+Aw3bEk}2dhVT7zL%V(7yQTP6dUb+NQlX-IfJwCCd|7VGabCt`+MAj)gtqUaKgqyp8 z>gJpuHq0glT}VP1SLnaROV%%?-<38XfP`@-*-ES^#?+E9iVZn{s#+$J@S`#G3cx#* zIy^smv5r?30zxoKhyS>strh!8*lZdwI=hXIB;pbl_pe4IYLp(smT8TXO_N8YgRI7O zreo@@M#WA#tm3Xo9_|A}5LxWE5$9ZXIbIa1aj8!qjflsd;wqj0ei0ML&9d5*U5f2M z6!{hgC2yB!nSnI$(0@>~Ta&O6uj;-eT{ABQ^AkT|8*j zUw}w(>KUNet!NJuXSA+M;uQH->xY1V_*9bVaKG>Wyr1dVb$5L<(Y=4Uwk$SGzN51kn5V!pQnofkBMN2}}4_50=Hb&q=SVv!7_4u$H>E*koCyf)^JHo=jnx*qAS(@ap`wm@AJ1oXXxWBqvLCc2J= zw=w!lVrBU3Pc4v8Vm?;vke$c(w_Qoo2Q zlCA&1q)lQpT^r&15|(;6rW_3j>}qb$_2XEtY&FpO1ijj4$$seh-+Bx-ck#XHe4Zto zsAwN9h1{?>7<#uJTvKrw(lwL-l_GR5heS)WV0RP*oloBT?OMRvM zKnyPl3T;m)6 zoX(Rof8U4om-}2Q`}W%gvUwjHDW(IFNl}!Wm1aw-MojXv*mLkIa~<1gpFoTn43WsJ zWjwVysDKOMpfsGs4etR{f!_Lw86r}2I&DAD&;ESJl~AP5>_ji(j2qA19}J)zKGm}g z5k%`zk&_oCP;^c=`@R+u#Sl9`&VAnQru09q8>IBw!5wmYYLU+$hbT?JJ0Zehj7^*( z_-JG4T>A|~V`O;CO|aQQbel3#3dByE5l)^s+P}ja7XB` z!0eU!nH)tBKU$|s|9z`7N#tNV8t?&}{!*p@;(h5=$hCM3J|R6NQ$3tlPK-ML7_&2) z&JBDT(cjtk11n3IqZsQkVUFsEUJcDK-(akq9P$2wgbI+RR23kk&Ai3)+7t#-FV1x5 ztH#_&II|J!{J2_1B0Q}%%`l~}TMa;`Xu&M-FvOoiaQZu}sMnk##7yx@$dAYfhfzei z6E}whh2vSXUOkff6p9liQ#@H7cdH9Ncf(EoPpsXl7k9#;(2(cG_IBGJ7}e{poj_m3 zsG3uN1R_Z=ii*GQNE7m)eEN;|Q3Rl!$ZA_BiD4~BtD1!#w`pHJ7A=t~W#g3R5=&pY z%`5Hx7;HGQyl81+T`KW8{J5iAYHye|y|kTg>gcevP!&@~a!S!=HU^T(1tJ^RdDE+fjZ@q|pp`Q$OmH5X67T8+nJvnYt{u zH+a2<_=d(aA!CdF>kOro_s>Uyk}DdoZfpeZvd_?cx*&8U(6HGs8p46A``DR6|%9}&lkcH z84gg8c@A~v8be|TLUr@=c$96FvY|3|`j+QNJLceMZGr{8VX}76{CXR2r(KlAXR!); z)=6CnYo4_z1$IxJj^s+%Yj(vU%h)u+B_kS-A)W^w9-jKF){Blh+ldPRlsVDY@1bPW z5kol^yDoZlHy^u3E2^Kv0|8$%^ZYY;cp0)t%J90oMrHaH6dD0IUW$Y$^0$%&6-x|h znTBFSYbM#Ojz54MG>knT=4O&UV&|-~Yh@t)nY{<^e)P7%(_TI6#So#V1w9uCI~ z_t{bP`W`Et40QNA!2@j8rWql3g@F4f#J0!HYZC(+%jBK)HWtndARiF*+$h1POmGgT z5rR><20go9;S-Lh1+lCc&jZ!Q>7wx+#cn@|r*jeG#=DoKb6j$sWew0@Zm}#F%H&LI?hUV5L$H z0tbc}W{BC{dZrpIL#U-@wkMWS-rhd%uor^DK!wJ0mm@ZD53)bO7$8HjzkCDGd-=%O zdle(}nLy%X+L-`@j231PB3p{D47qVK)k6!GuYrDZznxCt-x! zEe~Tc#7W*2trO*Xo9TC%x8{c66~2kM)WNcV%$eC}7lHUhpqxM2wGwG|OmIkscosuE z5_tbA1B1Aql6*Q>@a0t5-842FcqzGE%SNnxcU21m6IAH zc?Dq`!Y(FX^}Hql_4i;BJ4{(^udh9@*AUmnwW;(YC9uYl1+3&u4z zGt>m(>))*;fc+BWUbD#@S6k|os7Ks7zDB39MexbVyny*hmTsUXX2B;z${gn#p;8R9A z?|j>$SHff1)U=AMTHpvfeKn2oxVqnD*Y4JkTlTE!oP^KIVsdUN(N8nzUc-KZIY&QG zI)44yc~9KpI+(&*b1%H?bG3O^)t%^rNr{#DSu>~x4(EFQ_rU0E$x9(mKhqWx5d?l6 z{%emyA1^vFq9mQ#FypSCrP-lD&1~m}U05M;iS$jc=}$*T`v80U_x_t{N{)^~2^VFd zSAe?ek>`!(BRz+|{C3yFga^&9neJ6+k$G}(P@w;DymzwZ(Az_OVZu-)W`z-5e8q^T z#pDI$Y{jqVRDL(~tQcUmaO&JLr_w~jjULJ?hJRLf(dx9hyOLeKk#g*EIbGB^k1b-6>_!XTW3S;!zh&W{s5H!Xur$N4yvW-I0?ZhZ+3 zmmayHw{ynie^Q_yo$x$eLIg{@huVOFW@?TJ{JAI5o-olFzf^X{>pvOr?Bf2g0?Fyd zrwd9}3RIW5T43CT*kWOti}EH})%hrh_F-PKz8AZ$>wX2|^j9HPoC|8b$^PUyP5ZhW!X zD@=}KAUFnx7_UNLa1s)#Jo%P)(@a|5 zbi?#Qaa8>W?1BSa|7A<|ph$B`We;6>6$0^}HFxy-X~o2^VM$+HbyP%7glXp!b7BQo z_$x)pPl zrsPyFc`mCvUxDw-?_Que`HRx4X)ySb_}?#X&CLme%<|;Qp8Q8EZmdjq#SSyvoW@+N zHvG6%?e@6(nhf;TCoQ5DsB@S^-^4qcM_!)IX|p5w@>KM__Y=c^W>M#|Ct)`xnuDOf z1w{mp|4U{RFk3mm4zj{USqUiFxy;1UMdKU3a+@8g+Dl!20;IjmN5g%1Ib9rHxKtL| zY|-KYVmb5Z(j1`1hs6!^XKE2;p;T z7#uf$R)$P}D(sjbO6gn5V<1bIx7^I<5IeIs1jus-PHxs!5Ijl1=6_qmr|feoG_x^o z%+W(shOQmoMm2d9->MaO4&sFeW0f)D)nUhC89TWj67CqlA?>AO`swl`=luF1PMa9v zm4EhPP&q7=0KjSQL-3Psrb;*ZNghc1KUV5nsg5PRV}>7=)UjCFUzGimYJV2F}(_#rqL8!J45%q9GokVZkG1Lpx7Wvm)vYJPB)DWlx|x z`cKB_ecqANsrmr|_N%PX7D*Wf@UVSV3FYNS)p`PNy{Szj`7lGqd-LfNtqT2_K3yiU zKufv*WVLWohH9iP$GDD8w!YG322C-ck<+{c(ktxHeNP;S!`{Ybw~+7T{*ZMjV9h;z zrQyfst!KA}(3EXrfGhb33=pM4r{|2d;?L}6{}*;jfT^^)SM|N^2!uSNdxamkDK*1w z>%gWD)z}8&pfNl+Z>6}4)*zvm796mu^70H(X1Dp-9R25#iH|}MN)BX;C!q!JmX0(1 zIwwTlZODWR5$b)kszO4E3d(&FHgW1V7PT(6t z=A`iXn=jeO6ySt)T7R0bTPbNVOz#L`Y>;;ghSlN;?bY2tiwe8nEAzp>G`bFlTu{7|RSpkE*`<&93 zJfY9OzSveq^jo(|CzQEMlMB5@`1H`ve9Qwuk;yi*qOLcf9{QzJ2|zcFedd@_*{KK$ zNnIA)Kpz)Yvh3nn2#4H;>_K#R@~-7oi|p$EsDj4xTlRYdr@fnd@hZSAG+&%dr#()bFY^R4z0V#c@N z@6=(*!oET0>4|fEMxTc(xpewz<}F>8&%>asROBjoXr!7G#hB81dv6Gor(E=sC?#TA zi-yGG#qR&zc-|y~?9-Kyfp(w$+V1y1EV=&W;y~OtbH=x$!pH1!;kDxhRhkyr0srnW zqcs89e6GkAYV1y-=~JaKhw-XHI-t!bNfmosWEXQjT7SBK5&jE4%=PbVUh*!pcN)x( zYWuWMb$u%EVL_Gp^`G~8jq2&)ic6zC*9^cDO#jYGNrdoo4(B{UMVA_j{dMFQRl7N{ z>BLG&6eG!;^dzZkhNLFT_3!Z}%TlWO`x&`8C!Wu>4uGxxzYK!KgYbbcG68Yh%W8c- z@feW|j*gj7KH6AlJOCvz7VwDh@sc3Aw56`?!WDtje=HO{*NK)W>-{*Q6=x9z zc^G~Jf*Wg0iY4*S>OUeQQk{X1m$IxiA?{!wzV^fL9wex zbx`ha;6n!F$m9uwpohk){hz3bqM#8~r;*Fd_9f_ySXsQL4p}bZd`{ctiAYsQ>4!8n z$8S%K(8%op>$8pyxcp2P5C-83V+&rc$+2-CfoY1}-fkcZWV`eiY*U1;Ey30QYlJ|l zzk$dHHqno>x($21mOBgDIRv)zGKM+aLT{P>J^$c+>ok&<*bVlw#V@U8xA-9#Y$(d3 z?mu!^ijlqNZ+(V)n7_|ikE9Rq6RyhCx7TK}11ljgPoD`~)oqn}L38c+LAA7NvJ%1) zZkuQVhj%=YhFc%sB~C5U^;86fY&Nwl@kt}SjtU)T*C>rAw;#Ix0;2A z8B!$jIe_CSLzHYIJ>P3Eb`)m|E~jXVItsCHM$1l^WW6Kt0hdtcH%sS+%ZPDD8@^V2E>;-La!avndsq6`FX(w(q zxG*&l9qz8)3;5$_eo@2!u|NYni~vCX=NcC zl0e~wHsEZS8zMYK%0f0CqWK5!U9()z7pNZkp zP(}l8sr!4|$I<HnNwJ`q-uat=UqOioLc((K;nsfIKK&EI`;Tq6NO{ldKG z2FoE2}AD`qKVxK|x|(zAYPU$jkjcMg?~&D!U<7B!xTf)$AEd-mK~sLqQ!PrM?SIT*j{~AV8Cfq|s4~ z(#w)P9Yy4?I&E>x;7>iHm_Dof=;>0@-REaNu$?Dl(hHUpl_r3r+)^})GC2Hg(j*dy zTsWpy?t$SQrFtMOSCGI^L` zR6#}R+<*Ua5_@(JFZDUh_&mVgs=2B%wXi@Def0tTsb*0aE3H3O|Ii0s>_IHMAGIXgph=k1^qWI)CUGKknGACuGLhM` zF|hosu(~Ht=?|nrpf-5HLYQ$dsl*=lfb7s5u&{*Dmw$>mX0M#i$>&Z|Y&!I7VUR8=Krt;Qu7Qpv`R~InV^!)zv=y@|EBV%~f#^ky7T~X`flc_)W zYbEGs5 zv6aBApfOXnjeBc(s`ZRd$Gr*Z^&9n`2?_0e7T5~`nj_#RLIp^SdvjAIo5%FOwn_N^ zv`u9D+6)94|FuOj5va0E1<6GCNIR{NAA3K*<8d3zK#&Z*BQ=dTkioDnmhtHb>Ydty zgLHfNw0b9@I-I!r75_yYd_ z09Zk%zUz%>EP3HMW8tTh)a}dkqT)KGt}LMG5E+-EDyh(`J9u}3JaHf!d2+iPr=hc+ zs0Pp~$gJn(g|)ahB#%?_!&=-MGTv*hp`A-Tq14??5$cI6sML4~R33Ze-t$+~Q>X4S z0!rQRGh_~+Q__-@@cIL7-I1gm?BteS9PDW7G7{_G`@jEutUEqqQpSYFCmUt@>#M&w z%CTDcRWp%DCK7QxT0jj(qVlHqh;TQ&NoV=Ve}9*(q#lisI`2gZArwv)#$jOR6tud z%pdKPtDji1ulMCuN%E^%&e#6ZwkHA?u%uztl7{rVIyc{%epR%&X^ZOP(9D6!N+FYE zAl4;splM$poo>zpvA*wTOQF}{UVh|;QzO6l_b<<0bXu)?SmDV=IXt8)SN8U&v-o|P z6JWgLM}Tl7x%vH~536t8@&+AHzjE~iY`SVd9f*1AXiTZg8PN<^BEz4nqFf1z#Dxpx zYgZQP)N8q%oN5sQi&`fr0Dcn7efK}J>FrkP>@4bHJqHF?*tE5kIXf3L!zabOzChdY zSku1Vy+_FFp&Fpq;bsK)E|{I6(ZRQ$AOq@jjJZftUnq0}41iddlwtLQN5i<)cMp@5 z6^b;h{^RfcOXKUWCld12pCB^bZ3F5+D0K#Ht#fOzMGIeH(D_%b+;S^=j-6CJAmo?* z-t5|ip2Dx*J2F>dVC96aYikcVdVmr{wVwiq zr_kjQ=&C8a!_KmE6-2&GtZ15to$}3s93M!tj*BCJ#nLEw%z+^n%>Ar@6!!Y6nm!nS zSbuGgc4Xa<6N!4r^gS(dU+-};=It%kfI5XARwv6fD#Pj!>o4wTIC2TnUM)uuzKHoWE-<^$ow!uac!Ps!N zNlpZl5kV3l?FxieD6gblZBE)WdFFeotEQ)?({%TA&-BdHkC#z(b#-@Db#?XAwQpB5 zqyGAf^`HOOk3!+-=RQ$+-Rdfk>CAw7!enR}$6T{CMwmMc+>G^^r4i6xICWc^r4sXr zv*Xrqm^1O4PQVpmwI;bP*aQ&3G2HarNH(k%%^S+++)&scEu_*E?Xd**qQ(WEE`Il!7I5Twhq_ zno#JhTD-Ap@g^p%4t(+IOPk(%>&sWveDU(?*vyP0u>o~;Ezh`F8tvcz{`W~R)7*F8 z{rGkZ4^mjNE644GlS;xm0cQxCBGjd(=t0z45Do`Hf#oEmkm@1ZQ;esyv~HOcV-<21nXj_jmTk|55?1)t+pa z4Z3#p@xd4nhQ8imw<;T-vx3S8W$&~nTo>Y_Gdz-BNe1@XIekM=QaD{?I*<(&+11(3 zs^_k*wysWMKl$PR`^WQ7lK4)hXRulzl7wThVj8cit*gf|?0#6|?ofs+ufDOi7EPQE ziMhwJSbCp}%Cp!z?2R?GB`U2hRE{%L<0ZZ40N`$Ge*#Mrs;( z<-E7^&2N8WUGsZy{nyv0e`-0JneiLjqk%wRc$o8db2W|6&Hw?M&3e~eci~7~pkwMu zQN0VZRA{afh?W)=6_k~s3yeZZGaiqtpumkKds*p((UIYen>IHtTe)G~+NQnw+_7}T ztYhj{)-6?@5pPuEm^wx(p|KKBX7Bkirmj~RjXh0bq?mJs88)&FNR6puLQ!WRY{Rm0 z=`5Ee8g86ddPD40*w$d<8%HXieDbMa5ad_@1Ul#|{HY@zMvSQg?65k32dbly;G}Zf zWy>oZ_TU#+pcQ^V9ULs1{AI>TSbRSdC zb)^pIP(F>jNae`9rlDk4u!&jDWm*8GzGTT#y_C9Xt^-PTFg`x)^^Rbre(cD{pwu^P z+6-cyDs@pZtkeO~v`TNm+K|~hRqARm_B4r+V$Kz2*vK{@uhaoFZf&sz!gkP3po1Z% zz-d`H-F@Js-y5*_7zqZKw#S7W(;*;=K}sD6g)Aenx2UiJ#%?fIudK4#EuUNNsIRgW zPFx0hUBlq|Z?^pC*IVv6cY5JHo2J7e_Du)nIXKvl6C|Rv{o#BTyu}+n`DzrCS*fMQxp5Bji zfl79YLg0Spi2Z>WhfQcTrA%J)9C|rZDA@x~towYv5Hocni1qEycDA1Jw)WWHITSp| zOgG6&_R}w|=h@$XJkRs-KVLfc`aQ{>Po5(ZK>LzR{7fE|e;DZKT=*!S+UXVy5aOae32FYD1xVokGb4(s32j zo`RBngd=8rp67~n0Hpf(_!#JQ$Sp|reJ8@(pYLlv>V2sxd@{6b*Qv>W`-s?{{$;Q9 zTnqMrA6ZLVbo-y)`R#8XX>M*3YIN4sr^I6g;~tSiX6lD3bu9VHdI(x^sDO z(OAnR=ny-FLZMJ{fKb@t4I&%!TSk2rU(kvd{UJ**jLal}SO@h?78sbp^_XN2hxZ&F zYd+@t)o)*Y;Hj49-x~q@sI&Z~Cf}~6qksC#YmYqg$UXP`Xxp}}2M&BBI*1N3-Q~0v zy3tYa-ywNlZ{Pr8J>7ae50tvGib{vQ!!C@=qp_urfs4Ske1J;!Jcpg)HWH10z#oTA zXJ#BJqfjV@k?fL3bC&y%`2xrSj5LQ|b}GcAaRaCEYiA0p<6%D03kVY?XqBn?Cl0LDX z2VXt{q>K3Wdr7|gy{~!qKi_@>DDqp^$5lIzM;`q7Zy)+O6I5E6%nr%-0%F?|e)Yi9 zSd{Fla=ZbQLTy=Cpe#@*#>)kTg+PZh;!|>l z;v3U19~pv@QEEs7CL_}USj!Bq18~m7&ba{GxN#u1ErONlz%5J~u1p7%;3KA2g+bG)j_zSm$VHb^4YS>s*=6!j$U?WZtPq*rA9XUkI`Z95{o)Iz{PXQMU?Wj6j~8J)z+1%? z@wf2D-BmOM5bL5c{g!oP=v^;xp5T{j=|`u7nyI%)29@kNiFv#SlhV%aWhzkOxHO&48v>AYe@$;64ZAlX60lhhVV zFig5Te@M39V^`t;{PJRq0ZVplc&0^=?>GPkk$Q}vOJQWes8R>;s5w`21EP@_b`=;; z#|u!Qghkz2K2R{6&q2|#s8-A@RI*bj6bdD6Am8-FKZ7})&U4N==hj~@SvaYG zsr%VAh1-^Tp1pcz(}s(?p8mES?8cQ=(Cg*pm7v%0R?#SOgJFVJKj*cRIIJk=1~6<4 zh8xZi3@j2=>M6l>F_%V#Ugv=y1|E5k`^qWa8{VOCw;B&bNk3Gt=LTsQR=1&-pVXOQ zLq`+}MGw*_RkDeeROE)58A%b$)(j(*%15SxKk{JwjcINe0|_KX z*74r(Zn-;W1C%U)4zW{&V1G~+n~g8TlNxN22hhugl4XE|xbK0dk!@vu6OEl}0w-e^ zxxgxj7hNTaH&Ld0JRayAuDYOPx}$0J0!wu%StSMNbyloLqi9$?6egn+;Yi{Is8*)p z^tmS14S_0k)xdSa8i```G;gv+37}>3?=G+*2y|xn{CZ_ONlF&n!00`e2bJvk3`lc- z5Eu@@q(P;Rp^Ghb!Iu_KE$fU4hy|@^StTSRA#YdRgV03_r z^DCpZqfWHmIX74NGv1M>#ull z(Wm}-!6)zh-h&;NUH7fi1Kv~pS2xE+8 zU-RyZFPOp__gzoHERD($Et)Q*yM8D}Kqb35v8HfJf?=f^oeQKN@g_K)QYe&cR7pAON#cJW$NhUR*q3vUbSShe&jK4&ddsx?70ERbgBECivx)g;0vI^ zbxI6+Jy5cbrH#z1rCXoD_Rjkq%3l)I02)w_pwE+5ms(~`F2IpM<>HMb#9`T`-<&w@ zf?zOuq-$(oH2zW38&_Fn`X!2SWS#emD9}@9rn6QyOQR}`D2RFQWb_`Z4Jz5Q7b%$z zx4?xASH!sHnrn)S6TUpc5(rrW>b?q2p-_~O7EcWHYH6aQIet%+EEq;0nDE)MDlw%F zG+y$}F>iR>8wm^k@P~UOJpBtLJ>-T`$D~8HENxiv_IvHDshOowBX~MUvcNdR!{dQ^ zpZFXU>#6u24FHs+=8Xf#|~<(^#W#*y+&owH(iG(0vQ=^POMAhG^J zol1Xca!IKJ8SAefdGP1DdcqJyMLCG|C0gEI&G^ksG6VEBn>tjlX9YnqnGQnyn>S3k zdREg6*WU8jCrBUwi(sJFApz)h9M2MoqB&tG6iW7jUm=BGvdoBe5;BI~VG>9RDD}bN zP>_6-l#)quN2$kDigvZaPLe1b9haX!kt@?dShL?n5*jFP>@cI`Sg=asn@5^4RLa55 zs6naAr$K&X@7S- zc+WK*2jF>o1~UP)(NoOMzUH_h2X&6#C1qYAgo=k^dDZ6$3-PmC!>9O!C*uU_& zqFX6O^Zg9hu8gIM4!fYlppxC3@XpAZHES-K-pP)m%h2HY`>Iu|=FXidS+`hMfUdI|87Rd_E2ptcQ4J5>%b`Et+gt(XGg+4eZh+sP9RYhOUvnaCt@|iTg6Pn_h!mVu6e&8m|G$IXb~x(fTct* z#Dj(wn$!iB6!~MZtAxju+Db8^HG^wR#?k@rFnBRd$IelxWH%4IuY?pA7vH$j${kHV z(cydS<*w%r*Pkx_QsttJM-x9jveff;Q1-kROhG7TCq}eL+RDubJtv8POyAdpM%>79 zGC-QM{xGR{v4_K9n;lKm*gKry0Mq~BHql}Ad++&ScVF<6OX4yecyd>CbaVuV^Wi-) zc(yUgi?cbX)PYR3Am)iViHuH~AT2-*@hoj5IaZo;lRr?so>_Pv>L9p5c5`L==}!Mh z)z^OXSjXM>{O!`uf2(rw#;d-4$X~pOtY$pd7feMy>tvY$k8o2cCdE`ElbL2|!;1SJ zcm~w=JMVY!2FrPHXH~}nohQ@Pej_Ou3|g)B&i-IWpTDJzL}J=r-q82qHnPBQ(>0fl zdn4cZ+SKdURFf!>={plf8Z!E2;=Ci9DjQ1;uF1e(nJ$g;+lPM6{WOx$QXUb{3#g!_=%BMTG}GTyQw1N7>mh_kdI?z?i|RwUVDZn6Bqa!}zyu}&5knSST(*OLWhUt=_#Z=G}WhnC34n-AMi{n8iR+@9o2}(Vt(XlO= zp5XT~G#ol-^&Mm(5$>l+CfGY>%$PwIVhHDxp-?C$g!@J*0OA{e_K2&(S%Jns{% zIwlwl+U(BGfnd|&;SWzbd6U45cQ+xu{_=(^=ABwFGeM&RPwtGgw8dRtK)yQc=>DO< zx4J3yf5yeS8I?NL5XzN=bTWw*5RHvO$#0ZjWfXl`I3vN`+%K45L6p!KdiT_BSKV*d zR=OMKm6Cg=p9tW3uN{V|_j&#YL_Chr#+G&UC43>zh_sIGB(iVTJ7 z^^7xpp`_EQw@Z9-28zi@;S!=(UydQI>X2C9BreuPRXA6yYa2~>*wCN#Fg~9Ti}mN< zJ==767{ofyXPw7TxNiH~ldw$Z_`Q%F+Ofl5-jG4Do+ClHXvxP9?hr zBGLFvg*Ys<@ok->1>DTR~ir4(@R@4ojQ3Blbi92q**bNc<0 zc(Lb5PtTEF92TX-6Mt$6Sf9x|qAC+*LT1B-A@&5B~cbj<)V#T zmvl`3huix1$ERgz4J`ZJYh$mz`WjhgC@B!>{qQ3JOKqk5x@$k}s$52vQy@IvvGcXZ zn+~%ctLPz6qPFkp~k%8XG>~43u@KrL{)0H+m0VU zjw5v;17qqS)7!;tO5;@4rk+2&W^T>GYZhSp)aEr`+;$__r#7!%c=ZBoHFM+h2T>># zeWBy)`of#k4DNreKp-xiL6L(lCkqTbnGUqHTZ9AZ5`z>JbCV|*SKjs^=~CnhfnLJH zd7KV1;PG{M>fZkMGhol|?Ax{H@FNV*KKu89fqtG$hi7t-=@7`n(R429AI8cu?-!wb z2gy#>r4F<}DoxUa>WZdkCL>V2t{1{Luikj$jn?2Yt`7|8@*|Hmw7t9@3<5lv4zj-a zs1LRx%M7yP%K1#%T5Spk5^hSbHHu;2S*N&!!(q_tWWi$T?Dy~7dk766Bnos4$aJ^U zie{m;nd~Vf6Qo(J=eVD`7HD5dp(H}}dg|D0WWsfplP6E2Vf7&2BgNa@By?MEX|q5| zo=m4?8qHTlY(wD==!KRum`~6axU3}wT3VO`%`=OfUffQL(?Q!PBAsHLDs?evJETwq zV7*QyyJm!LD!>2z@AkKb-tSu`KV909!Mb+WwU0mk7`aD^X;KM)f`S363vmj-)WfN-2 zD}!Zq@i5DQXIlN{g?LCLNQ2RzH!fNp`e^usH z-KCda@`+D;a)xtnv2Sm6;-u%G;9CRB4))f(_12q5jvOViF=XDz%=Jag>cG3c=J$NfWI;gJ#~m;KGCp{D)kr!HPF<>W3r5y{K`^Z0jU=x^~zR- zzBSLyd>YRwtJKp&o-1_##JX`xJu}`f7kU~l@HCJG0WbgfZ>T{_+u4q@V5gc+9ocad zWIEZ*AmB1fb2pJksH<6e9!v=JhXEXRWO&#Khk53VncI;t0|Uz&Z@lsH%P;@;|33Wg zzN0Vh8OHX+pI>?W$rnHV_>fSh!#-90{o0&lZNs5m5ykAtj29R|j>&Wl7&>T`nK5bI`neB1iXcQCUT<1{QhW#?lx?B;p_O4tEdsoapK~(K$Le0(u?d(SRcwbwvM!27F8e zGYrZ6%%8Rxt;Ol!KPE80elZR*OX%mE`tz727Dbh_uW9#hANo02Fgr?5H#Z$s>ZT6mfdQC<_NmqN!{Pl^$B zj`MHkvq=$ASi*I6?Q#T(kqT`|n%Woh0-%;j|5;zY3jGP%n0n;H> z-;iyw8b?aKbjgyXRH>Vm+}7(@spAW+z4g$TN~I2U14lGgBK0DObZ?#*8 z+xiDv`%s}WhG=C&CzlYNYO738X3=P7kOrVgfDsbhG0T}r8A$8;Hw7v6OuRO;8P zs#?7unz~YdYPYrN@Gw>CDWf1udga;(l-ES+rO>g~lVavNr=$^6DfQSrA=BvQO0GB1 zMX)9Uie=U?H|%VrbV|kaPt2RK`kaPaKXKWAU%&kJ)nr8m5LR=x)+&XCc`hVjiV%>h z<;6&Jf`JfcWjf$w-bO7cKndg>(`f}KLzf!LTs6}ZOrhj48CL4q_4o?CCAI|6ay*W| zmZAf+QnMbc*YiQLLlHHU5|1u}9LJKKwWM#3s-mUMx}!zhxSw8vFmEl_NFqwwpjA$x z)%BCA>uXHt{UQY~f5`h~czn2LsP}khcUF17*qwHp(*}kEL#O)o zJg@^7Dx=^EX75q)`es9cXz7d@GnIS4l$D`r_$e93v={gAFqv{n3Be#-;6Zd9C3?Ty z8S{SOmQtv-^sNKDf9^ho-Y<1ka?TB0RfhKzV(no^##nUIw$(GerWa6Qx&Up?>N}CStNzsRP_B=8jT7-M8mA zW>D$?R4{wd#VeZ)fl_xcTyUNGMhuhjt_xF>zUz1W-?VHg1?_+*NGY%w&2@9saZFIi}uqwBy5<(Cm;P)A9b%xUtnT zaaJv3lP1oXgj4DWI?V}V>RqFQ!{#4TXa2R=U3Qy;JEq>h=QnTQa+wU$Bzyr9vN=nb zf0aTfUpF}!A7W>xa{&q7-L3Q)zNV&Xbeh zI-tDPjh4ph&%a(RMi-Pi$AmMycrGEk=mMYEyO?ot>DmW>pXtqP|2LKldVU3?VUxl)agF} z@*0gqeZyl|srQ`d8p$rDj%7Nd*Rw^b*H*eLR{N^UHsQ!**#7+VcB<5~f(+_)R;dFH zSNXJQ=i+$od@Q02b~Lqo^d4CdfL*!`QtCVf!tRqQbqSKzITnw*VjYf;!l2ZvCfC$Vo1{&tcOE*^{I~Z( zsl(NXc8YdxnKWnMxo<(FtuXC09m%sMisndy4Ps;u`xAY$S zJ6RBbXCF_qQU_%$qtu~`<&jjWgB+Ivo@Cfk-dG?;C&m3rrhN6~GG!lxO zH>2TyzP|mpo1XpR)b(m*I&ksDS1brNY`Eb6n;&c-QEE}ur%<$#`ZruCriFQ$M3yns z9D06z^oAAUCeupc2q~6NW^+)_E~mI9Rn?;CzC)9d!KOwr9xB1J4SL47WcrQL6xjRJ zyU+gM=?>87VWiQcp$N$IuYP9J&+d9?(VS%@Q3`-wzhQixD!p!ZIWj6PavNH)`ACNK zy7ACvop!Re%4u7n!pn=_|~A*$S$Nvs_*0zPUoE8F6;?@>i_iJ zsj)XolM*^{Z;emfPkl#=^~F8ne(FM0l}uEpDcOUl8#-i8u&R}Iy5;4Q6 z$ZJ3K)Oq&1Pj!6MjxO$qB?=ab*3L&VeSQ#4@In&l&4OS9JO+>j1t3M7Z$OE8#)Y>? zp=gD9=p^ABLwMa#Vi;60SzF&(nDM0zD@iC3RhRRv>o+GKT&GZSi!4*>FMR)*-lJVk zm&56DI$REi(>`U<)X)AH$#f9YB#|+|V?b`Y!SGN%z5(4U*V0E?4@NO3xvkeJ#*^-D zi?XkI7YR`)6g8MYsVi27`~SMP|3ohcbf?GZa67;zFP?f$T4XvVSAEtM{RIHu*SMAe z1V_zSPAH}zSM_?*cAb~4o?hzN&Az7HcWhew@b)cS!>jOBj67Q;jH-M}K9eK{GZ zeDH-2L7fws&J3$x`JdONO{QbuSk=rIlyV;|7FaV6!pxX6pOkcww|YI7px3Sr= ztn(x|Sz)n!(7cPcifgbTNk^gNAK9VQ`;K)VdF23dcflIn<8&3c7O!2NW|@vz?Y}Bl z#X1^X$Lhd{`$2l{F>LqICy^f)6nG%P#20)dvqKcd%0yGQOxQiOmeJbG$DRn_HP=rL;PVPF21iG8J zr(d_`pCEG1oJF%|FFJN?f2PE`+^~8kWI{BBR)wHFJ|(xvZM{yRP$-lX0LjFf*~#RX zx{~T?-Fd|BvfG_@U9c*LZQUS z8g2-5lWTCJn5JJBi0DTYJf>9_svac!rNu%2~Y!(&k z_dW3R(uS2}0e$OKFt<7t-+7IUK*y_O5@ZLaR_fgc+VGSwSgC_>Co2SG`~}lEX}l$C ze~UDOx`93yP%;f2U#Da@In;XZ*mONltlz)&X)sXdtSxPf%k(>MUrRzdlHDqflKYrf zsgHJ_wL9z%C;X3IC$+omm(Kq@StmwD#CkTqS8A0IDcLf(ZnGk*E+vZ;iZ;@t*Q-mT zxW!T^6j69$9dtQZ!!q=XjjUi~y2yY!C4Z3_ESFi8eVA9NkN1y)I=4A($n3V6HRqBQ z(wJyu-Lz!CVsJSuZl`7Sg6RBu5<{VA#%Qs=px$!cREyhTaoR}?g+k%M6YCh>wJ9#s zwTZFZk#H0tIi=AtnNsS>>(Oen*qwHp!-j2U^*LmPEa?~P)sgs^I&>^DE;^Zq4(w4V z0@5?Mo;K)JPRT|&0@VK zW$%|%KUyR}WQP#JslRM-bfHkvMlOkUg*479*>LS-Z1--gd-ey!9{qM58-Ml6Dw3LF zPI9Q-KJws}RmhsQynW0?-W(<|nY6$+qkFs3H8 zTT38p@dqtCTCBZiNeqRe3yES~9|hFXX6YET_(K}!M%0F?tk0hk1*<6|ix?b9-v*&j zDCQ=I9#y5u+?cw^eJde~45izx@C!C=!W^N@%ft+0x})MI!Ja9?j%Y-o+^9@GU*#0 zA0Ha+KHAZBv}2_ItZ&>0t8iI4|BwJ#BL6S}Za6W4RG0*0!^}@?Q2?yMlh&gNF`ej% zXz*n3o(Fc|a-|QMHVBF%ajh?iA~sxIJ9plaDHs2W#LCigV9!0@TfcN^V_De*5=Eg1 z7$1jgcm!V>U;d~6m^w}L8xA6kHFVb;(oL73o3KZK>&vw@+hm}1)bNdfN=07~)?+nb@xG8=hRe#`Y zW~S_Tb=zkWW!+~x`6;7wq)Ta`L<%Qb~k2Sl48z8NI0(xB829@z6Es?;gTP^Q!Yeq&Xs z)B(}vu8w!!?;s(qZ2Q?QmXQNksh^qhAdX~i2+``^d)v(L@{UbwoA&Oe zN<9%B+CUs#ccuv3kd>fI-mI3L?{{Fea?u5K=pUVSn}MpMBt!i<(f=%(N~xRBPn~oC zp0Xn3q|T~&<^6&L2D!oX+B!+dlt@n2j_Z?Gt0`Bqc4Q8n!CX-&B4}=rx;5pc4J$}U zC!!3INF*8!qhAuO58MyJQz#nX{`pAH#!qE>j*#Oj!6Zr@T`ur{gg28JRDR6b#&mc< ziHY@(bQJ47c7akif15F94$WV06bb=%Oj*pfty`M*#=qbG$3H&whd(?Rv+bu(pCBuk zlq5ul;R!yE*Gi_o?d9kO^gZ};+jSipb8}8_5?}k$fXWcM; z6Invr&h@5Q#+BU(_+ZVjO$FJh!V4$72-woInomkLB>; z2e&-5Z432&NhH-akbtf`Q-tyd)mYwcUBCIZ4eH*k5CZDp&fC`_SM~H4nUXFvom-t7 z1oeJFh*l~$(p_2@?+YNHykAHLGqQf3UL)%u(@6;D5UF1i!OsqV$yAw*VaiNV@&{J4 zDj*9QtCB3PT)F!E^DkPqY{k;0=bwA-!jh82Z|f?fQet4I7jt>Ph!Sh3G4GeUx$_oN?-z=Wu--2=o9#rzY7ewg9 z&rIe0GCUR-8u39X035^i^H4e*03ZzUIOe9CZpM+AKmPGi5@KMJ3HK9;L|iUcVS%gA zl~5>c-Y>{OLSpL4U;mn4OxF7aZv{sYdI8Do5X0RH@{AKhB$*1(KvHc3eDvO565{PB z8L^B(dtlxzM#~Rxm-E*W(ty0xiO|1e6ZL+{akQRWJ=+AGrIG37;eS9@se?@KIdU3r z2>Glpnswu}uj56%NKve3hf=q3VgzKfQeQIV;$MDk>sTs0$^5)Zp(0l={%nKqwTdD0PQ|sMEt}Q|dcqr=Hxlb<1|n>#bO+ zbG0~6tS6P}7_9ub8Q#~l>yF#6$6>?J=X}J`dw)sLuGE3(s^!c~i;B5*L;O@yrJnO> zJ-2$c3F@b=6n9CXtGFN%jetxC@qT*jSlie!vQ8&baf9i#b;h04Q%7?fli!f(PZ@zA z0VCr{m_o^WK&g{Z*5YtDrcRwPW5(>7np)N-PSnNfcvf3G1%8W*i^;K50JJg*Nw9I# z<_(;0FabO*4q=EP3yk02&hi0)ZGCyO+;r3q;R@iQ-P^VCG2)o@;SXh*{M-I2!6AEz#%=G}2 z8EYhp0mORaG9u_jhs?QR9V9rYL*&XL*blq&J2tI_MJmnH0Mz!w+wVoc5B{7)DF&ZP z_Iyz&V&v=toOzTw>yDnlgvr&+$2bV5M~|M?dsrO+u|8+cdB=}`bnKW4u`W8GZd%cs zWZ)cDnq04&JbM(1X@EY{c$tp7415&*Z;;K+yYIODdTguCuLFrjR>at_DM6-l6L7^k zb`8S&!7%_5e6gJ)KMISbLGLd~QA9!KV$)jT*;E2PkNA91D0zk1$JBudlWX9{g8{L= zv+EyZg|5t=O-9xgiuD#9{ay@$N?Qs=CFvN4PTz&eI}$AFXk753fdg9a?@7>SAk#N; z++ZGNG#u+(0f1Of>Py1~kJplgEQNPYD3rV-XRiVCyirNYnQehI{h7%LS z!vaL(ZLaw1q&A0%-zWu`M!~*O`l~;m35S*b&Ap_goW4;?k!O5-*y|mIi=vHz#3rM@ zzW(y1o)Wj8EDLBlocKm5kaDjJGF0Y`(%!R?nKS29R8;8Ly+i*Y3LIi=Y_y}}bfGH} z3dSpe>-h~jSjiiuOA_DdTR zvzxCvU)?K@>e21g#4%u(k|-BNYI4Q>94YcgXW7eN0on%IQ!vt`OmCI#mjq>tV1zz-Wr@cUI> zbCi4qGV;(`74;L5SPvnw4uKtKo+az_ zCaG8lncge@E@@UZ5uDkqZPjRy(&2iR;Fr?9ZJzJ4aJ+3<{QY3H4{X!7LActe{NHOS@5S8Uk08Gdp5AZGF+|gNouj`vhr*UXC~mN51gz5wC1=1goh&4>v_WvXsp|_R|H!mbS98_P zY?xnIRvZe3fN(H;Y~bMQr~gLQ>5ZsZ*Lec!HvqC;t5E z$-j_wdczaz!na5zNc#<06^7*wcFZ*l8=z1qX(W{^kG+T$njthd@5XP+V%x^~G$|Jl z^xR}%WJP{r)Y&i)W{RG8zM1cjicG=-0v!bXZRqe)PZ>`7Gtp<3WkEg;NhN+zWI+Yym<5} zvRYR_te4HL+F!SqEGI?dolZ~09a>^>QtmGDZZNQpYZ)Vx$EHxSj`UqH`rg7DVy+Ho zF!h0_xwEGm#L|Wp+&3DjmqnV{hdvogziN~PP_dqV%%Ie@ocH+`H%y*89h7=F7{>O( z!6#lg^aNS0A1%)2_JvAkR>qi4OsW^xcnhwnLF;xDN}gc63%PM0$`BF?q1XJ$f=+;F zMy?KwaRv0Yty_4rH0lC&t{@8xa9nsoAPW@3p*IWjl7-Sd*P2sil)5e_e(J*6_2UC=>{RYJc{?AHMVUt$KYu6gj55pI810sY#oLShf;|&jksR6$IAHTLS!L3WZ`2 zv5U>)De(LKUav2hGN@yfH8@H~$C>mz7=TRQF5$4wvM=_j(PqJC=Vewkh<(r$o)8!> zYD#*b_lm3`3$=T8la<~tEHf6*{nX9ZOkFrD;0^e_{-8J5bE@l?kN)R>9o(FXUO#s1 zFlh80p64azP0s>|7FXEyB_x9dc~gbj^b`suRc1~p@%w$pjvYC4=%5{8i<$lK;e%X* z1RQG-+Q%O!7@kfZu4@d$K$_v<;jyvtsuFT^&47TGnY`uKzmCgv_61X+=9bxm+Eoy_ zPq2RqC9j~O+zeQa8w>g6&_g7|;nl}pX7nBho5gCkRo2x^oHnVrqPU>YgFdybK37NH zJ#hHl11MxgpK^tNXD^?B(elfxBegZ*TKGk)q-kwMpMKrly2CqfxO9%{drmYG@sIk3 zx&{W@`?`;Iob4O(jrkxR6f?m2hXlwH`9~yDDog_0aAE=$cnTvSG1&dsU3Qz(24;8K zt#<2RYv0}ncHlzkgx)PIwmW~cWXY1Hbe42VMi?I-9v>gU7g5`ZkH^P`u~YS(Xz~hC zd512#IH_G0OB+_)7xUJ5X#1829*7A|X0IEroqXcVNL6tJ^7grZ`fj-QsIlI z6kU)yd&2*fOH>%jQm})8#_F5=hV!Cy=Dniwupai`8L>+mWkh z?u84l`F~%Wy=?yM#`(SxAJ~D{o45YY|2(zp;a|V^D4IpTQpO zy6??`7vA)|;JiAjL8kLDvlwP=?6duf-4z5|Sxtvy^tyoxg+Z82CX1QTM z%&w5Zo^QUi2#(S?$1`Ry4B!*(}{|Hkl;WKFy=WmE;3tI%xD;*KJ-xdt?elKib>d zTU%R?9656I=urp^ojprdsK@8^o;(S=I*jeuv17_7XQa>90%(;W*p~-@+ctblRIJ~> z^=a-~#rZs-F4Uy@DkuOSLigQLQXxa$FBYrShW~Di^rX#!yk9D7t0qjEpxOIH31>cT zn|y9PSSVlMj&+>v&7Aj3tYU$9Vlj|=j3w^aD7eoWrikI6iMOlyK{feotPcG^29k#GL zY+Sa2ol%kf^8dpRZh3gy7QZs@7g0vM=#SAxd%vWel-htK#_W}k@&}D%`MH1VGl@cc z7k9>VW--2&^@qtrWGYg}$3BJ4N5>-yQQU+@6S7%Tyc;p7_e;hwNT!Rg?JcV1uk<(tN4 zW7}?QJIxz6wr$&XW7|n%+i2`GW@B^ich>yY%$k27dG9^<;5pCUpPg(ScFh|XSLNiw zEo8#;C6SF{F+Fo%DP=zmq=;qO#v&bQC+xgt%+re}um05~BL7G0sJqgoNeNyp&4BDv zt>qO{TcvPaI|g)9@7pR8Jsf4HG6!SfayhJ&o?ZQIYmTg%~v;ay7t8zI`BrX|Gq-0Ec z3&%1cVvoEI3gIrLol@HtRRx8x+;#`@mvXn9e+2AHiaN9bUwrvSq6qw(T&aNWRL}6_ zT(~q>p=^4(?x+Z9-o)qg8KAAzd_z4gRT#rgzgIp&L(meb$}xI~+#J7Nd6rr=`yzCKptlK!{iAEoWH_BBKf1>h8b4G^T1HIzK3~uk_k%qgH) z+i*Es+I~K`<_2-oe$9eUCSJu}9rLZD2hl!avy{ApdfSa$S- z?tXmR!x!xbSvZRrLu5q)Es_3#72i?gzX^^l>rN-dX*EF3A$JH-Rfcb<&q2$^mcyRR zS#?@kpe_?FEs`X?k$^0*)Y74*>H)mP{ITW}UwqFDQwiu)(+_uY#ep*1VP1HMC!~NX zROgJ}EJ2V58w(%2QY>EtM99RJjKumLmD{tQ=mCzU@=xb`br2`p48k&?$2_xI@`fAq zB#+#9Pl~IWub5G|QIB*)se}lhIBU-bz_#cCHSFkJMXmViztE*p+j6q0maa=px?YS+15Y)*e5@^0 z_33Aoaq(8Fn3AR*D2EKOBawuhBE}L~mDqLnOmXYf!z|4DD0>hreW1zzII%h%@X@@r zg{~vY?>YT0^1nBBIX)Z-<|%ks3PY!a2))@2CXT&BU$Dfi1+Ascci~%GlnY~S96(#U zJLG(UC1d)7{}En0NZUE*71EV(-CzNvby8CqzE;$v?bW0DJjnC~a9q--(xhBxxgq>q zwSe&8bzWgmn0BVW<2?b1?I*Mf7g+{uTe>*9m2vp$KTx&J77#PRTsZ3B;v>y{Iz-*1Y78ClS z{dGf}u|feR{)Jn~OY8vV#?)Ln6~Yp)oj`TgF4+`*xJmcB5aVP*f|xr9a%vIg6d#ZN z;~_scXmCdyM9nSylSv9?3i>BFw1P|qZ90;W=Mvh(JXRc)G!5Jp)GX7+65gTv;W8CW zLSRIUGUK+uW91Yiov%)t`ChO221D0>pBAl^k`gQoS3K$@TOtmxXHYA!`nK4tbUG7ozC*B^Z5}6NmSg$KxDSCRB}A835u1-aG@R!`!Mb!B4fmw|CWN97bNR zn`|1{x1_?YNr==Kw~3O0H2nMCAw1dBZH*no=$%(o(j5 zw?p7%xpAF*pzz#hVMWojA*-IY8#GqFu!n&4PRYM~NI3JQ$!#Dw5CZyN6e=Z_Ivy%` z7NJ(z2$wzl7HW)p<6XxBW2(I0)=Q(4u>6ZAu-VvBPH2(!Z*z8p)iMa#zS=!Jpj<9)U6&3cv8h3foq3@LyJ-*`#V0@cai}M+np6n(&P~^k=sJe5saB-d@DGGfq*r zsZ9PaH1qwF?i%V7#u5h(y*R3t)WS#Q=U)gjH`sh{@D?>(t>H0ivu_|Phd zxYh0A1Y!>PhoPu{d zQSwBcD=KV0yB=xu<>@RIyV25%J3p;O!=OTukaJ9;t+RkcJClR}CneU^2r7I$#kYPh z@XLg-X8#08s8ev!F^)OE7?Ycd!>@2?lR1vAlOVzYuDE9i3lQxoBiB6DEv~;ae|ij%6gIX=+{KL6nlvp<(`05J*HJw|U01g~Io$T`mX7x(c(rdgp)Pu>trze~0J2cW zW#EaYZtFlhhtL9_f>g#gyXP2pOUH;=Y9f^(k^?Yi9pJ18|<;v8Wfl2B26lvaU2)l(zk-7u-(4_jtB$)tHnsCdP3F!xO ze%ZXGo5Vn0B~zCD3EJ{09Dn&q3*lq@3m!9>%HJsKqUZ=Vh=2g21@k<0hCv2$JGi4E~$x|e)(^&$hj}C z$T@tCpU&(U5fEfePE?;KJL=u+MukuT)8G$ZJazW|dXoOR(B(($EQvq31jkOZR$eY0IJJzp;XBthz%wp31xrGwk}y~k0l335Sx<;RT{`?@pZeQ_J-b5^|Yod=7rRhK}mO|j7>GoC1& z-h{mch$f$}(iqVb=)bl+3d{c?7rp8UA^!B;M<4Rcg<8+DzG;TIQD1Kiw7?CeuV=>a@R=*pMfY&m%jiO|fq?D@> zDDLe|czj2a0jL0X2+OkBxEEwowLP^Cj5Tl74c&%Eco>eF-&r*$^23sS*P@BLq1o@I z`~8&_>R=~{bc2{0F~2?Ib8PSFzjaUq&7;M#+ULR1{`RImd7h_`W|ATsG`x1&CcJhT z-*CZw0(e`-y5~ENka-{946rFY0Yt2e>NWC}r{ zoVC067eQ0w;Gv=EO?*Xd7+Ow4o;7CTjE7`(QGdJYj0WnSC^lF?k)b38r_O%aq{Qgj zVYB0mWd-tsM+{*w5X<*V_sr7A^1UyhfM?X$>xnG-0jpRgi&ICul4ovAP|5*Ld6Cy<$j_lmIKx;q1SU}; z%8H&AEFztvlF2!`E5tmG{W8qO@yt0X6gBbd*!*Rq&1tDx>#^(7=aZ^MrT(Gu(x&z8 zX5v3nE}Fwtn6qop7%4`M63RyJ_1=izV}~S>*TCaOgh}4AS6I3Wi%_BH{zHq^=i4a> z{e1Rr4HEa9v}2DfEqfw0@|A0Z9K_w>8E^Ybps!#5efj@>D5LKeN#{NIp5eh#rRXwoYsD+}3qF|8qN49026lY3NL&2wuwKsyV7fu!q-GdrxPzegBR= z#u}0+F+37BG9q~;zTmpMcU_;L1tg!I0e%VFUB9uY-Xst#B2TdbHblK5Gr%W$MVtWJ z7s|)z*z_F(GJEQb4*}D$qZjm}-5oKVB>%+EpoyPaT7IwV+ld-T6p&JyU(J!yQP79J z%z*zejY}$9EJE=50}jhnFS*)m0hMcJVus;^?n{111A)w^P-><0?{CG4nLS02+~-y< zDGw{mmYyo{Lm79d`=UVtSFWfb8c4C2@ z=#NFXZ?{)z=#4c!EHV17sT-Z_~HOM<6u@aDSS3Y65XX)r{^7Hc> zr;CiKO?ox;cO9i_**-fLmgfJxbecdn=J^suye+8u`(D}U)$eJ5NFi4syDB`PW#AMJ zY*j~Bj*$C5Pgt6s?@9OPdgH-K_vIVrs-ka4Pg|RXejd?;v-=MR?(ZJtX3ah{Ts$!U zHERlu7v7o?x5w-I?)6dl&D`#uJ^U0bye#-(HR-)vd+r4V--H$QuI7e=X?Sxt#Kjoy zm1k@k4)3~~4?NWKCr(@eX{K8~p7r%nD#K{-<&$NI;ikD5a^dL;&cANql18F5D4|$U z1kLaR1S{vKZ`t)M%v zIJ)c;ZchCf(o5&@T%Gv8#7nD!sNM^wpU314;8gGCRSO0TjzMGZ3FMW1Ky!tfctn@h zWtGf6#u*V1c~SYoR-Rm4;=KrLxPJP16P~|?Pzbj9@VJdnQ@It$PF#xn5wlHm2O2`L zRxEtutd7%rvoEXOJ`n*wt@*lK;FRj~!j_vo$LbRk$=`m6+>M zqv;3zjb+U`LJYId?nDy44)SPt)DIm*H|!M>&&$HmhvZOmf-(^956elCPo4^k3S5CB zQ5&Z$8K1v6nQ-Ois<-oJc!n}3VvZhX6EVdY1Q z;UQRcdl2r|FC?en1>~F;T*vmj+98bbC&WviPMb{Xim#Jb2_KK!elbN-Oh0o_qAlX0 zd)nNw7#@Ge|B3qVrqs!VXStkHsfvm?#RTQ7uNQj`h{9544H^7ihGx^jd}`>*lTF-V z#)WR|3D`k_iVx`B1nE2VtRX}h1Hg5)k(>;A-;;D>YLQm(qr7RSt;zsSV{nl-)IMk# z&GqHqbdRPM5ZVt?#3;wO4ID)G&A%yn3KHbDaR`X;hJX>EPdKS!Jc4yL8dOq9fZXi; z!}&AImOUBCaC65|`?EZg#PQ+$)^tXfi+MJQraor@no{1pRm3RMcswneSK|Y)d;2ag z+x=BYV|9XJJf8l6w%R7I%D*d3$ovH+2q}p~$x#uCV&uGSy;czMQf8cop5=`|(>g8N z&_@z4*?(1eS6tZp7OF6&_9jB0Xu+xiE#(|Z(^wEL{Qfc*xt8lkP*(@7}c*Vi);n@ zcy0R3BqCyq^$dSa;8XmC!)6+fB1$e3Es{W@J~HtQ^tVBROst9sH{Ea8=bx8kKVMh( ztucf79hIB7q@<+xmJ(h@H3PgckM_$7bp}fZD6Bbri`0b|U!iD0Gd;G?(8s>cY$gZD z7#(}mtcP#CD6>29e$U4FUIUY_@tGo1?|a$R!+qIF@!!XwSb>FWZ5L_P)Xu(ja)qzc zdgmyR!8OprIMi}w=o1{-+}a-w1SL`{__Z*`n|vP30~rR-3NU+Yu=i} ze9!&ly?zMu5e<45-u^WoTe9NnU}{nIvXxLkwCtw^&iSbU49m~_e;_Cf%Gaeu}wog~6 zc{r8A$h4HQ&(7gO_U$Y=x?skH!tVrE;nM!?cyE)GNPZCi?TP@cK_j%^CE$x6+I^NE z11lt}hc68!;A-_?nLF#O95xlN?A1ov-%8c#K1s%4aY5$U_#Q0aGC1lyd&bdWY|BQm z#KxN6K|5+4eN*&k+PAoyx1bu~Lh++sfd%p=EhRDvDRI0QDWouf*b3A728rrJ-x04a zTYc0)=+Tw){&%+|CKumRC6VIq=6Fb`e9(;6+wqOe9@D3 zqf@5~JY3O>6aDDi7ZZ2^MYZq*)cR=$|1slS`jan4<9I{RQym_L*};auKOaL~f&URk zm(UUwEdEd}zqG$Yf!VZ2^-~glcfRw>M@8fGg$d@fMA#R& z=QjUNZT=CS5?;l68ZeCWyp1G-VToZcB?<|N@F`bn7d3yiX3U(jXylIX3k|CF@dEl| zQKszf>^=bK2bqgVaJQkzUxwvh&``%`^=*_(UQg;Mh_;&@ADPFncqs3)Wo&EiF7cyw@ za(B|Q<#`60*#?$Ma+%cS5svq}Qo#e7`@rB!V$?Tb727yv@9KDiS_+Iqst4+Ij_hz+ z18N#PCY>|O^?>N()XkK&y>L<|dnH3?ND^Pbb!$ulrIVE$xq+oy5Wno0qGB%wW?q!@{lQ=`|7dp68a=6#;uE9^_C&Y%^`2L4|ugJ|r|Z=@c1)IrtK zps6eJ8 ztY#mAyu4qCS?+}jPOVtr-rmS;=$tFSVKzsAvOpp&UM zS%6d)^K;slxB#UaWDw)1egsRnSSUDsy*(GE5U)NW44WhjnG`k?YnUmb7)v@2IJh0NQoet_-Q#J@VA}Fw+2TT7 zQ$~#}j0O6aP+t80=IE9N-C}34*6}KM>5)Z0;vaP3X|mo2e(Ca%RL+3!dee;0=Pg-~ z+N9U%^wAIh>-+H+uB6LLUxUvMK%{lm`Vr-pGhy9d0?or4%lA3xCz>Z}O~(acJtU7D z9eekAl5Zy}yeMK>UUbsv-Eno5hzpJPq~wez6?shv$k+sF%`Y-qr?x>_U41J zETFU~HZam@UN9*HyKvy$&;4rsU)M1;2i|AOVEMf1cIOVXaR7y-$H|PKZ|yU&CdO6n z;~NpI!_%#@R%Yhb@R7qn$y7`X?xL&F-ZQyzeHo!LbnuY`;+FmbRhbTj(W!s`g&*Po z0#!ztLtqy;?|{Eh*!I%jhSd2~PN1F`O&Fl2fi4Gg@sBN!%C8_8C6ejc3r7>=LZVnF zYb5MqTdN}-GWf6I_X=3WMn#YkUbw+PR=z*~{-5vF=u`xlZ#auE@M5%)boc1BfULTY z`>iFVr$4GfDo$gj6BIXQo1n^qrslwBJXgDrX5TFcmvLBAyZr_14~c84qBd7ZFiIIe zj26QN_ySTde1K%&<|S$R{YVet5R3LhkB8m1(w)zJ2^raxq=eAcj^dy}_8k%MeizDZ zBz5^;mg0#0Ir|dmiGkPyQoT}FSNxBs5JVJz`CfbS35wiK_jgVr5_lE~iI+z{2LcEo zQNflDBFP5!X@=(q#mupA;ybcJmdmFnhZh|1)j%4}~eakQ0B77Z{ zagR@6l3-K(g*%uH_(A0XL?S}1uvbiYHP)?>eim#)!sz@Fwl{4PslL}p375+v4uOR> zGZ8k9_v7QWZ&9NNL4NM%X1uzeTJ=u93(bBztVY65D>l6oQ~hjWB}fwC#E;C&gfoMt zK6V|IZ{I!eoFFIUL92hF*g667NVhsYoX$>nkxU5)%zkPq21;P1i*8yvI0@v9l2N62 zg0dmVd1uC!MiK-w&V7@K#3G;i9He>-59rz#e#~K(y?Xr5SOIHGda|dghpLZud9HV3 zNM?&)*Iz91qD1y^mmJWg)jz^>+^d+EJnYu8vS0g>l(vb! z#Yiw=i`$+p1WaF7__OIY(8Cs`E13&+LI+aySLTRGYz9UytFPa?il-dwHedcanQQzx z5Gp*emj;ZtAA32UbhSEx$_-ELy4f3_q8F6fzBjqss4`kVPT`@K_vCXnrD;#<;sQhfxfmKAU8>6UX!c;v4{*Z!Y5Q?C*#3mVoG$|6$O1hnTuU!W>)aCgvEEQI`8RwSTt z51YEE3ljDpte^_gWB!h5zARlUOM=V6^5vqkpfmr@XVUsiKW|zZgH2aK1O^l;_pP`j z8p2-)MrTI4FVjE6EET3xoUpM%TtJ7caZJC}SC}7ef#w5-?}y&MfNh>WTj90DAEZGE zYxl1^4j2dq*X5i!qdZ5Vmeno=sH=Iooo z{UUX8%OP_2U&`Za_$COc@aSSi#*E|&7t%9XAE&Jw2aI5Gk3;wZEvf1=q-r%dJF$MV z7ViCw-=>Y3sVB0}f)EOscB{%XE1!!Qz5DK#qf7d0?=A` z(iN?iqLctp-|E=SW~of;g)Ne2{BDC{s_Um|tIPW#a1sOWG3HJHEVc&!runm1h;g#b zvJ+>1S<3MX(~?pl4#(@atgcBYzbFT;4z@q^T#jC7DfF{VGm%?=H4a@&0W%REk~T|# zBE3IBIa8Xr?xo!jNKRwqZ}93JZ1D2Oxl|w0*SM#ID$r71YA5S+&1*A(TK4#x@7$t% zbF5OL%T zbCKo43+PwLm<3x9tfOzuG19t#niTvES_9=Q zn2j8Uvu7F&K>^gzi?Ky*WSC@?f53Dk<`0k)oQk$E=2m|t6Gl-D5&?}VSQZ#@KE)Ab zpeRt3n|&1cC-icx*h)W%;V8_%>eKz;G;MQR-{9Gc<6S z_XOw!4YPY5SFIzYGEv;=L8gNEm>r@nxLbz_-~9V~*9mi8jR{%grS)}DwJ0zvkCVQ& zwOI_7eyczRTm{#7qdKW2>0bHCj2SFk{V1}sj_xf&T~B6eGED{vJ3CG$er(2Agw8wt zwMfw=*xn&rp6A`ZpjQtl98aVe zpj!|XBgV2pxw8h~F_<4N{XSpG%Q!Ee#SYte>p!{BOf(2dA*b~lF;l*!sma@8wG-3} zHmq$jUjBuV8CkKnzv@4oxT?S?FDnb!j*VUF>&qESGW#nv^_wemq`Hu}igc&WZ{dgl z7mo<{HpW8~jC}@&k(QS1+2AuGMVAzeQ|@a-xP;*-?Kv;Ge@p(9!l9WlW>t6ob!-=v z!=E{DwH;YJ^}MQ~XvnyZBuH+1Q4*3Vu^m1MhNcwT%IdmOKl}ySWs!U-hX^Z>@$#51 zot@)dqKH>YW#QgA#1`eAQQX*ZK(e13p;%J+`L55s+h_6n=+JRvhkYNvh7vlFp`?%_fTn_|6Vw4U4Ihoeb( zHO7lgl)#q-XTXexPLB2>xQ2<4qaP$mk)=k(Nw;mu?{j}r6(PoOS$kd$goaYiuUo@d zuJIOmS4f1~g;r090almQnPfOYee$N}%0?TYuA-~`_^Mk~T^S}GJ{W~TXkm-VL&#W& z_!Ht-1qZeCD=#>Nkld!rvJMvrOYRza=t)Py*`8nGwbk}k`IM`H@$|ia)BtVzi@o_t zp&7f`?%xELhF<^scEj{(k;qg}SbpC-?%{>&=lxK0f_w$$hTgs-__0nW`t}GYsIWnS z@3@uyeY8fJ!6P{+D7aLQiP?!$HaIZ!jjubmr0K$N%!{yl|%j*5aEWoL1kyxL?I^Ykfz4T`(7Vmb&RdN zNvep7%aI_~z6(h-J(5uC9ardSJF-PbtIbE<9f zW>BMSRxAkFY7|j_RirNx=0gC2{TTD>FHdP33bq^tE`HD7Hs{!yr9{L_eNfPg5iSW} zE=KW5n-MKG;^gwR2Dyh6y1zDP&_mEfRmyp-m3Xw}4SsAO&8_R(ev@k+_1Oln^Y$!h zAW6e42-uuN5jO{62=tiV7dKB`(lck1C3^OT8ttkmgtF4lrLvvydig|zcEH+Fccs{j zp*8$UF~2V}F;=jY_r+Ezi!!sDncw)q7}wkRwq;?T+xr*W_Jj>y_t3YqPDR`?zt-dy zz=7=1@HZxBZp{*?UKC>RJxX7RjI(RX(9SIIeqcd+ikBEAqi&E^CO#H(%XMC{E}|f5 zeHEUNEUo7KdDGsIn82HIyFY!L)G;d!J;6h2IA6ePz2Fd4fPGPHePuHBdPt3Vrq7o? zof)4%HGkq9Qxf>_{e%QQ*;Cl!Pw?1xu~N3q#pnL=KZV9kHPjeqhJ>g1$&YTh8QkaE zT7I-EbZ5PvU6?~sy){{fSc?$uNH0YZYAqGfxu6&A1C-R_rBv$@+@KY((i85J_eNOgP zD-NRTud*2YXIA8w3N#_20*XGr&KUHxo+nl5`0A&{sR!Gp&wyjmO={K20$r(GWH4D( z6B2>volzm%j1$e$8 z2BV!9Dkr3JjL8vk5p4Rgo+AHjgviB1PHikG&_1CN&0+z|%Duw6BEP zSxmBq-v9$=s+|;8nsuq8;l`7IIyf+W-%bNcw}6Faix_dW7bVY9>ffNKDd~4$F)lOb zH!IX%F$!+VX{636Lg}?mj2Aee^tVTk&qtvN3YB+^mRbm&;`Z5h*=dB1-^^Rq)N1Nf zQwhJcT7#@CS^_!3>eza;MQV;LRFl5jOhu0^&Qk#g(j6)4ub%H3pMB7RPj(GI?Sg^j z<~e!%YcBBlNSL^rIxc z%5XkX1~U!@=su=jhGa^~$@wiYS>zMixKz_wUqeF|!44nI^(K}|a^n|02fm%*I4CY} z84Yu&RA0s%1s!gZ7ya56xN}0ABPt^Ti60Z)E~u4wZAAAdSH^UrpBWw?%J?C{5+=4u z7#1f;4{Rb^850Z%v9n+EbeJ@@zwZ1$T^MJQbi;;C|Mjvf(s}Az3kG%m zhVtbX&EcGJIX1lSslnt;CjI_1VOINomv#0ha0_41_wRtTmx!t(5qPvj!3WFbO0Sfi zmHOw&RsfsNmJ-uG9M-qAMBwOy8nGWLO^o_SO3pha=52zs@teNWs`}0iYQ4R5Z`2A>#(N zWyVIc6XB33A)M9LB&``cw|*`@t{b2;qYW{ey%a6N)93bB(`YK}=SXHe5+EZWA;p`7 z-rPhMH)?NpH3iU9-4upVa6a!~Rrir5fWJQ<9FDkManjJzLghR+KT-O56hDvYq}J3h zHcS%tz~UbOg4gA+V>=Tz&1< zIh-gf6Y&HQ#ArWVXoNWS8-Z*Z+^coLE!It3MW+Ndgn>*KO)VT)quPGd8aJ*gWN`t& z)V`1ROTS!*`$PWRQJA}k_Yq-^epunsU~_SJ^TC1!LuU1W^&RIt)rJ{liWGDq2xJ#T zv0t?$;{C^uQZtfumI{ksvm}^2t+Qv4`Tyk{l1zZa7 z)@{dz<#FW!ijar4`;d7ndI}C-Pv*|C1fbDi_vWGKi=Hd!Sg_34F6~lo0s<4{$0q;s z2X;J%?gGsHG=8n9mxF!-Vv7EP`sWWj9rp6fG{W`RRP$y1l_S~XVK_KAOS<#4$)QYV z$N8WxhhEaAv5XKkT|;XIo78uz=S(3%7;l4=eM#+2xTxl2bC?uCOjwzTEu9Rc>ds;NzLpsl=+(^A%;i|s^vx{j9EH8 z`k144d4kwCVSxd}5Fcv*k+P@bruLOk@y3VL0zmrSbfh&0N+2^{B~T{~L}w<|p_yaR zM`%`1lHp23$U$Q+tWRf}x^SZ-7!v0c2?@y$(>d*^oE4mKw9JpQOcb1`g;UW$_;-dv z#7A2t(N*R0C^jrtFg8_b!bmFB!{UomB5MW=&^=}|HPD2_Ua~7Y!&C8&dnK)MBPc0$;v=lK zB4g(Qg`q-~!T*Ur08PRpEnDhj*Zz`~8GTNa#L_zpd~lA(<)6>?%XPsGw`I0V!3wbk zpuy1xh=D%sUzsv6yH&5aM}nOw<6SC%j18DDW&1%0g4{!V({HV|b#&nibSWD&pV~;` zjOgy@Im(fI1ZD)}gCwae0D5hVQahax2Ev$9GAu($JN3zd_w|ij%wM$ve(ulAy0qgJ zrRGaul}H}yTJj=A_zB`!?RNLSqm|Y*TyyPa!`C2K*6d9E=bMx`ffshoa4^>Q{C`@_ zcIyp3bPXk4u($4=p8|eAkw+`aJJqNi%esYVFd{#GEh_3zd~;cBOq+?5h~ImW+Fq5S z4y-P1y6r7Lo(zV-8>OBUl(lA=ADfp zWK~PSp9zEe&6Cwh|o$h z%4Wu4qLnDZOBXRZI!Rs(@xiHRYGS>pXjY)MJKhZj!Q7$j6o^K<-{6YNlGiY%WANoj zmlrx=B@A7K8|P!AW`wwVY%npFBUtb-lYASBE1}$%-}>#wiN5_1MD$irQ$tw$m7_}U zb)!+SUjT5J{2EI-dpuu->^aI+G|ch4kiI~&Iy+r8dVg8g`gl>_O+m`+wNp1+ho50# zIaU$!E4+)Uz$RFXUK;YAXUB~Q9Wa1*eoQc*ie8Igv&#RA0+q?|5yoA)p0Wq4;9{OY3XThP(hzOcwB6zVkhg26Cd3_P|PI-Ifenxtf!ETlSJPj+LgR z07G)~XRJ4;5KO5wO(gE@P*yDGr$N#K*cgk;+k+*+kwzI5sky$EC%Vdvh%v|W-3{6W z33FcCBVh_RT*XlYdhclHt71Xp7$KxWaiU<{uMFxNSy)(Y84l~t%zKg5x)0CU11|a^ zi)|b;-MloBmCclYOMq`)pfIIVWU3+8es^mq)KRT z9SBzjPFkFl*|AznGtDm2HdIcv+hbjv2`wZG@J~!-$p_`I&?6Mm1-}`V&}T`^6-&G% z^O&>$afcdHjh4XDi85}7U;Czd>JYyX;jt^?(~(_$N6=a@TBINTFJd?sCaOalF#$>>B50ce;*vN;}5Mqy}k5Ed54! zvYLi@#JgEd?`mM|ck+3R7%t@VoxAlmnhf}j=E=f^sr^#h$<=iB4%?HIBTj7};l1xz z9NJDh4Kuac-L8v}oZ9RjeJWkXo*Dk|B8O=JU#~Ok7$V{O)_1zEmQ`cWm(!k*RAmgpSJ>cbBBvpV687ceJz2nDb_rRWxR;1)BuWkfd7Fx{G? zsI8tD>b+X5DO0zkvNG{27Ov$%tYs9g+qoJW$)OdmwqvREX`c@=-#ZZQvvG-T@bLZe z5H~{AKMR1z|H4=k=(46Z>}8;S+|OKPPJfi0&bpd(wX}C0!qMjoL!7p~aK64yEGsv1 zsKbVQN2Fw0QcgS34#USG7F6iiDUC|_TlP^0Vq%DA&k`bucUozrR;g;Fx6$rn;D7xG z$_J^Bc9-aAWEgcg&Hn^oEC5VElC^f>Wd0Wd2=}LimX?VRJnP;UaO2}TC=@2x98xH) z$WiK(1wf!p9?t_=)gJQYOfl=uS-1uw)D*ejfH4cgAqp&?JnU=n^g8AwV?AoP7w4WP z`ERK~*3_q=9dhVt3G&F_ap~*?;F0(X&%kpJyrHG%z-gx=4deL${qI1pWZ zoxAfM6C{QA!iJ}0^DOpo5N3UScVOD-u?gu)s7EsWRk30Oh*2nG-*p3vTC=^Q(xikE zpn=`T)B1{QU(x%OLp{S7O^81zloEcjj>m|uja8?bs$Jw_{RQFDK!2}f3Xjtgzo!%+ zFY=M!8l7VJpr9KR#2dI|X>gVotjEfY0@4!w1Q^f`c;O#ZJMTbyl5T&Vt{j2%X;LnA zk#s_YTfM=3(n(cIq0l>PL8)ZfbL0v}!J!v2fK5ZU=CEJGEw)s8%B8BOPjCu<%*C!I^AH%R%LEe18eXOY=$sbaq9qR+eWfk?3}b33 zLk?R_x5rvScR1^#oQIGoCi42RA7#sI#Pcj!=wP@y)bl2U;s~N84!yK4@{-jW>Mf7w zVk%WZiKZqzLVOz7%TD+MfqU1qQgK*Gv4gk9{Qd&IzjHcNc}@k0rkQ}8I#t&97|>Ib zrj4tX%X<;-UCf-JTYlKHMESYi_7wDM%v^WU=DST-SE<)qVRxDM8K(?7Y7B%F-|f2+ zAt;krsNa5R?LR1?X%pKk$u_l5QnJkVafS2>ba;7kCqx5_0l3*?0OOeL@HoZErl+A2 zJvqX}MmgUm#?URcIzH~aqJ4^2th!&Ov=W`y4Qlbb&+By@bwW5Y(DVxt!v{L7h#B z36I1~YQAulQA1HkWJ2|GNfDxGCX9_=GM}U$h3v?J3kAPVa&zIYx=(huG{OjtEib#r zTEBOv&Q`M-TV@!HZ{PHMpAT}|?g~QCU)2@f{#LYO{e6U=c$s0aX!{r0VB!R?!-#e4 z()kT4uBwsakcu|l%wO^f+DD2A=2}?>$J{xj)@%2UUL-yCD0mFTvl(H^kih?6-APCe z3r$gU{a;gB%FaAH?)kVMdmP_Y2 z#jac)*l=MrSnatayRYHg4d7e>n{M&ufC$0f~8NR&$5m_4c-*gg z@{`io1YXZmU*Mu%X4EckjJd8Lr9c+5Xq;ii!w@3;66nqb4OFHs@A^~c{jpoWVu1N? zR|#W5kH8%SQl0*Od5p2axwAowRE*|k5$D*+fqB$ZS?C?E)LDt=B$#_&Idr=rvkS=Jul_EfJreXG^jJd1*bu(1f1B$ zWIEIL*dtg)VoB4!Jcg;2(0t6qH90zQ5%A{_3pQ+_Xicn-@6Y~mj_lsg0A2FUUH5-} z{M(W5v3NP_KsS^7d6O;?e+VClSoyBLd93pov-;UR?6-*MWV?FT=BMd5)l!rB+%z-u zw$}b)$6(clJ?Ed$W!^8*&6Ym584EU)*Xtv?ROlZ~IZliPkbDx+9$lRC>= z-jB<68QowD+)}rY`Jox%8@Vf{(^=3Ky~I9|p4q~23MdbKt1+0W)!y*@H<`4iqu|gv zzAkOrLqkJY@`|&^Bh&8ilpJdGYhNS^4C%|_IHnoOv-KO<;x$<0sOCx7XlFwDN)=`{ zkFqt?%oiyXa1r1f1!%_&v0iQnH#2n&61~klB&#U<9&~rI8Eu# z?a-Y@EkL&-wzhkSh z8@n+lNu$QLZKttq+qRuFb{eZ;V;hZ~{Lklm{~p})e6DNG%$$Ap-tVb%7z(Nxn};grQaib3gGaG-MNQQWi@!k|W>;%ei?Y}}Ttg=o9RBS&`JLkUH# zK_hP0jQi*A&{yyNj(p;f0JrbBo}b&Jke|n-6D+Ixo7)#ujORd(dn)JIC*K^hVa21A zkohef)H8$@%E9m(O29$Dej z_4J~hG2>Left+bRDgLN;V9YW)(*M|#zj&1sd)w*oNLv0p($&xHmSoC6VSwWxnZYB< zHe3kUZ!%M{rOV+CAv^{r{9eSf{k>;k59#9+mwq0+bJ%lkxC&5qjSmw@jv7?}iyb{Q z+w=p6zvR%2*5GVUQyhvJC^vIv$|kd<|Gl9E_b^=-K${R1}Mdz?g z2G(w(NXcA$Zz3EK?dwDX=c40kh^)KuTH-da{`t`@7{2qsJ(NH*@%$k_$@75tY-ZoJTI}m&8D@2gX~Hd zTgHZh^h=_O5(ylvs#ZdNO@DH}ZfVmHD*zpb6}A9*yhTA+eOSc%Z^p=o=iL+TE#12v zmC2MH2X8K0VFNsLF03=mZssTecCeo*Id2`6;?eu|tpDk7*mq(9by0lT_0l5n&KhnR zzhKe=e)m7&EH$E$!ByJa$Id2jpZ(YDG<)@e4d6zrbYWqJEzr%?a1*m~mdPH!3nPSl z8cM9*BTT1mUPxWNkNNA8YuMYA&AZGM-hA~Y)q@?;?oMG#W%@k58f6VDilYp_7r4ZI zpU)~X2>{w|0wWU;JoPs#EmO~E1%O9xeyiK((TsN;L8Nkh$LgPkHPrxFeEB|**g*i` z*S9%~<(C!<&&&BTdg?5f0m-sFHh1)(avFYqBDB0k`POc;N&8!W>wv%n+-GSph}RN< z?;6=1b`9@VRq$ip=pcpEa*Kw74OuW)g_TVIa)_Tzy28CzFv~=Dv1#BHdeBJ&ws_sZ z*&e;HY=j+I9;Rvk%M0OY*)%)(Y{b7RrHaq{tq=FZBF^Kz3zXO5=Oh8I8Jy_U6I_pm zT*;E@QM(FRW_W8JRw7^wwvyyC^!!C%v|0hD(G6{cvgB}|l9nd$UgN&(R=UP@h^+f> zaZ6pc*Z;@xHju6NxzQJpBrJ=;gj8;h*FZCLp>TSK4oBr}4HJxVMMG!OA-Ed_5$3(~!B25=dC5RWM}%=?X6KPrOSVFAh*uelx#0WWCBXY z`AnpNnfsO6eyeyIcznVlJDAkZ;K81vG{Y)zZ~l2ZwrRXk3z1ee3*Bp(bRsBQ?Ar24 z*GM9byC7vnV)_k6fH-yEOPbVbJ}Zp#X{15s_J=4P7IMb+O^atv% z1hiYRlUQu)`Rh@QKF;$Ps>~3MW5n$QFzKCQm{qL;nMW7~QIOyMsE5G5$T9)deN_iKE&^0uz{H!uEi$ICD|bF4cU z0;nCBp$@A&mpzGdr_ppV;UwW&I_Mg@iS|E@6)od zhu&Mo+qEuDe6MLOJ*x*z8%95p$#K&HTJh)LXcE5zAB^bulgjadLal0o`D!JcGpU=D zX8^zsi_V&ZDql*EJ9>!TvSuq+wz2m!H5pSbT|q}vQ%zZ!#ZpOCR~OkD(3zW>Qm%}; z!YC*zs;aV0?J!bKB;OTUX*pYDtZU*=#liU9d3&a06yht#R7`ZsKkn#1Hh0y}sBSyr zbZm%TmMrVmKRHeOp#^5hp~)zha;lU^@4GU?l&tgwXDskD)L7UWQyZJ=l5d6@K5Dje z$T*AB<+L_lZf7SrT-h%pFtsuOajDCRc>$*!JVL%uiQLPyV*_TF0VU!9%*ba*d?1o! zO7LhYp12{`W5_W>rZma+hxq)#uqS{JdTIJwC|9<4;o7F-nl`cH+Nr}>Hn<~r={EVG z2m`lvk-xWbaA2B5wJ4LN=6Bidgw4oT*4WrpSqX7f-=-n|eCeE~)R4>B?BkG3Jr79D z>YjD=fvtjCmgGjaK23Wt{M$keU{*;6>Kt{7O0qxNuU*2QtV>SKXDxXG=CBclEh{#y z6REmvroS=8dyW4#E*>0kP$=Si48HT(=ejJ(cVDTv&0N<8On=`BcNK6EWdDPpB+Q;G zWh2`i>9s_+B!@ z-rt`ev|%Ec?bi{r?Htk1vq51ra@-b;IEDvKgPb|d?1q}$JPLf7b_tH2Up7Ssb`&Vk zjY_#kNf zy*%6_ZzJCi2rRumT&fXHvjNxYq_;nj)3&yv6j`))d`|PBr}SHqqj9s^5&N?^JeQb_ zgO7GHQM|2lj!P=T49bW3HY&yQJ~@Vn2@ECe}pRKWKw^R1es7J{pL&^D@bf)XVdU*%?UfKrhdhH5*8+{%VG z=+x`2FtbffbuBrfQGK@y1w@=-fdzXYH0Z4nTmz8^Wqq<<1C|K2mm7R&8wytfHO}cD z;)!8G`)B+1GLQ()M_jk;_2TShZ!aKMji}wqSMSc^iNp7q49fq;`(HJsHkWMDm|@JQ z#oovY28yWWAjUAz$`SwJliK+I9ilEj$)5|LbaN=h)cbcD7Gu|hl!%I!h~|=^-feVY zyB;sbg|5ElFqUmZ^pv){-cKFL=&C3vs36`1f~c2JDhnyJkc{hgS|88wVX}${ zCIheYdploQ*)Df;<{OgW(@~)@IuCmnN2B#0a$*OG(ed}`r?k~Pg}TbIW-W5DZ#Fz) zGAfUcx*gDh@p9U1;g;7pK*2+!owXf-!SCKa$2zy?dZ0$MK;M(`;36$||Lr{77ZfU# zfn_&ao@6D$HP_QR_<1|UrO!>RqsbhI6SY2SH6AZ(o?AhLV(#PfJ~uCd7AyGv8%}fx z@eIQ~R}f~sIB&L>s4d4rBj;Tk0VjMYB}o(p%jQ=>wi9wDLNef7=(PXz43z18K0GTB zQ*1h-fXUEPC8q|eR>0HyreGfqN{~|AKt{;BAQ%`aic)7=TU)l_Krnnt3gC3&_=hOp zi$Rs_#djGQIi84qXGCN1laPji!C%(k3n%OjF+#|juK*#OU06#?l9knLD)^GR|F-J5uXkF&C@^%x>Q4SUWA0l5hN zU>5&(%o^DKdtt(AoDX`xZuOjI>UPTu9r@ZnAIfGatOxJwBr)N+rIj%GSxn3cvE~tS z6`S#Cz}!a@uuB5s<5glR*gk&?6EbinNC>jCP#LDMM%eGCgA7#8$Z*@e+7zxC!ahhI zQTecEVM)kI9LSyO+Rp>Wf_7F5;1XGZ*`J8l6<`2j)}U=4TIf)6pDV^MOZ8>Sz+|cJ z!OD67V=V;+O8I{q4|QF>?*3Z_%~UYD%I6>ZQ$-lSseZptG3|9eH3D%XAjW%N3z!`B z#0Edo<({C(O}RPK?|miM+8)2#;M(fKrdu+UZyOFHUph5mC7RBk;ff{d=6Gb!tq`G5LIX!q!VM)TJh*7=`V!6hI_^6A@8w0$xo;(Qj{P3&SM^e$dQVP$tS>urqxvRr|{phxV{45%3q@O#;_-V^s77nNw ze!Qcu4Yf+8`ZIiZR0~#087TOxsE(^)tKjR|xboQh;}GA#t8Rh#LwdSO67)My4-d+h zq>4p^NTNGX@Xif<$gC5-4b(dZSR^632*uI?XBL+0clHI;>%BcdeL(Io7}!#eP|E=q z^uolz5KKtO>sr{^iE|-LzXC2+qjc0F9D=*`tx{OqH4!_fNjnLP+ty$3$mcm6md1r) z$)%2TZoX(lvF&ws>Ft0;TKmi9b|Qonk-z_?)P^^ZL~uNwQH=DJ@1F74Jw8#6>&CbJ z?DT6Q77GGGn$vM?6a?w-*D&Dhx+UwpU`Ofz$M|?lX0oh;YFaM3N=e1>!oc9N3E^< zNHS2OpD|8{4jgqI$0%`RuNZ!f=(jSauW(x~qDqA8BVfI>4j8Z(mzJiodE9n~IwX@yWwJH2wLk@hg)n!ZyL*!LjZ27MYmipC z@cyo0Tf&DpC+^2%q&g}pN*WqET3UK4P`wx=FrP3GzAMu3KdBo)IZ$yRwm!QVjZU$#{5sYSp@80SJil;tHX5v zNmE9T=gW+ow9_r^UB6AFnN2!#B$!5(7|p@NpG@z9>IWnz1nWeKe`Qh7I2P&a&-%7) z%+R@j-AsB_CIHYzQv8Y>2COqyRw9ia@8Rboj5^3znUOES#jM?RbzUYW>39!feeV^` z%{Jr76#yRsJd4E`T@8!>h zg~A9q?C~l~N&?KbgY&<)KnlY5pGMy-j^Q!r(z%2Z{1C(K;QB&m*S7hGAlmMCDH{>O zON7_mwz>hBGZiBCglU=&6?%k@_cis-97-b#_X+_LOlar}P|zX4@48?|Dl02No_9|l z@35nsk(ym?h7+kZ9w+aCidhxKqDSYD-3a?0edqgSJz(m`vUu4AW9Q(3 zpz$e6XS58gU`~)&7}&9k!UZ=g8}6JZhLB?xBEvA*Q`HZa?_mt(?QC0P-GVPafryx+NQji5@7iJrWq*VX$W+Y2`B#UW5_8dV0>Xi z-V^XHE=lc>r*c)QH1h$pX(PR;s#D%hrL9VT&pGL4+iClN8HiIFnG43^*9u8!$!N^s zTEOAB7CRmF{JXE8n;SKt-=EwteYwksiNUGXYI*6pO`Xngx=f~>FO|vA)6>&bVl8NE z!&K=U1h)-$-_s*7G`f-TIuq+~5Ts4`*lQi%W8% z7-K4Gdt7Ql)sJ^~lbIZQUANfrwlq=+)vi9^0lvWAO=ZmaKf=ZCsaDdUm!AsFJou6b z(R}_#Q>oQhFw`_mV}Tyv#24=ft(S4*CgKdUb*%~CLX5kMy3drbb%Em9rYh9-GY>zP z6StT72UAF{$DYrKXcE2;uav1)=R}?1%FSSxws;X97(e{-+bm{)i6PJf*KmYN4bFxv z{v z9t1#Un-{vlh#j5E+FV{jeQ1P z%ZR25E}Q$Ws!yH95Hw}j8*^b))>n;4F6?deqru-{@pXMe?P&w;hjpMZdg&f1aNf96x2ZjD96)HspEc*cN$nWCYw?^dL zO%ZI9iYgPnrF-%Dj8W}s?EiK=l(h3RxkN^#9@nB7Gq|!@oIcMtSODc)r@7qlaFXZ# zeqOK?2OHb?@h91EhFFv+k9brOnpSv)t6edjp2tCm-{<30r)#&eCXeNKGM+r zw`$r1v{83k+i@UbYCC4<#nW01xnJDTRj5U+j0~$dt>ZU` zN_GHihaF_f<$u|YcfJWkJ~_$N5@MME`9y=ew6>&3nLhuzMjmraw_+xRbDKNA)l?-P zw_cIYkL0=?8xCEwVnMK)zNwx>?Dvn^A}Op&|}1c;e$Vu$<|FXqAU|1`Abq(aFGWhm>TuX}^Md%4``tgN)6md(^r zR)+oWJD|WsNJ&kdO>n6>c5-d|_k*+ipO0*3;wm|+-A;rH=uJjaFz9faI3|{*PU-7c zTp{CAl7$=;xXJQtaloXXW26hj1{EwqbXjPHCcdszjjFFKqRIpXE2AP7~Xy)$XX&V3qsx84K8 zuvg)|3B?1C4D${-kJ~rvNXh%VLr95I_3`J@xM%>{2J4}#pwQ<190_pKIDpROWZpbb zhKZK;)*T^R4hMTnBgc48m!QEND&o)o%1F&G*W^?+e+?%3s`BdU2Y0@HgZk=f=Yw%X z39?8l^yz%5Cj!S_r(jc%rUcBgbZ}vS&3uW~tU@b8HA)lReK{rbZVONR7Gh@hkYyI9 zA){tV^tyA<+>$KGSWQ1cveyI(DV8v@8b|Q&+8%X^LC-= z^ZnS~_wCOT6Y6@FGD)irsbp=;5y1qKpi%ZQT^o;Wxn4^@F!zRPxfyiEL85tNmINVxq|D|S-~K7^%3St}bI zDJ2E=z!~EgIa9m7EZ9(Sd_Ipx>@4V#ybq+>hr|SRFVDWM!1@4Q( zj)$6Go1mY&P?~1`R&$;;)Wdx+d1QE#nwpxF@Dbqnzskxm_T4rA2AfVW>a;mr2SP_x zRaw)~(QVjqdHTSa5`Bz_^+E6>2OTSQy_`nb_r9wsDoW~ZG)G3B{`te&yQQzq+fd8+ zt%$B&9%kC|0YXdX^xMiSv3q9l!e;_$-56U23Xter1?3EudXm44Hzv2cXe`HtD=N$b z1Vofqvd!fLqCuICm9(|t0`bN4N&9BL-DkVc7A8P3z(R%%89eRUzz;@oDK)_9m~bXc z6=;lQC4wwLL#YbVgKd~5(!^oKt+js8bt;|td^xL2D#t}J=A|H#v;Ww>eSUp;(P89T zNu-=Onh~&HZN^hoT{Ja4m{b>@n<(m{6a8SK3H+Mp`(Mf5=yU_t%RC-8&T(b4KstzL zcM`R7Ni7cE_g*S<{ad@*8<-N5)@DQKWx-M>*oCb74>8N>#Dh$20yEXqS&WrgH%S(? z%L(h#vF~~J3s=q(8)cnrSdk}%g@w@f-Wk5l8(viGy})Du_#+f_tu(tyURtChvs?Yw zzA(_%|DJ?U+ZVE8MLv|<$PP^ZF|S&h#4L82e8xBr&M@y`ibqK3er3$wIDM~q znXRI@7}Lnz?`DAfSfh9Xo6-`3-{T;~uj^^IX?VDVWQkg)+@W(rR5WD1bTMfWZ#cLt ztB}cU)AzrSR3I&{_NVC!xu;(~ySd`pbrV+%!wBH_E+(4`W9>UX#-Z?f)sV_FGaY)t zhhyjH=HXt6B1fjIEN~J0jFDv_bJV#ec22ul5ehjgRnpOM9*hhwdOMsk52fqvcu5_h z!?B0Tx?L;n_wG4c`{h6rzax{2CTjeCVqVWF`On#xro49>pf#u9fJObh zqJfH=7-uUZPbtkBZ-p^xw9$kF&s)=Fwq1=zWa_dwT>$#7M@ zO#9+E{H}Ms5+Fd1&ny zofLM|0%6qM*=gIfP!do0{;W@}}75?G4D6X}+IXWgL!I@C7R2r$AARuC<8y+rf z5O~Rz0S|T0vBZP?IcqB_Y@D=u)|`_xN&+lMy^thB**J#xuA6ZI*9%Ycf#C6*oAKRU z)?aJJiH7%l`-ZW^svpSY@h4qZl%@&NZUC!IeBLFLUf5CMul9ZBgZ3y>7%>$oO5OJd z^m%hOB9CgEUw>;-lBm^|my=b~JP~j4!;tONRr%#ET-vc_~12BQ3@6XDTN6d z?^(@WaZJK@r9A?qXkn@H+E5eXYo@Hq(* z4?f>|$sbnqoRCi(U^hA@O(;3%Yn}J9I_xdmmJ5H!7KAGF9qi^Fdj)l{Ucv&e{McD7 zAD+2BCNL&nxG$LO|G9D{Kt~<)jrH|@`huzI5f0Y!-0Du!jyn4qrt3RzfxH_a(6yY$ms5qHs%I9&z>wLwqD;oh=C>owFSOR$Jv#Tp& zA|f8g{gn*1924DWpqX#A`HRqT3IzXAD~`q2A$m-%Jl#>Njj#0PPq!ECNwIS+OG7De zeCd>o_oNC4JdbKGGZ*nfJ7h_r7er{tR8ZyRR;E>_S)Ug3rl>}vhJ-qIeT~4NZ4daz ze3cGbj}hV)E-{w%_`N2zs~m)VM7~r+vcxZk2i}Kw@zXos9n|i@uYFASMoQ^aMRThTD%A>1b(bzkM?X(1K)m)38SI8EW}X z9(ytB2#8Ta)j$R5+{mp^E{n&C5DamL=Abh5E$aQ766G&^5b1JYQXx}T43%<%M5T60 z8PY%i9%1>Ft4PECCub5`)Eg1~-**`)P}E4(hIZp!<_?0h4A{O1#9TcGdZgI*&7WT* z!dW&`NVZV3qj_eFkq0Y9c|3vD4F_(k)P%FbZ$%$d&~L+Eo;ujnY)!HO(sFf0f!wnS zo{|9wnyBg93`nkGb)-3AS@-U65eDJRboj8=BG|M6Uo*WHqX)5~e0*_M~6C(qKzI-aTp zH2y@G5L%$iG)FcR zEcJA+vA?;(5{V ze!6TV^_@o=-X-C&`$GWChM(mILMZuaZ<_WG1z87;!|r-0bYzw;o&Wd$x^ahh>{{ zt9R%2TnRLmpqICqi&JG^RRk8@EH;GFd=F)1tY0EYsTBg1)Vfe_N05N9Lb5D}G$vcM}h3DFQxtIxu@x5}1C>WdK*#w(sJH$hi*v z9f=bU29do(4t=eMv7BP4To?Fu9QvrX3!WsBN*dK&C(uNZOqI!I@c@s_j*hX(g_C1= zV)ZYcr*WF8H>=i6ojSRvr&>UIXT%S)$#hOmPN^l9&0tcMh1arWzU=QaKT?oKlji_;8r$dYc=J9`+%cks>ng z;vJ7FItGK3f4{eWv3DM_-qB!36ZYkZ)-;WgH4A^fZ)AQ+`LcvdWD2TENofwBM6-sM zWGRI^tiknxM`lNUGyeO}i=cZ1{lD;810f+p+l%DP%m|?Q5fv3Zew}snLD7TmwIM-t zzi3GVDppjKbiZ(c!cUf$b4cdFU&xivbg)cH(c2$2Gw18`6{k(&nh43)Igh-FshH^N zkA3s;i8}X%~N><@L70(XU24A!=xbN%L7yeV)!G?i^&4Xu@x9YF7{!cZnMNczN~_-=8SqORu*%E6#g0s1x- zm1G<&tVAqKa!ZM9LVo#eS@@YiU?U+oK%RG`R<_CqPo;cnbX4VesY0=YCs>_F%-`B{ zB-$vat`gzW;3la#WN$_X(|V1p$k6^LhlVeCz$6k}F?^(V2gheN9thoabDQz{8W*4e z>*a{Us&FwwWDn)_cFggW5S8!c_)5>~B8EAagNj94{)$W3 zM}F3~vVyyG_W6q(>>+354fT5iA`<&cQQXJJ{+Ke2B4MJo!W-WVGDn}>s4tRmUN`mS zFmA?lq64$BH8mD%9@}UDZ6!5-25^|pNMA+6$O!Z@3^aoJIY~UM=GFY#4Qn|vl88GE zCeG}JFE|LI1SCEE!Fg)KEPOy-T88h@#d1ih)#ml&njYi-T-zY+dh zQ19Y$*R4dZxGvWgG^IHLEF~2Wh7$Q%bEHm@jIm2{n@LqJO&kqL@1^E7rs)T4=3v0A$;XJAnxntr}Fc4dNUV5LJvU z=^2Z$uI1=_12Ms}L-F7a13f)##-*zldYShaNvQcQa9j|46NrV4oth@k&8Wtf+}z(| zIOeohx=*H(TtzNtL`LfzLcbJ;bY=h3Aj7Uy ztn|h;b$wp!>eU#W4Wy@+oWJZb=ps>utsz*1(>8>P+7NkL;s&mva=AiKAN{ni!XX_B zd_XUn|Ep-iz{cB86j+}NEa(|CUs&Y2> z&q+JCwhd^KC7he8^$h(wJyy=ux0W zb_{Ue2mA_V?KfZNq(_jRlkmdt2L{HwFJ!;UtPcJtrkfWfQu#q{DtJO^my_6;D8Ups zU_#gLNmSiTf-r!IRO}(j!Wy!73|vB2Ih|swI$B!(oKGUtI90r2Mr=gdczxtNT=KGv zlr9cZg+Urd_iBS#f$2TOH=^VXJ76FEzbPnQ$vpQ+b`dSQu)CWG;nK0aU^IVK(uOrZ zQNTqH6T}{3pQ3OR&uicNF)eG&1nP}tP~M#dcUepqt4MMxJI0)DcbF^YQJxD2VV?dNPRNTpQjsA!c+bq4{q#sqb zu~JN8G9J%2r~{yWBth$TToPn5KMQ#00TibK9l3lDf(-4vO9ep=J@@^FY`TJ?iVBb# z-*57HZkAYDz{Z(H#5lRMgwiNeaNOTR_?-R)Ybk^J_4fix(oBXTmm4VYB*1|NEf8#_ zU>Y@#|KG?F%3A`3R1C595y2(S8&}L^Pj1RdWM*}P8{10fDkMdzI>^`FhNZcPO8<8< z_yb+HvAsW(`(!qc6F~md2NK8$1Ue7L4@3>pm|T2aS_*}DDCWr%VP!Q-jnND52Ahc|Tu$rS9*QWEqvqqm3D6MmeqxU(IhH}uW5ui)jiPx` zA&KR{=cu&u^>{Eu-~D%brEip-oMDXT|At zx`*b)lNMrT2QI*Rx)WaN;rVx6VsRvJ(0IN=`q{pz=S3Z%L^4kbDWq>;W6<{LY`-;j z`SGwhSD?58f%WA>`Ufs#xERE>`=e4}DuLHqFNZhi|6r zKhA?tQI?lyK%Z~&lUZ(Zrluuq5#;y+M@C#|?SF><&{qT;|KBR3(FBame7gPl(1lu_ znBU_@Lo(t$YwL|n6I}hc=~n`v%{QDl`wBzsQ-M05rSG@g37t-K7q$lYrUrZH#yfsG zCFmovb6xCq_?sghJ4paxYQji-yVITxS#A8I=CX^%>48d_rDWU0?7QTKA>4Q*2EW$i z{|93s?Mwlcx@_%W$cEwO5F>{T&M_l|iqL>nzIPnx2a);S6v{9EpfI0=c0uVSnewvH z{TUETx|md)x+~RP^Q#Uk*>mf77S1L(a&+7X<&tYzpF#%H zU}XQ_28B}jN@tE~T1|GyJLTq%WI|AL$+ofN1e|-9(9}f8)kkarI0Jda41AkdNU3WmFDHu89fAVg7XY>!&ib zW_W=3@iQ`=8VZow3+8pCp1gxKB2*zW!*^1RHTaX8FnUW`#mhdaMKHqWJD^H&y)nUw zD8v=oY+(Svd9Zf6y%{+G?<`>ec<`Z`G39+`@Y<*Qe0Vd*p9|@ub=!|yxS?IvuU!As zzHPedd0Nl=`ab+F@b`&Hpu_YQwdZB(%J1Ow{j?*G@BJ#S`}X)OHQaREV}7;=o!xUl z_{HD%TS%?!8j;)fkC|(AltgH3jK_MqrqDB$tD7NLyhp`|IbcTqNG|WC!)68VBvaE2-(KXklv=|U> ze^wA*Y%&>r&=p3o>{g}cjM{_*jIiIK?%g>)sQ8`5iip&V-YP*k=^JG_mN_K^(={2& z{T%!c4Mjm%ZeV15up5Jhd$r12@5dXve{A)za9`E1L86_o@YE|BwPu5MV zuci;@?fS2)9UmW;sNdZ`Co@{N-sIO`O)b*)x$es!qde1h50x{n)?V)Zgtp0;ck5`l zL%hezTB}ZBL9T87wyAX$;h^C$9Jd!8m+Q5}hhL8?&jUGmCTOusRaA)-qb#T*>R05Q z5CC|7q7)^P%n+8F8!byd@ndOQVgD?or0s<@ak=h{bG>kSk-MSvy$+>3#GKo2n3-p_ zl?TY>y>FX+T$lEgh)C~W?eB+CgkPlW| zDnW@DrT^@TpVqTV69B|p*5E6p@)1mI)Hm=1nhhb=jAv@QiljCSN4U_P*8ZJV@cP!A z5xHKcyCQ+E&d=+O*RN~uOZ+obX(#@AJnTsK?epyte6T62QaEpprZ1hap+|ae$c<=4 zKpxD0M==2fXVsLLE&VQXsdyUd_stW|Bs=b6gnX*Np0m5(o{GEq1mwyaOuyulvU91@4G1!*OUPUNgXurFM9gqC+=HI}ERO+_E%6$p5$ONi! zp)vve?khS4obeeIcwi{m4aU+1oFYK6lri6jPORbnjv6jTwqwAI2KVFuQ z(8tWR=DdD&KYH4F`1*SGQRMerfBT+9vLwD5);DTKMlm6UU6>yja;%IxK+Sh)!bEPo zgO|kDgdK_G>oBr#P1T~xSbK&@<-|&aAaK=Hw%k`&dL|Kmj3bni~-!E#W7DI40A*xiYO(t1># z`Q$Pi0_T&W`bd@dOqb*SwaAos*ZC(2}+n!DH1oF zT87MG63^$Z5e<1r;`NhFH9aAO1JX;-e_hkr(jMKIoX!oBZ z$0FP$!-24%=x@D8BVE**k5~cuB7BIj5LD)$v>~Nva#VcP7a@$rEcNQL^D@D)YWFq&z=GK*T?&Am&&V}q;C6M8?RHrwIo>2P42n( zmx$WsSX7^dgEQiLRx!@`3`_)TBb8LCFsW_Ylj#6KrX%pmKI5n#MY=Ut54qlPKZcJ# z9SGoAHktevtx&`E3j6mKiZzi*^(5d7=R<-1sE9`%6hCH656j-sRM=oJ4Z}QXo;X&a)%gmOQ-cvbSBKbV$tq*fN+a6|_e_l1 z(y2TqhuGlal(4a33j;RTTb%62h{#WYka|}Q1v`(Ru&oR3S3B`5rxDLweo%9jkAwMZ zAFpju*o$D@t5^T;QL_k($w(!nO`lMIr3%_~(v&`|vqja~kA}W2-}jK58Opo*^>%%r z&wGL3KtuEFO^5LnwJhg`H1#}WDJHcPp`(wLVogTzB!UIxhl4u`=NI8mt~>&@diwgP zMnuHXLe<(6seMI=uWm31qB#4|&4-Udj~rJ$#>#=Nf3&OT8yqkUw;5ur+K)RpI6J2f z>q7v^k%mr%glTJ^>CecG4W6+@Ol9SieDx&Z9S0K3e=p)|CWJ#R#`_gghFfB0^e#vO z*GT>GA`TToY!AUTND$I@KcB5k?UuY0?;j4kaJ+d7Eyh3k{c-vE5!< z-M7_(-;EXt~8x z-d8YW;Un%Ll5|fW1VUp)nYG!eJRD8obk_N}Z8ZR%4F_F)KDoO`GGzdNA9A0fmVsi@ zBa7f2#xl8)=k-8Ili6Y|_#Z@Bq=P4=AM)FoJ=C0YfXp8s8?_>NFD z(~ftk3e4;=U+-;k{T7XC_&7DVs=0(zwKZr8_>qCc_l!Gb97wtLNpk#tE74MPQLkw) z$F9g^4v3f(FyZ;HQuQ0K;z0TwG&wB=U<=}Stp(5c03<25d<#dO%!l;m9lU~4G}YwWAS!x%qv(5Xl96O23;(JbtG=? zQ^0{JFK=x*Wt42!sELY&wwK1{VnCep!E|zV_TbqqbVx*6mExsu5Y_ih`p}xw#cU>* z00H{lH*c9&Pf>AkaS=Qrzjs5fgz6p%{o;2XR!eP&c zdlB1w4MCjlfw;n9jF>a40Na=?5t zJZ^e*78QA2?}mQUZVjx3a1lkvi%7gVBFq*(Qhv5iaZnEU9lF@mIv&4TgZ9>(uTfDo z6?+_%wuF)0rb`i7Y8C#Y$PSh#GOb;8KzH!?$i$he%=c6n$Q}Tb%2%p@jIf?mf(0dM zH7wZY{NDvby@$*Ha3L408LXSfd$hnKAi!8W_K)CS2mvIpYHFdtku7kUH-=UvdfL1P zRr>E@qN2dm7%&C%PRHXk`Hif{Yx-M|CaI%A0!^yM|EitJX_~I9k9WfPVo^p48Y7%ln-gi_a zdon)#wR8-UgnEd7k((5^8dmDHR9h@)oUCL-AGM~vhwmW7#m6`KMs4CrsAtN;s@n)L zPcaYP#4c@ooA9#9%ew|-?hS^A8&KUpk(py5lwbI|9M|4&&*$~P)b{M`^aHxo!NF|Q zuL^&Hcrw9WOj>C7h78qRnlBD=dcM>C0cEt$8;npGwC?V1z-7VcM-JL^+bj{GMNOuWH!_eIzAYIbkEeu0< zbI*J4_viaHfA^Vv&fe>J)_T?gqCCcv1!&pB^$sLe)R_|RE9y!yk}b6%@vp_fCFb3e zp1SY%zviH~k*I|VD}-ijY2oa|Lg{9VT7ee@?4bUF#;}qfrCwE0@lq7fTKD^RUUl^! z$EGioJH!Zp+uGKa0)4MR62-Rs)0Bc}o$D@LYwMD}zKFe}P){((*!nPldwC{p?lyb7awf;4wBj zuW6^k8BSex*{vy`ImYppx{*_NSiR5!=b((Lj8Rq3N(=v8YpleFG}|5D;{Ci zY7`_pU{tbJ8;VH12dGB=P=*ghDe_X?XYbG4EG#a%Ki=kwk^fPg|7uAB>NV7!;&RGA zUgOX)bQuLEF8Tq*8^OM)8&nuaotN=TEQ!C(hRN9g~qNwO07Pp##LBsgaL?@&}9&ZsW1-y7KTFp(-Dr;R=QZi*w;Sxgyo zO-<2~;OpJLGNd_4x=$#?U!$yOF~!v>=j3=AqFH!XzA5o3Gy0EkQp06DjfZ1Y?O$7F ztU--bY&rMOnD7O1!~L3sJK*)IEI|2D0Sp=c{8en>rOvjM##v<6b3krd5$;xY5%1Zi zxfd~aMi@w_+Ieue*wxk5F*e3YMRf^MkDv&Q`Zs(D5Oc18dEWm9ww8@mX~6G+SXdy| zzRQ15g7QZ6^m6P*kX%@g2k*#?AG1-4YX5`b0xU#kv$r3xA2IM57;=pw*3lzTPVEU= zV;|iNb;M?XB%%#fn~`t{4}w3vGilF46yrA62!~Fa$GDYZTBa#A$mWdHoDG$>Vs%GB z6RR;ph0~GJVxG|$oz&{mlCyh~SQx`L_0-q=A8!k4O%v&9#=q1#Wufc- z?fd=hePTqOClh9!Y3Fi*w2_f@@Vl$$JD(M$ZbJNnLvu7oT(RQVdgRsj%%1 zoww}!SwhKYqmQ2bxbWv!oFErU;Or4{-Fb035q`DJGgkk?vSO)~TgNEQ zy_{f|ZpZ3kua{6}nE0}Kv%2cRPv?snrta}wdJ1b$`FH%KXib_u$U6*T|^{T zlW6cVZc@D<4tj-pXqI~G^;;tI#t#{Bqs#g8!t(4aE{4ote&Gk?*s64Sv&_t0ZMw$7 z7v0wvLMB;-3RTh4`I(s{*5h+zg6_?Qg=xl{2^8h!Sp45fuv*fGusJfbYXc99L54|N zF0Q6T`tiP9Bw|p>{0mOf@k1su8;96q!P&K$EZ=sEGw^z|DGhkQ7Z)z9U()&8e^j!} zDHm3IN2S*;QfF(VrG??)G5L=5mvm(&*o^|#e@m+OB|D?>Z6Z}+Z-P2>`H7wXRhr{8 z_tG_Do-H}HR&H5-L!D$U^5742r-r5`$$8h+=FRY4!pU-7=|n<>?+p!6B!d1!36@7k z4%TC0P%>f2LDIZkKs%USLTmJ~VZ5E8KoPP~9dgA+?Ndiy`JplUeyGlAa9W>r7hI5n z89VT_7B-HbEhy5@Q;h#1t51c7K$ZVS!tOG0+u>0th!$7h|1*%~$ zieW=2J1;0z9PKVNb&}W*7t84jy$7bZP;JejLm?MiqUxJy>a7Vt25us+}zZJ z^YiH@B84UqJ{>~CdkBUaQvt4rA8P00f#G%`MAWKJz(g{!05|Muk@xnzBaX7Inc{X6JjmqzBJ5b|{?sSXbFpXA|M)R=r{|BTk;d2h+X z%H{jvdpdW8d;eW)?$7wz|J;X#lwGD5`;z6Mks??28uacXm*ok$JyrB`yiU){9ezGN znr!7c|1y%gaT)^_*X)A-R*rP0w*AlWiRcTcC85Aoc82eiIrP4H>0 zK|iB)X%s9m9i8ESebzaLR=6 zo9UtaD|o53oM$omU0+s){rahHTtvj#r1OEYBwsZV=344n6i!lE>36K;Pm2p_lyk~ijtetnQ^Jhy_xm}1| ztMXr*y~<2ErPIe&UasEzaBLaiWNXUI%v@c~{jNJ;wpOfIK0-8i=P=lLnfm&GYIZ;+=)|1)@xf~LiDITm^@F$V}j(+k$*id%JPp!d!bes z(Gh7i9dU7A_@p=;UGv^M)A;=-_s_EvN6^fMpnnbq*V61Wu#g__d2Wl=aRs2y@7t;_ z*4X<+g0}Py(|Suj+(j#0-7zQb`Vi0Nb=cKn-QJ{D{PCP~lWe)u+GA7G`m+*mfdFjb z=<05;x$giu2{fi+tyazk@;(COGt-NUE}Ih5Lx}@7CoknCCGp04TWHiAAO~HS%}j-* znha&Zl<%RwnJOpC&m|w<%e;1MLlTWn;!cBKd>LxX5jkggZXbYgNDQQbi2c2nJ4HN? z@@xt_4R6{z+8;%-_n0E@jRj+UkLVE?_B7Bf2+G7T0(J}{SJV&4+d>iMEHNxrsMQ(*gY3iQCBE9wmYuVw zf5(iwo^kLJ6DnV>WBVF@g-*P-)Yim^N+ei`rY=%e6JVRBttR21`H0-M9v&7*%Bqpx-k;D-XGOLYxb01?9&+O@OarbsQNTmwe9KP zX1}**5gPm`+~USw8)f*fA&x%|5?fCD6!_IRb%qM`Pj(XKj!nEosNNVkQm$B}yX_~R zmNl{f38cB(%3}El7xlVEUs;0H8?Jpg za0G_;CHMRR`$}@ed?7SuBzLErE9GCHWmgQY7~%n3pD?mJHdY%t6CJdX5l6nI>fE%wF!gj^c~C)P zXvz4o{-iv~cen8sW)1A@bD~tvA+cW4p1ji^tmXQrhLOXWj(pO2H|3SgWtwh0EIhI8 zaW^ajE63wkca&bK=PWqH)$!&4MYQl8CcsXmWxXP(Ir7b(QagRG6II+L%R?nLb^pR| zkehRf-*MDbYJ_Gm!;{h^p~haj+($=86%{O3S4ARsJNYW2PxL7V@N!P8nNtl`o;2@!`$L3(Gnb?N zkM$u^lEKcUG3u0Xg|+s0yLn#^mvGCq)^+m0DrAQV$lLu_n_q6i=^v3}K{9f_ub(f7 zBXYRfU|{5b=F%EQnWjY}Gd#*5V%75j@YUXzC61<&tbpl>{N+hcwQ$fZe|g+f0k+LS zN5{j1w^smPnoe%#uui_RGr zxklvZm?SN1CQN4`P{=2C{|5|#v|sPVu0L7~w~^cw!>-x~wpCsj8iB+1gf~;+Qnkpg z7R6DS@usN$te@mUu4pK+NIHM#TqUct`(9K*{P9HVOMNhsL>%V2ipUeAXnywyd>)9r zez))17q7^gA)1iArN$@*e~%mcp0n&r0KT~~wcnl8SyP%&mJYSCojkD@Jw0AmD6qw8 zca3(x4Emb#jRj&~W)>1xhzo!Ix!R(Du7VKY!=obLhp%p*37MJf45s-L*5FZ8`I$x> zx{ZtryFo(6zcMiQAJLF^+MMm!=nrw}50#1-n$}tm@*=GO?H(Rx&WyRC8+QxXjW@C2 z?b&FE!2p{{6NM;PU)uL*iHwBrlwWip$8(;D*KteuMhFdvH#Hz48q4H!`9+*~c9B#8 zOLFox$Hn4G*@5-Z&X^q|P)qDRuh!>hWl$WrU$qy6N^3z}eI++ZG~B}oD1}Kxp%h1a zMoLC3yW3jj^*Do<;QRfH#-#gku>s*G8jbm%va{ulhM6MNzKNX-6+*20rAzjMej(Gon4pZwQzB}4bs6$TLt zF}4_z1#(=Vng^Ot^R1zVDn<;0=ZUAL2|N#^LXP@8!!)_D+^vWO~ubQ;eq1&k2;8-NQDXpdrJ$Os4s0Dm8uK>f?K ziYPFQANNeWV*Jud(pjnAl>KFYrSqu+Q?I%f(g)s>Q8@{+8c315ZXddjyW1}n-&bYPSLE`z499IRn<>HphiDU$>GEh(%C=wS*esVJW6UG)B7Au$wBg3u}_tV1BB4< z_52=Jo!efh{=A%G7#;HMZsS|i%W3F5Fse5(JG(lI8zF6OR2AzpnzW+YyQ=?NQIx>( zttcHcPRdUU*c6;J;PDPP_=$*~9`D?M38=+7>-kF1a?B_GVq<8)HgVZ4L+W43ug9h7 zcXrvh?QadK0?| zdO7U>yvIz7F=QR9q)ks|Ot!SW6u|SENNVK~D%H%(}Mc0I0(iVF54x{s^W-L=mqBTFjL?XaP2#OJ;&J4xo&! zB=w?LWh}Cm0yL(5t#jbFogq@W)%dNk*&h>g=fGtOv*g$5se6uqPxsvgTj%3B91vfl zzIV>UhvqiL%sEB+Ie?{2O-hLvSYgRQ^y6~HA zXB_`NCgjykf2oxBs+@HQX(4NiZA-gxdGE7m@*uOtLlq~X^pw}CPz)RID#kxubk!8t zyK=zwu)%^aEhYe$XK-DaO%Ey0a1H(6SaPgH7nM@BfWy*^&11xy4BnTcfakqEV0uK< z!J&eLB$I>$l&i{x*OU1+L71NpZQ>Xyzvu(n%-zB4%X&ID8!Ld-s!geumY0cv@AX&7 z%kB0DkCU|q^MQYW^qwFY@Xc11+OjsR?NVTS^n7Y1JL5dqNmHEvFyofaK|&syRB;Xv zzq$`A8TZQ@Zm1|{78k)kdl{2wwWqO@1twfHWU+NIiQ`!Y`N6HR8GaH_gO7FFBT7vk zJfWtbYkiK)2h~mpM<%6k|4+F=aKzVdQN!SP1U*H+=OW1>6k z`F0z0()qF{`h0eEf4@Be2TbiUGeH10*JUP+O?-w2TNF79Zt}9HIe*XCE8-vI0*vu* z{Oqm{Is>-CuYMA6+xmKVcqk~qfe#gfOyqWmj?7`b12U3=p6y%Pmfxcri+>vJRIY!q zGa~vifU2Kn+7tHmo4#55z%W=fHQxX39}s)V*4OI%5)Z%Xwf|uuupi!T{DuRo<*)3L zcHQj5Th;Yl^G@0O9_Mz$+vD>c?rGduly>7mrWOW)za<+<-lb8FC-xXrM~52q(B)^y zJ1ns#S-@SjZX(_B;^TBsJ1PA?))SL#*mhBGiB zlgr*(twduX)i5N6HNp&3Bl9rACQ`}%7=x!=Qd+w2Hu3NC)S$>R2TAX&rGSIdxHQe+ z4<)4KQ6{1ZJh;#G;Z{*n*npp_Km{mTR0 zs-4bi9WZS4Yw!}vN^j|Kn9Wt^%ozK-MDMQiPa&4guvwDgQn!98<2yFZnt-JZ>-$S1IF-o*c<-Z zhK7pEgQ(54c>55sPHG~I(9h8gKaUO%dwD7|bIiJvPoIaf^zh16{SZldl_e2g*F01L36p^3pQYF?{l%gaZ{;Wl>Fw_!G zh0B@sMP?v<>=^hi^HvVtOg;x=6w;jVXJh`iJj0+|QvH9sgl2Uze2HT*+uZ6^rIocv zvc8d;uU{l6`kqAl$3&)mF0P%QI(`wP53o7`HODlAp9%@O_X zSS9mclECLrV}DCq;<8ebf=_3ual<|)H5Ck&*$u`W;rZ9>7vj&0EiQ~k9kkevzoS<% z#jO|2%$b>WU|&?p>|=mvoiDlavRG0bWcuC6VTNi(93 zrNTmfDK>Q$fa5IbsQ-nGgjqWB=f&+7>}rejCtZA%UgwOU9i;~qI`T5ggGQttlDv&# zriz<{@4_3Z^y#O&{@RA9WDi$&wg_qze3V-X**H|6IRd5hgnbblvCqZDrRICNu-uMihJX}PWtx^-?&Mq3_BMC;vA|>y_V}1-ZI;Nd!v62Y_wki2*A<8;h-eb&8M>my=-Z|K>{<*;$7_Fqi+xu9vPj)vW*>mk81l9r1Pd@M zb^kM)3Z?pGQnNrY(1$#A#jqZ$7n4iaJ|)kwaRYkXU;X0p@A>q5%Cstt!T< zBd=I_N2Zd5t!f=Op5XiK-wN)LFp*kW-uK+BCme9Aj!fziCVv}h6Wz6aQ^2cDmm2Q4 z&O!A33lwqgccMirj?5>(j!uRE4PhJ?*Y(pRPz911DRtzB)6t=%mYx;PZY#hT z`6HqI$d|O(d-_5rM_TRubH`3q%j;RCN}zjbScDzYxrSAV6UvjR0XD5`wNhp`F=kVV z#^sXsGHaW|0S?u!HAJt@*=xkI_0^o97L=~3u`Uq2jY9Xv{;Xe*LVfCL2o@UM_KNo9 zd!)@h@`Blva_R@MWv!9^quKCchvtE%62ubB)Z}+<+U={Ee3W-TK2B(KW5Hnn&ZEoB zG0YJ76ihw|Pg#DTc}rP{k-#3F=i|gFIy}q-pGQ%Gm8*wR7NOFprYQ&M>R6n(oB)zO z#w&)NZN!JuI_aR*4XCm??Pi<;Bqyz!U4t%-Ufncg|*8$|upG-<}E97pJ!2 z``6QLrfQ$}t_0@alucaP;pmj0%J#Mr5v`iPk=Zc=iOvmzHwv)1a%a#tuKn4=3=i1> z2m33}AW9uY<^(N?spw$0I9S3;6m*UCJxUQFt%x8e)9GBG2U)G>S$UTVu+ z|F`YEKb_?pA;|AvONE3WWYh5!7@NS#jRKm&R5*)bnOInYUhlt;H>xArtGZxcP0tF@ zEtJ(+_c0$1#ZyYlDyVelBn`SHq|&9G2F(m<6k?n|iKMgq(0o(Y0+e0yk7Ep~d{$c9 z3N4yYPOVtBZ=sK47*uUq9BdZewJ1kSigMz8W(T_|C-{VP{i&5IV-Y1lO%?GbxJyik zsN;IesH~FMbErO{(_jT&26zH$2m~mOAbJ?qc%GSsL1rYwActF9l&@+qSjNV~D2VQ} zh%aMzCHn5~A);G*5WtP|Z(I@Jc}&fr2Clz}oRG}yzV>gi$-0~JbgCL#WAmMt48om9 z!@2LuFgbAHBTneJOj6n>f~``q zgwl5PqxyhciDD96^*S=4#6X1uqR5Bf`qiHIA*LX28vMqX_~iYN-%1%kK#z1 z^Cve~tpAuOt#S+VCcjpbLsy>u#9`Mj8Ni!n7v-vXJ+KSlaT>1=P`vV7=$+T&T-PBN z_nUbF4eFcHflQCjP*eQZoNIuX{u}ZKv+(n$v9oFrH=d!;cV+qkM-%s=~}IAY~@)`2${4prgUltV7wSX)e=OitG~XP z1v%bSCGi>nrX8kVostu4!*fp6&l|Ch-R2Z=>vGHMf}bUDbVG(t(3$ojPs%$v>d1}6 zpXFOI_$hPd9Mu;~`;qKulavWbv-OAAbS#XgC$PKNeqT;00P2FScaa80WAQQS12K6n zUBHb&SjjeAkUs+q-fZ?bibC+MKie;aF&E17oUPF#fOg6|-RVAWY3YC5$y7wndoA~J zo9COpH0Y$Jwz*JaUYQ1RpXbJXaS_ZWeUk4RE@LX~zum6+%-TEYDVF;X#L1Kv$+#$L zQY=+J9Z8yoL7S9KM6%FgzsRAOU+KPULPn6A_(R_b9sP~Xf8FlgRz(ji<%E9LgPjI- z52tLe$jb>R-weMowjxrT1oT1p?e$ATmu;HzM_gHfQ2gELCAnu^J$-%G3;a~(%qj0X zDSvk~dfDQ$ZvsvRK>r~fVRk#BSQkIw<2OWQi;DC`M?Smwl1;u)H0_`jZd30J*tKw_r zN99?lf6^Qt1=n6L^2TMDao7e&y}CHe$Y`8LWw6BPW)+Yz^^WL>aP~OZIuBUnA*c`BwAb6oftlVRD$$T~>UwcMU5|#21E|tT3?PUa_FK_)CYErhEC$;0b#+4-WYhW_5ZfzxCFv#=+w7n}4klaVE*|gA&No z;>r~0q25Gd@ERr8DDEqYGD=fskE=mY{n|JLX81>$6Z~%Yp>f%<4g6Q{XkIF(*fAa7 zSX)EhV6Ls%Lj||G=yRsnnp8?dpy~_i@6ENose2@l5yw|N(H?|$e<7Z<>@&~dr=kvy zi@&Gu*_6qmv4!vl%a*=a3W#n~fWWs5G|p-`r2K<1HenElH04Q#IqrUqy|8t{8f6joq0fP~9%GqVxe&wcuF+spGE43p2htf?QXEKot4k05>2hBj@b^V57^p*rcKGt$D$*{5* zf~cI%U$g_l^Rj$Sy!Uh}bVBMF2gCz7r}ag&km*D9mU-NO?n zdR=d9jM%pw0Ye9((o9@Yvtx*rZ3e(9&u#OHY`ZYy&Ok7 zGi~?(S)b$VD<3K2e4!Q4Dz9swx{4)dz=uC3i7b5Rpd{6P+{`H58U; zB=!<=BWg)7oKXaJTvnrr-C)I{1^PLl;vkk`fDl(U>$QeiKdp5^imqKdr*M*4CY9yR zW!-fN-q)vVnUU+faZHth@?t06c=(V#uEGiWIN3c`7xLyi7e^HLqaml*4@q7cKvuI=Z{qD z^zfrW^zk_T#LxP2V@rzj;aovD3+O5bG_bEtl6;Uk7l+AO2z=QLUX)zu?Z}j~Fe5S} zd8m~ecaG>zdGuY{*L@WkOj+hZZ`uchq_5{`ePmY748(BEzHN(t zL%sAcSZ?4GW-QMIE&d0Fn>VPx&vD`kO~hKG&GM=O#O)+j%0SBG>hnTROFt?GxTk<% zVH1T%`4rS}N0aKP_W$@(%Ykr`hJn6!3d-fJ4{F*_(W}33;-;)W*N;MoZMJu%GQ5t0 zxj%7k-eSbTlE6$~KW_*&yRe8-K^-5Y0h)T73aJfa+5edDd8a-ZoIm~*hMUM1AVK~exb*W)_ibY=|Aqdg)>^>+d;gA6)*V$#?Yv<(|ua7)_Uw%D(&V2{f?hj2# zET?86!DtR(Y}@F_4}9p$#Y55XyDO0MppQpVO+-Ei28q@26Y|s%aYwWhb8VBbqWUj^A#x`6|LA*7O^IQ}AXaizN)=B8>TbGTwGW zx|bTb*8b=N%)K5rWpC_ZuiP|PCQ7HAa+0bz%wJuBBx?kR*I#+Zd}WPebFn~Q0T+)w z?*anju6PQiNeeQ9&(^NlyYpy%xBukBApRebE$;0ywrjr1F0}8dX8cf39R!CxU$H%g zITXz^%z>DJTt@0K-x%j)0R->Ya^rz|L?$-~?b{;R-5Yus%{2^dCjB*!Z3@IuVJozj zq0R28Yev{hV(c0<%9HNV@XKzMvLLiKM64c!yN!Ym4BrQz#B ztwnzk!_(;j6NbUQ`$~|3k>|4u#hC*Ce-vT?@<|(ExN%ZoWnQ>(FUZ{*nlK{9I_+_! zcz?Qunuo^Cx=S=O>*xjR8!*-%pz~))G#vyiIOaDm9|m3Qot(buT4&5MA>-*_(A(I= z0zj5=)i;lsdf#tWB=r9or7ri?5+Wvk1vYDY)(k83igZ;r8R7q8)j# zoZt2JKce|g6BW?B?Jb_dCEctxzMa1%O~ictOJz}!^&=d~*|Js7dk|I$dG})mMMl^< zz5Q@?>CK+LEUksEPI;)T}-z3!|H$Xe?~+X5K;~C&U$g) zeeW`-!iU3+bg8KQKYF4xaK1*%1cF|DYivGg@x5!oekbV~x?lzQ><6ww?i4zI zS>^e6HjDkdey%n>Kr8rO6583gSZ9uWr;at&Od3g&TAL+p`e(ZAr(r$C+`8WlXr_!f zfFR(++?DBLpqR{kpU*1GX!PbW&y249`gCiDZir#2KII$@C2=cZ8a?g46-5n@gmDzc zM#uzm1RvEoRdawIuLL~NV1HJ_D8#hmQC z7`}hcUf;UT)ee!&(_8gtpEbrgM0+snG$(4<5gTiM1(N!S-g3Ro5wexa!}sla`?DO)**qYy*v!SaiY; zLxo;}2ZF#}o+HUHDn$Uz0B{a(&Q6r+MC^<+CEkz~W z%#U_{G6Y)m^BCqD&vFZBqn6#Nbl3>pqZ2K>56lVCFhg^L($k43x*GZfET+G85>XC< z8LOwd|8Lc(7TrJif5FpUYnD&1ACCbgXobh)>CDwSE$qaYZ+3BRBRX_n!?OBMGOW=g zRChj>AAqbExazoRtnG7hNljTILJ1(-zHCLT&Ed<-eFXV-nSAibaLKYR-e+AAXrDK3 z(O5_?+pgzbpT!Fy!Y!bdvOanxSiudVe;nsv+ES0ZG7>EzXT;lT7Qe;jxm%@4ry3+tXGzm?jK_J?LhgVf?jv4in6QBHcuU#6~Zq6_&ZhIRDg~k56heHDu3IG*~s-r z>bi{nkmdPtztJ1E_FKM|b{Z@EF%o4udKKY|*6M?<2gf|~ zzE`Z0jW@m=J@{DxzL~dudR5y1b>l@oi($j%BEQvCU5tipX=&-?8;S3r3EfV36HWRq z5#jvznx{)HBw@@%>A#m*!=5(|gEn)-N->62#URXS$+2rsl%jU_lKu_v{OorziyA9b zt~T~R{oRRyKi*~X9d77vVw_L7QGlHr=A6+zmgkhsE0JFZnZyY>Jot7112U5#DH{`^ z;FYU*4q5kfb>>a`x;?acQBpb2p4c(k1RaXLuax)d310{N8o*HgRg9-=#G9$>2@@nD z7C0aMj}DXf;zAnNuZz|P7yXbepG~aAIu5A2qQS@?FgwFMJdGy20TBXVG>uJA42*OmoO`&2F{_+zTEdCSB zs)JFfkYIb20%`2?mMXP!os#%lUv4mKlAX<`8vv&crF6c`o@T~|zrSlvHIH!R-;sim zhh1)cZf;Vmi7`MSY5gddSFl)P97vj0i6DrA_Ld{le=W?`1-+&+%z{Ave%=eYhfMZp zn-I+twfR_*FGiM(?A^O}uSrI7Cmmq)zl>;k-F5Gn{LP1S_c6&rs73276iuL%(?D;1a+VQ9so!UvN&+%5M zS`qrV#0ftARp`%;bBn3+i&{$@B*_jV7!}7{aj;8vu_8)qpH6y8*v*zFfOAQuga@$a zDH>I(E#|zZ%5nv&Cj*Z*(WOJm3MWNa7zC3P+z|wP zI*Wzh(f8ueRhdAi^R0kGe8#n=E`T@g+sJc-)_QM>nL&v{OR2X=Q+`Au7vfQuAh2?^ zQA4kU&G>Hcyx00MM2o>vU`ks0UV(M7_+SMKEAU;RGUs$9l4g=K1@FEw}!heasud*9x@1iBC#qiEm>}`xoYQiMU4_) z+0Jqv{1$43kwe*g&$%)TO|^9v{VvU5*hBa>$)f>JeAEwao?;y?r>JUlLLZoVy1qo z1753}jK6Nfu(Gk{Eq7mG*=cnljf*OP`IlGUmipn+t+>fU5j!wl%R~&m#G<8}aeyV; zt~RztKaz7vkxW49^<>@U!YR^N#RPVQ9*{)MzaM--S(3i`QYxzj;aJ8kQ}k<}jpq=S z8A2~qo}8PpF=UqOKW<2oY#}&rb=Lg$t(1pl4iY?43{-^gx+*lF8Q1Vae6oPkj*Pfl zFPe>4e)VyY{|P4FB0iQ!zFqK-*}al0k8aPs*$8eRDwd>|IO=t>{Z#rp{=gk}ITmugJfqr|#!|{~+;D~48tu*@kK+mm(Tkdhi`V`@fuzyI* ziD4=@WRrvesD~uhDc?%$L0*Y2#=ubbFxH!|-ejhL<%}UW`4YT8EihU~dI?VfmI5y@Z)3eBCx1hM468>{ZD;UFvnJSTu@WWh>!}YG@-$)d zrwJdCXU?h|75rpQh6Z_#DNZp%ej9u3pVK4y0LTGf+f6X+VJLxe)8sNBUhdGc?zf~!dT1EYC z9C0C%(MrmI89;s#M&`jlyoR8N=epA6dsh3vb&z0FH3ta_3;Y+$Wa&y*R|6k*<$v2J zt`aS%Gr=&8uv6k55c}7>UQp2TN#K5zyu((2h5r3rS@3Vm)p$lBnid$h$}u3Wih#i5 zl7ne1GZKrDtR>1Nxr_yxuxbU#iCbM(QSGeeHK(|&wP|>;v6jG$;2`JV^mL|IpE~~mROJn55cmgQb{?|OlC{5Fb1v?p@7-j`on16=V>?= zZrC~~pSy<_X}bfv)Jp}bNsEz~y0L4es?{{_ebPGgWqky4#id2Lm|`l`AI|0VnLh2 zJu(Z`HK`~ z6+227`OJM+>e3~cr(;Ft8MKklzb0j!U&gss9l4~cd`Z|8Cryw0CPt9#pY^N6p0({^ zm?3H>LR>i(R$H{%7>|P6boN+-uIo#@rI}nMMxeZ6GLDXXsrkh+-JD?0yEN7@JZ}=4 z@naUUVpwLZ9IBP5Ca+2WnpC{>(*Xi;kU+)&nWOGS0U68|d11z7g*(!Y`loH>)LEV~Q3WS%% zZN0bAEHRK>k|&YfmcI2C~E6u#wb#X8PZx&o) ztOqF~M|b+qcn=G&F%Hp1@^{m=M3Ok;PynfJ#@o8kQ;jjPyqS-&&jP05>ekfFILF+t zI(C<_3S&TWSwv>S(Z8?A=lA_PKVb2*v$Prmf>*p4D>ox@K~hP7Lope@}HclVhePNypWQ$;S))de?$i=Dn(mxc5O0FE~;A z`BtW;gg6SN$}0^6ESS9IOk6gO6xofilQobs)zdRCHzzL_yZOimOwY8;BY-|;SeA0^ zv?<81Q(9UINa_P|zmA{(&KpSOcP$VG@X6n|q5y)%_Tu8|`uYOE;QV!_uQ@eov`o*W zvkvnVcfm?1*Y5z6+rVy@?S9jYsVQ~wiIE`Ilbtnz-8~X%jD`}8q;@TP4P>Gk;hO7t z&a&H}QzN~XH<_w3It;KunOvpzRx4I4(L_>i?u)P5HuWWlYSmj!XxsHlBpMxCxl+l- z1qyW|X-_Z9Oj(b=RF6dR9S+2 zFT`Ws#mIV$f{A6fzYEx=B@C=gd%sH}{`ZY;`G2*--GbHU>7yYl^TM3K9mk`Cdakof zxeOii_tpHcG7$TU|HqG|nMFsIq$@MJva-FJ0O+5kFE}XC_$7{`FZK38!D2*bmbrzd#*7TpQT=O8bU|>fm);>yI%Cmuz=<|ed)O^N7BBI z%O+aM#QF`ToS)>>FUN`!qA&mYyzeTsmOui%!CNv&!GXHrl!1_(Jm-1ajE zNr77P7KrApl=u7sCtvKucF63$W{x??K*u#i>!ppL%~qZ}7rRc@SEt0&AU@3*-UfBEeK zCO)iUvm>(Ws-(B{`aaqFp1=lIJ6bGN7x_LiP*SbjfPR`mAhWwrOs<4V;G3G7;!%=t zSX+!6e?Equ6*F?oZ$f9Bbpv zy{IL^f?c!tv_qayYsHnZ=ox*4tG5(PF>(EX?rWMNvK6Y1WvAfDmLQuAPQ1;Vw6XAw zS2psoVDq_?ixfOuoVSm>%*-vD30Sou0~#E~P_zD33$s(^)-T<6!sEbT6X|&T=Slc- zlT)aXlbzjmDm18UW_BY}MWe(n_g9F<`)IQ=-UG4hB z)+9I0q9Rl$LnQa^(q>Kv#`Hob%6Xdu*o?1~9?vg0oK=$jw&&6(+_pb`-Y)bdYf(p@ z!w+oST%mWyUEqNTFHj)U5NI8|TCS4`A|(M0(A21byiaCIGhy=P-9IbXY#&@EwYA2Z ze#0X*p)x&Z1ZqD*-aaRE2QwsRWw0@&3AEz8CPB@eoPE>!J!V=^aO@C^TJRF++M1<= z0gSnw*kco*1;pWSm2XiyypZ0$IJdRZ5ZJaa#L%RQi-b^44`8Nc5j|ieL`Jc54j3-@ zPlc%?@1XD>)2F$9-EK^LOcH306!kobengAqp4<~t;@!^kC6l3t#38<|3|1?|ID~&t zV$YpH@IgVNzhX9-V{3Ri49B}!oMSz=M%IQ7n4NWtiOW@Q^uGbK6Aj8#AC_j`wMXQT+}XU- z{!tW{sv#e1R>xa=n2Fnt2Nlvg z$LN~3if5l4m=D*7kG|@SN838~D-4N5eBf#PQsuzM``(a{L*5+H;3}1jNa)Z6NONe; zFhd!lYeNG`Nivav2lLk&{SD4~<1D}wosm_L;^V0D^RuB|Sm+9_~$wBW=1d}J&G$TyXm z%5TEf*fgMukIs(puDG@W2842@ZqrDa=0=<87iErAFy~}|=R%e@!0qyoKHJq7at(kC z>zwm2-T)p;ZxYyMh=NAM6`-ip{VD8*&B2N8H-cDSw?x9!)zu}8DGE8-3qGHocwA@l zFsia|A3v{T&x z?|ignl@;{;L><!xw+>3W3(U9?UGTLBb zf=j(^as${PrQEm@jfjs6hY{-67!e|Gp+d>WI45LLA5?EK)1!Z~Y?AVQLbp-P7EikW zyKv~Se%qc!y3BDa;ikH{xbc35e;M6s^Oxx(j*335TmDkoS;DG}WV3RRw(Z35;+GJJg?U45lwI_kY~ipJv~=8F$(lD(0sO>qWWK^gHMGE+=U4SZ_F zGvPN_;r+;0EFCVULrSSB3l!4~onFuX?j;S%q_1EGM7P%gQa7Zr*&+^}KYg2S6y9@G z%rLyy6D<7fa4pH;Q}jKHNF$5ZgOUhDJFS7bWuF`?-gYi_EB&-$dKopTS;AKJKZLzi zR9sEi{TV#CLvVKj2~HE-8+Uhihu{`Gcmu)R-7UC7@Ww3=2<{s6f8Lqzn^|);ti?@p z!8vuR>pb<;-oNcrcR2G8>AWk7jrToMggqIT1?#QU91NnD%Sv7><;UbHWe{JTNHVQaZYp|`X% zuJ`X1ULHq*@*n!?XFI0&I&W|yfFVG8&Z~Ga8qwqTHJyh|?wp8h-t`3PsPZV!tuOYE z#+yVLsN01*Qb|7aQcqKJxOz-Tus~ts%D4J`*!n4V8Aaxc^7tlGe(7*o=_QOP^}ND6 zxxY#D)ZDc{)Unc)mlW(xXRpMj17aTD3`mr8EOV&zi4zr6eJBZ88eRSy(x^#_s zSE5*zCe)m??Q(tH=HqXln@Ah?nu%mIh4MmiY5WzK$|) z!NEKC$u+;4A|8Xf!;xC$VZ& zUZr?d|NC$Ym(;A?LpieDAEq?~rd)N%_}&wONUbr(^wj{I1mVyJ6%fQbs|xdxkr ze5j<`9U}0Wnaa-P!%`7K2U>U7x+8`|R)#kLcIOw88RTZgWgCLd!+;|@mkj{wTS68%y1UvUJZomn2H$ zt0XUv{>tb+If?+ay(q)h`sAa2fnS>DM9tN9dtvt`%2}mn`L{?LwHe;Iqu&~ zHFJ}Do7y^)5&D{S!=oJeh4>6l7R#i|jRV%bucn|aLijIC$) zSgwtTJO%=y9Iir1)HnipUv!gbXm~KU8rxa+XU&Avv?*sdiM3X&|H@Y@QA3ON5G;x# z9})W#42CVjdD$%5Q4{lw(Z%G_j@rdfdq?<jrgTL9V)QWf?L|Q(RT%>@0?5ln!w|Jv}A4DZ%*9di(Em+E#S2 zDz7i%cV=*2mWh(A|7{VHzd78pn#+=XMvG_$3;t8`F;^{@8~zHTOmaon674~P*^VK! z?3t81Hv)HGM%YZGDiLp%|0WtD=5BkMs;_<&3BkY=gE!jAZ0i?$0SZa6WM|L~X)y+{ z#imRK3lhW{aMdgo8nKdot{d&{BiehOKMf5P-I|H+4^taIbdG&Q()3F4K>@Zl#=gJ) zyZovD=kg0m3!O5@l;|`$GZSTVjb55hcGc$(NB#>-cicqJTSsqtDWu-@QIAAiokS?Rt)6+Q~{-$$bFv|)IUC^ziV#XRUI$@G zh8r`Pa&Z?FLG8Idwql?N=x6ymrE(;qQngkA)$9C{$cWuZNpQ%>bQ4cz*kNhmR5f0t z`u0?d&dhp)|IpRSN-Cey@mh0KqpB1P)UWoKdVN7O(W{mW<|_i!)?K67T{jU%scf22 zk*t5UhP?l=ttIL8vZgpBe2X+pS#VMM{xsZRFDT6ZDjiqCqcp`(>bE}eAYvkX_$u2b z7c*@8YJ@Rs@m`7M8S-sVYQ1MJ3l0IH4^WZ~m;iL;pOWP!p+!$p(AHJlGE{^*S zn(pk)RYUH<7DDy9{+zQJeDECw?ED4i@Pn!fpN~wRSGQ(P{gNz`lK+!jgz$#G`fg`M$y=W5l`3FB zk}Rr*Ue<1F+hZC6&mCp`f1i8Z6x-HA{IfdwcCveRD>0lFzCQ`LMb+N@-0_s}Ow99>^b-UmV`tU48?Bo5E_aWEEJ9v6dh|1U zici6HN52uS3gzMV7i#Qdkel)SobplTyj|n;cU2_XBVGT!VTdrx;zGwe9oR}};dY!X z4cIDbkFil71*9S06SDIJJVd%=|*-6qD6}3KEug^ zgw8HR57Ym7l0>j!!OwE9BEi*B?&7oQC?0fCZ(+rfSL(_#Y>7MrOMl!et|y`riEhzm zt#LbXGZrFu##Y?;yn5BAIf8(c}VG92vKCDmT6^e zDId^?l0xG13)lVJs5)g6QkIX94p;OTt_YBBxHM?$!_=l_=xsaegow$y!x8@FEgm|Y zS|%(JaF<={BOjMhf-`?G@)phn9OV@i(GnaI>tcW4uX^Y-`Z!@Oe9Ienm)rBS7l;Vg zZ9MbTo5ox}Nab+k4LDvm^DH$dvsJj$ar@4;mEOGvnLxE-WDC*mQA zo9uWNzFY*&!Xxt}&vHKf^>~`)$Adsfrz#W=LjDYakfWdz8}O-uWE&Mha2myDjINDk z9$&MIdnLev#N?~fydL%|!hY?1$>5h;t?swX+_!fef*&q~T>rekk5xrr)i@H-(m!_u z^(&1n8?@eTFSK59{&(@I6I%h-9H=^R%kM6r8b|G7s^tvKKODeh7d-My7IQx)S*~^| zzhA+SHcP1zD!YcH{I1frGHHc*gn*RmO0CL>=DuX<)W;nJBt3A3D7Nv~Ph>+Y=oxvv zXGKd`$i15PU`tqvlATjJ{0}Zba>2;puDZIJ{cE(t<8+~#rPCOHxF>i{9`K(^cK^4@ z+!rgA839l2%a1Wg?O+2KV3m}?UInaac8jkWxhkf!Au7+1Fh;(V7jffKB(V2?Ltf>Y z;uF`);!$F|QVxZ28j~;}Fb9QoYgO<}b@11-B~D@GB@sMANXiPa>LqR}6TRyl%XG;0 zo_hsTdCTAyKn0BR&E7#j3CnaTn(hz8nfns;+nw4);rQF@2eRhsT)UwG!PO~e)1fW5+dJBNC$PR6UVr3wAf!1lwT&o zJrg}i9X2=m{`s6=Hq%+u@tkz%Z?uLd?%Lx=OMML{TMyVD0N^=4{+m#b3{~gv#8oa> zo}~K}F(Fq|0YD~GicgIQCEnl-H&PJtw~xzTc+NFOVuQdZ-3vT#fqNS0hSGd{C2oT_E?Y76BE; zeIQdZDE;Wo&w{ZOxn4%SWLO!jOzAPU?Se-6y=DO4BYHKsGGP{*p_&+r9*1u7=v_ur z6U1GkCm`T$8}29XFLZOM^0$+fw}-u$Elj+x(Ww4fQ)ga>-@CV7YY$qK^xQpFk^XxD z+Z3}=x`(a+6EAV0b=8m&1(Cy@GDrLA=+{v@&Dc~kP$2Y9w9|^T{!S!ld1%FIF zo0+~aJQ6=4j2g#v%D3p-7U-K^OwOdm=Pjsu7V>)9bHqtRx``vvqv|)L4rNhSaoonL z3bxShRei1ixenB>t`e%P^taRetY>Dbfz<7#yF#R<5A5g{ECB{cAYn!oY&>S*6? z!d<>g2!70d=5o;Naa7DDGDD$SJayE}q(!nmA?MzOR zV5AeyqxHV{#DOOr15m`{Hvr(@@;;EAOE*yb_mU$=U{Aik4)%3w(koXx+Z`@}xU^)9jDtcO=EjIj3G2DZiot zMF-#XH0`1)^6;&w)~m9x9!HXxT$CbUk?v%Kf0-5=)yF!fg{KGMek;sb{H9tuc_cpW zzck6x+NtAz8sGi&oDsMW={Wz7&D5F~!c!(7UB17<3w8*8kq6emBA#!xp419UUd%ts z9tT&A;o(2eU$~tgo&5APuc6 zMKLj)`KB)INsuh2`NZ*96<0mkT-9a@Ku?*!5g^-39XK_9jEt-chwwZC!@u1+A(j%x_9_-(0MRrYLr zNIIlcuwkS6t;EwVRamdgsK13*>Gb|wP?3!r-8ZMSvdUuezPs_S?^f*a&g_Tp!&LM2 zGvDM}@wLj2`v=LC*%q7ec~Ie-3bae>Z1vz08EfY{&__9&{>9Zox+duj^iRI28$CNU z5ddm(5}A`S_NLhw|6{!O6mMRvGl>&g0l2REA1~KjXfta#12(tXuT=gClw3$ZW|Z7I zGVQ;|e@Ncn9CQNnM@~}ytI|bi2 zk64IC!|)BYUmNTPhtmwXuJXY&4A=~{6va_S<{vgUf7u#JFw=LS?}-PTvXAb{7Y_6f0-A_==*U9ty#~1RRY2SgJS0f!Rk%Rkwr(HDtV#jx53RtlBKyfjS z%i?FFMHCPY1H7jQWicb~!nCb?>x$sW;rN`Kg4y;7U9PhA3RaIdEcdGZ-^V1Vq3r^d zWCa?4D+KOcg3wqvk5{}>eVZgMUy|aA@bOE$S(fn|w5%JS%(=#BXV%>@jeQ+yRqre~ zJzmn|A}T-=jD-==x1{kk>FuD?ur^}+rk0J&c_Ia_o|Hon z4~4%%lx(+4b-LF;WSoUvkO~_x$Y4P3CdJ;v@~ml&3uSHtD5sztW;7KH{Hf_r9NCKV z8uS(&-JCMiuXAl9xV}sylngNR=05aFE`!C(U75D-RTj7gdpjX01KnD>t#+JizH9a8 zCx4NWEN`v30Aj@Ls?%0fe7Ens3P*|6K+gU=_OU>#W83vGi%ZY9-vN6zGon=^N(xa@BG^6Lwm3Z~G z+v_F|llcGMzY$ImjTf8Phk!~C_t3h<#;KjarN-@F{OeAOvJuVdr6s?LIt8XOIr=DZqNq&5TgCK_UEGqS~;~yJub^D+Hyq*G%DNoTG*_tA# z783(p-$p<7DBT@um`_i|Vt(wg-GftE6a{Oy^{ADilnedC9K#?`m+ z8)e49^S`uLmG`JM)hKCNoi%MlJxNx$dj-vCI-7zO&IVW5v1;Mt?wU}P_Y+}J0$L^H zX9Ms_Cg*d|kbZPuZ&TO~{aFWlZ5^5jJoaq0*^BM#X+f@|e2G>kd)TkFD4ahl9*)te zSV}laA<3}0_RFe_M;A2=jW78trpN4aqPtj-LFHYns>4YYTf@&&t`gk)3F-Eb-3e(I zrRS-N2+rF*8vd~kmhz!CBYPRYeHrvfPR+k46fzuA74t~+2W6+7{QNS68D@WYwkH%a zDSqBdai_DrYyUSF6Wl`u#>K1|GA^v;m7&t0y5s`m< zopygRyiHhuiW*glrvkF2g>5+u4C_wP;^ir2>JSJqw@U|$Sh=zj3e=vju=j)7RdGIn zusRiWL1Phed#pMQ<~xH?s8WeZ6l9czeUyN!{MIjaj@b`|ZOoC=BCO8q`OF_T|F~3!D|+?#nPY{~BXsH#os4TyhSneSDXumA zY$Pg^!+=YlQnH9O-$;R)%HGGP8Gf^*i_$Qz`c>?dmeDuCy~*H{)62&Fk+tY_i`|U^ zZpX7Od~Zh>meQ?YqMgSq0GmPRf$0gm+f$-6@zY1ye#>=oA_U1`+QZN6v>mCA$oCC9 z`C)m)G8w;gzNSz0YSJ2ul@#6_TylTQke?RE(E{UIuowf-q%OMHI^<37{p?(Tc8B@8 zFC}w|8Hd)6Mdy^Esc_&ioffgxWIjVjc-vJ~@jSlr0+heq_KHIbZY(v~MwgR4mCtY8 zJR#%m);CUXS~qJwaX_!s(cV6fgDf1+fj{_}>`78|ccu6#p|)8^4#^X5f2z8gA#AjN5wW@uabHZp>^Km(a`+)p;JRZCGE~Did_7h97@F0wlnh!Ca=Y%^0 z^JAFIHeN-u!&5#q6KjfQt8HCIt_Z77VJU|?r!UkAHxY{Uf>62*UE1uW`IN)y4hhjM=M9cV=V|0+&|qtX!Q<~0?IEw>btPL@&*e!; zi-6iWrz#ZC8HxlWt^-<>hrl?e8`e1)u_zm1RnmDo zu9DU=ZZxB(9^sHOaEhkn{blCt0X?jv-H5tt#Y>7m_U!hvpqy#_SCs@KSn=xYVerUl zspH2nVbSi+!_kc99!vaB-#C_7Up}Q?$9$)JIW9p7!IxD9zLIeYJe+%3#UFub=}Tv`lBe5mM?2DwScC<73!WYJkuC`08_+{81BV+g^%D# zYs3Lp>akNHH~hVqpOE<@F-x{_82!_30t^?m#=&L3=_Nw1wr5eS5$oc7Ee;zSKZ-dQ zSyz2i!huJRD9i-v4QzaY6ei*q1O$w(4S|bGDl@u0Is;{BN^1cg>F-4d4wR*ao=in#Z?+7Tp57||Qohd_YFtw;N4f2c* zZB>W}JH}P)fmoV*kZi^5yc3wPqkB1c{;_=I6ZQ_MVm=I{a#o6=ibSYor?Z5$vn**= z-HUc+<;RDH?9+2LR(-yRbBbvcYmtM03Do|v5w%u$qg*Z4M5|Fjt!$U|EO|gTm5%f z+4)N*5|n%m+-}JXRxJNxBz|`>8h6UQ`i*1HUx`{8(t(t5TW)2zZ*^m`Ga((qh*ULG zTLBI*2R>#3SWNB^5ZS-PTx?OG*Fs>=H12LZ!qms?p_vBvKm&p6Ob1lMnvYhL>{0Rz zDhID_5*S7nUzf-TMKK7OL{9?ZkOsuW^Vu_{%v@?mS|~NkN&XS5imaxnZg)QVc;ZeS!9Q*fC@a6raJv0YJ4-hd_sYBU^Q&1R*5H z(MF>Ek$Tu0M?Fb8=nIVLge3E|VC!+jdpmKL40)jIWmR9#n9yth&ZfQ<%#2w0Z`f8T z=ztTfW3I$8XLN%aq}Ik*rXsN5S$pGZJ~&%bUk{TLd*|2JBZAU^p8 z1ay#xcV0-z;ALgr%DC@jZdX zJ1xkz#XsAPxksnG(p}FvYBIzXy9Axo81snfd!;_{>;HhSf8r6#$CpLYKJD5~sHdlJOebD?9VqM~ABqqEh$ z7m4wk7mHB@PeqKDG_Kd?*G{nc%pBEn@lt=cADfLhbcdt$DPgkE zKGZ=cwPk38#Y041nbXqzadDsLOt+`GsHo}Z&#gL>0Tvc%%nzTeXYx$^pEQ4G-T(7T z`1|8GoJ7ef_1rmzS2F9_Rf5@lmTeB@auERtagf16^KURQ8BxcU$r0{53!m zl!_x&)8Vi9`4iTKs%&QmM}IPba-0SmJ}9}P5>Qze7nc_nR=2k!f2KxaUX0mKokN?? zFI2gcD#s{(g*MjOv3Oj}b&SkEo0g%BF{dDKm@L=DR;7e1vR<=`2ZOr4a8uR@OuUe? z$%ibzkYY-SWz6#Fm%v3Zd#sk!Y&Ao{WIvFh!~ONG>-es%OL;sz%c&MNN`4&0Q}5mU ziC>oQ25Q;fY|c0R85FZPysvKR%@{;W?vHt~jtENqL`7$g>1tyh{K_syKNA4`CYNU^ zN{6*Iy{Q~Q?^i#;A_p}!I8sJp4V*I8nh_kWw`q zoB73ba2W;;k&rMAF*Gb#go>6ACGyxcJ_ZdLW&SJi;gRjgA8GM{!|-s<*jOtPlIams z75x*GeaJ&)O2}L+a&e7xiP{P7G0_)m)BoQQ0L}6lmB2{@K>B$B1K|Fn7KX3tyAFyG z?Rm?B(OWEZR*l6q%8!!|gmDN@E=Z8ME(l{Po-m8ztoGFG#t@-e@q?@kJe^z_4-yTkiWasy%jlSiD zV^U}sZc>Q;^9#rpl`PzrpYvodK+nxYyePO4~0+qty+fzLiZEafYgR3@R%kL&5Cx;sX@;H()`@^q~EcZ7p ztkl`4?o*^naktAFazL~l#}@Ff(rSIwt=%K!BeYBBQ>mFU(UPbJhJOL~>TVhv2;A%8 zUOD3b-0LoOXYQZA(a(g+HKXncaA2~co7o^$Buna+dWgO7J5{(A66mn)b;C0&cU~3L zWAx^&<7JOduBQENm4rc|!}@n`Uw|+dNQX|P{)gl(K>&>2+M&DHVp3rLcFpzvF(&!C z@8eBW2yEcR&d%A`P8x_6J$LVv;^p#%VXONDh=?%o!p#vx#3Uy`BS0ZGz)3^A%FA2I z%p}1iTlL);q`D#uou$iXN_6gdzoN(+4guZVt4&`~pe&rN^xq}So?ST-)ZiVMhmR#_ z3|Ka(5rgW7+kb@}9P~qj?$?;k_H933MQ%)A8t?vi&lmy7(_=58w=wSwevD1(VoEIk z;Fh#~ciplE?X_KNcy1sf-M&bL>*+k7#AhKlY`;p3VK?M+KXA@k7NRI0PEyyp7it;# zb|J@LK6Xr#Z9!@3-)DR|lW%4@_0zon+o4dd@Xx}|hikC_C4qlye*!n_9gml~J$ZL@ z+b+hp2c!w`@m&lr6=6XtTK741%A9neDDWsx_Y@rdkLxjP8G72<>kYN-)2R){X1W`T zZb+)0D>aQRNlSh0ZEd^6?R4|OoGBgsDcPGF9|z<$c{ZKwds3KE7~hQ-A=g)>76 zS8Oc<%#ZVXzC4cjp1(w}`)w~?{wcjVTF8vlL2Mb*XW)W6BTUEkxn<7fDz_YmtVl}I z<)0ett@$K>WXw2A|FgmEbgtd%uuviG)NU~(Nw{!xx>lQ)7i5%1Zm&EvWKk%k0JO2D zf?z_Ga%3qDj3tFf@|LOvyN>_D19hG#H3 zXoQv};>m0uUPa8AoL%7T;xZ=;BGzs|M%(Fh=p4yR8G3u%{};P)EYiq1Xj zZ&6V)w0?Idmm8hDCI#-IwSQ-;wPk*{w0<+%yc;hVThjO1P)JFkK}BsQZnx2IZa&x0 zV&5TP92lgQcYb4_H?2STcYR9{(AHkO*FTy_Gp)((es|dK>L7owR!fsxrcMS8Bcm9W z5WWRU%$ za0%B&O;Jy%01vJP8r#+*u^oPO~AJA3-yLUvEFUQ%(40#_wo3 ze9W_m@Jn_3_n()Q;Mil2xQMV^Rcq(QiUCQ9xMgo8c3?XGZCtBcQ%6UqS3|nljm5us zO5qxJ=3pfLys~mlUmcG%L(j)V9aSe|`LjaHm#1JWCF8yE2msuzr7n@tx)1`Z$>b6D zkT0I=cQrN@0&A2T^>V}x8erFy)+nDQV`E1LgbpKRsuA+iJ61l_4X$4GxT6_JXI+W8 zCUr-j*4vLVSv38Vb6sTNVk;RVe0Q*vbG5eI;Dig~ruxSX(lN5$q?jCEkqrinPq(%Z z(lH#h2pd?x%OjyEHh8Np>x?lYi-q#eUpc@4wsH|SJ10ufghP>84JzI$4b=2hvXn!S zA2M*4^$Fxe$Cq3r6HT_IxRay{ozzLDLXUa0x03tT=GG%kQcWfOd^*d)nF~ z^%Mf;N*&ae(t4hoXA4JE(=kp^qbGDmHw0{R8Sd`Y>8lNts)Y?WaQf&Bmyo?|)clbXI*2%y`%j3=f z)p2*2?2pGl!U$^yknsTSb-b>#G~;*hK>|FrLPc|rj#!uVpY$fxTFTG;D;KIYkc96JiH7C3)ILTuWe0_dNBX=n=07&+a(jYE9ahLCfuFaVoKT z4MB(*pLhbpchFL!Yz$jxf)Wshl)T)V&Ne#Dwz@GHlyY1x|9YPaebRL}3i>QP`xdMk z9W@O>aX6a(a{UlTX5R{*&TA8Dmq)x^CjDlBLO5rt7J7!oGB&|Ok!LCh19RqTP_>X2 zZS4P9M^5)OF`MSI^?MMDq@g<_S2NDjn48lMubIOUkPh>0GX_5?=BO}3S(yT}z-_80j`Fy5DEB#ch_1ll~+6yH)#~ft; zMfQx>P{YoHvu`-t)rySNnEzwU)ocvBpCQt4qYKf-I@VDK^ye6XUq9wB&ZaL=x2i>Z zw96x5s2z!Dnta!~gMeR>drop1-2a9#fSlU4k6#{T@ju2mR}=#}`DZ-AFqbn@;qKZN zPhfcbI|;&)3wYYQOzvJ^x&_Ytj0YpZLwO&RzE-In?M7rq@^V3)*6x;^`M9cl9xlsE z+iu4JEoX0ns@4fi6?!E!@t_|bj8QD=O(aYO!>jn>#S~m1VoNkBRux&Z;^%$^?pM`4 zV1oKF*R_3TW%&5EQ*9uzVx6b$!^d_de%h3F5exS z`z!c;pL4XB+Mu<+;~|%Y@L>g`H^-GQ*aryC% z?33&6U|d|BwtrEZWY>nad=?&>rxj}4o7OuHe*hB(==D4VZ7grUh&LDlF3hC48%AcZ zKjDx;W3w9byuXkUm9#9Z{Gae|d(Q-<2^)`V!+Cr|9Aui$VPTRoKRdGq>UQoK&c_m9 z>)TodPWD!XEb(-)w#;lYV-)pAp##!r?hn;mu;^{F968cws6ns>;y220`HJMg-! zgs3`>xa^hQC(1x|6-YQaRg4Y2Nk0t@VCy{%c@AVR6f^rcX#i6v`w~AZH1;&)@L} zfuIvE`%hsHcuM|OH1~=wos^DWu=bSSNtpHeu*xS-lMFDkmL_FyW#IDSa5Ev<(V-87 z;1@iX<4<|#GK6Z^fi?FftFVVa3)YB)kgEEnfPB|Xyke|F@66VQ%6XTC)Bs>+3 zjhxHc%Iir52#Oj2c=1Bbj8zK%Ram#ZkpYToh*X|7QRvkdeOOwi z{%wDD2H45%c3shj96?-moUOw( z9>O6{6(fX3yshl23)+FV4+Sg97hmDVYG|E1|Jm@@QR6Y8knW?_;{;Qm-3`-(^0O>W zoyMqhm*n~AU!Fu+EK4~ect{PP^bWiWYwRB?FyG5qDMn^NsqaNON*bmKo;g#j&Wn>Y zp<6w@l~~5~DfN|d7H4PFz*Ypro_1&p z$6gZu-(*3ZMu8jgB>&K9++gM9yj-^}RO3RXU8*A~1FdTl{$2+=M+NNH%4BE>gf=HJ zVZ{lq-;PXvFZVr=8S>jg%j)|mZ7dRhXo^qs;6OdMQ?HM)vbT%?pz?=<+qgK-?8zga zuQnThWXwkmb#_{fd;2$rpUNv$kil{BN^(k_Lgy;S_4tkKhyVcK&Tqs zBX;G)&LBfOHR7{0hDubh3L5IT;^o(aWMTEJf0BL=%jb)@V`&R`4LT-7)8?zbIa=wm z`p)#z)DjCWumf~Mlz+@r@v$XhsZ5JMBGhCG|E^(2 zGy2qw7ZIx4Zm(;sqwu+CKXjs2zrnnI9pzGIZw7$f)$K%$*wWvHQ+=b+7B#J69E4?g zFO7YmUWI_eBF=(hlRt|?BEX2q(lkikaSeuiz)2Iuu|+V|#Q=XNC)Q1-*#>%TUz_%- z(0&H=^;TNl2jlBE@UhUj(ZhH94HfN8oQv@3Bg#hNPfEjz1Bo|C?YC0pq?`W?B@1}L z3g2$dke+4s6B-NXJ^y%5R%J8-Tc2mNLyd;;mTvLx%&&#&99JFw(sEaeKo%~P%}H6I zq;aC!rx4=*t`21A5&&}5@-4i%Se)(>IuD8-w_*6JrKN?B7pY!4)d+qgDaP|m%_OKU zkpl^=wK)1eJ^y=5bQ{k4k@^)uEh`=|qSar>XKK*!P0(+)fR2u?V6F5luW6Gp#i{@s z@`)tso7eg4?~83E28E2Dfv+Zx#gMq+MKgi>OHNXjQIcZZ2VStwhZr2|eGl2%54eTh z%6MChLk8OvZ}4udvx z%2Ql`lXu_s>oH{22s=!7Dp|JvE5fU9nOq2(?^Lqfo|2wvPD3XIlcgXRmAJj*E2#O` z4q=@_PC#4?x?Guj>2Kmqz4CbiLH*?_7O}H(xbgl*hI?XFl`;a1s(0T)MUF7s!^Czm zUx>~A$Q*o6kdAZqdODHq%74O0jD@=d;m=3bDrfJz&!qn&%i37#@ z5~s>xReAj64d#yt9q$OEaTt~%Q77f9ZG`OcL9r@If-h?S3Qp4u)u}O&G{K0|Ae@qV znQA-)7ySnv6k85|kOFj*BelF&GLA_B!0nBHnhbE^>%Un!ZaToPR)zLQCmR`ms~3UjM0%e>i$LMLQVe} z*mqn!Q1O~iHSuVYgG2awxLofEA6{Sr>*~!fe&+*!cIW+6+SX;W8>$gSweTZPhwZjImt$~KuRU+~?1fUX zf3=)v$jMl7(#hk);nQ=jX7mMo_RD&w=;Tu6v-lGKn;LxU_UCv}^6}ELte;@g$uXM; z#w`d_MlC==DJ)WFnvG&fZJ1~*^X2%DpFWw%Z|{ma@ah*(0%P$Vcazcwhn*D@He8fgC$1rJ{dp!*k7{(Q?vMgF`-uD|6vmwIozu z>qz8ZO{FV4PuSVdJhd=Qw{e=qTg>*Csfa}WIb6`3Z)V&9#iEo4nly&Bdz3tq(w7%z zg%jou32U-e6c$W6(JYF;@~`&f>@x*LOq{CzHC2DJ<9f+a@54aIV0SqR!e$Cf<- za4x5gj*dLcwp8;^7_|pWwSmBAyM-7B_G(J|mvFSy)S@PF^tsbprAm@II_FbU7^sjA zv@$pA8-bzo@7+yjE~D;4Q=j6(7UtjG=U3E+VO9BuI<(=I!mlX@3ltf_oasHQ#wkjz z%bb-g<8YAqnr!J2+O#mcDYGb-xm6TrYcAYyrTV@|h#3elgnh*cN~yGxkV;+H`ubu~ z7xL6v^~2YTnDLBo1QHRcG>@~6uYawzgOQuD2B&!>+^2H1K>)|h z^?;wtjs9^2|Mcf>lH70{*#!FzB@P(ChJM*6MZ$LwVdT;^l_}%t)`kyjDPopXIM&d0 zb_t{wO#7%ejKUFw1QQir;ylMQs6)kJu%Dj~>vg#^gu}w8fahDPoX(~#>fim310k4= z%EUreC*4{^^UFe=<~J)6HUd+Gc>qsXmCi#inXf|BW!y&x;36(!_>}8c=8@)aW}HXD zARkJo<}W{81jRL$)V@J?lJ;w|1gf;yXE$(>!oJ`~QhaGLapL*MJTFQPoYlQ)M4})n z094qjo(OL(ozK-s*=vA$&HI?E3um%E)x&s3M9yC=@6(Kxbx&g0A23)VP%|P6UllAB zp9An?s1sYhr)uc$oo;k){rH@Wh*n0b#t~+ekNG9whFo1}nG?u3C=b7l5TC_`B(06n z_Oh`uF_G{(+HxI{X?%$?%EtJPua`Nu;%tv#EB>J+B*b_6`QLSUPg2Ph}&&95M7#uKFO68_yQOw-2Q!5>9hB)>cAfBr3&jf3D`eyNm5O__>kc;Sp)t zz~`{|hsOL2EEJ4SuFj0|gnyO&`Q{z^H>=Frz?b76QrmSFk|qkMbW(crYU9K(@P>=+ z$;15xioEXVM#(EuG->nY5W&*qqWb6DM-@N+aRn)kyoRmnhw`Y`D zww-0LW)Q33Jr%2O6oIcIexN?yGZ$7y$0bQ@5|OQBpnrG@LgCTGxX)M>?VCPL0}d7E z(j$daW8 z)|yh^=vuoZ^jY~RUF@Z#l6Kw+=v>F3o#a52@>*WW1;;c{6S@(b#D*upnaSjHiN@r zG3Wp*ATW=nSL_U~5&-Zpef-Enh|S2(5c;J=0tX?Jc6&x00A{GUjU~|;9c}1Am(9p) z|76SoDII7=kNpp8p0m*Ng3h{cMrkNRJZ6$GA6r8PYyb4#?Y;W^yWrpoY~KvSf3DCj zFD~Db^rE>u=Hp{2HI|&q7FSU+%dBt-!$1)Af1Oy*((Ekhq5$2A<8FsPb2ksYOuJ#|vMT z$=!$&b7h6SIYRn?!qk%J|I^f4M#a^1(YiPUf@^TMMgqaz-QAtw?(QC365QS0H8{Zu z?hsspJAHQE@7^;`{obRxc316^Rcp@YlZWYt-nhbwBM(2nQqsbwCzyq3rAp-yqoKn) zkyQ?MkD{hIZEy76xDWx1(dwBJ*JmWD_!P_KLkbPjJSw|;4A74>tst#lFM)b;I<_5D zn_KOTL%@EZ4K_y`^X235Z{bqdgfBKy_J8Vi{jNn#5%51pbH)QH&KAY?%`JOM<7(n1 zs?FBvxTBc6x)#CP{#5EYbZOAwJNv3EcVM$Tc;fj>z!%JT{UB34Z~{#~q1Xzk z2cN&dLY6czCHbXqv2n6HA|X*7ZrGWgwsACbjt=btNQ6$Hv}M?uL-T~14IjtXNZ%1) z)HaC}j~Vspj>Q#gRg83Q$EHlzibp+;(8aU*f@yh9PEpl}3>XRt*(sv;HX|tmT$7Gn z;l{_OBJ3zF8u{6z3qt3&1tRKrYYKWvAwl_1*$ae`1BIGczS0y z)^1oIoHQzEFpvjNXy{>#!`NX!XkoT2yXA#dE{9Z&Gy~B^)1o3+)HXtsFy+_~tyDXG zh-p#-K|P=NSA$VC*P?aujmZQ}VQ58aBf7++t)%nGM5XiZa-ALq*Q^P2k_V8fT3jza zw|5lZY0u0kIdHkFt-|padt)s4#d{>p||h{+)U+*DFyrWO@gy*u(KoGt_9 zMqoZN{-A&MsVcxGe4AFJ(@Mk>fwi%g<)BAW?7b}yQBaMP!`1C?O2Q^b!LDjb7DKNh zO)I3qXG%}|7$NYH)M62>%62VaM?~_Pa!?gMX$D^6=*}#%>-%w^ohoPCV_YTOJl(Re z_xGG~|0T(A>u$*-h{S6#$uJAmagBfOe1SLF$|s7f^Pf{}z4yPWpCcL?CKWaoq9ml5 zc8sFL3P2OZR{M|PCJ;&I3BPvqP!q*6`j08W#)&y7l`}niI2Se?4JI*@0N|C_0~eRw zaMrw5i=Eq|rZDU>NPmfsX^ki|UnkHhBph9IW=cFX1cl>lw2X&%sy?3mJnS3bz=$X` z6N~KkGkHUrZfS|S#iYa+q=M6+4AWR_w^5qa-Y>k}z=mQlvE!SQ2P5_~|4A5?$C3U~ z7{dE9B!JJ&6*(`Z>+-RjHbE;Wa+bEKaZ;L!m8Z^Sp=`El^>e9%t@t~Pc>h2l`p@pA zGV&t80pbH}Sc$u3oH+H3Dq&$T;^c`n))ViDCbc-tI7xJRt}z~qzrlIX;xI?z#b7Nl zD52%id>Wq}l)86#F0kOe?RxE%S)uzB5f=jY~-&I7Jo@`-JGCke+;2JYPMUHZqd ziqhdTJ+CR$&->;W&;ad;J#UG0ZFj0Wy#kFDr=hmEVa^bJnFHT}e(>pdY(vtZXTOx_ zBPU$t=FzB4X8YgAL~kSQs#f97AMe-bpc(8T9?FIcnZh5Kr%HW)-UmNt6Rv7d+E^`N z`AfjAChD7r6GWx<^r*J^Tz~nn-z}NP{g>B+wJ_H#n^22%dl?>e&eKqtt0)+6?g%8p zNsB}Y?>LJ#1EHairRcveF$WS2Jok|8h2btxc}6Jmv&<`aq^oI4lmlgc%=5F1%Q@y* zD$v!X%8N#uc7p=WG9or+m-YLZa6Ig;Sp?MPztCoRPotqS=6ao{dQ=M@K9TmYv$4I2 z(7X*hYAdlRBor|tPXvy0laR=2KtO=->u2Bzw1VU=&ra~asNF8~D~<(X6XM@Hps(U* zESl9W@uu){QYjKSrz?EoGP$^F)IakjSp~ewL`y@OMHIW0m(4odtol-91ziGTg0#zL!b8mbrPcSiW_P zg5#O3N@0=Olcy&Giuc!V(OYba`-)fFSUX+4WZXUMe1jK1=|}5kqTL9Q>Q5>%NI3|& zm;1Iw)&#KGMNJ+mD?^4LS-G0X)tsQBj`mB{xI9%B7`(3+#!_Olof*2mS{M3Ry4$bR z9VP^|y3zfFPY^^d=SLb_={DWFaw%XAb3Wk^&-dyUC|j$!*pI`9!arMScLGb_1#z2; z74ENwRkG&5OMJxQE~K`DtYTvmU+JxsBg%LCyn_B9`ElW80TLuXndriJ^7eBOf!#|g z09rjUhU)tGgK{Ge8e7x5E}B`#j0+tVH{-l;4#@4LMt<0wXQz~zznpq;(tNalMl1Q> zKn{Fb;AmH19XHWunn(7#T}TQ+BFXW6{{06;EWC^Rp^N~b+0Fa6{g8r)c6lXNTx44i zI=_YAoom#WD3lqsgpOQ!07G#FP$)h`$*ucf$}`vc5SH67;gEf(Bwc*suReI)Ie$$- zq!Vu;FIC7kNtKtZI1K7ICy4)okDtZsk&~-Z3Xwt$NHC61rgL6UTZr(p$U9V*i8DBNU+z+*F+XWARuDszDWot^+cvF1N19C%7ls z?o@LEY}IzNQ%t6)YhvEsu~w7_)bzL5&z1I;#cn3Y19lbF0+| zId*?R<-e?V&_Jps!1c?s-(ntZTbsqCKfxEL)S2jGd*(K@Y;gZ>-d=!!Vz=M7iSjxcz5)(%i}e{}V$JM2!7bQ7@bq#- z-X@-oA}=xpN8m4eBTPr8kKlCd`bJ}>oBuY_{bM@0xsAYm2jEEUinkF6=c}n+fUt1C z)U2!NeoJ@F)b1ST6cHuFJ^tR)%@0Fr@gV=_`X>ecIwtg8#4@^;D4RZiG7W zNsEJ!lbh?%erKIUEX=j-&t?T&tfOaWWlD?@Of?@1TO-3`?ZPX*K7Qe+(`k=f<$!Ny zEA?KYE;d-x&^vWUh;uGV@ThbxVl3SuvRzR}!q>-}HUB!v$1bj5KqIePW%Id?ye(jF z)$bAdlvSU|f*M(WQ*-^_q(aE&el!H-ur8EBw*{>4=sEBj;tH%kOd zp=wXR9v8;3=uM}uxPnySI>%?xdtP}3nhi7e#Im#0!qp3$GMx>swEUiYS8taCh-N%F zcFVn8!a{qR6of#ycH>a-tqKa{@ODhZ=gihDHX$n>BJ;tsn{F41U#SGTHb1ATh1KoE zbu|Vlf@CI)=U5#}am7xHMZwaZ-45~XO|>`(W$SGlL9iH=eZ}u38@1kAUFg_H`m51i z>V&IZWSs*0CYVnJ`<^#|MEAnf|uztTQC;O$2d0+&nAi<#)s57>w4uT={wpvxYg zrSIXs=E}~2;6qN7r`+Ci8wW*qx?%Rk%hd6i>+5UvRwgMeGLViAMZ^iOBx9Syy}C2# zvif;$n*itT@Vhr(t$j3rEKyQbr4XFfrUS`UOkdQMc4xAkZ8(iwuTj6o8AhM167f1W zxEy8qSm>vAH7J8Fdv6TD{;<7|?#|!P5ssEPe5P_MQE@zDQq)W+WhCZ9QUjh#11jjB zvuAvII(gmC)DE|~9~K#sb%YuGyq^Nz^k?xXINv{SuFm1bgd-v)A%{}B%#u{@#`E82 z@8ok*r_k`?W^--)ekkay_@lAuRogb&c`X}KoBq8DqHb<+admN+1V3dtf&@L{)ZNa1 zdz0W;MBI#~o8?09ZW6n)Cn{>qq1Si>#hEE3Eln*Rq@$tw%m2Eh5v23^>(Igk$^Kz` z#_O;6F{gf_p00SXX1p{a<8XMPl(F&bmS9s?$D@a>WXyIOcHzOs^t7W!&N~Y?lcyBH zOzn2%1e^go4L9kS{5R|ryf~CNBx}~n!06~``?u>qd(jVdJ6N%X+|HYRuW|$9!ya2d zFaC7D8FpIdJlI$uKRh--)HYM~3aSQ;LN zlXKDN+OgF8T5Jh;J_GleUk(3~hS0E@_9AGA?08Do*Ba&q|9=Nt>*BD z((q)ZrH>Q*VV5SUwp_4LVjEH)Hc`V&!i2T1dS9o;ov5q5 z2JTbi%xD0)?`W5pHtHl&3!Ykvo&M`TRNyh{?W5#yKP#uIr|^XBmsTx25J$PX;@;8m zgPnbh^S5rfu|7T%d+l#MefpH^cR%Y80K#tewjDB=9Ui_33Jlm~RFyqwghr3_z?pVy zZpsCpiRF$%>IcNOl5`mHlnM1c92I(p%sIenRva7*Yca6yU0T4>V=tur%Z)t+a$}Q^ znR_3(DmM&u9v&}N8NXB>DwiXZ&XX-3H!0kL?pmg#&U?~ITKxo?UtC=!PEnfJn!=fy#Gm_QY_Pm> zHF$VT_rkFQ!0#-t?s}>Z73?%*Tw28jzf!#!sGn)6EzD0$TOTn_(mekjC*FtL5g{|~ z^rT9Ivi0k0E*>ufD4#>mk;PnPsyt&t#y%U>6ekb5ZMZFMG}q<$LEp)VK14+5OtXc( ze9ZL=Y6K`{FY8;2{D!^W+l-o&xja2@r;ja)YaN}ddC)+6E$wME(wOwU&x;EyW0K-w z4)H}vi0rE!5bub`byuz-s|I;^P3x|I7mtaG=ECDoF_PewVJ=o;iE0 zdQvkjTbj|9XY5K{bT@(3QL+y^p+StBsM$bKIoZB_x&UxWL6Gc+Orf2k^^*kBM50`@ zJGF*XJZyjm`ycjCkG}7K3Af95U?c8>Vhducn^>!_YyVR3vn{5@A83=}ZVH?z&v!tI zt~(TV?=9jAr2@Y@C`L=(0rT|s4gg<$kFP&0#VP3Yhm2hK*==-x&9eXK7GbK((X+Mr zDJ1{m!t?iF!{uf+)`#_cX#p|19Ok~u2PX|`1HJlWzrV|kwax90&*eAyN~`uR7v#wiwDPdRI^LTRpW9`OEh%WO!5&bKGk10n?pNv zWbxaWtO?lVYaD4qgOVIz`w-9cI7@*WUuat*E}boHl5Fo=IZaxOt)?A*!e>XWI7h_S z!SP8s*t}`zySx3F84Oj`lX9JT?14jzwv}}t(=Q4zQHq^YkPV-qTZAO2lYnkF$@G?S zVwMywht{al1s1@;VqJ5g)innkehghA8LkAPOpzv?ya zJ6W+pkHYh>Q`d}fSGhVFeM@1B-nb^mxP~K5(OwmJWXAm73u{YThoFUkQng! z#q6s!$~rF@{B#!gYb&!j7xtp>)~!)YQ-~KAXs1b%!G)!~oW9GhJ=`Bb)kH-$thRpU z$^jZeAppwlGEc*|$SR?@J%q8It7;u^ep!m$7}K$`M(*t{1g6nLV_2$18E={Zr~C!P zhlRw2X1yqGh4PRP8eWcob>9xUg#|)ka~qrZ<`!`>7^)qJC>0=i?%B6&Y))bq*eGuL zzYv`n^7WOwY-9@bI9B8nm=J}*iAU1=?d`q;%Aq7UH{d(*HAjgN)IgMeUCQ#b}CXioTqD$${^2wF2u79Z~}hjudRw&~+HGn3xzK51_?uyBkOn(N){% z4GBI3&DP2pY?c5_1c&H?WxXo>}e$rjm^NRSe&CS3IgrCpMAb72TRW zB$%6apSZ(Ik1p5QW$eRn@C{9{F7oPf1w&GS*6VWuGOUuAO;R4$2A3C_$y}mKTid7v z_)MjbcTXi$(3D}}rE!ZIn~01o;>8NgP#Kh!NP6QmKyED{*Nyt>W~5MsR9IVgR=!q2 zmVxadJ+NPsjT$yT<21qE0pTVI&V?$Yd43Dh8ewkqJHdzb`=6h2|GCLrSzxbE8bdI*@c;YaA@gt=_qH_#lrbc-T;L>T`EJGRW`k#*=4Q4n1}eO-+l8Y!Psind_l= zfmgP02fN>)QfdpX`qVn@NQt7)o3C<<>PJc)i_UC1`xmnP4oUx-ELn|nD($aey{&P%w6 zRZSk4++ib`ygjT0tQm%hMr);$Xl!VNh2dC=gk;Skx$rs}3KX90Dw0#X!=s*FUPJn= zObNOxPhPURl2{R67q$zeetj`d8AWRzIMI0yEm19pzWc(!4(KpoO^B!#v7=*!^T$w- z#g)rNkwOP!2aQ%5Dk%eE^3GnXimSiKpiaURi{9|eFT^5hK)4Yc#-PY_tMf_y+8v7d z&Y(?>ds<4+`9O3Tnwl8mwCG6cti z$o?FI-xE;Hz1;|cU91kLVnAjVlQff`A!AWMG8VB-!bECIzkIHW!NZ{dR~8V#e9Tfm z@d5&ZqNzNiMOv+}KjCa|X$ksQ0p$Yw+NFcQxZ*LiiQnZ=F71JP$3@`MVf9~R@IYSY z^F3oiqz7kUPaczeIWn_Fjq=HTp;mg;M3{!l5!H zb|ur~5v7m;mV0nRlf$UQueWzgOAop#%JpKa)RNMM<&8+N$~nfxHSprao28+*=hXN* z>s2Ujy6iw~%-;Z>^IeKQ&q?{tXOAk(ml`d*%_+J%g@*V;UF=yT{nfc<6maRoBOby7 zdyrR#7&G2y+A2fB$CfwO(p=0!Ox11Fe2J3(nMDmv$&XSgMCbT|lE}8ppdgnruZncx z2L^>|2pn>|^M%rw;RiM$r=9W;Y+w#c+_LK=tXQ}s)jWwrh!2~gsn##BRURQ-bjZ0R zB1)kb!Eq-^mpeR#cwzhfqw1Ki&Upjadzi(;;7fUz(XhtjI(4f;&_h((_cxeNFtzVv zh}YM^f%3RPz6ZfS?9ac+Ryj@+A)*rFD?x57k3JBUQo(gyX(=ak35yW(4eo_n@nMt! zH{SRQ{X@9Z0rvV0^7^@Q@MAxjXzyMVj{Ag}V`~kvec561A|V9}GXYk>-wOEdC8K#f z4x>WJ(bY}Q|7rB1TVn6Qv((F#cwh1PX~?WT$E-E(YFQHtB&aC zW~!TY;9XsGM`(CG3h})s?+otX?~MQR?byYI0(-gw6w7HU>ENk#t59?D z`_Ti{OCgdC5sDw|JbXIs`xy!hr?O}535LqQ3u;V^^tepRI?{ByG?*cirtX)cS0J{0sE*2NAUuR4yAg>=OInN@6HZE0 zSEvkfL~Zme%Ae476bmls{6zPwq$IqxHD}H$Y}_@JnO4VJ@0-azgEEy8huX`H&;jlC zZO48B*=y_O^Out!@1j4)T?t{yL|cybvG+DSww@*ylbLPR-fyyDq%1~V0N(L zA~sq~U%$MqwNSx(7LW|Zma}VCphbH+ErjJmv(>$3Pz}{V`tXl?UbNuW!8xy$DkgIx zcr4k4z4Pe@1ef%SCRG;!@&v>QD{rs24CAGE)sGbTabi59Ygp#_kkCHJLqLaE&!vTJ z>W;Jdmm;Cs_AX^+7jO2CnBih7UoMWg|z^7E9aO*=-GN& zN3p=WP-(~Hg`;4*c`piW=G92Kxa_4dUWQV8d{3_YR)sjpv@Xb1lEnE(4g-u!v&W)RW#Lu%<~p%Nom z^o~#dJe@pFqT5xLe&y)ENmlhW88au?Q&$z~*gf!-3R@k8Lr94fE4+b5BVoEvz~J7e zfWaAr_UTrIbmWpEY&Z>%asSN%@kz801Es3#!Rhr_Fi{lRNfCEI@wrY+eJUF`{v1E= z1w8+>F)QZ>ER||&(&PU{Q<_yvNB=BbK47Qa6L7ToiU@WGd`bw3j+lYSW+Ww%m6$SH zy}Xk#Fc!I8eNLxR3TmghkwK!oVU8kRa>JS|3lOh)`q~+a~zR zZjDb2rv$(4>v99@Efgl<>b&?FwW$sxF*X}2D8})R7;raECk+2;8>iLDy=Tq1)Bz?RSU8Cdegw5WRF^C+7BW< zZd^}W+iTKoAGT$WCa(9rB>nlD4TF08&Ea(B7s>Yqjf++7S(R$lXjbz)+^97&BCJBjw64K8uGWdfqR*ypR%Wq3arn{r*9%YZu8oh zLi`IvSh2PU;}ee`q~u0X#(bRf0MAXL{=rEx8}u<0eq?Nf1hVYD*kn6-cs)ria>T2N zMNBD3Y|!9GYPKpNYc_WFM7j)9K4MA|+HG-~h$;+6gacr~L5%SN4fQYIH9l=5fHzGC z5!vK>=l)*JSKlFvEqZoKvnOEu$kXV0H>%w<`ym)w=b7O#%hr$pg_&Sk2er}Y=K$R- zV#ebpw&J%Nps7V$zb~Pep2(7c7AGdvkI2XtN#kwl7>xGe=&)0Go~8-4<@EdwO07#a zw(9{Y@YIF+`|%|mrQ}?3#JxY+NwQ1R7c7e{!y=dv;S{{{9mgBrOSP*PF5CPME7xv6 zRI{#ugfhF<{j42S6o%+&yQS{b~H9M~F}=D|$Cl?d8SA2CI2Po5IZD zEjF(kW{zLrX8=dnw+_3I%44^!URPvTmE3c7`fbcLFMr{<$%?DKvT6a+K36K?ENN#a zFmFjafuPTncpFz)_-FI)s3Hi}=vln>_Fc_6;tw$0Ops5lt*tTDXu^TE#=(hDGQWdE z{5S#)Nah5&iVFVL4&+bLi5jW!9ft~>D;dG|{>JpF?#TdK^RP|2 z1mI{x2BT4ybtuLmI4guEtfLG-VTT~n;nWOr{YeSzS&}V<)wh%?S6%Q^6PGUs5!;Ab z(z?xjx(_uI?T4_|te^30AM5`O`Q8tQ<+%r0-0S1&;y^cA4Z$P^3(8mGe3)2b+qwD> zIfWmN_TUE*Uc@gBf_OsOnRz}_G>66hXp)_a4o%Q+M26kKzzULMkYUX(pk0Kla_mJ6 zTU^a(B7a4W&00zXFdc&hl?#8kl*>bY#Q;PF;U8lg67jZzC;zFbB__KRic$8tLstO@ z@~J$;%fHOXJ*5tYxjKzJN?FZf<&UDPxnjXS2!6& z2gLWcJYjJqMkw!K8E~u$DZ@7j3V0OXe;+*O-c^OXpie+QC)1v$(hmZA`r?{j*QxPE zSf>M^Qt1@mw8F9l$P2(e9P+!GJVRAWZl%)GcXn zlt4{pQBIbT3J~>ig{D)8nbm`3F#GY6P{YwpLTuHPm7nbShoZiB{c+TAO~o@pmd=VF z-ZekbP>MK?l(w#0;)%k}A3XY9sL9f6_AK`vt1>SG!15yR{l^H3?d!_PRM&kj`BC|A zAq0Q+cN=DSzR$(JWFHXxh5#(A2XJu>ymn?$??K5Oo17&O_M-~kcM_2r-Zvbx4$U6x_`47$eqM;*pKKP5LU@cHRgl_h-EB$Uf|d6Yu1 zVt$Cx&hSES4C1ci&HT_Tg89|7p6j7UpD;ruKUSk#CeIU{^D}C}Rd94YP7VB# z$T-0~2Q{r)k)(C3GP*VEwi{aQwn{}ANl00RU?|C8eDO`P4coxvv~muSEZBu;l@>ob z$6QNzkQ}pIbc*d{CNuuDW+a=!Y2PH3p+RalHk{BqQ{JTV)JF7M`o~T(f;EaXM9Io8 z#-M{J%KfMhztXV0Ld1Awx@8JZxUL9Ih`1@R;YLaP+2fF4ypJ<*VoM|s>^4hNPP205oi%03RX zw(_ckKkFQuA|(@Ce;Y&_%0leCv3B5 zt~P7r6k%PovLuP4-Het4V~NRZeD>5wHw;2nN9`_a2DHIxn}`dq23zh7za8X zjXN2qxW=f?2DA5xFqc0YH$plmZE+wo3QMRYbD1K7Qwl0w0hGX1<2Nx1X!++|uDs}t zDtRLw+!}-8^dxqrBsO~Dvm_eAluYZWSwRg_OaZRfm{MV_1=LuSJ8gsH#5V0L$w9W`zUq8S&=ozne^)<9l=IT5qzJ#oAYnRDxfz+ixmJ0cCWkNcYE)4 zXNI|t$;{ij&R|ymY$ll8#{jz62nDy6rXiDh<+qZ6{H^oi;;}r+rH|4|5-;UQbt@t% zS=_4NrQY`*tEqHF4qqS|{JjbXo~lDV@l#Fi^I?^Qq4v$_(e;P#6}PIm@cH3A)oN&) zS{uzS6E*sBH+;!9I&gR@n;OT4>CIQg8(Nj6@-RGs1RLvtt7xX`>D;jV5yO`he@ftp zif1ha-EjEL>2Fm7-rGs$sW^o9n~R8}-(rTGhSWiE`z4el^UdExHT@R(*rKImbT73r zIXxB~7k6`{7~G;}F~4MsU?OkOMgi7+mb8#N3~i6QPf|ZVFDL@@wi5Y#z+I)`)t7cf z6xx4;Wt4x%Jz)1E7e$P!Lhm-?-H~7X?#qCvO^~_aaa^#Y2^%urp+RmvuL&e?(I^lG zoK}NB7;erkZaQ181%XJ~!*y#(76so8$Hz8a90kSn)VrAsS$FaIg2XVOO)OzjdsIdS zkLT|QI9~r4t&Bv(6L}sU_xgfol3#g(_SJK8gH;4O-oEh2&uW}N?dD<6)<coiE}qiC-vk$j>hr4(~A1flxwuECCq95Xaii=KTiM-vO`~`aSv_ zPoN-jJ?O#K9R^H*QcCW({`oUm#+Sd+=YgYmD}|o`udCP?5xBnt1SCE%>yZ-nVDx*Sz8L)t*J} z;nF7w#~83?-qXSp63rBOnHC#I>F$Ym>QY(?+97u5L!EFeK09$gX_*#-%)UQgT%N$I z4K)^qvXgm5@$8Mq3&xp zf?k(xKnbk%;_)h%AAq!;B!DKMr3i$MS~L-0pffZ ze7~C6>w%c8jC1R?9Zk)`f@UB}Y}AX#YEGPUtIKzl4YoMW&q^_;_w`RJ?9y<{>&08| z>t9q&KJQ8OfB^p9u)wC{X_I26JT*KFSK9*2Q|AW!&Bkv$KR%f1a5T8E%{5qePpr^| zrqH&fS}79guzCsTzB`wiCKhvn11U|M<^CL#x`@gkbzQT~QB z5X9{8y#5JocbI8K;VQoc!i|4+zTDi$#N?W`ESULV><)fcv~=P5!S_V&Uyd=_R$pJ< z;(nS=Hge)8x%GZUf@1sndcjFd+$sd#{uYgpa|Lc-BNBAEn4zO}D}sDS{~r6eE1rrw zn@1UYDk26zZefPN=|a3^mTa5r>kR?mQlBYX8$xyP{aygq-~K~QKHtd(@FkBw5+rsy z%0kNXnRPN?jK_ppJXepF*|-#&M)K)y7T*+SKk0Yb7i&F{G}}_v%t>;xWz(&xvIcz< zi~;&BnR&(O#ADKj|K8oEK#74{OASh==1@xS-n(1_0sJ?Lr5I(3gvafm&#A(uaOY@X z$54l72Q)Oa84T6ql)ajyrRFMhgcaAE&}e5z1f;_)uPLo@)EJ+VY=YNR1MrpE@uS_( zUR`zOVKInlz2+R7-p}5XDai-15Sa<@i>XX|^i*~Wx7w4zvw;P8SV(5Rl9IT=t1agt z!|0^~D~1tyCW*^`Q1#sY6s~3)1X>!%mn-Hnsh`kw%ZPWp@FGsmjaEvr4@h^)n1#D` z|4RH!cmI4cS}Odf|!^$wbcQ{h3da3#c<0ESkX<*&A9^l0cCshaUbL*6^T79 z&T~=iS6cUbDwzU~to?bBq#pBk6@64ER-kEgr`UwcDab?JS4L~~1TH}4=KTXA4M8SK zKN5OFqr+w`tE#JS*4rDKo7Z%Pvnn?_ud++GM6_cw*zd1@YsRMY=4_>qPYCx&^{SLw z;&uu!j1F*@;Yt~VjpY+tUkq8#?GZ*T7%&rQAhc^fvDMYu`T)j=?G+0_pvBn26K{Js z^V<0)IZ7F#qo!5&o~QlNh)hM!xiq&U9fSvQ(;nxQAIzz#*todx!Rv=x%Nj1vF;tJS z5_|bdO_i0E`T0Aei6M7arZinI3RwcLn>PW%0#Xx(9S*lcdu{rRp*;Qa6^_q0rZo4& zCFtTJMak2}g*|+|*MMu1_xBVSL?pkzhQwHJ;)oH2`ATig&F7C-g*1f`_a1(2I}Z*- zD_#jO*s+Wqr{h$Wci(Oc>PE{{aPuyTh5v6)a;H$p09_g5`sQxE&C&6vF2SYwV648} z$R|$@p1bP5*Gyi$(~Frh@BsVQs+B{(Q7c~X`?@~(uU0AiX7p!1X{~d}jUMmW8$r&{ zP*FL%@$wVM-9n8$1)_-?8)OK#B_+dYN#Ttar;3jc4$n7hO7)T+L<7tKN%?nb%!T$i zK^-1bgW68^^Q|QV4sXi~L<-OBsnkZIusFpCY6eT!ber_guQ)r_I!BV?B4Ur?N)W=$ zt*r*MJm8&h{dy~+fafuXXbHIZMdDxy$(?Um+y@PvHH7>=3=Sa$q@zLCDv2tGB3j(C z-&IPrl+PLe-~O!`wvOFGLE4gV$ilL!S>*oUj%78Sa!lF^+|{IM!E+lp({)YvAK3!e z1?AA9!=#I-=a1ix?n1RnG11E35aDnigRiuFl~xceHy;B>XE)$~=GR#`?my;GG!=6b z$C~=QY8bFt?~G4K{*L@pl}b4a8tR7fxy8c^j;;~rvb-v+rR+cOTDa)drqLt)2 zyh@>+vZ2QkL`jI6krPKr7MdkUB503#R1FROwW7dX@9`Y`HR~&JKM-b4*%GoQxY26G zj2u0PAp;{`cuKvRO^S1bfH)s%W0uOrL~(w^(4}I*$62}nJ6H2`d~r#;AWKm@u&;#5 zu4&r*%b_$aaLAsU^p{?>HPm97v0~aWDM<>CT@0aRE?cQrIT5Ha*A{ z;CQ}?=H0|xL-9o?H3>8y6c6TnXn)xBA@)9k^be=#>z~$wGYeId9)-`JFvo&2%ct`={ zk&9obuq;KQC#;-E*;}1lw=CQg3%^HIHZa_(+hrwkHBBfh9>@cEDqIjQ8SH>U>Cs6K zF~DsS8E;Nd4K0*lsL3Lq#Z$qfOOiuR+SMbs!Nxoet4YFIYIvb9ZsQZjR+R${@fq;b z*^_%UV;IIR@5`q9Mt^{(`l7@+-)E-oN?Ye=dWxnccN72izf2> zIOY2Y>H43^z8d;W=NR+TkNcUV^+<0^xt4bQIPJlp=cWT;k zW|O(`Ym{Jt*l24Eu@X1k^=B0-tbt#hyaYqOYTW9i>3@Gi!tPdyngj&leIZRdM)C(v z2iITt$5^MEP0hhx4go<7kNw!MDS>2u>3tJ#79U2babm8%AkwC@95;q8 zAT=2y^`Dx0ERIWU@i{Igb%>% zaXy%d+uxv^W|Zq2h2*|&`~+lKip40Ti%T_r02^$e-^rrCks&oaBwl!+IXVVDb-H5P zLJoj#rBYaMEF_h})g4?3WkhW9#V#+lR^MxgKHvQ*<#O-6HlE+1_8*qHzN?_?7fRqZ zAYJsi9EBPyQA}qYk@5}qmMmWj2O@LbWtj$xPDTW(MI26vC{VT{J+;F{;yTy zMVpA2kX)v;W_QF9(U0m&hF4^2@ge4w}CJ*5^Qx71*J7!^J%$ zP0aRAvJHAqiAONj=RD{6cW(OER11J}851L%Mdeb?DWQtr`4t5CGXmw7Pw!tR!3eW9 zkk46;3t&XJmQ;~ni8E5Q`LEu+ru?t+DZt(u7Z=*m`t#E!?RPD|GSrUv_7r)_8cQ17 z|H^mQ|LP~($4@~}P4`_=u!__+w!ow-l(My8Kwnq*-#_{U=#}*KSW%fl=7q_ddj_p{;rHk*Kq0Xq`Z1^dnJpTNE1NAYa1xzEqquRI6dx|aj&F2totB0nH!K8uSCb8795=eny}4o=I{CnrIDLs)BXjKtNU{|6q{e zjz8bY|7{uKzyI6+{I|dU`s?3iiF5w?>%SU*{qu_Tj3U zzWnPSDEs%-KM?3UZTmk^?jHz}&htNuCau?W*#0?|J7@y;hpA|)rY!#MgFp!MpAhz+ zFyz6|KhO_Mf&UQlpD=+YfA>%8a{Si|@qa?#1^*E?V=?_UaA|npKNtedC%Qqq@FkXcH@%Or-*p;5i$H<* z{u8CCKa&AB+_Xy9=Kp)myP9%O>%UimsiH*gYrao4KQ7p@UU{PfORy z01uhB99trPYE0tr!#4Hv9|$9Y|Aem_Ch7v|E@&W5M3Ac!Gb(U{GJY`Y%Q;^ml18Ts zFM~#*;u2zfP#gu_p_20p&?u68H5SKS;9EuX*pr%QkXRLh>es+e+X0SQv5J#L`;|^uGWqN@)m0<h&qsbI$@J*EDL-QD{2PurZt0b9^oGMoGRr3Gs+|vn zZaD6XP?Ue)^lE|=U~oW=!ZqM|HD&CLgOt3p@wDtwEvmE38h0KXctjFu;*QLuG7k%-Q~cP8Pl~WX*%-mMnFh zgd6kzA&Y8(r7#jkMi2Jm4{-au+PWhHj9$e^14l178mhdUowujm>OHQN z7Od{eY|Px0#L+wJkkMbSoI!tH51dR{m_i%b%I=s*=k}mxz^O1k#4!&t)-o<}u%cm; z&sNz@Y^&kjS-dJ^?nK8~5NEIF5fA_j9c8EOjQay#EV!nwMPJ@P3|&X@YW0RZoL~wA zCohx}l7s%^&eLH^(dKz|0T3lZb)8L&&A0fJUW{7KyVg+w9FI!XcuM+uNkS=+LPFBh zbmFa-_q}&sL{vgcC}LKZp7HTaW875uMF)pw=**VFkv>KFJ1xq`IyF09 zf)wgV0_Dbxk~v)pTd=mr$tERmW`2IS9$asq-znWrULmV7AM;D^tm`@^K-s2 z&E;5gHj9{*C)_^ujgDR;hw5;4!bSP!Dv*0G1grFcSAjE{;Wt29{Yrw>Ad5viBjlwt zDmDr11AnTuSI(^077Uizyau94s34|S&wLW;O6F<5VLalhXbIe6CT<63%_u*O?7g;t z%TppmtKg1|*@%;-y;~x>EF)ufP!AM-PX1F7>~ZS#%(|C)zPrTZ`E0EfkCQI)9k%l^ zH-*-68jLK0+u)<`$~tX5*d=C;#&D!!jsn*f_$SmBP%nZwP&AM(LVLaZ8c_K|{Cptu z04pM~0-BUi%CF#}J{3+?r)j&jc0aXW-ue<{8H4;0o4bj83K=1&g{Z=OF2(RA#hvm= zgF-p2^6=feE$BecxvlQoG6yK4wd(qrR9eX&vd~__-wllJ!M6yJK!ym!SWB~jf;S1j zgJ7iyx+-#-=qmj!V2#Xs63-5fK)~}HEJ-lA@D3(zkd zthaZG8Wl>x1!1jJOj}nhp^S!>oyS7h+QEq7M|&*sT(FQ}1Uf1sNTI_JuBC@B!Im)f z1l|JMXa~L&JY9h7e5e0sKRJ}(u?MMI4AL1nCadn_5wFPnp5Sc)Rqs;u+~sK5@xLBh zCJ(}2K9U;EB#qEjvBJZEOkqlk`Q-V0`qFtmt%cuJ8~rE~Vm)PI_tpyJY#;X@>0NRC z8(-m!z9Mt=^7vD6Jht(k(HGC#cFY!u==+)@qde1=Fxzv&iIhT$zr@DdyNgme}3xSk46W&eEdC0|CO&xRG< zRYreh2lGy0^NBAZzG016rJex}FRbvM&pURd|18^(MV6O|P%Oala39~tl^w2YKY4UQ z^I&^lHYpjXdgdl6uxG()o8Pb&a3oXT^g&ibCbnW4(U9r9d$1dlR=f)Ki4a`uHB}eX zUN?E63|vZrEzG@VKtoL9L^^9>utu&i_!INrb=l~zt9HZw+=q{_qk`3y8ZR~OOAQLd zfnaD6*bHSyy;fls_sOg}V0uDimOSOS^YNl*?#z;E%Ob%I%d&RtBIfBShDiUliD={{ zdfr5y-V7`zhEH7w7~9lnU2oX+oX}VPd`qy2LOl0~y0+kI4>3`LW^m^aV`8k}gMCR@ zI5H07YV=$$m`C2(3BHvv@i<;1f*~0BL)~Yy5>J1bkaFdLh@m1iCtUv|!wOV9(}bF{ zo^o4Q5YRu$+f>b?SixCqQ6cuS;Y%YG8Pb5DHHKEFxOUs?B^sL z1!Lh{62Ook5$`}IwtK+22{m|4FLHCQx$V|x*DiV5)*6={oDSb>cbq(JV_`vo(B*x> zgjp4I@m(vng_Ul*Z9~$ceGoD0pM4?&!6X zx)7z^@*Z*^*}%X8%e^{Vpx{^5Q$#Y2^QS;u7WWO%4j~A)^=5Wn5=jLo=wgLu&DMwA z^%wW*ujQ9~>oF;E;#}?C&U8b0`RE?sz1^wjU&9!^bA7vE>F4V>e$mK|bEy%)BRWECtXk`QC&6Ml)p4>ES883g{#WQl7y<^XUN1?x<#`Jfpmxbl- z0Dp_*l@1!oR?j}z?&~}_v`?$8A^COr`UApgS?YdmrZAfh{&t}6_BTH6V6z8Oe7TAB z!ogm0Y@9STn6HiuFO|I|Ns0U^Jr-1{{{3U_Yp zkTkJXn-r1s4SV#@!qv!$NJUh)HJ%xc5_ebQr-hz2czXWbS}ywSjqEW^Ldtpa4&CkV z`e+h8z`q%Ag226OeT7gZLHvQJE<>oF7;M>O;I`@hAZv7M!Q&Tv$cLT{en!<)lK)zl z01J)^$(^bjXlF`~i272zhW2jL@_E zj99e|u78DeL@iJN$xoWqi6tA#I}y~}^qs%I1QF3Q&2aHbsA3O;{@}A$4?5+Q?9(M% zy9wma5|`uVW4hd>hLwq#QT$2{A_*@0xswh_qC!8Fiujl*QSo2}F$qi^!4$Q6jv=am zdz5WowFaI-Jm`|uIpM_%3OQo%_{4S(0w-Zld7Ix$ij(bm0T*mynu{)n`!Pp=aU*$%d=2H^l@ z`Rsw+^6M^GY6%H6bnqITeFE@K;b&i%WcOoHI|Bixo950P+wwhN%IDZ4bCT^Rt-U4M z`BQn=_E>KLDnB4?`It%wbPbe3U$lx-^cKRg{-W|% zUIS~9(8&}ZMuY^`8keaVEWRqHE1(Sl-#>Ooft+EC>cAQE`|^Y~!3w)gX$v!<>jEjs zz~r35w~_4N8Zwa86}zeWps*u<3JP6C`2tQ=t)I9tbsR+h(8$DuJZ)6siuWvW<0+F) zZ`y+HgZ4*2q&~{32P->iH-Vd#vr?mF60;5hD27?i>!B|F`yo-V<^;rWT0UNg4o&OU zkXuQ++2_?FLxh{q$%a&e?!WZhsFmG=j3?Z2VbU;V<*b=ph{~AKpyrsOH*9KanR(T~ z>m+SZV7BTYSlWIt6$pfxQfy(%LweuglYKC*YLZ21AWo>HZZVMNN&&A36Oxd#rd*W` z$bNT=t~f{7aT=Pv8-uppuj+uHW6qHZ8s80J$sljXp%xvMCCoW#`tSrC<%_xl`W zxG_(vz+@D=bQ(%1ICdtO{8)gn40seckM6K2W6Nf+pL-%}<7+BYRVIx_f56y3-(p&%Hy_d5lzlDT9 z!EHk?u;a)fu( zp9wM8_7bHBB#zaVwx1Q^Ej9bKr0WSE-~wB?_sYls#3;Z5SCp);boHKF=8$h_yIKC> z4THchj;G}<0fdelHy587(AESHQ?jHqUs$GP*njzA#ZbBAHG7k<=UVJ6Gt6@x6nC5T*$=!OVC>MX*LHl*BJl%Mqc@f=uOjkRAf|+}Gip|F zs{oF{{s^`*GK4F}E}4M809iBAa-P@HTqBOW8l|9V#?KNfMT>gy5$IUs72T9!cJA30 zcn5JTxxrPRpqtLXk@hxwW&hWSKaF zh#r%6-4<^&o+{*7{DA7eX+)7n_VeD{K#FQd?!+!o`o==t%~`UQlJPz;?3oNu{qm*SC_FteGL!)I3^o+RjhUPJ*#4}C@_Cd8jSQ|xm9v}< zGfL1WPkzIrKW4C2n%@=bIJ*;`@j(s(tZ=NMmNfKm=bi1{EcKdl=UcQ{b zK=4%xYc|GlJGb0IhDl0%Zj}GY*N!v8qzcO&5gZw5CedE_sL2tt2BVSoj(}=E*&JmJ zkWEcH5issil-AOBgha0g;CuCLZ8og% zwrcot4FB9eY+qZXnY7ZrAggV3wffmFlNu6DA*vO#%GXYi)#Hn`Hh75!vuFyN^XJxt z=SE@G%)8&qced~hhiZYuOr;OlOSc*^coGz_kC?-%Hl4|5@GD3>_V@xG4}<&k{t;g# z$M9cU7%^Z>3liWx;l#Kv@ukWq8@)K%RtT7s!twQ)*@mDmOU@%1PZV@1vE9ob#xAX! zn1C&*$Wq1Zj_i$<4-7g1gh4dl1Ot2tysod{%(cOOg}3q>DsGm4Zd}}AZL-Ye*>_Tz zwfTIP3+NnG=LheH|3>e%mkSUp&(n^6&}4iC@|dEU+#(xH1RZj_pHqonNoaWz7)(er zZ^D4}|H$&Y>qdT^+x6r&xgZSNIv{I0A08bFKbQuK5GJKt|B#t2E}`$yfpUCWvx|IT zzVac7oL(uq9?6n#we*qhx?39V#+-}n zuKXwk8_&R<3#3^)McqFwc}gH1p@E%*nAqZ&DlwlH%3U)I!P{W>n?naaVAH;g)=lXKw5#<*QyL=% zD5CGgEsO!~gwAxg$kV|E2u6G(^ivArqbb4Ya4_j3@e?M6Gk?Ec-;EBjW*Qy=gD9PP z-K+4^KfN81WMu3#Lh=ZdTSeNW@Cnw4ipoY(9T=86zmMLI7b=9$UO&s%ms9l{@H>4b z+3+*$A^hzEi}l-cG`ufuxdoZT%Qk$pps0zf@?ni2bpzI2%&69!$S*mq45)uWagugn z6mh~n%x)gcei?wmn1F!n7|~x@l>%=8>>`}4v{mJRSPfDyDo^u4gri@Vt~}RxgYJ>G z`T@RA2`_3acNR7Jeyx|mKw89{8{hufx4qcyQUPWaK-dBVCJXU|R!=^f-CfS3O$9XE zYNfvNK&(`KABW^&{Du^1W59V%>U9lnUV2g%mEWBcrte4g zIB}+%D2Rsyhz7=-L{#9g=-$IE3&(Jc5vldddD*{NgH}#JlwAcynbkiR@T{0`o+MqP zZ@%kaxuSO7mS%`)Oqjr%XsUNs6~jdHDV$2`V@8BwcJeN4iX% zuL;a%fo|c8VUnXBAba_kugy(eTY0ILBbIE51LGe3oV4~Dyx=qBLV_;Sd@c-hXJ4Mw zW?UY*vCS)z(Wm76uAdac;r#yJU#kyw;y=s6SUiQriObe6i8WCDTk(Go4(VxFb)`3f(+Ldgq$F#sb^9Dql@=W|Jl~u>Y`@7dTi)V;k`}gb-?Q^o zpureSpFdF_YyvKG#;eJ+cZB#PAIJ)SSsMCWjgr^*-mUYT&3;nuHQ}L{i zoFu8%*wS>EAcUh4?9kz?4xmm(5QpQeUaNF<13{RVtUsC1@p?4ueO?6-rTC^Ta*%a> zXD!Cdgo^f%-`p~?k48@^3wo*%Bt%mS82{6p@)k`?zs;54Gl6z5WfcYxkzW9Q$aiUYw%+zym1SYnu6la^ z0!BJEybeQOofe!Zza|;jzT1!1EPlN&Hnxlx=sCgq1RKeroEi}~7QF$Z^kwhPbjj=p zv&tP-X(E}U*S}Ch7#)_ZvLgM&<<+-L$)arq!7@lY>uRAV!7Hf54j(Nuuv3YCNsQ}W zzHwRq%fWRoW1Dp!LVhNwojb@BiH{A!Pvta?!FsD%(e?~90Z2nc>Y9hA&*E$iATB0Y z=-1rpHgK*qX{mz^!cX%KU6P`+AouiYF$*uc+LuxZV*D;SGegx^XjKL~1=dPbqq-)) zi@UzA_`4sB>o)v&wVj;`+|?9_hr+`8WUZ=^W3w2C#saOJI!JQ#} zQvOoE#kiqhqS8Dyzh?|2al@CwcPSZaCm6RMp1-}*^Q+EfT$Q8fM8XC zW|-#s@%i+rZrJ`nbw%ZwS@Lu8?vOr9ze)OOSMw4G2Wg{GT;P$9*Qp0+c}9Qj|G<`# z??mnyE&4;>`)Dg6M>(kAuMzmiqA}m53cZGz3 zyv`rC8i7XE0c7ekLls61oq|J-Od%RBN)?A&GEx~N{RSi~(w;-+(!CvzQ;5)$+c5U= zHDNA;iRN^G!H$35o;;SGkfn{$WP`imO5fQ>1VjL|M*GI28~ml9$fE!pYJ5fV&sQ99 zgTWXlKsi=LAFOO$pteYId1ZX_#&QCpf`F@Po^sT~h1wPU% zU#p6d7=8VA*l5U)sF>Oyp{tHH%&^=u9+~C$rJ4jlo;=r%$h{D*N2x&)3A6%oFo6+b zs{m3V2#WZP9}?B94xp4`fu9AW%$Njkcnc{0S820jS8#p;sjq7z@JaMDam{aear{Q? z0~LOY6k8Qqq%>*48@XV(O$GnrkFdUWj^j;M4oziAXwR)WzAlyTUgX}d^1-)FwII~j zrAA>CF<(?4-fi}#wt<4d)$+q%v;=H0I%v6(Bb^~fDEx%S8W>ceOoHco_~W9L@I`K` zp+7ZSFsoi0=8%8Vy4X`P00FjN2;yxRQV1YQ>BC7}?)k)VJ#$v~ELqO=@mNH8uGY^1 zyN)8G_b-}EaCgQwbdkwLn?9=30D0LByUr*_vKpXGG=*+DXg-A&tKNl3$j9`4ul3+c zk8CtVi!rsteoRw9ZNIVr_`>aQOTC2kOxdfn&PD}cUZ z=t(y`(Pj{kwk%WoO3a)E+sV!T5MFGhpcv$ScbUmM8;NU>eEVdUf?w{BaSiq=b0sP< zxw^SRTe4;&%G=;+MXyex|8O8|Y{O6ztJ#bO1o~>DX)p0DzplLp7#k`|%fdv8T%bfn zKn!974*MLNFJn)m5I4MBt@TF!x97-+p!=a@{aSB^t|4|n zKZO%>qQ|G38V3a4BX$vSC}QfzssOoOmiWC5#3gpe{(-8YRV{^`YM#*0{fYa5f%W;; z_wK0`f4F9wZ$GT+yjo@aXjjxrs|T=;s{-ts=psD;;UQ#0L)z>+f}?TQC@wQdR_4@4 zmWP@TYyMotOMeL|;QVLc(&U-#nyD|)rh5l8V8Sa>t|tu>vNPMTE$^9>=^yan`a&c~ zO6|MVFoXF14b4fHuN(tvs^{n|BOu`%8{qM45cx1nRPeLXW?PoLnkMC85O=ZaNnzDL zLYZv6ePQ_;KqQZ9_=Py6*cjr@ATnN55Np-hG*8`?Wtn#x(lAb$SUuZSi8%GqTx9m901O^?KVTLKpWM(b6^ zi0Z%#JSSpCk`@nq@V@^x{MY{zpJ-V8S}H_VY4}L&#=$ z%jvT601u{j;$hWH$U!u+NvB2o(z&Y^;kIVwHV7V9%-!Iz&IoL@sRV(yf^rtAGALXr zB#?*k8;7Jcum6B!6@D|pjJhhL4&kmUSg?VEAf2nb6dsJ*r? z?xT~^+t}7N;VTyYI_W4rPIzGB6DzAMZ!OQLi<|>10xVqylLC0ck9*N2*%48%ApffOYn1oGuGnwx)G@fSb zhsY7HE(&n>r~KKFNsrK#mX@zQF`GFEGIead`Xfzg#*1wRdB%PV7g%*9lM7W4_*lDT zQQFJ=*fd1luk&*|$%Bm`z+6-u(L3Vq52e2#uPPUX&AQk`6(TB3*6|5=xbteycm)&4 zWRoC?9BIdF9R?*XtG}2FeUkr%3f{qr8b|>}5MwyB)u6FDRngV7?!H8&v zueM1#A&!F01DJI30KEhz=W+C>M2mz0`5>u)83R%7-4D_lX!SzAnE3DwEk{SVbAU76WRXEumuSRh zd6KOL(tZFkTtkdPi~w^~tb^yPE*nM~Ro-u)0PE;0y>hr8X(~Zsq4N*xlVwY-)7}B# zg8+Kdfo@Qnv5}RETYs!kk~++fOy*zHF3$b&_M^(TR~g#$$}=FPO6&LY1p&}8EYj}G zMWiKY#@Xmm?`sZ5CVRLgAGKF02ar6^b;=lXr_b-Utu#ZO!XUK}(hBfGp}Z5yIcU}@ zT~8idcBc-Nv_&y@e(qWK><=KT*H2~j-`8Oxd$pjr5McBZ3dfA_WmbnoqCUmv6P@-f zPse(lvFNkzpm<<^7BGgtzdCVlXNEJ};9B=Y-6=yizCcR{bv$RJ;c2J9*)_C)^Ln)5 zHS$w=zbxCV^$^et1A_p#a`X>AOu zd-nx|LJ#1gaP)v&J189zO8t9^@g#LxSWCkF3Ffsw_H5?A>5TKOv6DJ$2&u@4OpJX6 z9i`;9I;$Q&5bF~92kzgKt=zW2@nV%i`jP0OUmWD?T?1===$RhMk&IsBgXc@;h^0WWANHETW8&lbf7@RE2Rg<`X#L9PX( zTYCbSB&7yUJ!2P|1afIp0tZV6%E^!i!MzQ$*$NmKwQ>cI-yf4MQBAf3QP14I8+6yJ zY7tnBBFNJD4-4?6F#1bmkS4Fb_g#0G+Cbse6`YZ=IHlJky( zn8?Llq5m3wIZA$JfEH;eWVRgw-uIXs5myBWCPoLC;A8M% zvA2V-W&op9ft!_M?+t`Ws~%{$iv+NNoe)m-wm^%tOEYRyPc2vMBP>7k&Xecm>=&GKaqe`Xwzsj9e;C8 zrn3Z4{LXq~xKv|yykcR?U@bFx#sUNtL*k=HVp;y`k(#~b%Pv1QK^7F)`)19hb)(HT zUc*U4)cJRFuL-W!g@yrt6Y2h>9vkE;&9e+}YL;F*9=z@bE&(u( zx#5Fw$4zhmBfW6w6{Al|ym6lk|2ba*_xqXnSA7Qu2Tso(6b=8QhopkI;d7zKoF+dE>yaIPv~K&20%n5)jZ28xmRJ z?ynov_**z1 zn!SL@Qpc}1Rk-b72%V79dv$D51(VdPsL1nmdwnpeYVvS&wQNv1*kXGp&Y&DA;hSiq zO9*&IPW`+x>;oax0Q64Bx^4*g=kt&=xO+ajb;T zwzu;7MYRjcSe4Kz~*- z7YcwZSv9D6wS%aQC@qB?%C{R7W(eE zoW0e61JJB0F!k*DwGpUlI4cv!9$6*pl{n(K{BV5*VE6c3mpWt#4V(P-1i@Nh#wDw+ zxuE_g*s7^%9xZzJ6?}%*=qR4wStRft1cSq!j!vk}p$~x_XcQszF7*Y`us(Xs+TKGu z7E=hASw#VA0TJ=@^5FpJ|Nebf-P%L3=$L6Qr1kSzkF|NtqwE=8Um-R)rrTITcOXkS zh~Q-wymuC?H%l)9MGSyaa2OqT=&^%zlQ>ISb^}*KtH6m)uL>!XzrPfZam-P000Obt zY*y?)t3W`U1ZSk#qfPKGPzI-|SmV*DQD0)%$6QOC0YRipvQdo5>M zlA45r+2m`(9mZ06ZiuO`!s-0L=aHfYEWyA4%U=fy9n7jbgK~@DmBNWtWEjc=IK^cw zFL7;nSpg{P3d)*r7=RT7<{cFPd_~j;7}Bw@Zf)$Bs=9cVkD|-vpxMU=`x9$gssZWd zbp&UY@d^sPWyVa90k-d)Uq_9Z!=-iZ#M=7ll%LmrQJ+dI&;W72u%Gle`O3$GcnrL` zpxEZWgD`QVtZ%RCH8yWMnnw8X5=L0A3Vh`JWlylOf_`O}8bn%kX!TSF^b87OnGqV} z>*u@34SrW4u7ur%92bFM1N`j4X5QUZB%g1DkXc2#5qQnmY@$XMrE39I%K-c~g?&w{ z0(Co@qky5wRg)*x4v!(hu%Lyd#S<)LDy)(L+eniy_;N{(wp>Y6W z^la%WCahCIF@d)kb5ref27d1X14{>>urFWf&*|(3?10HX>z}M+PoOeoq(=hFcdR2{ zeLd!vU#5j~6qkRtB_huQs7K}#@k?+>cp6L6^=z-P2`quv+;;PJc9*`u6UG7njM&`) zM%vsMFLL(*{q}yPZid3wMD7{UQztn&9aldo^A(Utja=3vNEzZp#6GjGM=*vVe5p2-@_H31DPspxn1qvt2Hw#BT)~)JE?r)LmWS_ zLE@e7#TO=j_G{2I<+&l|_sl-XGZQd*5#Cddj7QIViQXp!S?cK2i>6uh$bVySOtOsk z>geLHP7PFG1J=!IHeSXaAurV5{*jKaIitWu$!Y+U{mO?QG6df;4GBq~74@7qVkp$` z{2)9qai)gW;osw*Gwi181HjtFk<6EMtWOGl_GTC`)4LP{0wKrXtakPOfzlk~wWu&y z*A%iwJV~-Vf;B}|al1B#hZ@)7CP`uOufMBMEyAxEHbbVTYws&9YF4&uK!%d;$WqV)x1ye(>ZU6N%Wyb0da4G!IR zzqhRmZs^0P)C3p!k&(y-fOzoJLvMum^^fz9UgDsTkoh!U+NOeT{`oQd6HmC`M+QZC~0Jg%aKRrP=0u{gIPOoNvHS;TYhIJ7DbyGqdet zZ6Ugz1qwk$QFg%BU}E-{v(;4wuw-+)Lje3@dEjM?f(_Ep%@8qNoPUl))Rfgx+5Y>@ zs{VVn=?EN9fVrfZ3$w&jt~2fHaqKx(#wr51vNxZRbLEo?dW~t$Iaq^<_uWF>u`$Ot z96akKG5P>9OK|%F9m#f9hY^LFUuYNEc-Sz?e<>JnQ$d!C0h<8sDMr#(rr7JfqiVXm zrk>Ds9WzKj>lhceHaXEPgk}(06Yi5L>;a%6%Q>cCTkvx+2PogD?j966fk;x1d~^b! zJVEI)#Q{t@?;`mIVi>61WwZZ9_AJzIax&UA5a^t5`=MW@*tyd56&=ZWD7u&Q5pash zeu|)jWrPd_?se{Z<59SD+n&cJEg37{L0*A(jte$^#Tzc?ODgMi{w zAz<%sCb)iwa5q*fpig~ahKz`o6kXAo$?&TC#lny*Qu9PQXgQI!c*YX((jvG28~Dm}uD zX87T(-a^J$5-$fS=ZQIVPfas8t z`0L`J?(@YSuI@1W6*rIo@~iJ}$=CHJpzmZfy@~ID>j*)65NPlqBZAobLU#BIhfhW|ZJPp?7Gc5|TdkU7V7sVzUm2Anqp4RA zN5eSx=dh31>x)>}agno_saXUov!{#}=~{yk%CK2Nar54P;76zdbHwKA_oun>d`c9G z1Io={s^Nk1hZv5VR6c2zwU*et%%7@7?~Ek_C`ei#9W)Vk!X;nQ#*ZJYnbnK(^(DdCggm$M zb)h0kOlM}7{8#Z#AzDBb10blLlIyus(6jD5UeUYwQ%UHsx$OrQk#*~f!;vKo55MR< zljl8=|449m7@#^YbYGy94fV`py_X`uCGYb+dF7mz{lk&&7)qsJD;N&*I=?sdQ~Et_ zu(niLqj9FiEWqH_;5+!@R)^|nhcWW~F3E>DMbhu3@qzip&VAS)2LuBqYvKf)He)rDS~CW zZ#8|-Jl@@G7qU70R(aroeINt$yla4H%_n$sh&k$`;_i$%+8=V?>$WBr!NxvXs{cbi!hx3uL5ld@TWa$!zuY>nubo1V* z4tURUb&WnmKdU@I{iccDdwj2>it73B4>caneS@8T!Bq#d?{|y_d>_(1J|NxQW|d$( z)*Y!Z93RfROwag*##r1d2IapOFSX3t1{`@`k03sFk?*pzbXc202@ffi|P6rXW(v1W-sEm@YIPy=A6j`?KtN?3Nm&xdYRriE6-w~wYw%I7L z3EWMN0PZb2tPdvFJ!1+Y>ysw}Vkbk?Sb^+BaB*j|wy@E>LwZf51q3qo$FqvJG>FcG zK8F_>vKtHsU|fCVM;O|YNt#qVz9V+GE=(qZ{9*;!4-x9(5l3f)xZ@-KeaXZu>pv_3 z-lK-zb6zq1*-nyN`XJ2nm8R9)CDHoP^1!d|6=VC|OD&_oq~xdXDyYZn8IhMsy^|P@ zsX^EVmkU21=ya~2`%s?5gN43KruJGGZLauStVkfWWD_;GUHBy8DR#ZaMK?Ss7m6ZB zw{)8bX+q=@282UPaYmv14k!*s6?>KqTv1r+9RyOIB)Pj+Lu-Y~&1l3<4ImDclzeT- zWdh46D-n|bTLwg=*k)fz)!LUDG^XAL}&fQAO zgIPq{rgu6_&f7pnPh|(VOP*2RzS04^S&W~QA+6w^cpzBkm~38n4i7{K$t6??IcOe4 z87N^#&0`rJO1&}oiD+v!eHD)!f2I_K zGm>@Js0U>MFgRij{IT&YPz)Za2=SB)vq>0wGynbsuRUxF*1Pd9u#5f(vnF4n98iDIQJWd-5>4DjA=QnGgQkG{RmXYE_rRv z_PvQ0Yk+@Y75z;11B6c|6D@O1xnhFqUnrqsRN0b-u3i~$i%{8Uf*Y(Z4a*NYu`Zwa zp&o79z3Onf*81c zgpvi}-ceRM_^hY$_)dxUEK>O6c}N+G`+yDpvHSyIr=7w+=)goX37;tql1!cA02?jb zYjx?EQ`+n4^~euD0rj5K@Ld^s=iXlK+lBw^#BTR~30g1-+emIuZ&K z?=VE|OZ#Z5UtpaJVf?I|#7_mJTUMRn5yj`ayJYhwu3qgO+Y1yO7Sy{0@F^L-eX^PX zau0Up0_D5DXH#b%T;ZKhn9KYJu{H@f(Xp0)S+*1KdjIj*up|I^)Zb8vLGRrgxQL;E z9#H)*&Sbd?A`kFZ4s-(q))JNWS-$CPucc3Wr9s--96?J%992mA>jv>)*Rf=e+== zqBAPZ@u08sey5B5=rtN3r@K)YA0|wJ`x1a~go#&z#oW`QzrP5&^)7*noxhFe?wRY~ zjNw!RPyUosH)lNSg1-U(S2Hya}&`%yL^l?vF#Fgb15 z?H$x=GYAl+I*_{M5Z?%oD1* zb;z~#9+d*`=}I9w`?PQv>_&hVp1rl)0E&<^U-L;-DbN_;@fKi*?irH!{Ijs-4YfcI^A@Kl~DkvHN?kt^w~RD5O|0^0`1=3 z`ahx6^32;h8ke(TT~I7Vt_Ttc1i1AUGW_f_$ua8` z-DSRMDm{5UK2mpv?k*(5KYLQ{xZT*A6SyQOBQN6odW#R!PKC(3?#M*tt>km7<4D2t z`C?7YKa`vY>=D8&b^=lUL;p^3igq62(KXgRQX7R4a*sLfAx^bTLziLLCILn`i$9G% z`sokbF~+(*@OS)Mx#JYwecwagGijj=(c%r0UqVnbQ)@W)_Bs#JfJbuf8xhD{UuQ6& z@w)=f&hrJW*)b&%8B${rR46}}nb42Ip8@mk!mYjou&O1WcrwWr83KS$_Q!E|V`BPI zL?y>NDF5}J&W1fb)=2102!Kn#5Fh)RBBlT;QK;zAh{Wguaq7Fy33|;`_Ad}6i^X;T_mC)0QW!aB^6RF2Jp@q7 z;k~7EJkvIxv$eeFHQF!`eOaD9sDl7Hn|^B3{0322j>m9qr%s{Xp0*(;%tSLrIFbqI zd5EC(m~oG|!{R`D_FlzIpQWQ{vx$W4Nilno2_XY0l8rGKHqXQ_yzX^*0Mo{CU<=$c zhKlfa%Ju{G`v5Ti4OPNEnq8b434wq-OKOdTnAf5fdSFb=?@wnqVI8Xj|Fo;%`{|v| z5kcU%mCNjU7v}Pairj35eo!tb7Fv1j6U}o?hSQtI{hnSvYRzvif*xFYSI_iF$;iiX zO%1RFELgekQpW()4pCVK4meKNs^{Ej7yy4o?*(lS(dnbs;{`%nuk|e@ay)i?QY;ro zLz|U=VULb4#Cl%E3Y^hiV`WbrQ3D_|Zrza)ERAZ|8|4yi zfBD@wcaLX^X?4U_mYU)TEOi8qlhSy+fJTmtZ~>=j!(Havu#i0nFyL3MW>{3U@0F@D zNBYca=I^$(oMwLfCVxb1NhOnd$9gcE!k=Qdlg7&Y>&^>J7AZXkshScCEki*kojtDN zcn^I+BA*$;C%9R*@HpBUtgr6WlakHyC;k{%_AIQD*(C2tIn0Wg_5(#C?1T9&a*0 z`Q2=p)q2wB&+5{b0LUoS&RL)D#~0lVKfa3(??>0Z-{HZh6IalMgMA9HQ=0Qky^n&^ z{enFcyxk3u|5xM>h*pmt+UuPP15bIEpWCOToKkR-oU&N8sMDXYvF5!?EdS=Hr%8%tu@~+k@&tXi5&~&-ARryEn1R2KDR> zq}K_v=*j0d!$N_N&jZ@nd>JuNl3w<7^L4w?pBMWUtz4Sdd&cibA_>oTf zL)N5lo`1s_t*Im_+9)GA#X(fPARwwg;InSdD0)|+j4*06IzvLx==JG%Ihs$Y2pgBW z&4cZypFI?P+k1pOzvsJcUW8%VwLrN#f9bT|F`<43`b%1|>lWDZhuO~c>1Ow4hI;$E z#9*KQkN08mV;Ny0OMB;i0oHp5Iw0wFDSIoV6t?YGTHj#^yObD&Mbc8bF#IL~T14{?6HVIc6nl=R%iSBlx>*~*K1Kq0jKBBJv z5!5aO5FW7d@^|Bz|C!^#mg3d4zawJOM>}7IdgyF6gUxAr(0Sdc>IP!np4By7^wqrh>vAC5CV} zq%Tu0F8wmNG#Q<0G!_|qmEUH1J@2rQ+0r64sNMa1?*4^jOgDf#9d&418W){Olz-f- zxT&AuMiIIueJ@4OI6zn0I7V9fC7>Gc2SKst_YWg8u?9w4O>}TApzfiNQrzTiiQZ$Q z8w_ht%Mkl1K-9{Zg#w0I@$eNR$A<=07obty>pLRh_sh}L<$C<*5@JG<@G#e8p@`qe z5HM1BWB1+=5h4d=J<{74ye#zYaev7?i(Y9UjQCfqzc54tth3C}bS9=;_h2f&phrm7 z7_hm*$PbieHv+2pJV1S3!ry?Xgd=aU+gsDZHPb(SY6i91Rd{tS9GuP<^I>M!_!E`bcpQqTew)AW8hw zbk;?JMos4>z1&!55&%FKKR^_#XYU;C5rt=v;I&8j^^i$`D%3+Lz0Ck!{le35sf@mM z4$xm5886~Jh*ak7xn!Ds!Ndfa#Di!-g9KihKvnC|*+#atcFYbSdjZdHnCGtUWzh16 zXvyM~3UP93biY%fTz4X=A8!vtByneW^q?V)tf2_{9&2+M{~J{#B_JEa+wf92MGlPz zTxd@K-RJ;B9JD)7L2H$ECG5LgH>IynT@yL1( z+GS0#RjVFFtZWmkk(3$A;$}; z0uUA%+GqY8bUnSdPf)+(+nZtIKlmYFV@psh`MU!w7RhPcz|DJo{f-nsP2d-d2Hk-% z?}>W{pjyjl(#Hyv(nkWjjV63QI<6YZ`5}9#>e=6VVq=35*L3>af%~mv#kWMe0_gqz z+pH_%0JUJj)~Qq;X-FVJa{BKq^xk-DXGGIGF6*2LxmQmU!(aBd7 z$%gK*@T=H@chSEPfI>!U3&B;n8{0+EL1kS<hK|OYrW`4PyD^MVMx`u0kF zaHNlC1{$j-955um2z(40x-cI*-XeUuH)~}USFs9X;3$AT(N9AZJ#e~cWA1C<=GlbR zDJp&M8USo?qFA1EcVGrjqJi)Kl*#*{+5ylIDf?<-{&nR0Y0uz*zEwl16lA|}e2|E* zljgfWTU4Nw#{x?4c27TSkmq(=YQ}B`BCmY!^}=&^(axUexBLut!_0|~%}?HgB=|S4 zyK{WsWl}9Zh(T*0k4A?Acu~Am8sxU%5OSHIWB-7_bpeg#|JQjxPRq~s>`8=}t=#|A zuT=Ot@500VE!O=B7bMMcez1k=PfP|zB7179j=Fp}NVDjyr_wZw^Tn82b z>~sOpG~k_b*F12{X&wbm^gohFldOSdPEx-03p+eMK7ZRgeS7d#Sc!^#Eua@a6i|F? z)E>Ygs$vYV z`W1nJn)iiy-oSyY$*;QOtH_UpL2dIBO22y6UQg}BEFrhX3=nXn#ijq!kOw+D6g4N2#bkW`Ln8@u4_*A3o2ESOkgq(0@EN&jL9~vJ3V| zPQoFmb?yp1RMizpi{`P|4n#nfVwk_3PU#fhO?{9hiSKzUS*VJ=H_j`dcd2#V?KR-j}<#@1-^JNM-$JePVd8O z%9x%Y{(OoXuRNylLl?!X)r8|7uAox*W|o9yf5=70_bm;qUq3?m5T5K1V4r+$bvJ!& z>y-{Ecu)XvnHUH}AgQc82U>syc;+Qs615`IR`k7T+zXRveY;V{$^meVmpx8CtwT=9&Fz zD9loq5%;T5B?6cP#34L8QqU@ClQXoPBQ@C9Mt83)OR1$ft$B3x?E%_us1g1~$X_Pc zzn8^(m-)=-xiT*{L16g@=Nv}|-j*8ysrN{97r-)69~P{4FMfAm?vc%}mfIK8_qXou z9~GO*T@V8FrWxv_V6T-ues0=;mxz1=C(U3eCkhMhSO$uL*~KT++JV9%qd}0vkK=0D zB(*TW%PnT)$2^9sC)^C_u`#V+kA=9d*qEP57f4O+JqYSAGCf_t=1U*?g@q}(1t|m6 zM1BKognF;wt@u!(bR>bd-MMx}4giQs%a{2wqxPWG4d@sZ@j7d|dW9b#fWlkYtQuON z3({woLfo%6Mh`T~r4(95T)tto)1b$N0y^l|L`eCK;a=Sl(6EZ{RT-cB1b@sw)edq3 z*DQDvB53|0E2)To=jFE?>KhlT(Rbh}jow0*q_M)J9i8}PppCrzOmK9OYtY*B3fZxY z-mEOpQKK?S$_&po)eVeUrdwqXy1AOPd286v1KdE+pxI1Q#6Wi%o)er5s-T+PeYEEt z3cy2YE#AMmb2NYC(LlcgmKDl=etJYR;!tT|*4!&U4(S=F=bb<;-@XD_;i2py9Eaue zM+nS&h`pAu6G=nrVvyidBGAnD;eFsyr~v&bakijXi9~)dZ&W8_ZHEG(2@9A+xTjR& zHYN3)x_&{v8|~w+`EoFNc#`WtjUu@ekO6lyn3kc)fTs^FeJ%jJKabf*K6j$LMe-Z} z%hf%uf)-^p)L`NPPna50ZKFHVs~i#F-zMp+SfYz5W5ZWZ5F{`UMtJt{ zSazesayj=|iL8_VvTqFZC9Zo8CDvEOUC^P2$uD^Wr9?0OzSi)15-J712(QYz2OS0C z+(1}WN@zTu3NVC)gFFtDp54yE)O&V7Y=3`;4gPAN?~T-2#PBVG^W@Vsd0e>otnf3QYgTDmpWTBCb{){v=#{Z72H)m`Q+*f z0v~45wL||YWq{^>CvZ0r-N&?o3jo!@3IkDwKaroo_?_ZqzwVnn;`eIST(LlN?#>~m zcYoOFfI0@xa)GA>=#z-#S(RuVwcQ^`9pMbM*jmL2`w2pr4?R1)VMBs@z|Q)XoVx-+ zBm68i^Mu)fE6lglDQw;_d+k=)c0hN5a!{p~-n$>PYQ% zw9o~(lJGi#O+9YKi}uz-b)I_t2DPsz=r$^+dYu4DTgFe9238zdT#iJC@+1yY;3^FD zTU;BzL+UCmCzIGbLUL9Jlj&AwM(6m9&p#ZzRzSzK&swnCgY$M4@u(aWt`2mMwqSM` zpGV8eKGTZ1Bc(x^RB??B!#id`Vcjoe&k?yl@#i@a(_}Kkd5)`aa$skcZmd#zO#sir z&jQnm-w}pIvPZHFZmK+(6>$n3$ua2qRVoj9Eyz;o_L|W6H3*GS9a`i=-x}(wJ4F*L zfQ?}l;{kyHt@yt9CC_t{GOXOC)kmwIQ4)j~0FYj_p8-CNEZcXLm9K>eW#t13sE-n| z%M3J&!9>Rv$afVcp8UzXoVzLJycV~HC33a8HfQGMQ}GIGUJXH)1D^B;oj0ZVSbB5E zunmr1f^$pX05VH@QwHckbVOM;UwGm{27o;rv!(zC*`0aMnlClx_wyp{=PWc!>Os20 zPeQ4tXtLl0>9OSK7yPK^vP$Pw3CDm9k^d`poQ7t`AOU3g0q19wafSRPQHx?CPfrId zD&W!QH=bk8e6Z`9^}!Eth{0v4OZW=c3m|Ktj*ygctzs1@M#Qs3^HSL1pw$Kv$$4TeDy0P!KVXNHdTqKtwx*A&wb&pr9O59o77)+-+MC{mo^IfP(Z&~pHakNz zc-pC{&Fla?7r(RtFQR)8aYk(!+v213)4I#DXl}2hS7vZXbfchrY z`5beX{GV(KSuZ-UPS_6jtY5WW*ASt*`%wI0mNN}yy5iUY8@kW%Jgf6gN`dy*pC|AG zw#d-rcAPl0I6&NMaxD_DnX6k-ef7E0xs!j)5~2hsgTVo9TY;Ea8tj*2wID#tL(`Mx zgD3bj!o%{rqs5nhu%9QRHHcK8-(UlglDg({-}D^Td;Z##K^KgL8raq}7nB+Jbwugu z<15;&p)YN7()p!WnjDG@bCd%(Mg~}NCOrS}3S*&qAOQz#qc^>O^7qgZ4**FiEfO)W zcvz{rjldVGh|UaTwZU}ja(k~&f&M3sZN{Ui0V)XH{Jg4MNi=&tAtm#jd!vAJU-Si_ zfzHXu^&Y4ICw4*AHKbqCADW7l)#ObVt{ZQv$3c^tI(c`twW{sA4JanBL5{`vk~B}`l^GBxb&)P34n0LnZnKpX-eZ%s;Gft@<%e9`>c`& z=Cbe)rE(q|mAOg%?ke(y0lPjV7Kn12`NG6`z z<?nX=Z2USvb;`@WD?R)OQB~_Y zz00B-5@*2Pgx^|}{`hqA3tC$jYtOjAv=ti1%vrDzC^iZMFS6g_<+le*^b9-Y%N^cT zG7jxs*L&wL!8gS%`{8k!ND^@rk@I^b-sQ5{A4C{VQ5*M(A`rspbdY#!A%DErW=@WP zPj?^fNq9=4vZ)6l-PiVdXiy;V4*J6mAC-E-uVN>`8q6EwrZw^MYe`s3d05CLpjNY7 zf7KSWwrR$9jgM;>!v#V$K_7L2DWAuxDo2z&AnsRGz}nph4&Nc1fS(O;q}QO_iG$R? z6yfw%3aY0rzx0k>u=lFku!7O;xTW`)h>?Jp=KyG(B@-5@r@M?m6E?*OXE zIA)GDBR=SBbLtah%Q*0A;OixlIY#^{2`GnUtLn-j>9uIBOKJ z5ab`BKIwaYU5IK^7a=KdDJ}*NL}`}3+x{)RcoY6i-}H2db`Zk&mNN4ID^|eOOYn;O zfh1fMLtq|+o|E;ez{Vaj!%H#mNEwVF-6w!X;ALej4D|9MGun?4{^=7bXf#=1IKO}$ z67#&vMorp%LE3B{Hb@sTkcS7mKoy{U;&|_Wc!6lB%AtqRQ5ArLxXa&$;YpEqX@pl} zZQn9xy}qGmi7RJ6%do`NQ?*Bcqr7MQyU5d0%iRD@Z1DO!%>C}B+^nB@HNL|}ZCn4) zJZgD0hWVjA4p z6M10nPlfpjaEK%C39X&(=}XlUDY&mNKz(I@gY*5xfJeq>gnlGA>5MOTs1mCAenaGG zpaxi=3*%gac_BcFdgJ{CB=<4H9N{;uhU@1yC?P{P`~dh9x#l+QJ!9SSewFtX;>K(X zaA2CDY(mc}_&5BMAb!}Yu@$Le`k641tAUY6tN9Z5@S&MN8+KoC z;rH1dWe8ay8T=cQxa7L-3vi($c(9N!oN%=vs+O>K+rzkZ^Z9#ELI}3d?;8nkT(V0u z`(a<@kEnukWkzfrat8|g{pv|y*?T8B{!Rf_137$=l2Pe8pLOLp8TjxaTy)kVWm#G zHcjm1&?D* z5L-hQrUkKZXpcWgn76iLHkqR5LI>a?m@GzdweL`nC@U77&TLokz-@4y0n3WK7dPoQusl#9CO8fshjgod`z8YiT6(&pNNC05cicyxgPmqQ=I z)c!*AaGnr{6`&>z$ROv?qru!u*}0xIe@|qgmRz;6{}vPQ7~27gS_#U$jTgnrs8%FU zzzMK;7h8P1w`!09yAi9>Jt71Q;Pl9yOWmoft3*E=SnX1-0h3i2t2ZlWG8=l`=vi_e zRco5DTAJtxiuxb!SxTR_`Z({xA21wDw5C!4qr?~5Gx|t@s1V?UDYz1heo`QC_e+uJ z&!8k^@p1swJmGPZS;4=!w!U1a{Sfhu-Dj%UZNxMl9t4uo z+7XgWw7X2-JP4`Mt_a6o^A9ta0^2)g9-44zK3f}{AaSzebqhGfPcRNRX0TL31boa; z`S*0-&5I$MsPG0AXe||D16X8)36Op<=e-ng4)-J+U##_rUk(%$z&>uBKqPIoe!T#yf7!Ur(=1+pNAb8oA{a!~>P?ZeU zqziGc8%oyECw($=UsXPuTj;#APiiwPde-h(`*zP|(?R7|=6pt~ zm)~mX;*MXVvT9|AzXwbK#56PBv8oiJGRcbVU-$-cbqzTDM1&r>CMK#O;RP^$q?~zU zi!7^8!4iUx_5d&JI~==u?s4h?jFaoS_S?NcaxZiFiBk-VmEnb@1=$sS#jRLHWe-h6(w{tKPV zsnPkS`&BKH=9jAWUZd{>J349zqVKqzw$*b)5f4IVz>P<*&-|PgOaZy`b3~mrkl)T1G<;{XzQ4lL zcxMBse5~TySS(me91m^&Hh_`Z?(g=Ayg@l|C#ZXC6vsPM4>byXTwjbCoZGe@m{~-H zfky8VpsWA-K~a~8)B9!tzh&!E#r%z50X#)D@hO@ttTjBa)4_-J#lCIO(7ekEPlmuU zwol0#9cf+%=?M_$aDS-m-S-;s`u;_~Kcm1K7~Rb92K`;9dv(8+Y_tQdI ze1jetm?JU5+1v>6uPFmdTLx&*r!l zx==5o=+JM|)+7lFI3GaQtv`Ydr{y(md3^+%yT$EiXy6gXEYl+Xyf-nZb?wMUv}BO{ zIUsTaZKgLx8z_KC_UBrkI|63OAz4mF1cfhR`+6i z=W`GTgGt1fzhgr1DrJAxvIX6}eS)OMoaghoQ#yz~EmA*!3j*X(wvg zD0cH4#kSb=R-OEcN?O;Ht}=`65ehHD5jpsyG>}&qb@d8ZT*T6w*A2$wJrs-_{nNn@ zPtD@i`{g+pw-vOL9uy~0t(>H`O(BX0!a#Iewhk@ zO90uuMSenri$oQoEQFR9634K#pXGz-%(~~WK3yj6DD7w1;sfSyOJw_d z#A5OpGLPg?tzYTqFGLE-Dj-{j1ahVw_Hv>EP`(x}tWeh%6P=qKu_)VPIWn;ZD! z%&X)M&G@AJ^IgPGnv(7nL3fZzXM*!%suAmePPO7?%~lg5dLc`_5+UoEJK<7S5*mc@`5$&-y)dS|cg;@^{MceuZ36T`}@J1;_QcQe4IR=za z$BiZVO!=0#8iJG*EHsOx7|;%2;~4lZv;1DkS>Kovmx5kp2E;i8=KHL9! zLSX#AvUa$?Ca}g3o_^z%V*(aN66$n6G^%1iY0}~$4T=Gzw=}Y%4|bN{QWj*Ye#fAP z<-Cns+YNZF%oiX+F9_(21^fq88k(ap=|Lc?8a_~(Gdh3m;dA|V6a>Tk6E+orB~y~{ z7TRctVLGz2@R<#Crycc$*CzNK5oz!d3Zqq7V+XAa3fz9{%4~5tS7bHyxtR>US~@bu zJ8#9H9`FeifiiUFaurQne3>@-{aT_QeP5us`0JaxKRQ^N&Ftts@DAq7jr!p+@Ky|n z$M^vMq_k&ChyC!>eOvZxZJ&}1&bZ+3H<$N)hes2Mf@U(Nv45($OQ1Wm*LU}-%!F;a zNzUs0(yuwtpJdfsC+Ide1pw{hxUy$AvO9(jzNH{Pl@hPdgM$h5As}BMGEm}Uw6lS;j7&Q9jTsTTx5hVK06EP0}lCl07axw9Q~?a`(R*0 z@Brbm-5H@mX2F)G69ZSmm;~7JGb0XAmur8o<)?LX&uYBaTFBT+*Z#@)Ck2W~@L`_( zVw4VWyNaDkq#lukpT3m|Ad7#Uq%h3tZT-Pc>$`ip%=N=R@e54o{;-*-y4`b>;DAe& zf-Gu@xh9YsJ_@0O3BgKI415Gz#NQyybJibdbL0tHK@_o#sGGA-0j$;TeEKCDDV?Km zsKH-<<_-_>D4F=41-`~40wV95&S^&LW5&#&$F@IL;m+~H8c?p-{k>O0(HuL&KTuj& zGe-m~u_c0dhPXbJ5(N>&fn)!dO1dw7@zp?u8~%tPebJ%aU*?1Zh*}o#-oTM7JK&m^ z4%Lx*&MNe%pihtt99z#*-NnU$-3updZe5elwg&VC(s9sG-oI~mfTk|gTJP(L8kVUN z2$TUJ@ev+A27JfpbfHV|{+d7w2s8g>$43ld2qtXLzU#=Y1;vVZNdfe<)le&Vm7W0F zpjUoa6u1r40{IDQto-%G0z1BP_EooqA`ftW4;knORXDL6ngMVpV-sPTBZ?8`N}Akf4?7VIGxZD3W3L!|bA4}0(L#r847BpX`1H-? z#c|U3_qpLgjRPCSs(E&{)EFS+P$I zKq_46_a|Bhw>KGM7VR>oc+-LhqUoUMVlr2P%m@0S*ap6H7MG$hxXWiEY7~n=9B}##XSDXm3J7U)Aar) zCq7Vky`*=aM3RCJ8w*9JdEg#Yryf*%++UXD{UkQ9kz;*QHoa5Bcf|tPyTKr9IlKi< zeq0h;{!OQd*gOml#i-@y>wucu%J$FiyK*PEt1-7z`$l5URc$`B7ckmY!Y>a(g#+v{ zrR8uVVK$yYS+b2jV{4^fDUkR)QdqWDS^MoBZ)?4f-pEa0jWxjVxN{^h@nn$ak8~br zNQ8FsfdZ4%(?5XeA?~Tgik4E$J=gCsGEW{ zvjE(07<$-HjEv)zA^;m_px|`Pt-cbra_!B#8`zY|?67|C>IZC@K^x5y{mH*0 z7oPS*8%u#u^(Vm(HH+eli+S9B9t4q1_te;Y9Kp{$+aRBOv0X7u^Vi?C=^?fY`=xeb z6wC0Qs-40?^@FE2$CGjkRM8rIby8{QFx)}DaT_eyNq|V$??t`CqWW}r#XrHO6&4%* zT2#Y-+{Mtxdz|ko!2^$-e|*QE-0uT{MyMg5ZJ=QcJ z(|v%#dw4>evH-CEKsd$(qouBEIPuXDdQybf(u)s;p1EGyL4f$r?f^jr_7Si^rU7A@ z;H||IVO4UNg7g_P5{j~C4saqbPLCm$mrK(8T^EbW%-v%$uo4d4Piwf9qrVvdIE&gVK2>T4 z4$}FLr1R=h6bPd5Um_!q5*1JZiM|n4vP9+A?`8I!IlD6kRHVDBt8RU_0~_WBGlPtj zAq=4r%Ards=y!J__4|Ruml_FYY)&8VBY4K&BIy#@dvx0&{G4s{Z!wrmRH~FazFr?g z{ssw!M}CARfh>0R@yTUd>%9MTK==#F{FR5!=q*ikF@0)S2>6S}TkSHBjU5#8yAbz~ z4HAD!u0sRqedXaJFHOeU{0pb^`D8!Y*??I?4#KOKU0>h?A}$o~?I7`4zGY>!GqzuMFz#kWoxEUYmd) zim^Y#17JTfFQs{WCIKqjp z%^TL*Kb)6=R+a~;zQ1LBVvdJSa6fIeqtjKzfdf$9-Y=K!&Cl<-tZ*90gufvv#BA!o zFNXV3+rrbY+25A$Qh(2%a(flg^&w5H|>`XpWEedGP%+cK1U@k9> zi|`^W8o&+mX3By5-S%+!f;uG9Ck+&Jl_o<@C;4y(v?3D$^GQ3H+3X6fEyPpkMtwts z)t>C(^xXVwn8NSR^Dj)0;`K8=`W8e{UiL*6KO%iXBSFNEfyLDM0b>Z2DF8+15aZ$~(I?TJefJzBK9?D3>S%YYU_y}@06aIg{l z0gw)5InpJT|F;Q&4{IT5g-0s!uhwUgC8eG^j8bL2e%o-5xxuKjt-jui_i19USBFK1 zpl11`e#(Z*t1`nD?xOk3`e|L&k*C7UTof3za>&S4huMu@ z&f@&wlOO#ibuPasU^z$!xhop@b3FEl29gy$xkd(mIbOl=_FLBgO`-8VZHfdA9?-$E z(n_-93vA!;lRp5~i{&sa-RcZ&cAY-h@OU)z*EjvZf$;e-V-f+G?{a<$ASi!zvLnu7anYN+ZLr1NQ!~)gNe6WIys2f&{hK}eg=>aKD~8y;fEy;{&0WMXDfD`4UwL1{j}fce6*Q5XPN=_29J;cFue>aE)caI+!4VS4C}xczliTD&}SiZNZeev3kt+_lj0j@kk`>sqBBh2@{tbiaj~86ZuN=T{Wq&7t?- z#9_JXVw#U2seuByhX@(ROT&-QPhLusQE@K_4@AcWmvp%1V>-pIyehCZO5Kiv!Q zjwclN&2#FDcg5C86e8iSSgiZ{=?J7dIB7HDRBh%#kC!grZbSgdcy_zo-n9Crlw2mE z#`t@=-@}}*yy#&lp-l-hhqy$TIo9R=JnWm?QxKlRzW3fRJ;tB*o;Stl@pF;u7pr|x zsq&`s^fcdy^1d%D=6yY!nE_6X9?Yn1^2Z&x1Q4#?KzXTvEyot6I*k>(J0}L0|8cF( z=M|~;?(kj@b^iTKEJBIJQE@o984^#|H#}9ij54T4r|Ch&2)osufb-TO+|QST{SdyC z1}m{7W$daO6F4CD0&7H{m`sm;x^F<(H;5@ZM0x&-C&O>KF4#mJ-=Wvj-@Co>V@(AW z`~-)6+Ly!W4#!~?&7AlvIw6mzPCB|@D5uK~FeHj>8y!b$I|Kf;TH3aS7cji%)o{K^ z`YUSlGXoRe3^se+#~)+tq3~5;WheA7nebUT?33{3j|?cxCVpl2i?S^DneTKV1A^Zt zH|p@$ZqR>{cH)!^SxQNzQx`a;g*}smP$I(8NIP5JyUzx*8ItRx9UL}k*QI}th0FGI)+r)-ZWKzr}9rp=;iyUKl z6YYL|#YpC9XKRvsm|^Z$>wYcdKkbAmmAHVy^hreL2+hOAFy392pa(QzV!b+v#}ZS! zcy7>B^?8j2xgCGp33i>~hsh4AQx4QxRWOL`@C_*5;b-ov`6I~=MB+b*?e+3w|NI9P z`J}qS!655x{!rm4PhDgz(s7eXKoje^*sl40zUSY!=JVA3c0(WhmDv@Z=C|Q-WmtJ+ zxM|gHP>oJineMAL{dC{FUkxe za!B0}Huvq+6X%Pi2}fPeb*8=25Fx$c?2MPH&}sagtw*2r7*}62yZzOTA5|^hK&?ZY zTnqOFtWA4zZbW&-<3oqcv`qE90}p)pLG>~*(TOLywdJ^MNAAKZq-BYvcyx?HuX8@1ocr<1S1LBUDtU}YoLIpK4p%NrZj>PtMn-=sVDKFeJU{3Q z-%%pLW~V>sch5hdcoSA!)YYUp-D_6zq*tuy`?s^3X04yh`;s$s8s7Y=F&^aoD&quc ztkU3JFYf-pgpc;uHdCTz`?5+F{=T>`{bM;7F}sF3EJA)slle}>=+QyKr7hm+&qXpR z9*LLp(OE8>Xi1n!RkUSYKB(K)?@wXBJY)?HN1|<7X_V2%6Z82U`Rgx;mm`60d-fF@ zr8CMGrZKPZ?~a`9opdMonN798#>Dpl?;{hUSO?u&8gvm9>@0`q4+U~)wLPvltv3m{ zHB)S9E*y>x&8(mvSVm3s-uEr1Hu05j95tZ-05&Q9Nf&-OS|1OB_e7&I?=@lZ{niI#O<{Q)v7b@qYJWcb3tt!TchfKPU3$Txa&f3nm-3QZfnksyt4oP>Gr z+=4d&-{^VCsD*dv=KIT-O5aH1GgT*G#dfpfcy+cIfW&!1w@mK~u?*_1%54>{PzFVZ zeV7CvEAfn+D~I*xJo}$`$-kSqZMPcv*B?UM3rrCRasKM{H>x-QBh|6Du3r{XfN#pa zl2%y0@*2URcVDCu)gZ}=A4_ho%7)bX5`+Hc(L&Pc^$DIZNWn+HW%h7q=#1csHe>_t z**=GDfGk`Yt@t3K)+ta0-H&jtF3G3Efw79*xrcGI%SFZusp@n|8{se%;&!IC@uU*W zZ7Ru>BAI0VBc@#W3{FPST#}ij*euDQB6km&aFqYxlIOog9^PS^zBEqaw>CC1t7pBY zk5g)xz=Oyxn2-w9p8(Pw8wDevn&a%OCwaPSt~@Cb%}|0X7%`!fs!?h5L?};QIZ*Q> z1bV~r@xG_;AxTR9cXtVOvLmxbxw!qo{h?}!A-7-Aa?NWbrmeNX}8HWA%Hmyt~)%Ri4*KHM^;vOKF&px52_<3>_S2(U9Bbm?4O zuRqccV|W>zcvu2_(RAkYwT7Z1ukK6qWDtPK(Ta1B&kyY$@X^uSH<685KF}riZNx2G z-}}BnF^VmWu()+Y^XOi_q;9U`z4>JYO-B+>0q$b z%4?wNIe4AQ`HRDK>~nepCEQ>FP1qGe!t13Ax8w+=R$)*fW1`**NB5o`_aEFzX-{(RGI5TBA)wH za-JIuXHhT3=q2pwGvXpA5Abc-^aBJxYkuXYZ6ldRA+4bL=JC#O$2+U$Z+##9->1xj zKgko?kBTkZPpgqzuz835VQDU&?zQCEkcXx z1tn?Cr`yrKESC?yYyMH4Kxm24o!VW87`~ zM5M+?XGm!}eo$qP>UZ$--w*5qGMte+X_)&NipSV(dE4rQUgfizdP$Hee_!gd84@qe`YE~Z@5O@mUSwIaTT;2Q zd}cx$(NCuTjvFNj&EF!ul~%d}!`%Rqw$f~#OWl3FgtheR98;ECR{Au4c74;eU))wW z!MIheUBJ@3Kb|imYU-($Y_#FrSGl5*pbPS~a(X|{E96tqMqd0O>VZ6H8*`r_q!W${ z?l;q-_vsA<@cSismm`8@4W;mV&0p}KMrJqf7$rnADu>aAt}vp^$THpNIAp^6^fD2XW(a38vfA*Klc^Ke1ct zt5Y5~!rE--w-L_j9;idUKPmX0PahPn;eSi@*G}-jZN)<2(CL0bu|(*jl|x>?XA0#c zUZ9JCe?dui$esgxxJ-XlH{&&=8g_~(r@BL&^5R^gB`uh66-=9D&;j%2x_s`?6k1D`J0wGgysj02Eyvnn5#NI_c zwL+%tapQRq!GMSpG9G)0dOM}6I6zn z1<&STQuko~21bziv!wW?;TlsgA$`p1(g8Psvbra`;{_(;Ypl$XJJL=(~NQwbKoFc+z_ zZ@m*FPfHDPL0PhlBH?fxy;FTMsC zBOv%zOGX6Ylau!#jkKkdDkb@96UITFzpz`_^8=`~U!wAr)P&{V4yOWF&#{i%vL z+eRU~_TlTKdj>^pw?-q*2Ai1Q>+u?rYK_%S|_kO7-^hPx>tNO(kAK-(TG-tH&lbRF$BAJ6+X;$56te6L3v4~;= z)A|n1??j*};fzFcBLud+Jni6Z8V$`mGxG}$X)eE^sU1AV67SAE&s+2$K5oz@+evr9 z;+k5B1PGx#5Q7Ul@&x#aaCn#pLSg7vuz$ZffFl7t@lzcmiQSr6-(y>dPoU#^RM#3( zD>qF}u)n2~eD>;Py=XRdIW06_n{*AA5s#66aKC{zY zI*U)8(UDDK<26Wc5pHGnq-c~4fv$TzmcO6YraXn#o6VS>+)Nfj0g= z@}IjC4pu!EXBus65<3XsZZRI^xu-ENsRj1bIr%czOPjqZh24nk3X0Qf$2RSz)xT3nJK;WsqnBj zvc%SWv}=I_cEe!|-EKekt$d5i!+4CSuh8r>ANgg@{LfP6I}^V5+5dpV4b4-!_htjb z`#!!OCi>BrxE^H#qybPhGt$`nV-h1pRU&HwdjRbl7uSm)pS=x7NWbhcb|ZJCUP_xL zVH7`!11}ZqYy~xwMoMeFP&mKI-vL8Q)oQkD-29{Fv&P)G2eX9UJOn!Nv1#}A;!fr{ zlpGuv=Fe);qH>*lzUHQ#TLa`2KSFDme_yZ9e(fKXe8tk)G}td&_eGgHxEXxWWBKk} z=cs5nNJy;x*L?>*earm|WS&8RNt=7ub&45g--@ZRcRaM`U-{QkQk@fSBi-#=?+e}< zJTH(Wv;EnI=F6!7KeajUZA+id;sE8Ad}RfrQ%t0q|?ci@{gAnsg9Z%RsOnS5|^_)1{x^W4Y|@$@?oY36Zd|_ zJWKgG|J*wydE48yk*^OeM5}j#f<1<8Yh5SUt(={+u7+)O6egKd@{_=ptq8g<3<4%b zs4g7QNVlJTo)_9OL-hnI71*9fA=QssjAX|k+p)eYMpU#PathwJH81*Ly_zAbKGMBa z>P-32R(kR8kJr_r%ng6dYO-^LF(b4>DJAu^MC z0`b@@ows5i4WA|lKK6WbhajO3$$_8rNySES*fWmsg2ulq^R-X!0bE)3TE1`lMz3d{ z?(zD7pe~KB9`_7>%vPfge4gLQ=Zrjs_!Re%daT~Fp@I)5@hfh;T|U>P4z6s$O~@L*mp+;PeKEr-&D2iEag_IJLaryinHC|@|TS$*>aoaOyCj2Q2K;t z2z*4q(!J4o3Sf6AC#h|a0yy6Va}(#1?y2tTp>Y{61v~hfhi2|^NAft)o`IwW9Mz`Z zMUOqLwdVJ)AUPnJ{Q)OURT>l=5C@spU{IPp#6AtkEve?1@K>e3^~vG8%*PT7j!Id# z*oyP58X2FtDc8yWDDL;xFJd-#n2J@ke21m-RGBjdsS2adc5Q1N9v0^ddxb;*jRrnH zUF4HpkCWkMy=G_yQ>t`#I&*>UR(^5#=x+24NEmwEsk|uX2D(?t!OZ#NEwfbS{$1zy zIY+w>uq}Q4=J+ohx|0wh&sPgEy$^8nKIHKRCfeALyj~5S*FI`DyzVZ4f)9#kGhswJ zs%$$slx(?N2Q-Yd|2FrYZhzPnx%JO6;6CwPNFfQED)Tgu=-kPE+WEtIGIIYgoRqZ7 zLoWifq-S!)E-ak1_V1r2m#jtylR57ZH+8{_DAd!7KhgcE31N9icTj-1;F>t1r!jjm zN_P@=MWVRR2lE|h5>%Fy+5VPH$5FAyOjqudaPT4tfBP}CjUH!;_O$OsnXm<&xs*TO%49h%2x@B!qC$uenU#_e+B{ zb#Eru4g1Il2;$GKtEi8cO14zw-*AxqHT&C>Yu_!W+6sSs5fHl_Kl|;$yM6X&tCTiV zaCuAp{8~n!HXT&)Q!+886HK2X`*`qL4frw`+{cait4;fljl%P@%Odga)#(rBiT*I{ z3`encT-?{3t&dAzCA)Tr>I^zw3flFXc_X{wDIl3KFa0fZ|`} z^Xn_gWyMk{8s`YQe%cP?V+D`(3>b#5ZOy+=u$YwRq;dynHNbpb*Xd zdL>E=2DF|JO3<{D`{#YQ&->&2*M!V9h&fc>+a{>@TgS@Fs_7rbxKAJEeAenfI~7Ea zEZ|AI5}jzf`NgvL*yb*=%JpjH`+ofOyj`ed?g2I=9&|aR*$*1YGHNF2H|)6-TV*|O zXOL3cGpvT^=LLk&Vq@4h0=r)$m(r|9!~`acif-=1yQ3Nxj>^}*igV}w(XPY;OIPFr z9Y`4fG73KcJV#mOp{`G3J_HY>Lxu3Bz}L7RER-$=-PyLb!B|AdCHSGC9G?9kMm zedamyD6NoOgx}$M2^~hlP*fEk#GW*4)_r0F%*NjKnu%y4flQep@fLMRmXB@EQj|XM zHw6MrnUC}3$F3+5b8^`4TZP5_YXoF~NxU8lc+xiAI;^hY9GH&#R;lj}$!Y{;0Is`}zKY>nuH@w_XBzcl%Mn zK|1pXE6F8YhZ<&kv`6QXVHvZk7tloKeNi8jv(4$q%?2b`&(@Tgx#rx&BU4l5g9V$qy4|f|aU954t)!vnV zjI_^iKnU;q-0Bv*TuJHpt0_6T8yKKU09nXFg~zJ%_pIo@Y%uieLmUyRpfV5Z`Ypa` z_h|p7F0XMLI16=X!GB*=3#S;mfEss|tRrRKPZy1W(H=qndKmy!7IydQfJ=eVT8+p_ ztj9a2kG*A z#MAd=+=$u4KTf|7%4qqc2>GMLUv8@&E)}Wn?`$WqPKTFh@DU4}yQB_oMf1kgy1$dx z$2&*G(nYA@^?gGD>Ff*iku_1$;7pcc#$UFrbn)sA=Q25`MPu;q8&z{f?%ekAfOaP{ z9q${+R=1?o4)XEiO?n60Vx;PEe{5Peco6PWjA2E;0~RfO|ECm`ifj|jdtxM*@Nw_` z{`F18K0|~dN>K(~E~eSyG5n}~BSYFP2l}boCe}Wf_Q&h=>%nkg=pX4JYUeYp^7eRE z*K2-rPSq+1+=cfBW1{Ov3N2cAyWI^bcDRCynLdWS+is)WbCRs@FAyKySk(s7!TWnQ z;H&bygz$-Utmlmn(`%}1Oq{$gD;(XC$ovaEWvJlsa0*$A(~+32gYhXFCb?3KC!E?r z>f2Sr1E4^{KLWn|4z|_m`6x_kP=iZ*G9W3vR;zXRJU{I6dwB=LiYdMBfv^r>Pbz_> zS*A>3L@)^9QyBhS^UU_0;cnw~U#}s+V%5xf&RQ{1aQh-XRMv0m7RJ|xPtOoW*ho8a4u^-fueqUemXZgM)OWz72 zQQOM|iO(Kd>yY*4O#Rar-PKP-Z$yB@7q^2J&qyv%m-w%0b42&;y!9>2wX)9@)t}F2 zThpq4Hw@*G-3+5Ao~Z7XzCbMtzV1bwH>FdJU_J&-Ba?TjlVHoD~ zdpQR7T&h&1FC-HH_l`Dp7kL=7oHQUa?XUzgW;>7)-j9%@K$r{iO z!8^#5{rmE5DIqdqJlc*=Y%mz*(jr z@WhStXFIF6o%$?tzT7%pC;(2}{oLO@(ISN1Xbr)A2+DET7mZ=0qEQ$&FA{LnVYGFa zenmIj7lc--4Y`b9lWy(FqlS~f))Geh*hz)-y4^}iAEZ|=^=N@rzsd*Gk6M@N4<^C< zv2SNs98z8dWyhVDZbpep3JjVI5`AIEAo1@lLxH%A9Ae&}uyR6*cc5VZ;LYO^e%O

ZB9se%KIYggTdg6NjY|%HSObtGp zV6XP1$_3pp)w+jUuUhGfXw|{QjTDmGw~Ybb_j)vLh8#-7t33?&sfd3F>l?SW_L;iS zzvB419nd^Yb?yfHCHGli{+$x*}ut4m%gky|&aQ8%VeW!+wK(URdi(&5gwv zLV}Dxk^F@AQu%p|7RjmT)}Ncc&o-)dYmFc?cxAn|2W@cO_z}6kXYtUd(y`Hx5WD*T z#t%A#WqSQOtb4iCt~tIg))H^j4SYL*7apreIXx=L4asIpeM`l=(frRGM^GS+Gl@Q) z12QwW$IXhz1r2+`9>^@yd3f?_1IJN-p?NZ{iR{Y+4v_?gb3;Gs#!p#Y1^^;A(N|s0 zU&?xHEH{*hkz8YDP4JvxB=Lf|T=RzaZAQEc3BN7-60P#g>C!^<+b*nBI@vw?8W13$GKJ6QZ`%x47t} zrlL~D2R7HbBuHT+-SlPpo1+mq0=?yXD2ixU`w!a833+r5l{?X)O=qV_@6<*Vq%0waYteNg>@|-I zIETRo2?0{k4m|$=snTqUya};>SK0*vu>IpqtYF@pyCiujr>SQn3}clzU1DBGr+Zca z-v6yt9o2a-0Er`Ye$naS^&>KI+%*@Rrnv2l z?UBY5;yTsV)JuCFt+$2lMfA(cjo9pAzC-_d>XPY4snNI3IZBz+A#ULbvYM%xuruZ> zx%@6IEU2y`1SV=N!P>Aoc1opOIVN%KVBL$yP1q@)NJVcs*_CTSF8E4===7J4Q2GbF z+@(d|%aKMtKFV>?~YND7lV49E~0c92D=FZlfvxDl&iD#>Z160N3G! z&06n?5RrM=ub-a2}17hVN65 zXFO!bAx~KCq*tXrpkRGefCyP z?RG#<1|L`r&ta|PY27+lCxscesH$@IEo!mJ9ekQRKWn$QHU77ld>YE&pfLjsWerHa zAsEKANlbz17DKP!-y!G^V;P{B+KnSS9h6&iA{H7;x_Vja)u{y1*}IL!BCnam{5*<# z-zBl9)8g040sI2tP=M^c{PYWxZmf!&9v@#{x6N-ohYHxn%B0b9_|pH-m-0blYidX5 z{w;x$&|dCfQNw)r;?rTC`hG*B&PML9t#!m@Hj~Pkuu~AllmCcLcbl4+!iDW*g4^8v znl?|>FienAR>}V?J)&C`eR=#9K1Rax3tk9f9`Vop$#05X{ieRoRa|KRIZxu_yuCl?@0HmP z`l#y5crfjM5~^5P-14`~$9GLpfws|W5*-*@OV zOuR>pSA4V#L9g~evwqL}pF_31IyN~iaa?iNjUZx~fq4K274kzgE?Qupsmnw+Pei~3 zJ?*3W|SLwY3-|JvmDpEqoFCW&j7V+&I{8{d0Sk*U| z+~RwfCRDcrY2S(Q`-RE|;N;o%E;MFD`n!LQ989mmM@4R8;{I%UcMrYn=F$#_jldde_OrR5bbnP~d4b>mWXJj;2&aX=06kHz7EKePLVpkT%aZk!PpINP z17_JRu*cMfJvR8DwkBNV;dRWXH%4$_NFVz?ki36yg49NWF4q(DdKxwux4xc_;eJ+? z^sF6FOSjc~z8T4J-H7v~IH6S9-Kd$2A=OMfojWgrIa8`n| z%bY@yGmKer?P96>QgE`x0k{oNO@#R@YOmg>{{Vse5*^7zyW%bn6Hj$krWj^oxTi1g z&9&Kt^Uxef_Jr+;$Q{xlVV=`YCsMHhjQjaa_%EarZ;c)`%tfjvp;C zz2gu79srNciv1EfPt=p0usn$Boebf322hmYzcO|1;mj?>0XdSrncYtWsPdWm+N0NM zEQOsvul~S#_}kO`+@;XLF?+c;2d&QY@pn5ZXW9MZkxA>D*$UT13lP2(pB;5g#&gru{uSt#~LeMc1^PbJfJm*T=h{RrCkd%lJ+ zh@Z1jEts~Q_9t<#YYmfLfm9%+I(G)QU>h*S+(Ia)^;-OWPUc}x0Z z_u`ht-tp5?MqxkV&B3i}op_&FX2*4BU9d)TO;PM2K4N_9nd5wfxy}j1pHhFnC%3J? zv$Q4J@m`JhGsxmF1_HV&-M^O@lBAvCBy!F-huC_(5c7$@eT|?YYlpJZzG>qKTEoY7 zu+h;MPa8lU=K|SHx1Gvm(uUNz{uG)|W6y7%AI zf^OO^wlZekDD12IEx}Xe?rh;PY)%GBDX}|Hmluj zN~F)4lLRi{ncV_2Ei|DS_8sD5nHIB_-_P5wLN0Iw`j{L_NA4;zGf8~o7=Y1NU-e#m zrlCIGvHt`;ta-s)rG9Z5H410O+OOb4T&Y}YUA^zVmWg2!r&(YHF;+hH{=hPR4)EI+ za96<8h+(`(V-|g$^>@FHhMEQmFKu-9q=jT9E__H&;I=XGX^Vlp2Djm1|M7+&ll-B0J&oUAmcFX|`PgKvLBr@lQ4)6mBwdM9;n?}rO zevz2`H#sj|2p+u~MRRzQ3_wmLYcm0;+0LURO~t%A?2nc^x!4z%EcZ?BYa5R=*E-4i zndgoXw9!tgCwEbRD~jw&yG@_`rLr?BPY&vLMaKqLzuR|y=C>g(ABjiUqEg-PXBBp+ zE9UMKyq`;S#qXg~L;e9xVUC)-y0L)4fbon&x(WK(K%A!&y(Wb z9$-vtpY{!gVUwTWa{`h9(gf70q=_#}dwBSJ9b=DF8{%=TQ&c{na|yGTsD?aT1sl(d z0~-lGRr$HE!=-a!gB7#KeNx|t3w~0dyOwnSBQB0?!iQgm>-2rH;XYUX^Ep}53zo~J zi=^GU2X1@5PCN~}|Jp0?e`o`2aGCY4--1ue#Yu5qUZW527Oqj1Je56vsj!5e_Hnfk z?(efzC|@3Ag%IzoBs=B>`JGcarAfns8*}{r`mtawNb`p7ZDqz&to*pg?0QRM^o@x60F zuoL4xWqR8O^ex|a85+T=#V?~hP#@q@wiavD*S9!9-NKfdqUDkyq1nlP}+RkYk4G2y&%2gG1JD&F_bwIR7$GMsyFL(O+((kj5E%ImuX4IWAKk z6mWzSb4fu}v;ceKDouXt&+3b(-dEBA8_w&BrxkvS3h1sIX}m1U8(y>-@n5Yd6)%ywW_!pb+Iq?mE9j+tNY@K{Q+e&4NolX zKx&+1kA~<)9tmog(Q|5w#bwJoWTtz6j=y*IepxK_5Rs*MIb8xj8xqnsofGpUPSz#4 zeate;Wchw!2(JH5Mhoi%P3C_lr5`BkblMZBSN#bl{MC0oTe}0JL{tWuFm7Vc1jNA= zLCLT1tVv|^LtG6fbbIU)aKLg?=A#?W<&!W^QsC!1gR@ekj1icZi1iZa2kKqsJ#mmOkl!$wo1ZL5JAAKC%>HEabm( z$xeT^l|NJu_H8#d{HOFh)y#|u;`B&gv92Qsfg${Zp|rEtPDbAozMT0qvVsRif3|0D zD&j*n<>-Ng=KipjI(Bp4LZ*piZ$pR+m1>#%~R3Y&Im`t~yBeUgzxK_nEeNbF%-`Mw&{tU5A}>@owPo|ZhaDD|>;CiD8lJw~El0C}hjWKWfXd4}E% zI*r>qcBjL!oHhwk_(+b<>ls1fcY6%NJ&GkS=1%#=RQ9B80fnrhK_xVvr1F0562dj@ z37(h)76svP0EwY}v(MD!jK?QY!q`01HccbzeR~a)tQ^NF>G&>;-t0S?Y&0YGLF`=9 zca|C^X_jw~ukOVx^EX@Gbc{dMD8mt}HF;%rSr5w5Vd`-Xx&RJC1&Y?(T>_|tuvFP#Q ztlk6v<6;A*b=kJ-pPTpE0G}ni3J@cet0f2z_5}qyEjmN9g`LBn^MmXS?{W7_;mG;r zBd6Imgem7=u_9FOY$ka-M=Vv&!xbSO)*BT@2??V#=8OGa2qjM@by{$<+5Tn-;KFSm z-k--?e*0AT*@KzSOSmU>JnU;VvfSSX{zMM7y6Z z?=@@twgT8(B;PhZ3Bq!}m8bf~ zaqEcCMa3C^-#iT~qQ7Lx<^CHWgP}g`V6x=z)>WhC`>a6)U#2y^DND9ftE`QFgW;s} zdb%fxkuyVUh_xk(=$8ru!5Edl3TIvD_AM@6;^UF}1AbFF^vTa};;!x;Og(TE@%YFeh-i+MLIDj_aNhlIltejx& z;@ALn<5il zXf|MMzQ3(o{vo!|Kz(hJ3zTICh%S;aaP$`Fc-;Rz&Ndq8Bp*45UX(x1RsH!FXy`97 zy(f=|EI{wisr#~kKc9HR-TBqe#^Bhyd^ay9j3IPsgPHKw@i%4-78rh3l0I6JU%kHA z8l3s_gFPFtR`phPGh-6IQPZ7Bopr5L6emj`AR`+D-;qFI zl#v^aX3w6&pi_(cADaYkE)@}1ijzdOVg^S9sP%f;LVukV-E#vW>EkJN51TFj)R^Si zp10@tEiveULj+B6cyz}OCIDY<_NmXOx2Fu4j3GI37vrXsFCX-t$gV-?JMiS7m|y~( z->0-5+gYj(pZ=QWbUIpl!Td~htWFFs_EY^#$mLLxZO1*Q-V;?2kOuQ}%ai1Nw3I)j z&)#QLlz?g0uezI81R1D*?M)(W?Q9G)T@xaRGcenErbrXE3F+#H|7s4e1B>A7QkkDg zcr<%h`v*T<_>t9&Cw;&T*F)?}V#|>Vy1VwdeP8m}^(P}|dXx);1|{%loFMQI(97tI zFQib<3w;F?u6VNH|HjMcs$pRs*LhATh3!{|=jKBrkpv=`t~75vYUo;|pcC6QLoZ^y2cbx%BX!GujwL| zpJuQd2*wEt_hkiUNA}yEN##w3eM3ogiVk(@K<<7&^{5w`(eE_ZB6CQV<&9)l^~N@8 zuuw!t^9=UN^727d!Bt;%$S%&(2jNyf-{GkK8ali;sT z(QveIsK+YVuU5%0V0XZdI6vEIXkUFAU$gV3p34XTt>*(ElOKF;Y);59vC))|Im{qup5KhgZ$R)v!2`7B)6F@#D3?Z?VoeJI?ka4-T!_z3zO{(=MOe%pPC zmOpGv_8xfnxy$_Z$J1d-?U96Nvdgo4@K2a;(AS4TK4QAR0{5DpZBf3UDh>|(=Rxz= z+N;+tKpCR<@#PE;pf10>)g_G^OlP{8+T4PLF3gXhq5ggj)6AiB`4&oP8njA3*wRfV z+568|d=qCM;tz(Q<3O0#AKrzcPpop{ByR%0AG~CeN~KB}wm0m37h7eD#yS~-epZI4 zXIpeTbnAqVj#mB4ckb5erC335HLF;+lwiY#}@8p$?cd4dlWBDjMJPMiKncsh{p_1|v;7X)7 z$F*;RSWjCY*{nP6wWHMvc@k;RSn)m5nt z(m`iI6f-}@CY}sD1iPzz+^wlplWF~XMp>8!)pwpSrfq11#_X4(z~twf?A(zTqAvLDx-4`Cw-%X;DFeN#u?+blR? zaa6}yx6;9 z#>xVD4*G#i`2&y47Nw78^Vp*MgGtIS-Ufsn!J07szG??|E}FapRPL8s8OR;_P#8Q){|h1bBg@Q1_q`+ezS?gL>q{@Gtu z-R?jru9W~D;mEPw)6Fw%{7legp(x$Dcl0@e0o+s_jm~8S_IqZ__qiME-BURZ7ju%W z!vHI{Y+XLab_=WKv_8K#C3Z*H5*!LxT4Pq5A+f^i=#c}clcO0PYo6zbbU$c;{!|F+ zMK5taRJ}$NhOi2lW787{k2pW=haH?d_+XCnT+n!69mS|0eqe}B?cW!DyhQfms(ye| zz~s&A&5#y?#GEu3t-7dm&N2TKG6AU40L3in+X8UUPZB-$&{+2PbdLE(QdPh!aUriMPT$3f!cLfR_44)^CaL zjlVt_UNt8Qr`JHj8ux%=%+4(g*|*<@pC39YpYhoXm&n%kYdtwF2vKjc?!(KiZM4pV z-cT0;rbrSHuN$~mzS_A0MDQhhlKVm++K&%4c%LHv01K_{c$s}6aZz-m_eDddOSTXe zt_q`~_I?S4PmuN= zG`k>KuAD@ZK!}2OVS3@gRCxo^_4SA@U;U>-4Te4ch zQ%D=`BJ-fnpWfV_5BAC5%SXp{Q@4fZECy0y7CNJ?$m1<<0hgzf7P@16j0EIO?Jdf9OiFZ`_xpL_xj;60CllQ8&-i{$yYJWCfg@kFx5U|bQjlt=@Wh2^VtBt_ZOXp0mVnDdh0^5fV2Nq$B z$mQ8#48cM!j?Cy-jv#6Fp?5?j3ikz9b0@vJ5^ygxRULNf1fV!h!NXRWs< zTq3=vzR#;4k%QE7F|QheC3Ax5I!xGtr|%!3?EfP_>!*|nb$GR}2FhMt$F+L>a$}tU zj5=PJAncytr<{Ur419RoqM?i3QL;EOpgDP;Z@uu+;6wZU!q|s>O_mfZ9zb>nBF`)C zdANm?Qixx_4xpwHCI|JRLNyRkAvXsHIUd?sdok08f?ufEeEAA=9pM~v^iC6y`1SVX zlmi#Ey1nVU)SwEDd?iI~k_UfdX_8_k-@wr^ed3ZZR| z-d!IpY5#0~!+8(RwOQMzDO|(Q9o;{Zi$yhp!|9(ruKv94 z=u#1ITV&O;(uPoVX=G+TOqmLLLSLZTw4?4QU z`=@?U{D;8zl8I3GS#zp;F=*hQOTjERg#vl_13&FqKQk?NbWhD=QgDUwf^kKN8ynBD z_M@9)-LLJTYH9Db$5h(QgV5Uj);%22wS|MH634Gf`lzbhoyG7f?v*4JUE1)EQizkW z8G|Ga`n7k9dq^CT#(qvFse!c(-&a4gEY$YtQ#U@M%lnI@R7&v=HsQBCvV22Mt=Ve` zKfVtOKG&}a_&f_?CnXv^Co*(XZ}TqJ1D;NM)HxdBrlaB1dGQHSOiji@`QVXo86Wc#iBs5IGrf{7C1S%PlK z=KDrLpN+|&PR=m!Xzk{$k?jXUTBIeQR5qpkp!6<|S9F;)Umi?-Xlg+X+T#dH>rx&c z4FL(SkDiSCUNKo>DZXEEl$@b##ZC)%V<|5-N9RG?7uFBWHc5f~z_^;X+m!^Z;$f_h zt2{h=u$~n1mEz>3L(4ZvU>yd|mi6N)Ca|>T>hm%2C1lwiR3 zXypbM9lWW*4T_Mf-wDqpu`9uQ5`26rbRhN?>64Bri!e!*AbJl)33FyUtb$!)1l3*DH@1;z+1Ei)3xljdYZ#o(5x>8;@H5h`c2{>#B%gt z;Ps%k=Y8F7Ufo}wiu<$RndKge7CTMUe=JSt!e`JapJ_VVt_k6h(4n~7{B zi`6@bwtdTNs|qGqXa_yd5KJvZ{{ zi|n<~6()`KH{^J0Ab}T-M;PYYj_>1cdX@A{s(t;XP&@y49Lv6-Ogue|%iHpf4X1^V2BtVvPJ2O)jZ^Jj zLS^iiMW|rL*RbI8IFv~EyFRU27MXHJ&qwqwN*1}W#P+{1e8ykEYtYE|@!^7#jl#)m zJCqER@8H8&JpY#Zr%0vS^Xp$1WxHon3`M3SeSdJG60}z%!)w2b6KY*JSbgnf6*kbo^6%xPQcSBy?BNo4Sd{n}- zl;LYIawj;K0f1qGcM2+6I^*6BJd70%Fh=Vp@8DGZ%eI=qDCHdG8femVKJ=NlQ8Y4t(q zVZH%k2w&wXsHy^9kwD0NZwb-wOG^ewMY9^a` zudWcO^KpqJ*;QNWNngLH1ah;Z#tjUo;PtS7Fn&Ay9+!*8*p~DR6-!uird)52-}lh5 z#;{I#^%c9u1-|+TcL1yFzw3RjOvh?n)c()xuWmUFu&f$>?svfAs?(+NK@{rg*HN9K z14A58?%;n;0KA&Vu4}42>9jY(3;QUbOTApLo{7pH(N|H`?JZtTCY!IdAWb(!S-HJymCCecXL*_)Y+D(zqFC z`8Q9GNlRGqRf?Gq_f}aaOyAN5m_yy|!FLbpx6z83hEIz;h|J}(Vv;qg-wt4&vQ#p`oOj)?8iH9w&> z(J!B&RG59Jf-Hdl>&77b6UIYy{jE9{)hEF(eJ08v$TR?~S#jYZz|I{s|<#yk9w2e0&Y+t$zS*ea|&bBWL;Q`637@ zcbmMahKW2GWvY`d(4j=2rmk4SR8A(ZfDc_@YqF4o=*$wg`uh$gv?hi%E?dJ; zH@$P?1Ya+@9poGHF}1&;vwFR-`vOaO zP$Y95l%%EVej#<;{!P6GXVJETK!xJpyX3t-F`a64&e$uIdl0M;qNElZh+$qa=quk6 zfk?k6Y|ikd+mBRg+6Deqrg5#?=TiU$Q2zoP1e4b1{Ut8%56xSU2ScSLRX8y9m>9H5 zu$lloQb!Sf22J?vK?x%h*dL z`ZPQwO-}>&_KCD8*3_8n5b8=du9z9o(tdfZTZX+SE4E)fuah|)NO!Wdj5xiHl~PDb zoFzkcp6j=$-VZU$m)b~*uqBU=FBtyzx5nIq0$|^z)PoDyXN9#wdWC!duu4I42Fjy= zeMm$!Q)sU3Vh-$A)QgntNaN-)aBHyPvR>_#JbfzHYq2G&w@e^YTU>YDT=?B6mls5h zUxFRVs7@}2?O|ls1{r|~>4W2Kq1D&0C*f@p-{tM@w$u)WWksxC61>(W`GX69p4}4c zH$xiR!TM7|7GK_Kpj{c+KW$kv;RtRV@w14-_8F-zPr^BjCQm`3S@EleSTWgvnC;>+ z-A%DoOc*uRvrwm1f!=rb{UcER&iA1a=SsvjT`A^(+PkZq3J-o}Ghgqa9i-}ry9w_T z`rVzrS}pT~QV#S`DGn(fuZ&NHs9(*$7RN-GqV|N(XDo9EL$$24?HI<%e80{aYPe%` z4I%Y4LI~Lc%!z=SV(!{iSQYzP32@Hynpy>*Ae$F`i$oTooM(I9*IYMHuxNtvF3i^| zlY?=zU5M~QKOh%Jig1Iy1ZI18c}7Ed>bz0y}}h1Y+X;vJ&GU0+}PI#8=fvR;D4l;Q{U{u z7(`^B!-l}2b)J}?ANRPg%icxM>BCD89p?$nv6B4p+zl#I1SAU?WR_L*4p2_%!!^OY!a*4tD$f1> zrXG64O`>4WDSp{Nt(M&sn(@JFes}KeDPvHcdXwy8IXtLpmR{m z&N;Kb$@lX+1lw@swxw>D518)x4JwQ7;--I^V-qtEWKL#MyuQ)o>G}6$q{rc4d;94l zm*V2|7nRNZA=N@aa`423cVf+0-3wZ1d?x~IHJ#2~^V=vN`Qu;rza1Xwa&ixMkr9mV z;n#FRehC=DzfF|w-^Jo^ywwYiPu9;q{^d<1|HcHeUW8`c1^Q5QxjNtZ%boIf%VE=R z@3}mZ1mBO*^K#^kHm6Rv*kQpW(7uiE+2=UEg82tkpQ$gy^dk9?^+-Ud9P|t8sPY|> zC^z1S_XWa-HfOg_SJ*kFUd1}@LdM{N65R5Y4V^h3PJ4w?*_qYqOyBAACZ8Unm}QVW z!OMWKJ-|2tuD1Al-T8K%idbvlJz0S@3$HY5u{qW~J^OvHhL9yR$ngVe>Nucu4#5)= z*s@W~?3{N!v$!x7ogZcUGMJ^g@tm*OCujZ@XlRb?Wig8xT|bkq!<+Lua>|Z#@c;lf zd*0#w>lxna=lnI*Dl?60C*2B<-Q zY=3v(PCD|^{mo>DQ};{vYmB0Bdi%av;l@mm|BL7Hoze4qz?({W;9j!ych@JSs>%B; zF5obkY#^bB@Mp8(R6!4ibs(QN^BCy+djE#FExu)Bds{V~zY*blyU;_ep4iB&&3>B8 zJ)+WZ14_19UKcN>)@k$QKH+{Ssi%CU^FgOt^XhQjpTosYj2v;+x z%XR%Pd_J^yodQ(|tw{s?C@e3ket9ittBUd;rQ8otTTeEEae$ZVn5y=FBnu|uQQ`&Z zcd?45sWs`0N@Uzc6$U1NhMx;8$Tae0>bjmqn!)}FLih@5O=*G-g9<^rsP3bK+XqYH zy71&!AN%K)T)>qjPw3UuNKDOM;Wiv=4#?=al|^R@)rt?=ohF@`!2{^ z)BZma3Sm!>L$<4G|xYW;de7af~u&s zJuFgXJiv3TuaGX!XTS^>6Xb7jN1n!{NaywBEK7ac4z2$!rF(q{LM2b%XDENe^ujp9 zkNy~%`uBQTd5aX~6=)J;Rm%psw->83@qx63Xv7~l2#RNNqR*X^c0#@3ymu)$@{CyH z_K}bR>aW>4IE7u$FH_!@o-!%)r8a2OJ7*Njza!_$@m~XSf-J)f7ENaJ z&rFyEuR%8v?D(vKt(*vA2TxA&a6CtkZH#;4A^Pv-_T96T=nWZzXFD4VnTa+n(1vqC z8c|2LTj(QYCxj>IirV2Q!>Rjh>;fq;hA7^&3h?zE%R4N23USUrT)bX6%TMbieXX!J zsQh^kBJ`eIDd*Uqhw0Ljr|S81M zk5HG=xyAg%nbUdoWCMw}+kemT;k5tT?!w%UvVUsO`~;c;uDi!=7N^7K4&Y4nt1lPaYAGMX z0*V6sy@FvkIq(z#%_;5k_`y^C-XKl_Y)5lS4+g4kF0Id6jVKMR%7cPhuI>P4_l1M> z?qC0xe;p1KVn|7=GCGE?B!0|@uzPYa6BP}k@g*G9bwm9%dXRv$Z ztxz3Qubv`wTl?0{c$iyexTrz;K~yL4(#vtgIp`{boh$gWOV5M)Uh#iv7ngf=q@5do z4n-9lgYf&M-^CZ+Zre3R@Xn?4BXdt&A{w=pr0D7c5r|ts+GVq{mT0NM@dhaYt(33j z7^){)RQH`s0q7xkPM^Xqq8ZZbS9JTTz)479N=cwF*!`|ftOa1>$K9hU{ll?R_p;&6 z2PMzXHv`_axxia_uQpLn_CeuEsPDZ!N)H0#bKG8!gTgb;2V!}>GJw@Tw~J9a{8`Sy z`LN&8R=DizcOR=xTFWz_5+AW#Dcv~4Z|37Pe17|N-Xr~yv1a^8B2WhU!<+B$>ad503d;@ce1Hbn2} zJpRB|?)H6~vdru9iUf^F31oY>$5cOyf!w6yVF_?%G5pt?BSB4%1MxU4pjDspN`LaV zL!u1f=}INvVWG3%50J36zSxjEGLz0wz8JsdBxd9fH^C#w8upeecpOh^@}- zUZB+ORCV|T@s*69xxj%R(o30AxF595(v4a#R;saA3#)efF6G}--ORV8nj>3M_uqU3 zz%0CuIC$Q4ccE#5!gyX$Mw2DuR$zVW%cJenkU4nQ1f_VL^48~$TfZW^DxG*Rpy|bU zMJ#6qb!8(Kx8oWDqI3^ENKdD57o18Bf{y{K&tFP}?`0Nd>h&*D$QTBAy6?t@>mKRU zpcI6rzlShfhI-ONHh45HB$oVu92$c3iC>N$v?PJcGtV7--*lT=@AZlqN9L)aJ#4Ih z@fET)Z}QjsEHrJu)K-vH`d9~dzpwf+`dyZ^lNo^VgRvfqU|d8f28$3$JyoM&9&S(K z0qvf{*j04?kH7eZST612ya02*7+Jhg&s6@rqRQn*$fCa3mv^{dB@wmq6&V%cY^Vm` z=I0)UJ>f+GjWw2h1z0a6PrX%r=90(LzDdDnW0sAjB?j`|M{>!%({|#hQGhB__Qs=<-aAyzYT2zMcS+e+uWWc8~M<2!@4_pd&RB2@nFX zb}~qp%Hi#YgOJ0A3rMQ3_Wj;6fa+iFDPP1jW~o~CniTURDp5};atf#VhpZV;u^5R* z3Rj27a`JAs;Dg04yb*84!{JRdz-pM|m40yz?HL|y=TG1DS_&i5_11rjCyTCyIAP&Y z{j2;GxJTm@82EEAL?EaGW>?%$Rz}|h|WzX=Mwk_o% zRe_vKWrl=}scoOD_{(s6WFCzrn9(0XA&UNOk=yhGLAXu2o47tJ_fvxS_VJ6(n&0&a zeB`Wpx`{{!_sqB5^f{Q9JJEIfMpeQ~-j*LNB!%fJ1zl{txmPiVP=@&?)WRI|&&je~ zD|4`1!T36u3Lr;kgTi2VU$nki3}0pORDOLg#Z}+4O68{x7%& ziC;Xs3KmQf>34%DeIzexs#}Ny+ZU*C!IrGm)2)h%klsJ!pihvp&eKmtK~aCZ=HQx5 z`y`U~O)64}s;orKSu(f$Xyt06r4a**o1YYx4rOttaXf{85X)f4c`$G0|B`RH)Ud~zl^<4Viy)M->?h8j9 z-|S$3bJvcdk!lI4qO_p}e}m8^z0g-z>c{=8=J@)z3-ma=%oS z!d&SN%9F4n!;C$CAJmC`&kIg_UzP5MJ2lduJGKFh7ubDy;x;N&mT-bngt9I%adEw0 z%!`5 zn`{G7Z4ycQ4-!i7w}n*TSEMZw$^`M1TL#t+q~H9C#{z9etD*zAkK#>9;piT*bWv@> z9zW)MR*yDsKG4j%>kT>%QJ)9b5v-(6Xqe0w&* zFGcA%K+@#++b^Xrs0#ylfZ(sE9={7ILu&PlKm}K0izl zOwu#LL#3d|nJV4`>Ko?s*H1^dtKON6SluqTK%wzB~-SQAH%SnGQ$S_EbZtREtiOOE6aju!N-8 zh87ny?-S;98TT8!CE!ZpyYZLQLd9g?e=2(4Y@UdZHQ~us%Y-0Nwbtgn2LzS&^T4uz zlQn!79LuLvxYvN(%u%6%Q7^&_M*Ce`2=Cn$s3d6*@BP-8sbCAf-Rm}TVp0;XB%A$t zrESHRlLP-D;b_?@93M5@KFMfH-6R~I;C=?oMU#Y$>tuQ@*1aES_>wcran7Dshk=d(V3tEqO>^&0);qq!G?azgWfaUGMTR7O=9N$(VeWIX_ zCs3x>BRbU~k9m*)&ZWGj^Ga5GW=^hVEXb1k;@Ekr+1a}H;>xtQG-a8`pjm22oPRK$ z5`_(pQ_4fyC$mKn^ZU-uduG|+?%MclH2*ojxwCm9lshV->S@>j!G2c4aJ5_2M zbX>RWmG;uTK+5)Fo~{rIrvMCT(Lsb{#d?}A3&3aiOfdptkY6eDkH+}uq$GLio9l+( z%B+0p`waYFdDPer;Qa2%$mV+IBA4g|_u$^bm=)Xbrx?WHx8XvaAZT#5-^n=N{CPcd z7w=H#AJ-c=<+i1WM5F^$k8|25gOs(2xAZ~uJ^I|sDXSf}j8ncgyh9lV@O75x-BLfj z^v;92m8xEr&JlLssL(`wC@4$6mZp11kv^zJaRE9kv0XBSUAdldT=9lt(KLaV#U1{l~ZoYG0lP7Y~HGo}8NK=}fPDmop(2yIjwXW(0B+`7Y6S&paux*tW4xd(7` zUP-SdGCqEYkem!&&gK1k1BwuSu%#U#`+1luI9@*>juh6CJl2g5ANoA(P+&hg8B`rU z1cML+w@f;y=c)PzdoAa}MwhuQzE7LFm~gb)zyy`I*`~jhw(q}Sb>jv3FM>w}k`VQ| z5PPhQSuF*0$z8|yE8>sr`8`uK*kP6{8}+ZDVYM3nKn1sx2NPXj1d5jeiue6MaWd(9 z3PrI&fB3fd($0HiD7*r=co0Xuq7A6|``%{1t$oUKk4M@-i!P)qv~=-I$edrAOV)tG z4J&XP0>{&GrRp!apAvPq+9qR0P5&oQ-2DO?b&*`=(QRmOLfylAxfZ$H6I@&M8iPy=EO$1!Kz5}9x)R4S_PFo~`qi#J2nY5CiadXJ0Kd6tjXv!g zH#ZwtxGh(y5Jo5ng(O&oDu93~zDrU0zNe=e`hr~{s~QO>X4f()$FB3^VnrWclz>6A z#V!iI3X7fnCBHx8Tty#;yt~>Q0+gYEGyk*z&nxYfo4=~^-p;jKZKR^7JZEt~U5>gB ztR#O`nmd|Yl!7yZUPF=(`*nS|ab`5<+0+U=4Z%RakUXn#2@LUYvRu(|2vexV=kw={ zbYGVZR7~@BB9^500Qfn(&yWyI3pTsY?|nEdE*y)1Q>iKy2OoPe|0)u?M*!`PPh-2;ZI@+BIN@- zU6_U%#Y_!RA%s-f{JMd}%?4muF=KdQ6q9HtIL+F#Yf)2JOt9i$28U^5^L$#N3quU* zyWT>0F#Nd1XlwHi64GgbgDlr0_5xoI_l5NL$!;hm-y;A?hO&*R)5TNoW@k@NU%S^1 zoT6B+nRqi-R<{)Ec@9R*I04^);x-}`Q5pX*q_nhP|YXkRlH z`<8`esO;z1X79_<{O%(TUpJV{J{`Q`p~@olP2=+q*2(5qzMRHBD8l8h@Tsyu_9&HAX2eo0mfMq0k4r4gpPwyj%z|(Q zs1UhZd+N(TQq8GO@TY+2Kl=mg;MM!In0e0xp8*21!<1_wEjRYZyZ#=yPf~CS06$*Y zTiV`W>>M(7J~H!M_!k-gBr6w*qXVkez2Cz>3(JwW%|D~yDMvXs>LYpG7i9i}LK_ZaYs&)yyD#eX4h{L0_mFxE z%s5-mk+~_p?f||{Pf&+@U%0XbX;JdV=P8Luh+aG4_saDV!OC72zQW_nJB8h-_vwxJ z$WVqw@6@BeHB@3Qct@mzHe@Ja)*c^TUb6&k0YRD&6rB1wd0+NJxM|fI=VB^Ch7Z?E z1~2&AFX{+0mzjLfH}4jl*49=0@G;qc8^1I_K;%7buRxmy$LD^C@%LePgkAC5gnMQ% z9JOL~YUoC{I0tBT9j_NVsYvTB_p~ltbrA~2V)nG6Sf3cHkS2;d!1Y{6zGD7#o1^RG zcc+W^Q~WHy4%A#Ck<#_wUUN~nBki7v=ZZ+CjnwN5A<(mM$gtmN>~hpTPTcMgg^p&U z;Y3d?*TQ!CGTiI2Wcq&eulxY%6B%JxF)NpcnHB5j<%n=Ni@EzMbhxdQgHyX;Q^0tFYRL(Nn9H+FQ5w`Z` zC7JwAML?-)@RlmFB)k1ua5{0!f&3}h3~tX_`aCxax?3~PJ10-6=-UNs3LE9pjn3rs z$JgI876a+fO^(u&eS}0ESZJu{!)u_hKi#{wC^YxS+Zkl*k0HK<2-)|yniv!4jbryDqBdbJ?{|lAz|iV=3(QUP-qh?)n^? zy&}Fg?bZLp>GI51gSk`XS_ed3E>4?A8#~!Uers&!E>4}9kYBCQh!@BFa!5m@2Topo zhI4cCo5L<^$c2sfQ=slbu(jVX?gyID`{GM>OiE7A&j2rW+JtjL7yEY#B+Pg|T*?Em z*7qj6tnC-(rX@t$;AtI?^F)3g@LXa~?Wu^4DvsZO0cOO0*H5b|Ap)y46kl{vr{ zXYyspAB6;ZX@0#gvs;J@T@@9u$eCeo3q{CS^7r|wRBQ55`MsW%NdYz61yh~&JD&Q~ zo(ysfl+}-&>x}~zw0(>h@_n@+UcOCG@3>ev28*^CoU?)Wc3=5&uBwU}-c7d$ie*Gb zxtSB6-)wel4y}YKfhBMU^%2KRX!t>pH|U?hZKF8}=JndKH|=f+@(5Ncz5GoSIyce` zN@2r(yt55??iVWP?C{n&Jdj+~7PsldI{1gii{-+TI? z$u=$V{!y>{Dnd0At2-Zdrw}vz7zWGWt${Dn-jSO$Ffo3#3r|N z!N^USI_Y+(&rx`gUtEiB>G<_8ihg$S!S}VWMe@@g}ki(@f6TIiDwP zgBm{VJVVffAHOr!=)?5Y$HxL1+2Kqv#nUr##&0@9D7@^ZA4lp5P2Nz0(T?2y#^{1FE&DNqhkxu=*8 zwVq@d2e<}$@ zg`v(kC>EUj)0L-m+N*uJv`bi89qJn-zgo(j7s(7a^mCM{9u|4 z{X>6G%@~9{e@X8ZF65v42|^#13g~i8_Jp?SGqR_Bui3ZY216fW4r?@P#nNyQjw-!> z?u*3t>byToJPV&!13LINKC;;)hVPg1vHBjvkrgz(@_0^0u8|ZkxxprVT0k!>w#Jx zszy6U?fvwecRqMa=Mwb7nlEkN5mIk-eu_d;?(-8vN${r}vy<|Bk(WZdfj~GEVD{{I zL;}o{Qb0NU=Ee$-Ee4va0OwrUoKXDwRvD+K0HIunfI|X_+3VKQ3B1IC4boDwmUIDk zypFPEyrlFP2L5uH?*3T`+*9`UFc}`F1VoPf9+)=t!>@obPvEcrQNONNqmfMd%e%+@ z=Fc|xct>&sLm$`oPCfu9l*`**;nSYW+QU8%6L^)`V)5VWN5JDltaGQ~2od;R$+9$y z_XszgS&yji4?l`Sh{Je)blo51?LW1=LH<;1tT?0jsV%M**SgS|t|Kh9Nzmn!XveTp zgR5h4>j`Oi1ExCGq)!9lJ?$HX(hEE|b%pUE&)$+qRfQ5^c26H)IakiZKJ7bqgUs|2 z6t6Eg1^b%X8R9+|!|piC!jnE!Rm!gRK{=nHFU!nn`vm8pks{%bkQK@IoJ&!V=L*;T zraaHL*x0{C%EFJtnyO2E66EXe6!SlPkS)3k0zkS(K1rgT)z_)sOO)p4gnjc%$t6)o zvrArDLtkpz<=+Y!p6^l$&rlz=^v{05*v#tW5>kScnO{4}wa}%1_`@ES*bG#P3Qbo6 z=j~8VNI#Iba>vT==&yk>H~Bt?#BMugVgtpctz*! z*ca-&ry$wy&YnaYbY~N0aq=S4_c4K|-kugx4}~W$*N$S%@_RL2UdP}SQ87sua-mfG z%wV9wfzr*c@3t=E!#t!mp}NH!+U6{t-$TK+ziJPv@WxV*^uENHtL|1Jeno06M&U~c zQ5lomxx0D2oF0zPqiBC_%$M1g{RD?y9vrqr`0v%9#Pg%WstuBuz@7;G(Kc2`#y}li zf!DA3qjr>k3e*MG7U!SzT)!JvNZC30-2x?fom=Wia)bma??e*vB!~EGb}Gmq>V6yX zxO@#kGH__gUcBKfTQNRcyH-r&*L75_3`r=LoT& zp1K~f#?f#n5AyBpx3>>cxChqDuf<{pgTym_@rIJ*A7?0jG-A6)I4a_b8pXGP`-D^H z4S=7n++Ip`d$npX4W#wnS0SknVvT_Wd76EkUcRIE?2^-;x`-OD*~2=&$(RCrC1P+B zrBFu=^3T{*6e^MI@lYH+?^+8*FYbYknHIb17EmxQ%5P8<$i8w1pP$o-p?-PPlvnx7 zLF6+OB9ro|R`*o66!kFI{+$^Nj3Sw=HNSJ)T5ha92oWP9ck_Hd|Hq^aB^0esQtQTk4t;Nx%oTeTI0 zk9gSAqW6BqFcqZ!gfasO4~`liO)W|>wk*4a3!3=j=TBqvflXKZ`C)n!g(tjV7rhBX zQRP?hz2SlG;?neCJBJkQu*v2MZ(AE-7qzj}8+LF;rOSG!WECz<6?e(wn9C8}_n$0$ zCO(#DrHh?C=DR{)N(d46!L_@7tnEWWxbj;x@y6Pf&FqUQ;4xZ)CeHdelq5q3mp}gu z?x9e*SM59B4&Q}W{n>q~opN}W_7{V9Kh=(o&>Hn?n(-@FZcx8B6tu~;zHQT_^iGiC z7)b$E=MhtqDM4n@9*~(mA)=TFAmGfPNE#E0fqF~(=NUQ|?}t9;KV$6e6Ue9xgMKzD z&@5gkY4BOUJwT>QbK=Gtc9y~xTebwsDtvDyswRtH0ixeHgE;fWMn>v6-u0vgwWas- zO}4k^Cp^WZxL?}Z8K8kD-n7G5?O-G6ZQd`yJ^$8hZVy-_)P$2@)m3SWXSWCbRYl%# z#O%ch_k`soUz{gkPvv{Wi?P0@>B+y}sr5AuI4Ic=`@)PQh=b|%DIwP9K08fF@3!4b zJsI2`I~>A_Ur3gG)?L+{rs?a^)4nHTEt$z>T?K5Is3X-{+P0u~*s3lGgSC5g`u; z_OTyCB(~S58`sCaN-r2NJ-1<|f$&lZqE?8qVnc*oG)rQT3ku z%5X!*x}a;b&rzrK%ab2Lko=K&oFedBZF7Gcx#HUtuA%S*eDQ02o?qwHv^-g{De-8X zf!gfE1Ccuv+Ka&)UC@)PFLOLOt73olRJC~aO%A%}(6Qb4hP}5J2uiGrUY4Aw>&niNg`aHblV{;QOf;pk* zL-00}!FYoD79+3oCG^18h?$_9!Z#^B84rBODPn$o2f_jmYm`q`cdjnyLZ!MKnA9)n znkfQs zxm4Q#KFNoSmy-HyQcKF}^+^Uv})bmWC{-tIkwDo;ZeoA~}A>QN114=*ZGOuolS-m|#8 zxswHFzTvtnk8mu`j|Y~x7I0p?fmT2WAJhAz0l#%6tPpRgoM>??zVD$+fbY9^qQsUK zvu_#1Y{TziU)u`k^<&9Y`5SFt{eVtqC;2|2DSAF6imo+a^5bPj6}`Ptd(@B|ux&|i zE}{i)kI#~Pi52$Dp=YZ$aQgeAf&E5}UUsJY$tvb~Qc7!3IM7Cry{SvRFFw+0S<~`W zCf37elUn}ioDuy5AJ91QJ8YcE`)}lr;jz(P*lgu*-lQ#xno&yr&N8XV$IS9@I?{1% zfDNc5(ZVlQ^t*RFJzV*zSw(|Q_k7nQhV;V67S?#~H#@TjWPDhw+-3eCYkc1V`}KT2 zt6zM5Gm>mF1NK;ntm5`|Xw8>bS=;8|oM9+|$MLlU)1Y2LX?=(RFz%;A+1-n9AA*;B z*c$Sohiao1zw~o^%LiYXzI5jifI8;+g(8cF*rSA>TJJI8i}dSD4a2-kxcbZf2Z7+; z_^wv)V8OTVdDyR-_IvI-fCK=(%qFK;;`o!HY(g-lHc}GxHdq1-At3do?Wc;bdFT2{ z=(zov?=|YXj5i%hQcmJWy9P7*()wLlB;eLhy@?u#%H@}8Mb0g8`99w6r@h-`M+Z4A z2%ozA@@JO~xx3Ny_sx0wTb;wlUJ5@b{;B96=M@gLuxp3ji2$a8 zt$q}0JLhwHr7c*r1q1^}Ow0=D0(r+Fq`d0HXg-)d_kDHV1^&1Y_NPBJ@&!9Tw(58u z$Ah@h-qPUE`)5v=>J}dxSEl?z;LrQ2cJ4%f*WOZjS}d$@drqLOG*GYCi*;Y0qr#l4 z&lT2EYoB*Nu+mL{)hL~)y)-onc!bP0bda-;uA+bl<6%!=DP^Xxm`SAL&sXVw`d%{C zE8#>#z~1|J?13Zm-ff}*r$F*hZi+h5YA#GX!}re}9*zJ<1wkZ_=SzsVWUXIJrVlf! zGa`v9x20|3-P{9A(fs*^v)-?iA+|t?{8@@qX8)i=Sv}{??W?t3_aQh)68Hu_z|c<1Hvuz{aPU2RpOg-q+VOK`Kx)&H(29{ zM**dYw2qpZVLGf{P)rrD5~|~TFKxZ&LR7f2$M(7IYrfi6Tp2pSG+!i@Ml-LC;P$%n z1%Vj3diT_ONo~RZxPv7J%Zp+LAr+VJ`)-&E;NVWTYlf-wc`*-e*l5{Fmj?cp3Hz#v zZ4{OBss^VbeD7gGDTn*%7_2$)>!@Cleb4Ui@rJdzaO;#CA-RPRTl?~*Vq^ix-@mHI z7li_1`df#S22DypR1c3stSlsiimneu>BAshKbKw?>~?vj(Ns)bNEl~_9cK}(e)~){ zQBt%|+)Axq30X8VN@^I>GVBqiNf^W zW8Ct=Y#~b7=_#zS!+i-$Z)a6I`28yKv-)gpZfTZesN%!*Ff!h;&Z(`N#u^GYt!6vD z{a~Pye)gpV-2iFqzFom3mf2A~PGIJ{eM{P9yH!-~arEm!JOr#P9|q_BL|U{B43?vP zdUdk+nFO7B^ur46G4gpyUjhfdT?R$r5M|3Ia?5X;!aU`4>L_j?Dem1y(f3X=hvs{| zNx6A;xVNkJ+GzyN>?`}@K8$7i8Bnx^rC$A$j=R6BTMA~-A=##Tkqx)m4OvI5yb3~* z3>c5|;6T{BWS5V1a4PTV{lU86BdysW>b7i+WvHl#{Agcy=MAA{(wb-!^KCtN?&2F9}}B#dq!UU}GtA5|gyA zFxG8bcKismejI>82qtf~f4wdpA!})>W=DKlhaX=d0mZH>i3H-kQ-Gz{4@_MbmInt< zHcO`Hocmv<|1;p;clnUP;dl;~gS7_V!Kv&fCb=Xgb$3ZaKm}!%HT7S3Lz`9ds}Zm& z{|vhz>#jm@hm7s&f)-?Jfw^6ANqCH5+7`$)fShqO`1q7T_IbE= zanoQPmP7RJ>u4DnUGg_MT>g53mwY~}{N)kUFVhDSzG{0iV`=?!6tWgJpf`xU)Adb5 zI=km?wN4*~-ng`fY~IrlI1HTjh}$OW)6Kpebd7#*u5TtP^7d#Y7QR`n=BF`#uWP|^ zgTu-{c@}In6Dp9e9muI)n{=xoO{f+V`hCr$zI2t2epGBJVhZ5LTYQ86#+9jUP9A+>JsELs z@N6l-R+m`0BmoT&E`fOOD`P{{{;wk_zgG%cIz-JDm*KF7V(7d}S68C6JteeA#0q`8 zrM3JR${SI#OX`8yO8)_}eeS#y9xLXkm+OHxzLd*<`rG5NFL+>DE}!U11e0loAeWO6 zRFRaJhk(c(u8+!InoKlr``SCN`Tbb!$8!ZL&rv7>wl4c-0=w*P26tE^pcjO{i~2)) zf}PFA_w{9}d*o}kyFNM=Cwu2=vTe3Ie*dflf~_;Cs+LA86WHHaMChd-dj*o8d=P8JafqVr5rCVr|qnCYFVWvDV37irR(^q83 zU{~>#+8`|8gR~E=;@}C1N*Enj!DzikW}^dVL7I^n&DSz2MH8eGZ#I91DIdbZSoy2! zojt}?ngX_qqA;wyC(?qUlhWKtG|JxBN&et=zAl&ZpbLF)gZpRJdPd-df)r`FhHkyN z-)<}lEah|zx?zm>66uet^}K4okFA|f7%>B==i*Ma4e*Cb8lU9wdlH_|!zgTMrHJ;{ zVE7e15qkB=uL{_7coux&j7sc_y3%Dycg70vRtk#jnR4q92Z)>@ixd2v~=puKU+fyzq;0q zl&fGgC6ip&(ixrTm9m@hd?n{_;G0d^1fOeDBERUi!x6mKKj3FKm3wjz1{vdvjBJ7vs8=e6bM}~w8@fJwzW)StmRV^wr+sRz{^M8JH z<(9XkF^mS<7LU%mavMr|_;a-0d*O*?EKrTv4iqDW@PP|&H%*yGm=k2j!Gx-Jf7A0A zh5|gQ2B~#bBYGJ1d4d6X=tB!A3*TCvym;yXKt)nn;5BjKly$Aue+h^nwpUk#kzoAJ z57iGM%zE>Ai^H_Od-ys=dK4VM3Fj68B&r5efdOwRAj>)5x>M0}-i3Ibh5+&{gjgot z0_NquIIm##Jh{)lQY1eyF$j**AHV0%_Ytf|aF=5G_BpF=N4}s9#K==_ zQ_yG*;3uh1l5ZFNpWfjI4VCr`g{}BA#GIcoP(A?DPGrer|5VW=_`d*q>iP4=me(6Z zUKA(h9_8O^=8yW=$7?ZX@4tpd5w4n7cWm&Rg%KK`1t5daoMKy6uD4zdRvV`=QVixd>=LayI)*Zp- zqn!`21#47_D#RPq5_NAofTsUu)K2(0Zb24jJo`YJA%nuc?24bg=q=T&%EVl60koWR ziOl=>8pUICJtf(VPHu$DG`=LCi{l)=hxS???l%Z)T|SKs%};0sU57q?ulbc80o&2J zYn$*7upPBK-|7&sZL=3~^Q!wWLxXSF7qI+$9v^UUaGwo$P+)P;L@1W^J;A`kP$H_D z9m=8fJ<$60^YqKY=CNj1`xXwOPEqpvQyIf!M1%M5a$skA!-##q7{rf^fOA*h2vT7M z^Hkghs%1BiE?|+jeF0KS#?x#IiD0Nyi_bAt;a6HzoMWs#$|a{f8MxQUsgk0JUCs5ie#9?oUyo;FT#rG~vXiFE=H319#oOLP zrR@`IK%<_5l!Y~X*fpoV`?0uhbg~W8=4T5y$M-~={>_Hd z_{@^OL|a5b0Pi(6a6LlMKwjYY8^&`KeY6nP+nRQWr*LDZ&xct%0WzjL5K>Zw-z=x| zB?)CFN;*$x=19c}luoJ@$G3F>C#I$hZG_9BWzxipggC@tB?8M14pB>B8Ql~C;Un_S1W!WDoZdZ z}?F2Lt-`9vouZT#K_;;%JLz=sc1({H+cxn7m zCl(-npGEg#n_yZPmV-Y5bCoWqJNZIqM7|1w#f)X{e*I|AJ6?}|4sXscB`j@8Ho?~5 zZr}BpgvkSQaFNf5?JM5(Bw;?@#%7s(9rxxwxS5bUdVxQJzc*HEEC1z(Y=0N+MuD_8b4{p|38GQGxDKB7?Cc;Z*vS*)UM7#QIcto$i4_vb zswk%CRMk&s zdWVGF1AN$X4GO%&nSBzS`66es>Sw{ql~)3GCZVK(jl*div{-$5#^)6=ClA)i+}@M- zPG=IG@%Qr&);QayEU-jO&yc%L1pEa=TWZ;{-`XrX_W zpYGj>;q0#wiLfh7yr7KFTYs*ov+46wmbDI(6-5{N)x@wc*vU@xEXln$A0$IlwJ$@ z)e4}&;WkQM>#(!C{S<6)nOs#2oIRPh z+e_yC(uKmb+1m`1ffJB_Q<+o2Rc*M-n@FGiLnMTyPtWiEMu#}B{_LVEx_3X&0WHc< z(j_I&Exp@u=8}@Ad%p${=iCYdgbdLlSsi*)AZ>cEn(oUvwtCr!hKmV33^S2#`+ zogpiH20P~y=cSQ~BS&Iknm4P4ZmNF#GQw!`f;Iz}Qp+0R;d9FT)Ti{*KIxH!`|Wzj zwrsN>MIuqIss-MlyMYYd{0PdI(#(c*AjB}k(Vj_~Bqi)d&`0Y>$z!$g>DtD;VV5Q&f}l2@Rz?`AEH9e1-xkP*LIMlr;|b_@dauTLx7Ykl3khZ zOYLmlSixo$3|Yn;^I~e%UkYZm(p7$D(FCPgMvJZD-j(^D$C?THXwoyjl=mxBJ+GqI zy}ksaZ60j>qJqA)>I&1m8$TUbDB46vnmHWB-;ouIXLu4PAnIh${fnO>5lBsdCfY8x zFsz61^~9{nzt9hdh?PQmf}8#Y`=4qOOpYErls}^=%&0@TC$hh51sl`?ynjIS;Tmyh zNWJEd={50yj!zS<=@~EQy0(FAx zRhkHRo3pFaXP+Ttlvnmm65vUXJWscu(PleR+!|b9S4b>6p?`0VMV1^f zs@Po=NsVvxUAaEDrtmirePvM@Y-6kRt?tqWoF zE&&0i34!ZryJycl{mVqavk0vs9nU0kDsNN2Uy7-j)--TwEOb0S+(lU;d>&#-Q>p7E zcYf|+>{pcllq;IAN)*bAKM9%nZXh5o#3s}Ee=Fkl)!S=rjVEUWa}t(4?j7cz)J^Lx zCC-fV?rOUqjf--LEB5R-%J`}F_3e`FHF70^pJk;O#uGORJFL-u9x*V!tWzq#-*3+b zA$74u{tp&iHY)6q6k;EFj(7_E0FVX$n8D`)yUDbwD1X3);P;3^og8^yMZewmjQa^a zcnkVn=jg|&=UJr#1s+Wm;FQb-5&KbF6t=J)pSs{@@iWEhC;kiYt|$?Vq_`-tVzj7LM!f zA9{IRAA)h&4p2Q!`ft<6;1j?MnT zy;_acuY1sWmMWC`>f^%4vYxoeUP-8!ohOiUc}EwVofg5xW{!uxOc9wlFQeKyy2 ziC)OU@Dvw?VbYOKGE<}ZtF}k5_IPAD-(IB}#Z&y{F_sZ@L z3>bcZO!7M`r$#2Vw-Y=QHdIxTap56GRgKerRq(|1pBm2B(`U+(fK(-cXukV))A%1D z6}UY-K`_@@;4I}oGnC!m; zRX=LVYt{3mm}6csQ`}0~C`dpbw=hUap|SL&A;+sR7@$X~$&^o@IG)q}=`x_0@G>10 zHAR~x?&%lLac$3FnR`ECkF8HK%&xLZol~W1W8#bQLHbFnh5kBn6(9#_yV_f&m%FAY zd`qc6>1P_Mng^wAWK1S4)e%j9ya@d@n;DtB@#laB$NSE`Q8jyn=S=majz)lIF*=Kl zv;nH_d6rdN+b9hx0{mg$k?37l5U0X0oPET>`S@<7J4Zo`?=;5WCKVG7jKYa17PBM{*hn6={z$8|Jnd)qCH(bO zZ@5>!jQn$t0w2}WwaOG*cRaux(|Q09fMV}nnduGjaC-=#t}8sC3P;TjPN$^2?c;Zm zddRfyQSHMPSQFX(zDgSPFkIP0FMr8ZRm%PVsf_c76biw@tN*1o9dvrGKS*sdPgn00 z)egGrS9lpG#6#nzyp6}Vv}flUW^+;9+1rO<(fWXk!gtvR_S3{z-TR%}^KIpxC+U)a zto=N1fSFBsj^yU+uaIGEU3?`h>lRG~ga=7V3FJ;9sxobcRvkH6!;4 z#cseR{usaRgF1a%{*%)&Mt_B`{R)5C?^0%y90=CEpzm;HK@~(p>sPUyjXP0;|6ano-UO33%1Y?Kkq&loE z!y%N%UXfqpxzktork9gDJkC?kYZ`US57tX~9bS8Q*#Fm^`pd$x4lc@m_}3Vx(h#bC z+%kTkdV+T?r{#hW0LF6zB;4wKIRBWs^f#=9-0L|MD~ILI%%8n>#aH_^QoUQ89L^E~ z*Il)j1Qepb{Vshc11Wi6iq_sk25*8}j|aTpYDDArzY&+(HY<`^gm`h>c(c>iXN}8N zgk<8Q(3F764%gCQJNSQXt@%Cu;~|Ku?1qN_?gwMA`nNZaHXztC&S)u4jJQg zxjiTT%}JJZro5hBvep@mh^Cx_A_9-uGWpLFqKbLs^`AMUxGs22WRcP&-GCa{x6VD~ zmF{RlNC}YVG(a2Kba*N-T7%;4V<17WA3$E1A{U!qUj{Lsm;Q7jGqT@9lJ_xj z#PJZErod(cPSY>lf%kZ~yec{C>!BN!67=2BIre$_eFvxg0{gc5n?*9l&v>K(pPmOy zgxc%txRd`Rh;<~&Cx|{bGi^`izO(EHOApcMIMzY#oayZL(-C*Y5RwS7KI`SJKEFu6 zd!4a^h{K>T*EwN|XC^rQczRKeEXC>L)EDRdD*lqHjHnQK3`8g;5lRHbZr~3UH!dz#p zUU6R#oKN0Zc=gyh`>9u1+GgomB-w{K)`EC}dW{dl z{NcKfW8v{&bs#aBGI7|qv*PVXYW7j=+pr$>Ou##%!_&TLKvDzWpQ`l<_G24CXX$l5 z{5FW|ztrU7?wJi-5gCjxkNJ`A@vA;5#CZ=t+TEu3)!n;6rYdu8Fj1j=r`m@6<)yp_ zMf_z?G~W9*XnZg=iE^nO97rz>RQ))S5k}9)TQjDYp-$ArCN_Y9yL6&ICG_c$#XuuY zf>7t-GbDTW*9qn-SjCs~QHVyO52i6Ct;M>$ToVc;j?X*WTZ9apUromdTD3wHB-@yp~QDH6QF!T@_auTJdGU3!vJc0(??QUmSAar$PzdF&8Gf z_V__B3S4q-fm`q6GA3`ZUpN|#d-0iWd-NpW_IuuS*y!p;K*qcu-gRqVtA`d%dT+UE z7f%FmO3tNOP(5^N_*yk`;>7!HouBUQ!;;}5o-*5%h@+d0#u&P|z)=r0$;d@%dh@2M z-tB9ymCju5$rk^TOAsa3#|p)xx@9Hx0S%P>4&CTn0}DAOqZ%q4x;48-P3Uo4vnRT- zdnVCo{G!0PV6gFM*)s=3K|jCuLP&ax41SROjaDFe3T=QTg=TF6;A+1wV(%@4N4Sz5 zZ+FBYmU=@`r5m$xlb6Z?!<2BepI(?O$H2_C>&fm(pUdyQ=6&6e8{Q&_JO3-Zzxrnq z_pG##+)DXb0{b8e6vEQ)LDuwHela_8TXb%dzdB5b9iuIVt%NF;RWyX>ai=?C7Qp3F zS^iEINs23#Je$W9!pzUO1jCCV9@popTqbISQ2W_(z9*`G^-3-Tlty#yha?*<;Gc1F z@jGBMDFK<@w3`KrD$&=W9^Up|45Y!K)b=i5IS&gWx%@FCd4Ie8ZS2C|z7l2aFenFD zK?>(s`}&jp?u^svl3!|L=!jHdJ&k|!_2rIj847T1Dun1 z`i%`zvbY#RHxL_e5BD?XWe_6&%g&zsbxgIN1*X6`Qfkgdu!50zT-PrTPfhF3HEF^O z^ztvI-GvWF+-JyBy@iw33_KT~sfWHpL`5FXCnDU&iq5AAUfs;X*h|6m4T-J$E$Cm< zF(u<4tjbD^JlPYymp35l7Rtw#MV3K+qA!*gut};ana}Da@~{3@nj64N54(a`7+tV$0s@Gt8>th{fJVR zd+<&LOYWkpsJKP=um-YWoS`1leZVFvGCFiq1zKWz#Bo(iLQB2Uh&RK3Z1y?#L_eS>w7kg$h*nb*ff zRO?$$jCj~|hmtGAXMp3q=xlrRGWDr(56FmNAE%CqU1XP!@Zh=rKuqV4`TFe{46P9m zs7FPpIyLcGJ-%g=%ho*Kzx_m|dm_8nDPs-g5qMUEB#GZHS0>C;NAlv3fn#5GrG6S+ zpCuD5d?PIB-7bN8-+1qL@t3UZC5N6Q?Lvo%st31lac- zN@FUjMqGkIzdl850NHvE$X~>cmwC^Z+F}V;sKq?;zj^Gwd!3Yz`Q>Oh>Z4I$6JOeKv+1In95*O{ddmoOzUQ23nn*)isd%v; zr#Ms86X@$_BZkllUem9V%NYv{>dcNvbup=)aKdxvKowesW{}uGX2jahTx+6K%BR8Y1*vyM5fKnEH!73vThDHuidNjlEQVSIDDK`6hhvOssBf+~E0qMuP z0-^5N9>3pw45%Qbz2RASE>zV{9eedVX)d6H7CA2~DsI=F@xBvSz`3JYfUQczzQ)ZW zJ^CHHLtCYzPzigQ7&-Tn+;u;t{Z`yyl=#;A9}ZE5*7AE7^Q?NMUzNBME~mBR zZ+}8wAPx`jaO}c1?PKgaA{$a9EE#Xv;W_h$N_gCaTaVh6d)z|38e?o$;`swP7plD& zX9C`%bC;bCfv31>F}cqQaQfi^xuahozzZt8Az=&GyGEbT`XHaP<+R>;b%L~eJdmg) z5Vhp+lvY8uRbdUnW#EJtd7WC8|2qQGd%v#S0yeV0_Ug?p)O+F73G32ZN%_??`1$WW zY-5Dto@T6sOx`c44i%7*GJu!YTJDga9AJ$f98Xm3uAd(7?Q56^$}MRN^gQY;Ro}um zzNX0;6zwMP5oJQK3Ur3}2!Za?;i&%zbCdhiXL|vOsYTI-_axgQu+-E{4!w=3}uZyr>I`L&mLZ3UCN{_s^>hIhZW(k9HEA~S6 zs+K`*saI#^Npp4)*_4!y$g7s~)1D3`UOf*8WQU)IiMBIsb;Q#2PZ3+yYRebw7DocI zB-Xx(j;yLfat>F-pYEyTxUgsoo$Bsa^yL{fr{_j!Bi;6oAP7hfRs!X|E}Tqvzti@$ z!aZpr*c_Sb{u~$ML6Z@Bt20S4_x^J*6f8Umqs}?Bof~HWE@uGZc07e^`c(Zlu?MhR zfk1F|Jj9Onja)^NX8;s+$M|s^j1|&UJn31s>ukD5@uqy3>l>bK6huY${rm-|J9ypi zXi`amAZ6mdmErItOi3;Z{eGkDH|x{nd_H|O^`c?ZLODzW%|TeQt%V2_kF~EB<8a7d>!BxdD~ZaHgg*y z2(rd~YkgPKb027lP#OHzplWY1Tjcbu#P!L4qG31<>gLkrQ}c`o24Sa1L&x4@)kouu zN4dp_Txfb9LjDFJn2W7Wgu_0$X(pYrBGgTt06%)P0_6(d5-jwzdfv`@y)4*Qu3YD= zd4DTafkc4A(+L~GoU)B*A!@*R-}pjJwXBCJO$iha)`O_&%ZamLU*ryBl9ASPg-rCR zY7OE_aSj4TRf);94hv_NgQS^%9eo^f=>-?QskYC|xN45N#LySo>&2@zMTj6$8i|+5 zNtNF2!KJkvstT&yg8nR|ND&nIJXtHc5zO_zJcez>mK zO{wL5_ly}f<`lDW1$h!^^O=az>2~N>@h*BYu>o%P5-YY?Pb>HGwi)!K=})aNEx}Zc z)cq`5$-zNl9@E&l*fKpo;i+yzPc4_P$uDFDfxhgS+?gPLAa}o$vM<|XXU!%e0Fb^- z=miGXe)k@iWKk4^`=|2)b$AXS5u64wvoz?w;vda{xTxrGKw(Xm057W}VXblKik}|J z*_n8Uxv)SERY4O*+QBf_F6&*@p5?>#dR}%|~Qd#(*^q~LmGQ9wq@L%)29$_5T`^g@VV6O&YCNA@0SvYM$n`yH}(%NM@053+m z9tB4Wm(ZL{MfKbA=zk}b^QOC|4@9lMX z_?wW05?oCqf0s&;{>E-~oj(y4q1KExrZ*ftz`Q~9hp1$vQ)U56Dv(Yxh-c*qAz+Q{ z0T*93XlJYtJlI%hkF=xk?vW(nro4C;&4!mvW3R5e0bCXZ$X)>7Y{<6xWac4v1vhwT z9=JLoPh3i;LvzWygTnx*PYy?o$P)cVu%lA7*Kf~9YOp=-`}Q57Jk(DZ`6Y-qXeGKhO}Vjt=CY-G2`~yc zS_Vk7P1nw$!?Sg3fYG6{!Iz`66Ulu4d0rwZclp2`XS_Z%`s4n`p!?@s(%YcnG8su;D4J(pWFmX|z#3%C`d7$M z*S@|j8i5EkAQ(wt6*kff!fwBh4nXlLBKBS<&pbkXq2l5ez@9o2AizUdr_+l}Xtq(x zMsxg>5QZyv>@@v_%4~y_ZbmBXg8i#vRQJK?l3yaTd5ud z(0|BnFn?wYADm?$8{N7@SvF{&_hhro?L@|Mmv%uob6kTk-D{ zLZY=@2vHI;avVQpN0nIgcP>ZoOP6CYc$$`_+%%l-_OuvjqRy3P(DBAEeErs)?i>BK z?#LZ4N^*tR7~ZaU>Bf<`qZh7ofy;!q#TI%^pcw;}n*C-wGel&zd#EL_3dl;tCWG{U zckqJPMt;F2{w-{#OOYd>pC3{Ia`KwAS+|P-iFURpUxUeec^jYMA}RGWWHryq@U_HK zycgmrceuU;084{dBpnPenvruBt!#Nv;@3X5Q>8 zOKX__Zgc-6)L2J5>$m3THdN{{`_gJ6N!hnG$$B4Y7LX=7YKvNTl>r2RP3(a98cxPM;A!+E!W70+q08s7&Lo>eIj znB)yzbtKclJ7Kf$YG1APVDFKX^+&Ufqh|mM2LCv7%=~CipJ6$eUh~q*1e{jkfdo*R z=6$OTvrN^hm!%xJ`l;TCUw{B{90S8`mzua@jYtwBH1RKqjraZlVvy7)aL<1Uf%AH= z@*|d*TOjuq5C}~3BoE9({4G~GcNGT^F~vPp=E(v{ZJj?HeYV0O5XAE-SgvmSzRM5N z)98&2e?6VfCx8#Hz}gnZ&3_#uLDz}XC6NV=`qK9G?I4bo;8J-qH344CX1u)V<_cwtNGqD~i8x}-o1B@rafA2vMX!frL zXB`h_1UwXvG&pDo{y^NfW}N=?0zTVkP;S7wZ-tBp5XZ=-=EI+ddbsn-3!YzAyi&XG zMxaHV;i)JS;bR56<*HWmtNTEN;rQh)*DkJg~GoROAelv*Sp z9uf3Q@rV6y{Q&@0=QPqIEU1t9GT9%0d?p@gtV()G5A>gFc`E(5M?&7dq{mkbF&R%# zFCM@2>hsj;{G9bds#)R=8(P1DA<{3%hj5v_HV|`vKUOFYG-|8_%#26;?;R)KvB9C(PB-y_dXj=3 z+2b{uci$RsPq_w0?|u>-P%Y&2_XPz}zmB(Z-(^UVv$L+tOgQmT!4XCVopw)V`-Ph%26MRP90G?JZ_|JuF0FHuP{?q;>@{c|oO}IV zBa%ejc{qZgBe4*~s%L>Z)21+BEYFs|%OOhX^avfvxV%MlL+&{=;=(h!jSAgBrYx^J z^wr)kGQah2on_z@5WsY3aOq}zTg?xJTAr50)0Ov%Xa4}9Zy!);RtC8jAE(%PknsYQ z*b6f2ED8$L2qGV$bFeOL6Co+}qoE_f znO!8}Aau**{WwVB<2Eh%?V>v3xEDsW{5eNV``$Bdf<8SV;t|PH@5wR=6Q{sl4)5Nk z@BW`CkAR5tqB0#OJ$2i!*_~qa*V{_+b2%RN9EU6(^FRTe%h;b+>3~ieVFZiU(&PqY zpsbvS?C#wCWEH&w%u`4K0%O#Q0sSejE^B$Z!w!Bd7mcp^qs1( zPPrc$iBgiD(rm)*_~n4ZD>ghFNNnI7=j&}_-D*oHDuwzDD9LIe>?){Yl0KcS9}Pu) z?r)!pmzz<`Vsvrt_;s%Df)!Ga@+Bp3w$AoG$pilv!so^!2&t2Yv!nZz{0RLwc}AQJg?J_q>?_NJy5y;GjQ+1!fGeZp<<)F9;LCT zY-I)`vxzX^X3p%k*xiLXqkL?ZX$s-4^E*pY#YA_QML&s~mj1Yu#B0CO?Fe%mKq3y( zFk`sn|7j~;(tZ1kFXsXD$F4UW@eo-tOB{L%)~z&zbKt6>y@Ia?P19GB33|i3G+8BZ zktkXUniv#jfPE<$+zWVO=vJ4>YlW zZtFdsyQ~W7-VEz<;eK4tXyS0a%e+-BGU-xGP!aC8Yri5njfu({Fahk2kzA{sbIlF& z$=)Fd>j*VfE5fh)Li*)7j)F-7?h4Ve50J@5*kTMHLE6RzHb|sJt}Mr#nsJl>W9`m*&A8H7!2JYph|k{7URhDQ{v@-IYPkFjLNc;dyKi4aFR3D90s+>GFm~ zz`2;>;r7YmwX0iy*?ElQqp559`eKei-Uh-PP;zwAqHGKGaUC|%s#Af`wqe~a{fluh zF<^$S##mbOTrf-M8Skkp6)p*%>u^ji$xZfRNsrAZIk3;?V++EW^hhwJaw(2(v3Fse zN4DWn=Cv^?n!53!bK0ZK{Ul0+u{`)AbY+{ly}h`6{sdgvFcbby^ zxsU!dGg6*bm~P0#UWttTM^|RB3V?->U@C(93mSzma^DqqC4MYpwFq@y(BESZ3=YUj z=f5XaX;Sl{3-Z&@F(;)BX2JU|$*$9BNC@ztP<6p3{M!lAv-+Mv0pz{*03pkR{KC9v zgMOy}NT`_BwID^jD8P9inIqmsbt9rzwWJs9fEkbOu#eU5TUbi#q4UZ3XK} z_Uc3CJ|ERN_{3^n?1x1|-OxOzu)tZ(F=MU~Cqk)Z9vTRDHLJszW^n=cSr-WsO5pWDr{JkaFpwFFS z>UVuZkD8kYVu+>=+p?mJNe35w)tE22Pb89D_0Z=-IC=E5XgfQ774@><6$&k17y6@K(N&whf*S?I736fDU8dt{pr6psE%DH^| zKJ1~*j&^_jnSu!AW4rm}l;-L|ogqb-J!N!4V3mGX0kS?{R_26(5MJIJp?%@9iWHa3iDo4Kaj%E4BYmQO22I5MeW)+ z;wQKY8H@H(KpvlpV_0$490RpM3MyG6aggVCpojNJdUh<75%;z1s|)c{8Dx~AF(4xm zKeWlZ0WUu{|NFL-BG$;xu@2us&wvFU1$96s3L)zdNJ1nvXsf z$?IL+7~S8?vp8Iq?-t#3V*8Qx=c%zU1OdrQY1D7i@A2rQ>Ia$GhqHUWSPA`}pYG>; z02}34O=;gh@Jtd-#MP#8z0mb&89|8JP3R@zOksf%;onj6IEnZtTtiDS*RIu18bq`cpL{rtfN*{)|gM!3fx zM&Rah?AcR#eE3giydM*3ZXg3pvwLa5ydWOayvATDQTOj>=y3CI9s~@J{%6m)`jHRp z&$HhvnCOL^5R=;d8}f8ip~kg@P@?9s%hmI)OzrZi9iV4u|Od zr0>`!JUnY9zOd3^6_(@ht3M*ie@-<%=}DhHFjV zyv~Kr1@VWHDXg$^Sx6-U6AqbuY()8?4KkN$k52M~;}63vlK2?eLk86U;xS=4Zt3cM zm#AS6YW~bz>^$6V;e6VwGw-!dvwgel@i-qY0^6B&p72=E($VXI!7?7F#&RLr?z9B1 ziqx{f#q;ZfLOi)u1hHyzYU4xyJziGF-eM*~U|JYwueI!qXplwSk2@Ol$EF50is?)q zpdaX3-0F6jaOFlu(#LmE+vB-6A@xvg#1v_$`?kRk4$V3RkmFl!qi`G8O1hZOqYa^{ znb|7_@17MMB-L$~_HT6sOYIZ?>3mM6BPDZ# zW+goUxTN$_BJ*q(N4jOzyYV5EiG<~e)fVU5)s}jBEOPUDfYLy*C~*@cJrYmo#bx*7 z_P0%>M$26v_p8#~hQ2JWIUtWxsXsf2G5220CRt07TElRbV(;+~I4VJ`zKuTQHN8Q$ zL;meu= z!qa}g56Rby98~$;B4giEgr87x>F0S<$N3e}=Z26~-Ii&#Pz`+* z*H~Ujj)3#(W0W9qI5n%`e^bEo%VK-uV=W-#m~n{OIv;Y zz~uY_B&QpKITs^W6j`y`P75<==z3nf0>z7FLa2`<3XCY zf*r1h3A&)}dCxn-!{;m0lcbu^^j-B`rUo|W(z_fapcEksy>;#S@|}~cpJXT^ z8^eA{7SAiaZoRF=HfohubafblenSM7XB+bhT_34Eu-h?K>(eoK_DAp&g`3gNKPaVC zCcVqoNT%$3_UQW5632np5&?e*X7Qkn!$P&Hd0>2f-S^DWl7`DI)?p%v{ZSk+!%fxY z$dx58NJrR5j%6T)=d>9vi)I3$X1CIM#<*hqFxzJxw4=Iji}^gW8z|Ky#9R^Cv{#ag zFGL>6IEgE)fO=Y+F6m7AdVa0IyDV0U>~%1XKI3I*lPZ|{Pp1Se${T-<&s%(KG~@(G zx5aq{Bc+A7#5_Lpu@AkYuALjY3)YMK?8oYRm>yv6klf&Kc){r=ohh<12)J#WQujp; zSxCRzuNO&iNB}K=>J@#i`yssnVsxho_wA^!!xOFd@Q0UMW?WB4XHTP&2F{TCP3<@N zAWDfjhQ0jOLGJOIheEA@d`{}wB5PTwy3hvebCc|hl(L9(!zrL$(T=lu_}H>bCjF9+ zc(Uyg5bAA%9|h|h?%MXR*Lp$#hMv?g3yr%cF5h^C8F4~?spu4zwXkwBdw5Kie4Y7y zE#oV&!X^HXrSn=^6pNzpD@le+5fBvtK_uLf1j$+C>1XlxR894Cn?*Qhhqb>|y_1zw zNU4A2-AZ0`d|0Jzq#2mt46T7FE0Kj=lD&y0P?)u(!uo-V^#K!AGPJ4A=L`|aq3KSz ztTB%nRuB&lRY=Pk#$~)W@-@qwQ0h`x#ZZpj732-|`@VqS9Ly{mwA1MiT7w$eB%He= zy2}hJ5~}#Ue>%drZ7k*8PW^!u$t0Wfk21L*XZ}4cF%$i7Y@D-NmFVb=bd}hxoplF( zj8(*TuUZ==y1;tHs$y1{sZ>>RyJuDP(pcfY-K~iXcY=689%dXyq%Q32_dx;yfB;Ik479)nISLoSD6GnL8TME&Bay*Za*@~b{Y%%c{feu*Pnl+>Az^M& zUtRd$-EJHPb}Z`edZ6a_0XVnM{#&W@Dbu}MK-y^Upu=l05U^!>(Hze`eAc_~SIjaD z&lP3#+kbaht#$`d9w=#q(IHp?Q7in_;p~3-kJ3;*V;P%CPfGx4{RqFWwuA+arO+T#|0{U2G;l-1N6w``mw=_?0 zdsn4jofuLNh&{DBH6=Wt#{my^KA1QKr-j+rFOTnfI8c!D;4ey9F0o1+?)G_s=~Ksv3Nf;r1$D@a(kM z_$p72TT*uHl1UQNTBm6CMeQeyQnt5R&fRt`2lPqtA@OFB)ukM~XU@gcS}$X~{cJh3 zqWYte=T8ULO?{P*J=lF(BA zA!zjQPOC~xJPN5PlcR^b62hlm#aP>TZm3Ar^>trPi}qgn+f@QSL~G__7d4Of9+pSN zZprghhXm5R^C>YKIO&=lq5ammUb^!ZM{&ng#CXT4dT~Ca9u~qALp8c-cQ}-aejly< zy7)%Gy{A45OHL2CE_pwe=7uZ7&m)}jF3VedKhB~cv4+zToz;|5Ly1n{devpf9F!7s z$xWXh+ASIyGFf~wfh_Y{>7LPPT`pQ9WETw1QPExrqNoz6&nqHD!0I6{%*$?KpcHxx%R zB@>t_iXlbvzt&sU9A)JxG_@BVJT)dIg;s3K>hRR=9S1K**oV2T@q`C7OoU+%12JbF z8Jmr*M+>IB|JN$`vaHdTFgkSFvFs$rn@Pm#(HBzfSEpqe7ADh~CY7UNG zQ*`57@%TRB*HwgvE*2kBMbqa^lMjf`aS!CiXt=xiL+!xQfIn(hNCSU1IwSOP4umAjxIj8`FVT#DwhNX8GR`YpqFuN+oa z*_U?nH+D`QuLd-Rdg0G=@JbW2(3lgUeF#~@3>-h+p7qEch&>L0z&d4=`1&ft!<4b9 z77!rkq*}+aD~W#?&8G8pI|(duF#p8`sKp%%%@+{{7wE4Tma}*<*%lYIGM!@!V)lArV0PM=5N_&llAPK(Q9E~$fOu4 z^VHE7vbV%jhIA6@ao?Rgeu)h?rfU_9X8fwGhC2E88Gp-Im7y~?U~+zW_VA3o>iXg+ ztXEMcv!5A(EwS2dS@!P$=Xt7~uyBG!iWNlUvyU|HXbZ9N-{mCS8){fJ3*`TixO^XH zf{X{)v|xxZ)${8AHK!!9uzbN2gASeUNSGcI*_9UFodd2Bc+8Tzao9)SR1L#T0i@3S zCB&vCT3`2z;Qwu7Xn$MaYZ*u9J}~z^9^Q_pxBa%YEf?yu&H&naIW$It{eib4DaRSxaJF2Wbv(rEDfg>vwArtj1Dpc&Uo;=tsFhJ zPJRpf>pGpi9?=U)`&diao5-`=1g5-T{?v3|_2e7&Qg}R6Y;c(_!8quNBra8tpY0iC zoCWB~ndCJub{*r_-F5hz@tf>;@9-g+2>{HeJ06O1!=jmN99{$e`{!!p*xG~tWrem} zS)L%U!3;N&zwj{1d>oj1ZBQv4WtiW|DCOPbXlSEqb5-%G|Bk@sb_5WM%2QKN`YG?O zeg?i)EeD+>GZU9p8`oss-M;gQ2_6kG5LYcZ<%&l}H}(ZW6eJ3_F}f3PB zGCt?3>v7x^OVFO2*K}j$!reeif96Q3mFdfI`Cy0fv*u}NhV4eQ)fa?kb7US27W^6SX|$jk!S5p?%51O z9glzy%9w;@Uj^58RzDUtCMvpHljAdc%1sQe!5Sk>0%lD2@9;Bdb!vU?3(v#;N6=NU zRPC$af%5dYIUf@8mj8ia)3=KC=*Z3>s@`WE5?`aA*^-;+dTm zG2Y-qv{zExD%^fv?0-Nq#k_sbj+em34o{7~JA#yB^q;b^i`(_*!4@&+o|7_Abkz`M z_P#~@{eD55q*#;PI85#Y=DCG`+mj6DqsmrJHVvlBVuMt@gRxemeqv*u#!l{x$)-*o zd^;BoZe;Bn`iE*;8GIt|wuCh-QGj`&M zn1heP813tn)EYw}up;x!=(@1-nHr?UymdciOqp=e*a%%GduG2p53}(4GEKwzlyMQg zDggoj^jab#WpXKZq!-k{!}H8tqFUF!CmdZ*GT*hf0YH3%L7UzCQ4HhD6`c<8lYH+1 zL+69}bTF09D%d2&GDhtkXoS|=vY$GpuUnZKbdNgJDj%;WAXVmMti$s(sV_sl6vG80#!DWpJ_Qt4XaIGCj+Jw8=E@Si)CCJD?&2n5 z(CKo$1s|X`--qMKcLKk&{ z4>TNT_LV@v-$j~8lFaW(JFmk#34utaCwgf2lmBsOZL&%9;PL*MGOThn?OqjI1L6}$ zSN`pQPrEm8&?~r1Z_eL4OAWVu8C5{fIVJrENX4H9)|XJjHOC7f-mm*tR4|qc?}YZP zGvD>N`J6|v^+=$HUCinC_x=ov2h(t#IiKn(@d=`AcxAe0C8&q5!H0`^COFuVhtc6oOCW2k*n)d0V`F z>AiP%brU-l^pf`RZC{M66E^L-zh_&G#|y`%V6B=f+qiH@U#XmF?q*2dp*8;e*k!37 z#YjB9+vI{mnf_a+2@-;C?tOesZZQAXM z)#e8Ji^h{1)a==)6f&obHKc!LvM!@q~Obv=0*?R3vQ4d&MZ@1@Mf! zi=IcZ=c{c1!nA`A8X1h(qZZ)igw zGf9nS!62IqoL?;TCb@@+ecgsnEGuX@K+U_s(yAevK*KEg9H zwdHls{l{@XLD~HlXNu1TIe2AEJQq|?V=(Zj? zj*D0MxSF1x*JnW?w3wp9U^oEdbahzF5Vnc4R%Wi-ESP?}{OMgO?$L1cevW)p?XvK! zvA@qb-hXsp0r83ua4ZXzei7y#-ra7Tj7CeyJNji$a9m896rbMtC&%B!JUI}cY(TYymk`uu`-B62~D^n><9Dq_vCex;**QvSYomxBymIX>fn#fDst82zvpj? z2c4ns{coC5k;cn>ed#vw=KfL@>NpUV5Z>McaSo5abQKQ?(Mk0TQ5%gDtm~AnV@iyd zXADZ;i>YTPN)qnzIm+#0)Q=eSh5wlm5_9iUZ(=`e3Ew_U>9pcisWJ-X${wzh_;x5Z z4K8kq3H~=Yg>mQ=-;%1hQR_~3DM$#;?Y?{B>Yw)yMCbA3;Qyx7Jd0D^(P!i^e3*QX zBw5+_h81qN^H#u1LE2_K?%L%3?ZZj1W7Tv9?%StYRJ8BF!MtEQd_PifAi|SpQZ#j~ zdrPJQ=1kmwQgyfr6I`XLb|zsGp1Xf|F~n2e<=H^HN#2iHzKYagc{UPNHn54wx16k0 zY}(1u-@ovoc4EP?OLZHxt3~nj>xJ?4Upe7pMa-Xw1Ee>Wg+4nGsBca1p)&l0#*A*W zO`ey*9v@#`dA;7>xG##krB(U&)DPLu)gSgsw`k)M3QRHc>ppvTC81V;J0e# z#d7E_T7K!?90S7&HulS_5VWdRgO=K7-Kw6viz zUvi8vNhg+?eO=n)NK-`@$bTJ&@&RR^cgTL{SBM4-E7-C!CSNcRZ@w>GC%>od`3rVF zN(kk65w^sc(J$qWt5IiSdpHdqQ1{zoYr}SFlP|n4wtGu6>m~g@z_ev_bP8&keT6t{ z=Sg$L%{4aCokm>_+e0iMF;&ihOIs?&TiKC#TKn0mm3vC{nS;7!k)?s$jK0yu$g`t0 z9V&n-ddIP=IrS3nEUWT$rTQuq6(u1HX1}6SqPiT6du_+-VdRSU-2F%b&NMFUi6fyL zmbR7Hn0mmwM3tQP&2^RcWCVZ*4=x3to8fZ$1m6#q2xUApZ@{xpA0(~}a$iv=Z;-T^ z&(Yb3ePsC3rg^FJFbpLp7~O2}DufB>FVDBq@VfH!r1Ud=+9R04J~@F<*szJMm4)bL z7DK&+eh=}rVAtnfQ{6;Kl&OTFhfUd*Wy)PPrlm z*!udL3!}E+tIo)HQt6UkiGw<@Ur+YvUk@q2Ydl~RnZHY2GFqF+&SnjI_KyQ@4oi1( z3ou@I$G)SqzN6*o(5F(bzub0&zg?S!-I(-6v`;p^1MKZe-y26*63vV;6N(Z)66!6lb3j?Zb$-YWVV#6+$X~S+IuioJxc3bqzl6 z#$KN4A+ zUBvYn5()1uP1VWZtiH^v;kJ1D&wnU)I)>=2qCI;s4*9(uci$_?{&#+7eL^)t-$?nO zT(-!1V$%9su;FhgWg@nJdidk@OUB{xd-v~y7rJN|-GaJ!yJ6Hvdr_EhD{Spv{+Lv~ zE6>C@A)FMCwgGwbN{6o3A(s!t3uto{&M0waw&i}rqWUN03vX#vEp`Q`ty6*(px)QIM`)1-mvZ@0VGImY2;$^e@vuZ{; z&tHnrt;%}#-q)bvx*cHL)n8sP;Yr~aQ}iPS9|ZH_ zOg+OwKYsc5K9~%?{dUMF-d~tCT#1u!+wYNrZCP_C=k0pkS40k` zP650D_@CDa07Pwc1#1HV>R#ml%$Up>eShx0B;Ak}RAFYYVMv%U;EScX!vs|rTJ=H2 zL>Z z7FYF6z4s#tZ93u1`~;ROWYv)pp7%3y|eK>rY$q)FQFlV^MF&6^#A_@xPAk^f{#_d9Xd z`@;K{(|{GEMG|)=ui6uD2@>GxK8*Bd0EyyBO-J#ex~?wrWrWLGIcxa>m@MBjV6dRv zE^fz*aV@ATtS!2_>L5>FQtM&xSHHCC98RDp0G0(sV&=UGbF}?l*H1EN0_$Ov_Cvv! z0BV`gK+_iiJx0z1^Sa&OKiX;Ze)NDvRzk$=VuKNj3;Dp(>|#VVEV#UiFc9cn)|5xx zF6&WPNz6T~vJ4faa!w`PYjMvW6ClrD#(;TlJ6L*w%oiHt6hUP79x?o^=`-~87v`&I9D>1516z(5Vc4pcHxrNdZfJZ zz-0!QZv9C!O=dYpiD!S$B?Y;a3tFixp)^0K1F)ql9K!GS;u4hY5mP&|s2u6Z+wymC zj=a7MujZzF*av}+H{Cvt?LsIbGHKL9OJ4@O(NlFdT4fWd$`5iTd4ieEc2j66oWzcZ zBHv1L&p8Y~TSKo*yp%Vc{a$_^g|UX8GtW85LVvzKjS2h78Oho%L=(RfC}ew$0Gj%m zH;C`;$W|WysXM3#ip%3xk;Piwy5t#$VoB_a<7%GZ$H6EgTp0ahv-Pmq>lhU+}_+< zk3OJ+gAtp5HCS~`)78mqZTu77!}#Q2?U?;NYls(hyF5QtR7F{($nk8SPfAma_~+=uQf}Bg8pPVF3H!^p3-s)q}N;r*jbdGI{W*6 z#HiYmRbTCP)2^}pRM%hg+V3YUW0GIvfj>B4eP!a!xV3fvo&>>e*j9ETly%SAYr;@^ z(k&t@-Wbb)dX-ExyC&@jU-c!QnPPA-iucBi+ zJS6)P7A3s3fW72=3!H2hvBCsnBn8#^7_Y9Z?n|$35O^#MWGdUT*AVgFNHl$y#)<%S z+*BI+;l*D@@X7ciyZ2Qw3a6F8U22_RZOC_D(qjV#fh$0F#@*=SA)3llhmyX0w4n)d zjh?Uiaq5Ou2PjF6)J3&Kw(L8{*t-G8sGH~+&vY>Qb2bdP2AYmnu&?>mwZr9=x#6x^ zNIp+<*i&W^El7>=#m-A?fapr!yna_rIFm#Dt9z1K7lEfhScf@@U$U;YQ)!gLd;jEq z$BI(-Grq5pWQW4yT!OnCEP3&n@`(okVJJ12^=C{2Z?fI#`?ovT$8KQXC)k31qoF=y zwYzNV+#YG$h%wo7QrW^^IgVsXOPb@=!!mTA65`PL9r3x6D`!UrCfU7_mEp=xoSlg}?nSB4PvqUZN1I|1 z&F^_QjCU)s$bwDXd_s}vl{`g+I?qJRF>2T{-a|EznLRI0ftH@y!%t$OdN&EmG4R6p z&YH>HH5jpd`T}H)SHMbn`ylqce9=AB{O=1>`E#0`Z?2KlK4#x7UTB1f6M{`l1?kwi zcdV%FwyRr;eRg(?lz-!dW1lpmbU0^4@>Kn&JpuiO`) zd{qc-Ev%MW{YiOM00Gm*@#q@$BiqikJLG#X@w{K`XTZ}noV;J951rwE(HJkHT0 z)6`!d3%64(;CBmY{pmQjy*LdQAnYH86le6EACFInxFxYCMn{XVX^UAC^3q)PS2&~A zXZ{jp%HrO*lQlEa=S?4Vf!YBV*6I0sz1TNJ^@j=r7KT2#=R~-qjOShjjf7L}@fm5_ z@xl|lnhhq?EF_2RE(jFiJ2w5|b1Ave*g-scjQcy{oGx6n3)@ce*q&PVXgN2Hy2KU@ zBm@SNq~F9Vhw*&qo=v=~gcNeGPl=u>(=$u}?)W=ye0iIjwbze?mF3BtF2>_5Z>O(k z8AA0!*M?OxZ8uH9r2pr{Btm-(>Qu!f9t}wzT)Askpk^t#z-5*eVyKv|nr5@KGuKS@ zKKCGnY!qBkBVoN%f_z!xaNtsh|7a_HWI8S~st4le$L}B9Xeanibx`sOduy z7|>XrpFi`v*Ch??4ub;eS3imjT<5r7S`R`5)knU z)XelT6Z^Sv_ZOBt^HC36T(q7YG2DzDNO3+ngmx8{vQxudAW)EKiU}4J;X{mqyh`YQe zH81{opq~%Dj`wS9b=E@IU$O9K83jD(Y6vYrBUfw*YL!hPv%v0|!S5r#Jr=&$ln(emrg=*|oUo@As|!3M@M@*JI${4lN@^*-K7%YjzJXZgeDF&j7IR5Y#LPT_1k zc{dgVqyAm*TUMN(=9Br@UG+=pDwcGd?)TJrd)>AF^KXnp?od768`GQBi~)t2m%ih;on8KFzs!LY#=WR3uBZ-nsbud5o-+I#P12;69E!;+pQR zI+Q1psa7pUMY@M1OG+%gre!$a9p!l{YAN9EVmXQBcIBhva}k~xc@IF+eEo(zY@5J8 z&coSqN%JC{C%OJGd!PCN)&Knx$}lF-DinO>J*iRTvBo@d$wjZ@-G%dB{={chE+BAm zD;Q1s2CF&-vUfZd@MBC5;O^6q`@;s#z;TIizKKAKGpLorRs9DSOm(|e*KZy=_?xC?>lgC!n!t%hFmY zjmu@|SbdkAff@~QN7@6SxhvdF@0HwXnqYikd zw-hejX)tjry(>RSj|6HfW^f5jenOdi21u_QBzt;S($~5bMpV@YW0IR@dg`C!!q|Z9h`c zN5{h7iK*5S#F+W8Ny;DL+qz>owJgn>!w240x-UxPe%*1(jW2h<6G!0{U0mPWk5K~z zSj4Ym6ze%$j`&AbEDz!bBT+~UppqYNb3hNP z6yJr9??>Y;lTw(TxJM@8=-X@GtN^4M7K|d@E^tO?Xj*FZ8ZbeIwXgPhpDYlwd*KH2 z%9hvQwx<|j1hLsHn1>5<*+8N_K`kmL6tHJ%ZK@9092SQ&2s8GX_4a@?ljNr|h2>Xa znN-&t)u2}^3orCLw3(>Rk66m{y?;9M|+kHVtg$YQEs?uSQ7XrX32?HeWfb19Ui z_pUop&>*or59=5~gV7&r%FT)H7+U-`Z`4Ncso@uTlog&EM3-_h!gJ?rW0T==#~ujl z*PnZlzOI=z0L0b&*5gM0P&H8+s!eqtCDdHQv#zQe8I{qHm?uVuJ^Dxbf*{<-x-2-;M96T6?c z7rNBq#@O6*-naCRc7;sSb>e2}?_3<9r^ z@9rQ3hr{UA-K|JFTYTQ$bY$&k$lu}!vqU6mi8~QBRsLQlQ?EqDI-r>UdA-xe3(Imv zS8M2wruY~=^ESCl`9b#aiH|6VTO9LU9Db|Bf~Mhy>-_e;YaMtSZ0-e6k;A!JH76H@|NYY9(vIO`@rs0N`=!vcP9nEap?5Qh1g1=P zcy*mywwLkDkbk37$YWBwdWEIVG*XZG4ZMaZo~gtcYX5EC-FXxuww4R zNkXGAenvmbM~LU#f_095CPsmeulP*q5EFReunvd!R$wfz{51MLxUV1s!4-<8R(OJ! zi6yVr6u*V5lRZB*>DbNo=O?$4GFDCH^LZbh3F>yylYH~4YpPPgfHHu)0;`yUT!n6| zht|r3RPWs`o4(Q-VstRayKAt$y%KSM;nY&hYxjiWm)7(T4`j`-9{gzq9^d-ZBQW%bEKN=TmRaCsm zb7dsWx50=7NkTbI7`%Oc0w(^EhT3qy z&)L&esezlENI4g@uK?316Jp@MM{VB^WBrsLNB;QHC>o5DhZZiQY|o!GH`H8^gN7fi z_oJ=Pr|%(jiP&5}_iR7m`-xtOpTr)$hz0K@wsYf5)D2s0ZxB7Emjbts`lSt>f&S}+ zuo#8$0HA*+zwL|GPP|^+sSIA(!Bt;)$j`&vp_fhR`5>}wrBvKF%E{^ z?P)$U&pv#v=1q(Ib)*g;7-rK#G@XWUsNA1_WMLe^z)}*kK}TSBtc%j z?E881?aNtsiysHqI(phLrdZqzei-bAU|t2_cTCvvkc-5lWeWVriuEFsiq+2JPguc9 zY3KW9-*(Fmcv*XA%35T(7>+Q}z^ZV?81iT6``vy~3}1En>Kc_6uZwNSQ_#z5pEjWPd%4=C?ZBr7-jytF&nEGQr_kPi*R+=uZX|75B^RVjLg1} z7|@a+Zm_K<4#o|quM*b`RlFEiH0yJK#@PIl<3(9184hoQ%C7;mV%t=(w_@%jWPQLj z-+bWcUe{-98NZ*bd)edgc#&x|?q!P~OzFRe$B&S4XvIN{txL4C`o+GUi_!!&Xz1=k;%z{!!JpGD}nV4a-HB1xa| zbG;vk`giF{fb< z0P0lweOP}gfjHC4*PVIjc(x0CxAi^rb_Z8O8?ti!sT5neIWpJ+2kNyxZEGUCTY?cU z_5gy94@3ZXc6q!<{(Ar6P-oYL^*cC$7%SXZ`cpNWT5`URHzUGmG;knaC{TLycrux~ zqEY~$jzluILR+^XK|#2UL1lOw^k*n_aAAX&vvnDMyLW0_@EK7Jd^dC-{}|N82nRqz z?2l4?q2!Hyx}$9!^*HZ9u%Y zT1vYO-ypro67UwwA^;;(`7%p;_3QhM~1}I0zxOTGD3}g>P&kVE+m4JoX(#KV6RMx4!c|9B>y_#RPJGmx+ysT^Mi9_kATMFS0{^WunyNroqsa zdrU%(J>yG=x8=1fC-&H@?y7j&i#Xd83*4+M@99|Ejehk7l4|xK%FiyBtdfBE+it+d z5S@PWMM1`jAcC9bl8y#*)?c=XCE87Hohsl~5zTgESBJ&4xyrj(gwalWLh_*V*b-m(EasY1dn@M-mk}dY|sFU<-$>0=1xZ&{GGR)N#+`@C-UYGs*fY)WpFr;_$n~lWLy=33>r7b6MA{ z@Sx-Tsei1+kKw2`AKADj#k2|N5kqbcLL=tR&JSGqc%;QCt@oZaIPMi(Ioz$v`1pGp z#<%c(8Juc!`ru4Z40achEdn$Zg@Ze<%JOMP?uG^5MFKz{G*5NLDgZ|m>{mQ<+w!h* z^q5-h{^esL^7K$rJH91FeYDC?q>E>N0Dlk~nxv8$8HQ=>Rr87ehxVq5utf- zLP<_)n=sN5*(!1Scz5Jf;>0U56YKH(LE%|v$ z^l`tgv+3j@ml9tEneuT5LvJ4wx7h8^CV|2WvxJC#Y?i1ZQ^gp}xiXWS8Y|Yu)G_1D zWU6`Y&&WE%KKI{CK~#c6qkqV>r6WC~=IzgioQrd_pw>*eruh;A(H8|eu_qZ)rcs~% zXC#vxv#gOWaKn}?`YooT{As54bMp^>3WCXZUh$tVvZj;gbdwIy=u?b@fHb--g5J=% zWj_7Ko<3|ua({4^So}y=l+(`Pp&hnh=Q}LUezp+jlsg_(OCr+I%E}wyjI#~^8f(Ke zi77pE^ilGz&*{T$>Fkr*bMm1u0#Y5nH;Zxm@<(PsHSy1D#wIeHsvf*&b2H8w=yPxM zCG_%(!>p3g-{avkX_yp=F2YE<0Oc$E^6AuDs4u5|KgRgCk;DC9ubNUAAY`6- zin`}@sZY?b&YxUQl0j)#c({rM?uH$V5K$NZ?< zrLdMIdCTTjPT5Iw-+Qw~^y~4S+cid>q(NMJc?AHV*sjT0OR5H~y10ZD51ne$_O$co z4JJauUZl30n~nlxel~>1e)4~TT2GkIe4t>m)T&c`HPUdylnoOA9xT{M54IAx8J1(N z{Vs2PBPC88-K&V9vp!EA`G<0H0q+I`bMl%>madD_2koqY+^ z&_{);#7F=`!*VgD2=cGp6Bpu4-HFrD3Dopk$y1LmO+{aW*7YA_p859?rd3$YT5GCC z$FokqGvPn6*6UN9evKy*+Wp(epfq?_Q{!g7E5C1;`n=Rg*1B19B6y#W5=Z4}d8WG; zBmfO2U0|eu=3ThtbIFaovuEE1`!a2u^A>p&+m54~hkP*tlviS^ysE}t?;O7wPC|oANVARGZ$C7PBYE zTWIjhezWmTV>Hy8n32h7#XTIcS|2{PVgG|RpVk~b#6r0JIan!H(8Gu(dV*`_+YM1t z90Y1276ZSF*px~44o(N@`6ABjnxQ|CpkS4tJYE0ZeM+UD<6PGsN$r=%%}LK3x~W-_ z7(P9bbMT}eRGe>qxbcZ?-41L~^!4c=&UalAs#w{Vu?32*uQrA3IfYGpbctO0xCR$k z6C7w0axJva8S|-yQl4v$TSD!Rw@R&S-%c=Ph(G&U`U6rHajO+qV0>R@@@f3&Q8ijJ zWSdYPuGwwb1a*GD=62j8sqg7~PIStTv5KJgn1hF8ru%uZ|JKG*n?syFTfVMpi9R9L z(7x0#CQw}pC(}HXe1&crEEwkKF5Cc)5!|sjIWn z03K>v8v0J;1Tr%^bU`_HTzEd3{PAVK1V5y%(1qbA5cy|e zfV8__eydzI%Bj$&93#l-w@ux{r(I6-eE;2{L$l*CF;|;DLjN9o$X8f@o7?j!*M8gx z;}LLl+Q?j-ds2tS8RkTmKaKl-hNnL`c3@~Qez}`94=cehHb+G>9D}{Pznd^32swDA zt3Fc|Nxe7OsGCC3&{J~thI?mzI}fV03DaTUF81Yx{>t~Cn~SEvEiT(Vjf*TU<7D3h z;r5_=%7$D`Adkpa$}-r-m1IbRrI&DxMLh=Qui+xe+?&!O$>{VSVZIu30{`aB({PLl zrUYvl|72Y;&-BH*3%k-=an|0t4}-{m`IG)yk9)?@Kh7I#e=*7VXD?||8Mj$|b4A(n zGR+~*W${$8qKxHFjNuYi4n4+szA8nv-bMOctH$uBqMnx0+)n~ebE7s?Dl7JKK4IkD zsX~0S-N0E@`J>avUF;W#hpC0vA36Hjc{u7&a|^4|vtM$ScM%W-1z++13(rOkf+WwTOYV7yuj-h4sZMKWgo~et%ZQOuNVxGw{s7@Lw#3D;HDO! zNDf_JH&ScdOBLFkdd}5jWx$kOcS9+d52qXbve4%`K(Bc7;mZ|g^@wLsjmM_|SoA06 z3cx&M2<<{2?ZG@S1*a^IAWi1wzIuyU>;M4D5#Ju`MeP?#=D7AF9Ww znCQi?${TkJj?tHpZqW@k0@bnajC1G+fs`NT^lAYOc-a<}U;*8fdkiGpDf6sv^07Fd z2zURfM*TJ|4%}UbV5U!x_E>S-HION~jf4h95oB?le%BXyoj*;zFIlSik(0>5_y~-f zf#fnil`<|MhbPF_OtErzT#nt$+lT z9uFPWMEigHI+OAD_HqYk;AR*b9Bobi>fPPE)&{=5@f%j~BCJ2<+B?2&q_-Jm&x9}%o9iu6@s0k4q z+Vkgba*PV2zzd~j7aX;(M9@-0Qqua{`gpUUsl7%E?CBYM@r8M%kT@%EM7|2YAEDxt zyqHPwe|wMus#JMYnKM=>`jOB13&uG|f<3LCSxS$Zd4Q0O*hT@MQU>xAAS=8AV~J5! z{F=}7y%N-_g|JowV#ThL4nuXzmo{Fe`OOn`FKD^uOb#>>0$8nPXCAYR%DxjMx3Pdp z*JI~jK*NBh>S&by9v%6Me>&{(3kM?{pA06hft{X{s%sFsznf%cy?-@z9S`qfI4e~2FwGxH}DE)%kNAGn?yQA2ZcP#V*%rIVbl1^=hA**X> z2e1?h9d(vFMAD*+F=~ui%eKnv^D5`H@EeckWN+l%Rka?<`MmF=!alGYw7v8_PsX?9 z_NZ)@Y%=;Aimpo7xTY>V-M^Ktw&tYGtcy)jvD}-%BDld&1JL!Al7jhjkaEf~Q>ECk z(ePR)VlIZiQi=seSr4~9g3LE$fu0!lXfKgm`@qHfsYzn}&SpxNPZ;V}Kx!}7#7c&V zJ!riE4gn-M5d%Oz{vsbS0H(TOcxx7Ey8lPgd2K5S1X1*t$l(!0k_t!?eIpABA{oDa4tLg?a04O| zx~r>B?Sp)}L@(8cc#)w%WmPCZ5Uj;d?-%|=@~?)Nh!OIn-aI_OC9 zyxpoI{Y4fuMe|ND^8y@@87G*oH6P%6u5@->l&bueGq(%E@bIWgS+)eZMBvHWZO~d- zWp@dk#(pB9@eh@Mn3pXiN@$^kT#tLWrGOIPb(aP4*y{>?Q{->0wdlqp&r!W*>&-51 zdgR}dciX7kLhJhjn>>Reh~(P6R?}ge3)tKo?GNy6t@5_qn2gGe!e&^otnZ*I4wv(& zf%QhQ<%RpoQz%h)lnPKE4ZDi%&y|7w2(``U%gr4DBmtlywEvIuJ*P=-tb(WR)=OHkMzfT#q6Y z=iOVoALX8DBOfXW4IHB)_;tkj$MNOaMQV2`V};po@^WLabC+9I%}ajyoX&w5KChQZ znJ%6yj$osaV_4Ue_?v=#3Cp~y4@g0~&cPN3Nmf2f| z3NTDt%lLPak7kc97N{lq*xv%E zp1h*Y1=PqZW|eqB+YQ)Ux3Ax1aY|NPf19kv=YpvBBZU{w?JNHZkN5!wjk~@meR4Zi z1hNXT+{=|G^U9#T<3Nk%r+qcYgL%@vzxb4U8JnKproOB8z$0Mztl)on7eV9&Q;@Je z!WTOf{?bkG56^7^h;{!A>A?^UV+|b4s|wbW2XDIwt!W^9XQ5brLHk*Edy%{g+`BZJNRvb*t`EhQ&c(Xnn3*zp| zl6-ulmp6eJzOl>0Kr!dsDi<*f4tcXaWhOqNyK27*ZF_hhqPsbqK}*b=<~=r!Zwrc1 z_^QcOMr<7U2UEN!AoKJ)Jpq4sdwdQ=aBD$__09!~2#db4SWTi6k$CwMzkjw}kiW9`D7Tz3xQqhnpbb)-`kIb2RvG%=yZV^;bv2d=#!=OM!ik7(gY6KVc8c`V+$p*h^1-)n>DQ&r9jSoih;T-T+Y;pug(*^b^jZ4#afm#T#rhJlFm zbP=)--QO&*wQ@n;GY7vpIw42J$;3Vi*6%6PK+Y#m)b!Gxq<`7o^`3f(OpC90b^D&a zu)0BSY%+urJOR!G!*)4|i>gt-Wlf>|OAVH!Y+`)gEM$3fRaH#>Rp(8cWu1sbGDnjyElG^_`mW|Msiw1Yj9DD(AMwW*)^$r3Q3c`NKp^BwM&J)y3R zeZ5~E#^*tV^*y&a&`8TcL+yV(Biflo0li&8Fb%+i1_&=YxR_X?w%&CPUV#-RInM)&pbqr)~q zK6oF4m|C8Xx-9!=^dstq&#$a>FS{!R9T1*6vY??+`DMIpDV-W~^q4ucar)k?Il4Uw zl1|$o!u}o*_0Eu#@=((N+Jj^HOv(+O3M8W+kH-RVvLWKj{R6y*!S3@klmkg0|8U^2 zLH>!~+kU2rRbiM3=HB`t`QUre$3NTr(2sZfae7O`XS*^Zx}(oop)00bE$A^9i_IEz z>0w4ftGuL*QK03iZ{^6u^ElocrS0LI@Y;;1b)(u*m@5hSq7A$5+p`o28)@jKD&X$? zq4Fo3{eILZ+~?_pR!#ZRNWt~|yX77;oSR8}ngk`87oY23k*Fgh30~i~RDQ(S-huJ* znjcs2VZ$F*>WZ$s@6uCBr4~+gjyrxR+B=UJi{J&?Zu%zw#K^hKM+{-+(;8OQ*#@hE zpUVFBj3Ow&G*O^)FKKeWUGK%v2goZ_M}#Qy_YG5c{ds)@nVuD>1R$GztNGxk!Z zHFO2qg_)D!lp%tKj{z_NF8#c{-Q+^QP>ZFXxYE*{JlM1eqhLp4<;if@4?jSetqgP|XX5Wc_JgCs?PxpI-6%(AN8a9IHO+=y&@r zSn$i9w&%J0M;v{JbU=g}5s^^9ef%?*K<+(gI_^#}8~o)&VIBChtO3Rn`?P6Zi*L3= zkx_2Iau=zQ6peScSQK&thTAi^70P&(1SEL=(7~1#MDgR`Rr^t{tT-Ovr-s@#pbmM*SKro7`cHoZ^CQ2y|;Inl{~fwlv~X2%Q_h&mb>b)TVn>< zr7(R~$M2Rf=zroMIEP_wpuKIWfnCG*+C5eW8z+|5UzaH3(-af_v3NL8WgPNRvp%<< zUtU&rzILzL&zbD=-2=Jvc&p{*{8JO%X`n8IKGCDnZizN^fOpu zoT3E~=f&FtD2!qAmeoW2a86fkS}z3GXUXw&Au=IB^#|@Wpu(7A7*FedYr&i?@oa*5 z$x2p~Y|P_xZT(@2-1|OU9=`9S%S1S*doS~{QT*=?dr_>70z zS$`iU>I6z%c&Pdiz044C`|Kdn*|49^_;j4!`vV7qgYe?C^x>`?pN>*R$cOMb4;``e z#G=ucK`Hm0Al%>M%rCdr0`g6qXALAH-A1oPY9FHtR^s!8>Dpn02-MOAjLB+-+Ri&0 zsZIC%q?q|nb>}}PRaQuw(3sR5Ofja#iv zM+%HDrhB?SE{3r;oDEZjz1zm&lN%i_EV^X5)H>BikSdQXpN$yO z>@(Vmfyz|FQ^fZXWj+MFFg|`k8jQ!x9T#O=@r2-+R!>h)qhj?>u#`AAtwZ}!nK056 z`u97l%~&vbeKz)QzugDk!8u9ShWlMuW^KXzVYMA@BHQ-uxQ7Hqr6VmI76Jcx-m}Y* z&Slk(a<3#%c2kZKDb@VVh-cA zD-_+f5fOTWtvR&f2|#R3g}}=E{qa&DIT*YDs9@?GDoYTI9|BQPYp46i6Rnx3yx zyQ*N^zxs@ciIi6-({I8`h0_{5eGl=G%7874LLhimGGG90f5+5^9jGRn#PjEz@{P#b z?;vS%I6|X83(AV)8xpL^(yqe&V%`<0LXvu)Kannzua`4P(a9^kqv`lconEDk+d*u z9b?(G@h!UHv=1#^$7h!Fh}dt^bde$x5`2y_CQR!e>Aw0GKfY7sTZjfN)$qYQVpn)I zUbr3fWWPQ0&^$#sRj4DXzFzSWwzYq*_xIMNLNO31LjTZIGoZxZF?%q9KW1=zp0dkh znor!zAG*rnp3^rR{36Gy9)J`KtFmuFl#Tb9Q0@F?;0S*6V>e~D>{^hD&G`^GAOA)U zS<53<%0V>6tAdU7^1C0u$cMQP3EVY|Qz`;BYrZ^EaGY#D_Z}-#G5adp!oBVvZLJ%p z;N92km=}og?|2I6VEfcuvv*iya8nz?7oLRv za0K)|&;qYaSA`D9Ly`#Ydc%|LXNk|tNUW*M{J>pm=#S#ciK`Eg%j2LQChmcmMSfj9 z9H_dwrMy-Kd`BFBX9{^~oGQpP!})SCsqGtr>^=fde#{^4fzkOWKqp0kxdF8UD=1@Z zK|fRv=zoTWN+uyom~2p&Bf9z00V#tHH_xdjU*r$i7jR$gp0hEAt|#*yrG;n}O% z2fQtr?*sY~c<0=ei-r+MRrZB)lG)(VcyxJwRm}nnWX{l_%TmtWx*}i3ZirXa^cgd7 zV=`zu5sn(Vt<=cDjVd=vc3vjr@Uc6&1R!E6c-&c5z&%Mkq7J;$_1EY;_PY+Es5CRv zwL;M{-_T;lyb6JtczS=WgCrg*vd81?^s@oRvX;vwI6HB-%HT4sdC`6HX&-_#0=m^Q zy^+~4z~h;g6*d5H;s^m#Z$2RPH8CL#C(vAbq+*uGdLY=ZVH>|&ijH+<+O4q%N$THK z-ATB^JP|gd8~34eW*Cx>;X15%u)%Ql?r@&Zzq_T-QOkRps=*g}pmzQ`zl7WTmj=}~^VgIY9*Ko;&q~N_EaFGS;uj>coo<_2Qb}G= zLO2w#vNHf%U3&R)w%?NcF)^0M=6dOSh(4_rR^IEGxN`l|AkC4VS=!$>0Z3X*25L8U z`^rK{RJfp@(&<>F$Xz^PbLdMteu3VasD>FCeN)AO+XK17D_28ghE%{n?z`6K+7y{Q zOH(OI&eDWP3qYFMAYBffU~+cG_nSgKRxa}byZP|b7vggt4jTh1U2J`7mlwKu5q`Y8`6Lt9xG@9fb^NA86n!yshqDeAY`O$Dv7$cn zJ_z3YD6}fF?&d+9@12%dnn3>n1Xa(};nV3nlY8T5V(HiObh|(_m&42CmwmJAnFwLWFg!ZL zSl+4Mo|M#^zn#Cp8O9FUVp~Hw_q|b;rZzrIv`DR`YiTGm;r-N0p*G;-j$r#aKa#n7 zv`40`J^i5Glts^o`WKOFPWGg=L`jo442Crj*)%e@3XN`rdWey8%#16nnqt0w zy`$l`kJV#t4ues=$!L};H+xHoso0Mam7ynYvwd8Jd*X{J6j0C$qMca(yh3HL4W|l% zay#vie^A%+{q&H1dV?16^gY)VBgBdD=(}4&N+kOKDqin7%Ss}MG1+l{2LJl>vG)cD zagsjO&;GZl<`)Ls2i<$c+xAS!^+GC%M=?geLcLyuVo4&z>z=r5ByCGl6j8tZ={H~_GY*D<;&zEy`mJa@ z2ik3IT&s0tw2C=p4`lfL|a8t#cPyTxPRs09nv63?6-32-bcpX^SspZqggAt zv)%9Ayjh8G->xKBHZ_Ss2bt$e&HS9^aXRK!Cjx{z9L|3fF{v#NQmO*f&&AC7&iFb^ zY%5!NF#PYku_bJ(Unbu5I?d9i!z&u^Cf|>=uF|4?6W*+7&IvkvC<5_8avFI28uWjH za03sH_Q5YZ9pq&=U;Sd$7@%yW%tp2f&S~<-u^Z^_;VOUy9GtibMLRSO%U-65{o$VT zN=6=GxU!GBSp%A~|KQDXk8_uVF<6I>8V%?x&JP~e`}USgb@_fiovC8DO6%zae%>!+ASgOI4B>)7)pU5*3g4ZAmMvhMPT1 zp(kR0Tsk*{H_suMeFL0YyEu0vHH6EyHrS)JX{27ib5_|-e;;7OIOI?;bX1FibII_OXiVRYEa}+=` zW#>v|dNj=YcHzTC)ef3X^mT7Z$bFnnuGRYoI7bS*tmgU5&whz4Oe0jgzqj1PhN}WZ zfeno}0Py&~?cC7nf0vUUYlpj5P{VwBo}{K|S|*X3xloUn}hwO|_hIgzG3W z^P`{cGcr1tG`m8w9)0f~^{h_CbUzaHOLEcvyDjZn+CcTl>5Oe*k2c%COPTdOz7uRT zwe}|Bm;F|sv-vYeK6)=l$b_qx5+IQ#L?lnfvjDA^-|?y9A0ab-FgJT`em5yZ*Z(3i zEQJ6!Qla(cr)s>zaxZH4i|=$VJM>DTJ-l4T{^kKs{H(tnoaBPA5RLpb6Q0C^x zDjHC~R&MS%pJ2Iuf5155H+x|8Cd1e;c<+QRO`3FW{tE(FKeS zn@R86hn${?!_3`S%p`x{XSOl^3gWDR-hA`g#%U-p7_t3Vr?gpHoX_)Rm2T!QSVv2| zG_9q=AQT)x)9b@y@9CK2Wjh>~7r}AoICeqaP{r38J@W^T$M?NZA4}JkZo3u~(Ophk zVZ)e5$)2JI^}JO(=~;(@kUgsdSUl+AozA|#3q>|_02t&TF!LYe|5ElH0rW%!KH1UyqqdgF?roZx=!=RcnxOeNL z;D`35lzu0%wZMro#?K>Oo9l!pFrrhBLRAx~hiAP0_)d;9m=c^}E`SyA8H?U7y@_rL))p5w%W)m|%w zH$*UP#dqrM5EN3vemHGJr3F6`*eIiDHv4*SZ_8RKe(S%Z~eub zp!gc@$;J4*FGb<6p=Q_HeYno>pohnN^TueX@)uQ|qeSZck137ID!`aez%FMEErXSkKh>+lGC2U@Z=M%i|h7AweJnvXVu;w)?JY7#bFO;UKzCg)q(jnsdlQU4b4Ey zp{~KRG=4wEx^V&kx&8VUkwt$FK(4?tf#sq2%m%7?l(YG0l527~(T%R}dbl?bJbJX>Xgv-x?mG1;3Y`Bnn< z`Pf*)i(gn2EaYHuA5{n^dlE0Zo&JE~kX?7Ca+tn!@+8XxI0#z|=~H<04eF&mN_T(+ zB`X!`;1b0#m(Y%YK4QF{nc4cUa1Z<;QB;!%j^-9EK&a+7B0{A z;FT#>Z$?+6zX&^}Ru!;lQlCw|!p8`AXa0peG>etsm)L%G$kAFm_u=P00lytKHcgZ= zPzluCM(1D=LN;)--sY9MpI+u}x-Fx?p{vnz6@a(N82kXvs#FhB7D1VkY_I*wN?Ng} zy0L&&4*S6UJu?%h!v+em3sx!nAj?Q`j~ogWQ#>3rvy&-+X<(?|w{}jJJ>CE^T*!=e zzv0`TM8#vgWnLSEYV#rm`Gn@;*D_RQ$O&IiI0{XlGm5+7cBAP*fnOK#x!T+GtlU7! ze|b-kg!~2)NFK&HK5*Z*LE)c@^4#hVBB^NiMxVNOENSyMKc_XlFY*#aclMd~?(~aO z&eP#h+?Js6fhSsz>bl*Fg)`X4FFd^`2W{jbNZ$gme0%Egcs`3gYB=~Z9k}*_-2gj9 z(X+PQ`PXU&XkuLzLYmYsVV4l;8>235whS`M{txz^?_4y3#sSiXGfX%vy z#sV2RjG?kfqCsIu^c%;{a~1z(o8bz`{A_;pE?=JM2iPk(je;8njzac>78O{RHd{ux zSlXywVCcvFp_2Ts`?*30&pmF&e%DUjc`!c5sP7HQ-;B?APXnwwRW`ubfodiGA#4Z! zHnJ*!_DD>F@A{wyVSAL@?BKKS{eWh8 zg+1=pt&Rb3u|CIY8|ds*Tqq9>5~MKt^8-$NIpvM@erX?%ZQ-l5dp5Yy6WG0$2J*QN<^V!(Ri`YbZ}p4q3TP*c znMO>iM)iHCp{kcwhF)DEsz_Pb4#4xD`Mdutvys;uh6nk2x|z@Nz;n@@&!@C#ohyuK zz7pmO@v>TnN*pe#22%CQx;R$KkdSmk;`jWJEQ-tF1)Wpu^~g?!l*Z>AeXcCt^nHp* zP+2y1pM}x2y({tdI6}U>8)Iz|hkyRmhVnZXldj>ULC3w@q^~lu+D3b^fpoQ-3_e{j zX{WM{%X{(2c#pf^$wDXSY7C*JtR&d_mW0I(Vkc2+^hK0Y%G?zdcfoKr2T)5v)AaJP%?99|>8(z*8yip4HFR&jH$?5I(l2 zkIEuKM+T2s86+laFo)e)#!~Fsg>Inp7o<&JZ7^*-xQJ z{U#$CyTyDc^(ibsR5YL76L>XfnGVyNLx>}z$QwNr8NfEPjrCHgrDvvk_JbGukF!Gk z2TT}dNL38O?t-cTsRoa^OYiX=AZ6!dQWZqF;$0t~CnH$JtDWsB0gwpdHQ>)|^f_AV zFKq@N4ip)MIrJ3``?0F_5uDk<{d+Q0!YT%MeukBY>aN7`qQ7rtLrlcg;JeL1&P4$G6>x6@B$^EXHW zM;+Z>h~F+ki|#=6hhmaK?7`^~)zaumh}Zq2KIwfR`y+FR+8ALdQLlq&TD5MzpI2}- zQ{kgx0zYli_XC3A?C1WgVacztY(n+Yde1{4pJ6gr@?CYZe+?EN5@0j9As38MQh!QW8MAj{O`#<#dNT1CQYEyqi}^I=n#hC4%3sH`Bw@A1z!ZHQ<_6 zvxj=Pg}SdI$6zM=O*iTpfudAg@>6bMzy-Q^zAeXo{Jrvhy*x6<6)vRvt^W*-ieN51 z%d%@AHqqb!By^(Bhf~O`{WzzQ4Z*}@kB7FTi%Y6BvtZK?@Iq(y$JtU`azSu?;*sP_ z*d)8c)Sh31&!W@J=1(Mx?(9M(NjN#wPN>cv`iRgcg35Z`-dFCIP8Dt@btJfbyn91H zg;o7q=_(1b7$tI*JNg(UxF0-DD~J_Sm0lJEsCdcA!9TV7TTpw?(=L3l_w0M)Tf|d> z+Z06#BsNVcsa@|^il2q#{tgx=Flc8FNbzoJq8;!AsaWMfw|E!qS^w1OIf`yX)69&G z#YphywELhyQdbjk{5fBvC6H7ZfL==Sq2TIQf%Y2T3reKI)5M1lG*9zf$Mf`l*YVBq zm58S=xa0Hff|diSKEyw@7&6btb&&-Ty)?}wyQ){$hGpM1=PeLF-h1SlORqx^63`e2 ze#~u(!YJ!FZZlK9_mLz|bIU3XTR#nnxEXWSn@jK0qm%)SHP-|#Q) z%NVtCB}?jSRk4oPz*~3AUN-Z=HQdMET)V=pU>|7lO8ZyP{VoloXzQUlvv+EY5U$G= z5fbR7Z9Ow=)@9QmM0{?sUabB;bem{(EDN=tBnH!;niVakUU_zK($veoThJWx;&3eZ z5h|m7D4qB1@C(B#{>ppX?OM>vN4T-hD|R9t&}hE+D#76m7lMJgZ3M{aopb0yUTAOl0z@LDIRtGzxbu;U;y&IZ1Po&;y)-lZ={#sSmdmP@H9Nscqu+~W1>Ju69>3d>uuym=l~TT!&vL(w&^3*I z`afjBEnuWT`pkvOM(fkV zr40A6pPX$s z+N0UAauo-T7ECckm22VY*)MXX<1z(nykG2eVqhPL5dioXZJ#>iJX!!F!4GJ<8??GG zpU3EWJDD}^0~o0six%BsCK7R;*1vVC>0wm97HxVLssqmo`97Lh>6aIDo_?Kk3i*cp z(Ezaj2-&y4d_3WhD@KpK#Zc3Ck9~ZBW0xQ}urLkG%Y7hcL9iS4x!-`A4sTd_Esf?d zlMBr?SsRsHFRH~h93FWM!Qc{AcVJo>jUCVpP?fn)lkelX;%#>!4yaTzhlQK`e z$-#*;nOC&EUfIIg`w!L4o>({SPq2_)b5igr?|HEx`q`1LGQ3aAZB@1i?O=_41SqjN z5%1ptEQyqRBRPc=%bpghU#xRX!6)&bc3}CyPu0!%brgG zka+l-KA+A9dOg9VAXov~5mNhI-ThTMm!xNP@PFKuK2G!y!`_{2wzn37#PcHcd#A(}SmZUB(C4+X_HkrQ* z%w>Aw39FBD=~=~F#|9p6_T!RVr&lp(>LHS8(!#Zn?-J?Jp9dy13$688N~;39B%?&13!ras1}gu|Mci{peN!rU{+CKf#*@ zZQwpX9zrW6R3{CtV7vDIbm}(dX@NCLlf62kG64)7|{j z>B5lg3ZJpz0Hic_Sehl8rGZ&XPH0s1aLx`ywu`gS<>ONGsmQz#)I9Ko!jc!)Sy| zMk{1&q3dtgBUziKmJqN5&P8&+Hpl(AW*!;^D?*_o&W(rha-SkV!FvBedal4i<_rPI z2HsWlSUvO`>vz1cP$F|r>;Kxz1i9WHt+*2=kRd+7aD3Ynk6*q+^e708CIgha&uNt8 zNjJp!$Qq3K=L0R(2fW_n_0r9+;F0J+MSz!CrRn)R!Ba@55|F&Uvi`ZumQiFEml~HJSi5;S&;CFo z9}I8U)JIignt%U(e8nBiBC1aK>~iyIgmv{aGoK1Q<1E@K0)PaR-$lT09dWi>g-K zq4?g{C*m3M!xacw#O7%77Q{?A`<)1PZqQ84cMaD=Yoe*_6PPoyGnT+deVgnbD(G#* zYq;Z5#x+h;ya{g`_gwV5^0uJSoc zR?^0xb$W3-e_*;l8a3e{uK$QAZurW@78(EPj6c|k8%(u^G7pbmJ4BVVsXwHt{NOF{piY{ z_eWP9O#hiJEBNNle&=nUpj;XST@=S0!oz*=o-%|*YCVHayPb|#tVFMCaRC^_-ddz1 zVTPO_`q}Y(D#@ia)7>s9dnz7^vIWw|dDLF-Fh-snLlARS7zKqYLP3>J&m?fg`E>*C z70YtJSMv2LK86!Eyo=klq8>1ga~^Srt#KS9E%L+favt3Fq(T7s!N-ulp1>J(Ig%MX zC3sJyZ;9jf{gwZu4Yz(I*tqy7w4LI~0?xeuP1cF4x1cp^hz3LK*ks(CwId&D2?HtY zgY+OK-c@5?Ku7lIMDEDhOpzIzT?7xh7m*M=cPlxcJeUYG4DKa>nSeyS>QFdpHL2K1K^lmpPvsY4KG0HWVvaGf@-*jEz$J5*8wWIMU%3XOF8+ zy$M@ z{Y)dRs4s4>8}H80QcCxAp(QJN3GU03&me)!0qY7NS6{Q4qo5OY!}ioG?`gh_{td^k zlHe?6Z!ar?*$VP};kE~U>SKi1|A%Vw{PR|{6xQ&)H8BLJhIG&pDJnW-pzv*3O49=f zv#S|V=p|J4a9+W>0JJIiSEwxb3qaeX?uha^mGnR~QNLj8%WkA=Z`6Pcx~L_m+G5V# z@5W(O0+W6fM6`nTt~a6OEUJq&;0hHO33Ix7&$7wBbW0&&|Kh3OmoF@HkN(gf2s*fh z`J`8_)7~d@KmIcaLC*MVbpq-N@eG&P+Xrl?rVC~93Qp0lx4y2o2oTO=YMTr6Mk&9y z8uosy9PfAAujri$v&TlUCWyar%5O_wBW2RFR$g9{da_%bVyoZ~#kpmheG;hN3y=V< z@f2MQ;+1C8BIDLkgFP}V)}w5oxp^8&irGHg1_hobB@X0f*krim9R6#xKiDuf|BQX- z#0*#RsSYt)LLxAh;Q`L0k@Cxrs4OP?1YQ+-{ZR-*eC&gcjX_G4L}N+ni)Hh)_|#o4 zc{(BGgZX6^%=C2V#t&dJ4LhAZ9i+|8xW!JfcU&a(qU#HxU8eo=rpS&wjaafy@q+RK zwzV4bcw9O(x%_UGzu+v(-}>?xbj8c#KS95xc*@hh1Bcjk=lA4aeSvw_^HgX$@eg zj1Dw*o5cpMl<_0YUF)J20VD8$ej@WA_kAXO%HQeZA_h9Idi!|CH_rZ2WB$#D2PHgO z-LXCCAEVpNhSDUc_Bz!>k&>9r5)Y$zHZh_{rt2c*S_(bZ~RjH=n3~LKk zJ=XN3GSu@LFcH!yx$h`M9YK9hw=;|h*70WuqIP*Yu`Y%8^yZ`4nB|}7G2oo|lWR(R z)mXSh^t64sz9G@{A0M|&;6;|#^>TCPBhi!v5e}$eB(nma#{iJ+!__pd!mZ$8RQ2s( z@&cyX)$oNOsd8Q~k0s>S`vCOESHve`vUMenGW8Vv#g;XvA1vp@E-(UMrOu7Ig!V`yITbZGvpB^M+*cRO5k-`cJMN~pO%7mT@uk206DOiMdrmR1^B2TBQ;*eJcP+-^5 z-lY?lQA6CY0PIrpkbgSgkpSSX%I!N9;zTR^2(Se=KNGHOE2$Wi+A8TvbQfwF zQ<+b8AEx`h`y|N(Jf(OSAR+v9lOq0_=xm_be4zwR!qcGkP%A3q;dGTGn!M~c-Z$>G zS2J5L95kyewS83Ia}=IUWqs-(ikbZnciN`7FxP{{YUYymcm_P#LG-Milrh!ZHhsTn z89rPmD+MTs{^s%PEWu;Y{f#IA_`AeYeT1_0M#@qZIOcnhD>*>mBmeHrOmut1W<~C_ z6*L+D5=MV%lJ9&QG-fFS$Ktnk(_5qHBPL7o$8R*tPk%cN*-QJxc>Q|Q+ozRb?06V=aYfgs_u+~(^nFarTpzZT4!bcG?;ySFcy z?HzhM#x($yC2vDN;Fs7M!%X*T>OdTUbez!*jj=*Me#$5EN9{^dh zalWH49?g?=v;I2APp|XA2@d?1+=Tt`sK;eb=c$U^{mu;3yd25PT=Vl7%A-Di4a{Sr zs#h)eH7Crt1#>;;e>~G>&|{d`xm5JgI>?Kk`tLT;P6?YWT5&Zg#$V!;ZZd_n8y#b% z4PFg@QbD2&SLLUu?b~T5z;qRMuCMsJ@}XTjxr<_^MUjwy^&p06-* z^%(AoPL-eD*(Mj?<(*TZT$R;3Hc-PBWkI2W`p zgsPFJl~&x|Uk3ce!{d}VsWCE+fOKNe&@{wim$^koi+{9>wufNjn$(i>=m$7{gZtLY zwkuM5DWcSsPg=<1ja$%sV|P8450CNd)zLmjtjTx!vSbKW-*9T}Z20|ZCgabc!14D& z$h5f9hqL`Idq%%z){mZDlR8Qb2z5y}7-;!I-RLa+&Zijm#>An%k^*)+n%>dhO1wRA z=|BRG9jSdxYZ%AHpc>+J1-$qO`aKnE^(F+Bnem0zGjy27U}b!r`gvEQaN%?6cnOQA zh|UZ~@@|wjl^#7G=MY7zPa0%L22Bh`e@Lr)$dfCHiLLFbbg^PTR{;*zIiH=Ka$0 z^WpS!@-^c0#6T>pa(|5WxwZ_$A;Q;w2lA-_Fb<}kd-v$>l6QqKn0sU+<%1Dhb*hp< zgfEZ#UqL^hX=0DqPrwB+r|fn|W!Tr0eb+UBWc!w(n{sx%=-qY*M6T$ z8S+(dHv+{=$9WXksXE~A%eD&)2dazL!{~*-K$ly#OOfdhX}u!BLsxdywZ||;&Ju{x zif30ddV>vN!$*?ye+H*sflEgB!0n0s=x7gv>4EXSq1zSv93CFE$E&dTJS4(>yrB)_ zi|x?a)Pdsq*{rF`Ohf^L~FICRZ z(_WX}!^A8B|^mFM(zl4cwR@UWV<>G_`bzc)5X*Ot^oH&WKno9Lq;N9q#ogXn+8%)lByLc!HO& z_&Z0Q&7A1$(iRFI8Kkk}%spDiW1@ZmY(N(R$aCMLdWo|AuATU4FH@^eHb|nD0u$Tj z4sadEj}Ec3wix z$mbE(bA|XR|JoUB0Kfk4>o@lzZy-1R-kr_WaJ?dTHy;$8sIbi8Jd ztb-$hlD#`7xhEUIbEuDebpDI+LEfVlY_axKGSL{DX0Gh<{e+Zg$~=J0XpW(L=fIyI zXfP%Qzqj}r9lvS9>4Jc0SjHt%-(6DJ=)|Vx)n8`fPcDyN(Z>=Q4DJY70pVd${^<7k zNj*|$?(fhkHp9tLzp&F4_glLY?jnv??*D8s2f^d^$1f1}k11U(z3}#^OASYcYxdI& z{bPmincmoM=zU0BKGXh_dVh)h5NHWzi`qWUw4=rMf+6k~<1OwV(I#3-2e*GeYY<$k zXS|oZPv0er3JOkqaX44W?ap!EhkNl>>#sC+>P4fpFinElvT!_CApJGnC_Bn3B%?=x+l5)9(jjA0y=cioQHk=Ref#Q-yX0{5hA~ z?=%BvKjZCnJULHsTHNhn?{ie)4f;IOf7g!x+%Hsea{kW0%APzt!>w>_FtfSyg`^Bv z(M^O#5qE6wrf#nvdpf>86(hlIeUfD7Ij`q4Ckci(qwuy@P1P`8_Xz_AbT)|ovXbIJ zhM*hkCiwgbxQ=b!$JTR7QmgfqVg>sOjY|j0o<5u()U@AKj@}nsBTVO47!`OvhW~ND zMxS*;iUm<{$B&s7#ePbes(plTh}pPpkCnkM+TR2IzJ<{X;ror>rOW;a?tlB~4wC{* zsd3S$z8KQDM$W_gSbPu2$dO0vPOIjz>LapVc!XS-kh;r%-%LqWx^WIfSb#nD`K!j) z%N1`s8ucYPbwR+{PNwe{I>(dvNndV-$vAC!MPTh)mt6dfv9U!xffZQ1DR^ zxjkli?vFL~HfzlnPTy@`iY|<*z3FTshtGYCXXHxgjTJ7g_nCbTOdo+3ksJU4Qx`sK zB;SrH*V7b#aE_JR?Q>HhX`egV&c8x((TO$NswTP+=*@(^(&@_cI%Rk7C_BkENoC_Hn6| z0H>{(N7bE(pSS8QRvL2B`5evg#Xj?(BdVSc?{L3NYmOE7nFuJgLOhWHKjKFJu}_j* z(f!}Y;I8#Soc#Bg%cL|wy)3^&_x-(r%@cBziFOU=_3e5>#3CT05yM){pAMM!#BJ`y zzuNFN{9T(erLG+|$ra%KpL;}0VF`-8G*a%1vna=5*u;?;ZoawgZ6G!M%w7a!(6S`# zN#7m^VvEJ!Q-dvr*{RLB@6aRE`ETR=6{Tk0TiSx{qv{DC?@f??Cc8$fR(@YArJ)=9qlkQFd+Z0Vu}72RED%cxY@|oz$%0df5Lt9 z%dly+`GOigBRkh=k$zM62BgRWDV_u_ILvkD>Vx`~M_OHz(CZ}By(P==iAjah-+fp} zZ)H5zQ2}r0)tokRYkQ-%%QZX4EwMcI1wVT|$HC&LlhBm)SC^s@9hP{%=T*xeTJXEs z=!;f7WXCi(U3O{^B{u48H$SLIw~deO)gUj@eY-I-NegZkG3{5^4|L(N^l7{7YXw8k zP9SMp@3d|5;mn(H3D_Cwz>8x(57G2gKvbk$6gV6B5&lYnhvmYYQ4b?7iTuT(M4*4X zqo~1o_E^gX1M-r}9aC6)Ly~gbFJqc@*=xD4CnT)M=ZK4eLPWc`=cSMP`$rq^^bNxX zp}UMK_d&DYbOWyb5~3oFVmDI{^ORb+&{g>gxqor@f3cpe3 z=m=!*m+$xG{Z7NjqbU$HlNb8cz_jWk&}7u~zAgGGB&k#pXo<`1>=yNO-luZ+dZs=0 z^n>zz^IHnIoIA*-RNl(dPonLr;y{-&I;y&S_Jz`dle6`qF5e}5;n_tR8E&d&d2B|- zqb={DI!7t^`T6tcGxxdqYel0g`JON`BMaBpUEaS6hia}@@*zIKknoDz?IBx<=pvI@ z%?G`;-F&O${;h|3-NR|g&_eAS3+2%%B_8y-4zJuQI8F-q3c}3!@?&2zwywvIBE+2^ zCxgo-;E!)Qk*!(_A~>a6{VAT{#moGq72WbK78Bvu72LG-x>Hv%hL8) z%hxBU{~*pj5BMKXT_dC!(*y{Tc7xd*Xr=GbBH!VXW-oFZTSus=wojYT?!+6SWi_|( zQ}SRbUrky3E-rD6Q6T+7yUEVI)z!x9@*dmM7?p2ZOn&-F&<3A={0>?_f{SFOid?@D zTX9ez>YeU??pn&x#c-v3-`|RP%zuCQ3+?pvtU)B%b@?{lF! zzm!ON1#ShR(hrlBWMr!ALhwKiTk5Tvx%Da^683lX?f+WIkzpfjE}Q>^6dze zoG0Cg*(@?`{|B`&-O5u-am%T=^*!v&;!^4ic6&ajt}s(87W=}*!i;XP1bb^WjILCI zmcrW>v|C_9C{Nt(BQ8Zrzunxg2>tuI;D0=88@|rsELhjk=MCD5kHX30zNvtk0!b%@O|)3&?JW)D~E*xaUftrBuyYNmmmWF$uKY3FVQco-ku;Y zp+|qkWSF|hT@katS{H3#lm~gX95_c-)BkDQtvf#8K0katoFd5zM8dfV*`4y-q7q6>QA4p|D3Jvf)tDA z$3X1oGlgNmyUN3xYJmt?YG;yAJU8{_dJjOZ-4%USMoN73tC&VP>G8L6Me4Am-)H1k zIPb>a&Q>iv;t}Zi>s#HeVpXGDxi^#EI3^BiZ`CPoTi?w~4i9vnAL}P4XtBM=s`Rz@ zR7HS$Yg~NR*?$J%}`_THQ95&DwaqbSlln=l}M!7P9y+sf?i z@eLt1d(2|9_@(#HY0=I0)7@8}|F&Z?{!32j}IYW;Z*YYepeF&Z3#ggm;?Fi1)hTY3H!!NIQc)%vm7C3r_>qj9xhkq^1rCw`i? zcoT&bc*&q0(w|)g#c9$cNAwQe$fUndi$fcSsX7S$KHa9>_8{$TpNeJDw!_$Ut&%s1 z6y6SFwZ2D3cN(xL>7j!MFKd{X?NvaQoYT9K>oqz#M1G!$X9u3P`9hU-VjrhA2s~ zPn%5L=V$KCfQbt*B{W$6^0*ExlilcB8ql{_0&4=;JNL`&k;Z+CvjkR_Q+dDn00tFf zT!5GxrRV*7Tf7=5JB}1uYi~6{CgGS8+8+e}l`(nf)ca-*P}j*n>}6MJ?H`YMTM88k zEVyIA-u~DY85|_R3y%p_KBHZaOrLRYD|;#@8$50QSF!4vJsMTE@QFvt1p}W891Ynu z{0#Q%^_MC-B1i+zVI6_E-0GPetrIg7w`QVKXJOk@^bv00_Laq z6#9VP`Kh?vdUW#l$;W&S@RczfKEbwAb%Gp&!hBF_cgImAL_55MKm_XIw3uj)shglH}lB!{OQ)g==EL!8rZ2GA0 z%kiwQS)pK&ME8W=(k?83pAFDmcycws+8F-|lCe`Xp#Kb=yFIpSG-#E}W`Gxlx42wD zbn->V(#QmFaf-0Zl~C6Er0_^Lv+IxFkQ_erC7tQ(kM&X{RJMf_nEg|yz8;=^qci8e zyu;khr`mnj;6?%Q_4Dgl`;Cu`cfGMd^1)W_{qI^O)jhTYjU$&vNRN`JRqJ9reed4Z z`2vr`^M+yC1d`7lr6fKTln*^n;@3yVS1%e}wo&0?=)vac)!)!DcE0-=h>oo0HDN;U zA?4f*fPp37k9ADg_CtwH#T8H;urVU{Qt}qQ11X?`HVz-vWsYX?9oY^Hz+ZxPq+@^` zxpaMlAYjQtPaze-rr5=AA-*V~sb52)_xg)dsYFH6~PXa1u;W{TV-N4&R3u#=t&&*;xT zW{YGPAs@m&miV(-f$6%{0_-=@oU^G>Sp&7k->Wc5&d=(RSo zZ^c#>JV;_1ilpt}(7%+&UR9;$U}Z}tTX1!&5d_E`p;?u&YY5b}Oi-E5?t&?D2bYEO z4|8(Zrc#z+XT$W3c?wJlFW!pO3 z=L{K|>2wb-A~xFI`_!p8aF-+LONIWD433^^r+zm6z^Sd7*B5V1WjyG0eym9P%#*5X z#Uz}GCF27KeS^pY?aG^fxf_8Otd5JGeZ+r|kyWs_wHzRM1;)O`rp%W`lfF zwb^3yIvhL)v_2gFSEy*I{sjS9)7fXW;I=q@qua-c$QSDJ$^w-SwEoSUIm#cU$C&?%CLWcD#vM1%sZ0-x(5qqxs%7d z^TYExvxn#S%i_NH7T)F0PP#%nq`~Ft9KgX48E1s2Qlf5+b32+&sb!#`u~*NK^I*M{ z_QEE)(v993j&C%xQ3e!A*8?R>Yv-5F;~aI(Z|NVZc`4!5Vus^_fb607h>r%S%} z!g!s;uVi~9Il+HoFH2wEXnrK3A%-tS&AwSLH%8jZ!#+QXFmS2gu3SM<5IXyQgB~O~ zeXmvXCZ4fUHc(|1pIeJ$WF^hl3&-I!^#SeK^(%o{2IJqgl23G=GD0^`jq*@8wz;tN zYKOjVp<(utEp`2QKz5in6iX;yfS2EEB7LyLsWMKy8v7bSJIP?D=h>S7cBh9ulKEVL zH2Yf^@t=%Tt|QKiic3+A?R!6c0?mXSjs!l^1F{DbYa_OSdMXklXsL} z{vxus@;u%_PoMRHuHyTZv`^F^sI&lYtTs7tK*H>k;@Cr8`j7_It8`*=k2lFZ#N@Z? zg)Y|d?@|MJ6I=wATa0^4AR@93$M1=#dqfJ`M~{l5MujM2x6!Z=%45pj1=3Dw_glVc z+%}DvFfm$_Ybn$&Fn2$<&Y#D$=$Cv8k%o|JM#j)kf)mtZ4~0MC5;S0^752waX!>@f zKjGrCbMjIym*IW6Du4@9)tB~XetY{m z#js_a{LbNC?bd-c-at#efH#EBz6~vZR^DXJiEz#Lxi-7o>r$&fJ6|g%d;Hnn;aUAc zzFx+0>*W5%ImXG4_wbEBBluJiXG>e>>{$kjwsZ7ApDHO1G!3^)(OIXN{em@zUpcj! zaa#JyE55CsUsXwc?c0SaBLUm-&-{J;!cZ_#%FmBFUrvYceYsTEVzcm|131|A)jcbdtB=(CuG+t(w5K4U_%;h@nD{*!?_lMr^ub*dYht7xZ3G~Rm5?qRIBpmR8J4#dQUO+LoD^PICvbMgk2;q+2nMn zzmXo6kk)H1Y?Oz_eD<&xuFK<|Ru3bmX^z&uibU@DYzxmrdj;%dnKS40ilaTHfCjGq z9#BFH24bEhF&%6tUKXDy#yml<*CXQvpUSW{E@txUMRXiqN`7N;bhD(&luIdAs+`|G z3ik4kSt&cMO?58u>t?5?=sOEJZ)k*b56s~$R4~`Qg^e`o1Wbfr5`Ts{q6|05df~rG zM7oU^ee8-+yyN>T*20L-A)U{fQAoBDM&bHF<3;t|1L7NS!-&MkxL~0az{85rV$Qkp zCEu&FFX8aJtj{;w)RNOY|j*}ZRaHhm_>;f>ZQm{pjyBES<{w|xl_a%w-S_xIWPQRbKA>Z?CTRXe$7rO>yBOLupJ^n7`X=JTDZ1$lD z%}buvz|XOBRqvC4!^E?C&zEc;aAG&t<@;M_&IN3e=kYU8Lhp<6RU_s8G!ms!=;Yg7 zjOKT_ziGQMK8b*%CM17fbgf1zJh5eXWlqHKvWHU2>0CY~-dh|50IT%YSD$mXNDqcU zJ3d>~syD|e)*K0&uh5semf1-;Y5}K)a!dl;K?G;{T?4vm`PJ?9Ds^~p?XD0A4e^z$ zD{y)uD%`7E`(bCQx-ifL81pb1duWF-NuG~fIy`;5R+r7=C*t@})E||VXR_cB!&1+0_>sut{=lo{(fG0wAje%z= zNjyB7M;2Bjljan(QS#Cm;F@xIwLh2 zJUs^a2q{v57NGxTBpn9V!dpLvxoT1i*%wlH~r5V>102@zfI&` zHnUGj0GkM=rlVPAIMF|XVJA=b&|{nWKXgoV446ojkUEX!-yX+58Jja&S9JO)_lRW7 zQMau%@L(RH4jd4_@BoMJHc;>S#?)}kJ`6mX%+*B+$ZT1r#}gjUws^Ul5C6izkgHdz zZ?VCx2#Y$t7l|~I@OTt*{pnu&d6h3*u`XP*WZG?jOPflZ)r18Th|&g_4vH1vp4P4M zg-f`*YO41)7Ki;)HMBbJpt{91fj^RASoecSU_GP!p25sqd^(FuZw(LD8b>DA0yd(T zL54T<{vGQ&Mc=ItpbBL`(aUq>;l8K1qOr4OfcHCl#Wb-^Mb^Q7!UgJ5Y;bZbTsVd* zw-AY8+*$wwpuL#lrW|Zif#}>#QJ4?{54iNtn~w>efM?Bx=YUa3U><%g<_d$gFJv|ly@caR^nbl z5@=1iTZ-7a-L41=epMZ2ses52Vuq!av^R7o`tPfuI~~2!AKfa=O7B8;O1}pvlaAMk zDgAigBLJALT(Gsk>zQaE^W`qBZQ13o_2k0M14j%@JnZxl4;D~oQ)R&NOk2zC*H_>e z2yo898E-V5)X~Ad(tCJwwPssp#C@%TR|ULHo}a6G(=pXaN4^;*m-1ym1@OqqM?v;p z8t4f7K+K7GIz+hjHTNB7d@gQiW|#@$?9lV3@btcOIiAJtdr@L9K_f6n;}gDNx>y8? zuavJ6&Q;tO%}bnMRXJcxhq=--M!${o?`hwWb$HijVd^p{{Q2kW3XuG8z?KXxbH~_+Fti>7(-dof>vwDp8b6Y!F_O%D_VAwKGln! zv7!z`2|wb+C;388h+ic{t|Oytz-ARspK~yo>!1GLE|zeSs-1#3e!JFB7la!8~@ zpWh^GKE?UfmKR05#!l|aAQX+zd4h0uKInV=Uv1x?qiCjoQ}liP+@k}M^(b4<_smmZ zKCd+Q8HJ}r9d4h+Le*r!)>8Q$5#*@N7q)4#F2-Vq3jzZYKVYZOsr^Rpxt58QWW)8J zj(5mV`tO=>dZzO6`=e+GP}0GmPhxy6tgV=QF0ZC$Dd_7wSSneR_Sz$`lfIeut&iIi zt3r|F>PuD*&*pi%*pry6HS4_AR$v!buOn?~o`qNC^v^+B8t;zDGWv}}R04kB+jOm{ zJ>PNaq*jL^`roNl*wW@P67e>b6_EQS?}L5uu@K5VvYBSC`av2$+!7#*{pkxPhcT@vb<1` z>4ZBvER@+?Ojxg&Gplr!83{~m%5@=JY4L%HuM>_ zvDRPFHG5nh;%$SQ@TPHoCCBwzJ@8* zAyqob_s|nlhP-+|ax}n${*5Y(3yA9%G^qQDNHf5skz3&6;3emZ~3Z+>X1$5^WV7^;SQ^UO;tr888D(B3s%vEij^v;k}bTy6GIgbjAQUu>!PhR~rK4^*xMU5gCUQpq*R{II-ax z!u37OPQ1{`a;@MB#O9D)iOA^PqP!e=MUPsR2&m!9yKrAyjpyl-%l7DVhD0p~rtJAT z7LGi|9^fS!1Cc|}50n>5x5&9#t&_>-Oi12=V99tHwcsO3e6ACWPkZ5=F6~}wA%Jwn z*?56i%TDlBp$-N2?UWS+b9*1rH+}OK{UJ0}-G?Kf|ZLbft)4bKB zx-#}z_z6o4oOr@?T7a4$sZpqHeZGQ8KJRPF?NNzlpQBYf`LOm-ij8O;yFJrwmD{?c zXW4>As&}#xQB^tukW}iP(!n-LdLIPoIRCipunCHDc7i0W)DX2F?ZwYNu<5L}IfG5@T3JYWAUy#u(Jl)3SQ4&{b%hH| z_cN*`BCYRZYFQX4RNpp(KJhc#m4jN~Y`&jw=k0Q;ep;*OPY7}bLi=pAPe)j8{cG%L z(|DsL64mVQEAd+M5YD%d3*eI`?-Udj$fbzE$FjGnowsPuz1+NC1|PxVOxYw`I1Q~U zKr;+a3axu$NpHgO7XS=~jtKSEfMuta=X zTMR@P-9MMuewMG_YhOgz)J=crWrnvk4nDuVq1fNwkGd{VxxS|11I{LKTkBV&j&dDv z;F(m!9&#K@=%zp0WAuCp(>W}uP$>8Abc(Gc7+gOY9n7bdW~+PtTMG1IWVro3+}|ux zUWdx(&Zg@#@Dh#-G=vH57}{S5!}2s0*E9;8E-9{*Y@IPP8L|7_CMdK?#Tq;CO1JOG z-ya8goT4-5UWb=JC*M*Kgvt4o`;O2b$`jn~rpS}O{R*`jFZ%0E7pVF!ZfvWVW`Rcq z%H!skFh-wJ@Z#(D6`XG7{Yi1Pzt;<7iaBiK`T5c^6>ug;_(;QGlLOVs%I;Q(VvToz z)7=-J%S?$9ZD2=#$gX=11asKs-E`m=z z-p_Bm()p_bI-TwY1r~s^K@LMExj7Oq(FYjR{EyuTZ@3bb?)$yUNsSyXN1RZqz?H{KsAeG|Q@>nIbAvQI-vga; z;;=Au+%1BlX6&^I_SmT%Y_dEshe?)oQ!A0h~;Gut_)}EvJ5Bp?f=?nqX`aq%q?*jg!Sf2v+qM(o6K4i0G z9{KUO4v}Rt{L;AF)x9=}M7u_oETRelYhFQ2QIU&zrn;Bd646O*L-6iU3qK>(hwnsn z#@7Kc!~CV;SlU!rJul5K_fL<*9-e?*5xJ+KHELGRDWV%>eSHQ@KF&|5x!Bpm5gvO< z0GlcFl>{@3-tALZ@XsS{ll69q-X2gwu4XuHJU|JYcJ~fKNIc`SQG0CTU~a7rJWzza zau~#l)Q`SgQfoW7)nImqo;)4^)W5z|PTni0)78%*2ZFyPyM&2{O|+-~I`+rT;!f zhIf6X*#OSadkgl|lfGR#i14kt`9?|z*c$&~y5Gi~CU1!yv_`mfDI7d#!J|EnPS&%L zpX{Kg-p3DI4x6yF%eVW&4(v6OYrXGf;XJ;`-zb0_H~({;!}FwTxnHtXd@iM$;!P}9 z+qzGiwRpBbH9W7ZeQAqEVXg)&0T~NfPXh&G1nr;tZsP^wfh)@7@&8mwBUpsb8~sHEu~CHgS$?R&!d;P%N)a?;xvnRVDTqfpY|+)(daPISinh8> zUY@m?`92tRhL5IZ+(I=e>F4pbVW5>I_B2^eS_K<~+xo}we+|S04@B6*bSIj6rEpkn zvYhbp8~v2hH*Lvm=lr_NdQ9T?=${FE6_IQiVZJY{^ixQ^_xgoDLGC&h0EY_Wh1I@S zaY>8&wcYKMfR|J5o8+NR8#W-yPChcF#DqK-hUf3pHPpDL35L{Jy}pDecWK)KT?2!B zOHTE6PzLb{uv{ox`Uo7izrbq@v>dE_t;xwE@q%&s7S?r@ybLoTZ?vK4~NQG<% zKe08e&Ch#FPvF`_4jfjTIp9q<3Ec1+Sq-Ul=9CBNY)Sq zw%2%w`SbZREAY~;Z;T1?C`98c`_xE*I&0E5W!`Ix_9p3&{dA_-=l%A$?mPS;`r+Un z`Vg+SyxtlbVE=RGxRF(Q1sLGY<@kt&noM6ZM9Yq$_p3EHTZPOr&|){by+ds%nSRK_U`mL0UC1mSTFc z-J18vXFi+E@;L@;$bp_Jb@q)#~{uPTg5RYUxQA)UKD36yW7>&19S`dxxj4NA2d_Ci*$YtLVUOn zf1gG^%<9iGQZ=+6$KUG+F9d`M*F|R24j)$Sgu|jd1{Zp+xV~IT{2liF=p{_9TJngc zs}H-L!Ll0ZG$wHfZ*WjD*9A@9W#3Gq>sMGdLiKkfpRnWHC!^~}LExFKllKLhQy8Sb z#CP0MaGu{3^a3H;yL?YRvCpqZ)ppr;ro1nPSGbFoBNhN{^&qI8c%0u@!aQ|w~uCB zDUEJGhXdzocWs|+X_{3=95E6E8>^QU-2^rFbOMOKewRIFNYPdBp5S)*?~Cx| z={k`4DHN&2kiNgu4{jV^=sQcVu zjbD*+PYF1v7>98=-H%`%)(k$VJZYm1hWG6rq92Ri_i<58 zv&=CcU(eJ_(rz|NYYJ{npNj#o%73LS$i1)47TaV5xTOE;^oe|LU6*Tcj%)blmmV1~eMaHM(_VrZv9xWV8ibW0|*1OS05fx&;ajQ3^?(wr9g*84Y z=OJB^kFvfw^;R-NfkXHXRPsno_a82JjMO{xM(&WoJ!nBb0zORNVo|^9O;PzD>`DYx zUFd8Sa%YIO`0}Rw-x9Pl(0^T@)_GOHf9XKCVx8Ys=Xj{$KHG}>-lRYP^HAPlUpWa|YrDqDUq@D2zp@ux5gfptdi!rS-cg%62#Qy@GK57GwDUuUEfc zSt?H434)pH%t36-z}58H++$N)f8p!uC->X;&5YNELhHKn3XYD=Tj_nbYOWrCc-GJZ zW49XVJ5D%A|3~wyMxarlqNVB&=$;>W`5S2E2;Ba{-O}>5H^=W|oErTAAXBT^isE{l zYYRZ*j#bRL*4ejnEEw|&k9ZyimWQ)lPWDx<&!ii{qY7pK3b*3iL0WoAJuVn?BlW59 z`V`TADIy_Zqd-Zr;~iJ1bTMYRyTU=KFh75)3~E7!#{XLVtu)f@_dRyn?G^Wy6hspq z4_gfG0z!1J+&^u|LAJH01g;LhH+o zJA`hpoF9BAZORvzc=8sxpBnlal5wqTlrBv}K7zCU{KAm7;F&H9eYfok`ooaoWwTfp z&b+qA0o43EU#)BQ)UVMr+_9dscLE_CC z!ILpERQ?FFgvwT$3q5t)EqHB3@RQA^84SYaS@vT`Gl$2eDvjC+oL}dqvHeZm%ms9> zC_=7G`l1_mbiVPI=Duy;`fKw$)7d7!uhnwUmz;v+M#{dbc4O&};IO01U7nQ=`zi6# z$W|e&{xNLMWrxOL+j&eIM_~&s9Pj{arb~gN21c@btZxm&k7p@I#^! zW9esoVX9^7#gRwneWA1_*ibH@l$O@jVO5(&jg+zp4-EIt%u-ejrxse&wk=ivR_OYE^w*X#&&&yS$o_#r@kOk8_7)WWAf9g2&=X%Tj8lTxS>N(q2 zPP)qeG9CLDk3ZHYf1Dcbrt)9!ibr0C(PdtY;NZU00%GwNVTMtQ@||>Ff+8#(&}w4+ zPS0D*vto2pHlhi$ZkR8^rMG@VRkPc~C3_r~j_;Eur)}{?vIWOG6^}g$H5hdsBREhA zSpiHwcLe_PbLXR_TY-`{@O8v}>~B4QTZG@pJs7DTJX%eSizLhH{IkJ}=FrAm-JmL1Z-EZ!tzq+UQ zM}gS$(o}rd9X+}$zUwtCZom@C$#0PMWD4AlXgP3RNj0zQxpyTrE z7oPXGM6c-6%-6tvSckQ z5z4cjVFi^U@rDxt+RKl>4+8(l40hlCK+7x<*HxfP?-dYKz{xj_+>#AungQONL>##j zUn=`bDqE)@I)EOq>W;|Rjre_qpW7`X;E6jk*f}GehQ3q|RS;VuH}68hilN&&l4->C z&1@s)3{ZS%f?%5M3O^z05Borw(P7F`+D))QGsB@n;gZ7S&+e!7P#zEKU={Tg7(_0@ zgNF1`vG77O7DS;Mw$eD3?+fX5`lmWpcmp>>t*pmvdvRw6V4MPN8$p?luFZEQ94H+^ z7%SF$iDS39ZBLJdzKR|C&IUyY<|ue(z!jAHX?fAAsPiXpIwlXoxOAtc*vF54;uDAK z@L5$yDE(hL&(&UpZsLG5m9`PBu+;h|{i21hP-jdAy~Hf(Kp%mLYmbm<123nx{W=`l zADNVL#!?(1#&eI>Q3G^zObct3oaU@|9_*2!YWoI+jKgV`U8 z;VG?OYpV*K%|N~-Lh0lr**DNWnNg>oFJFUGzKM|IXMcfsYP8}7)&)N|{kB$Qe%*aq z0d3@ObnVm9XLMiLx{tly%+(%E_aIJC-!>PGuE6k>PVUM>*A$~wJzYKR3Tw?dwlTT$ z*AJriZm-x85gy1rqmS}~@B7=9#Zfh1@6E=%KfQuyWeub)o$eBQGmhz2p-*&JPpG2G z4PrCtcPQ7v8Rj8tsM~&}o^ykEtWr?Om(MolVn0{=TL}h+HH_3z(9=pq@cpbC0sSr% zbk>x|Rq-L-@*lGK3lJG4m%V z32vAAA#d6T2aKUc!aeKV%4Myi-=!Z{r zfMwc@YHtD?wWaGP_>oFvB@K&&dZ=@@b*5Q9(MmBwFMs*qz?r1eN}0EQUQ%}4W_R7a zQKatz#4is(YL)B*eI4p%WQ?2s?3Sot=;emI)&uo}mm+{pF5)4My=MX>e_22eTSy3f zv)t{a7hDnfwEq3WKzWPg6T zV*qiT8`K-Ptbxzt(x{P@arb5PQ7NCvgrj5tD*5Y2p5p5%fC%%LKNH9iZ)f)|Yle>0 zqw!bRdp)9LqinU-_LQ9^f$>rfYj{dhxc(T**VxCYN<2X;&S1(oVmXo=*a;uO7RZ>* z)j&BH%DYCIxKO6Jd~u(fh5DWv!Zz}ap3yr!b8N<0G~%CH=&j?=x@pi)d$h*@i!vJU z7>-`bcC4pgcD`@t>2qyR^@zQFMt}vju)P2{vFxRaf5_GBTUdt?8kZiEJu-pwDZoiQ zniTA`wXlhMhyt2M(7}V*823Lv)55Y6o~FKHf9hzP#}V?2Ccd)Yj2)V%-R-Oo!*;IMsl^zykL1{1{V`&|mZ?LNhXB-L1k5WbaJiJ+`!fH>m#PeJXQ zJA#Kp;QPtxVML@$+fw=-*m{rr8rVJE8U&wPz?_y$epc``NUnW5zSPGUp%sO?eS~sg z){J;(lhi0MI66|GdRKvnyV8`&=@*6XM(PwTx$Mg|Cwg2f==kj{;D^E<9_Xjlz7{}Y z0ZcUU(#QCx@LX=mVU3LV1XyYypO@}b8cqp1M0`=7W2uS({R`f03#WwV^*WE|M;3n0 zjud-0sec4??NZJ2-giz{`_n_ds@el;)P3pSSAzIjkK+{2poFI5w>up_48KwE7-UKv zrev)b$mWo{N0($?u*^i)yC0d*ZVtb@c|EG~7Q@=@{5UFiE17_exdUIR`36)c-{4j6 zdrZl$KP|R~Y~m5dL3^?L%9`$*v+-6u8lee^2#Nb=1&;^ZGb@(v5_aBK1}WyrzR)}y z*H9;T5*YbmM2C^udFEpX_1y2UTkK{$1hyM!gU*k+3FZVqlW}NS570si_OZX51#CiK zB?J%-F#)kMiX&VJZrEw)F{>`4f5ChoQEhdtwa;&lBe54t#LM$e7{kj%k>c<(uMh11 z_rVy5v63n+MQ5*YnirlFtcB#(QsSIVRxYmd)-L=wy!Mis#1@T&oD#z>#hp_Ee(Dvl zez!c>V-34y`4aAK%l&osE~HVC=37|Ii~Sa00{&F(>-R8Zy^n&`yZXQ!sDd=QG<93E zl)ucY8e?dw5SSBkb3!Mnb4;gM4blq!bxIHQ43@$apGRe$EV6p{TNW~peqvuMV?ma& zFK5e8j1aPM%zioGkq(;nhg=hfoQ6izu~l0)$($uIQl(=nJcaHhgGqr>j`d|saN}2m zeG;tpI2!IFeD!=_g;xCx`IFFJuJUv?jdij13;Kc8SK5ll>!Yq=b~kCTN^$d9yY3_6 z;QrJthDp~dpH+Cp-;e=vE3>ey<#%~qCxn>VmEP<-Um2f#eG1>#xPXmC!NMD!u_~jX zL3M+<;m{(5Ia-sRaOvSnq8Oo_LbB=6p(!UI=5@Aw|2iZ95aXuu7({0~e}wEFBuT{n zErk3-IBZ+fXL9M7YARc(%}GQ{`KkPI*IuiEnOlfn*vI8dl>>I;0ydnILx;I~ z+Q*K|zwHen5PuSb@fn5YUx!8HT@#;mxtV<|3U5qLMqWicn#$Ptb%Zeoe2E9f95>M$MMzMZ;kICv91BG;1Go;cj5i|V(k37Tg9l<)0oO< zaxy<4Qlf3B zQqyv@;I4BDUwfcC9u1h{3^#lysaP%Kq#5l$Hz;CUojd1 z;N+r_1{itw!}DQ?94)toNwUFj&CgEy%Mw0P&b+;jPG?2kAwfz(a={uTSK&mwTR?_& z#LhE=n-6+Ir8=n&{XoEIGEwfv@AA9((jCTFBk_3MjUzv)tsjn_dEJP|6nHY zyzCcDe7|#29pgHao~o$94ZKQq^viP5bi_xI=KRh&NS(&G7F1;hqn?c0OTfYA60Z-y zXFICcQhw9`^DD?xg7f15L%lBY~zq=csdCi(OXYBNTB{Dz=Lh$t@^+Qhx$?@+nNJ*|xqjekD z1fn0FJ-d2>nZ%sn9JB5=gEgsR++0G!S zqAS@LZN^e!cluRT>$pP=>)VKaag!q!=Zbb#EDl0SZxtG79cX|V|?3`fXlYdk){Cq>bIotL6O!AtJ&ag$OiyOth z&xLqJ#}p{+by4n1n8-9l^Og@kP`La1FMV93k~?!2ql{wvve{oW$<~P8ti*0o9+UyC zyAkK&@L9g)GNFN<3GUiX*b;A+c2zwlSvCC&6g7^m48T`JlEilRq}l@dlamK@-)l|r z*50r6xAqh<&MlQ*amCOU=-ofbmZz-pr6d|%4_EC#>z|^OokQDsC!g1xAj3KVE>mZI z?%^$i62ZYs_x<6^=}0i9?0EF9-S&GJYaGYdNBrB*FuNQ~V}lp(d7ut20v3gu5Xbh* z(3Rgdwq5S-dm8D-##pvJ)4xQgpWGWqM186JkF}c#H0X!QId?iE&(~k06Z_eY4i5e9v$yjE zJN$g8+E?BwK>xxWJc5h*xe}TvyAs^pHtywOz2c~tHP?Bos(m^X;B6l3Vg{B?`!rIL zq;B!4>DI=9!EI%8kx<-yIq(gRGzYhS)peRZ`4U2Y$D(&DW)WVr{qoFU`>gWgQNNmW z{x{Xj79%-d>Joq6$ACKw?+I>V;Z)Cu7Zl~9D+Zg+w-wGqKcqUDrS}Kx{r-WSQ~el6VLF})PThVR!QXEBy8h+WeDYIZ%-u0Qzj9kv+s$+p@~NK(^dNUaZ}^tb9L?*-XfL^ znU=&@sUy8$=;vpJnQaW&M4!H5Xd%h@ak^g4qVqHEJ!Jb)(&g{tpnzOSz{#&oYDWdh zpf)@Pi3$-IROLWi^d-#4?G=U*xRus)lvK`4jbGaqDUjXi`X}i{>G|D_dwd;xVyDn` z^>*$LnQMou7u?-Fg3I@}_bomnC*1f~QnFQzoo^SPESgQ3W|G|V;dxEounCoMy3xwu zT%d+RHRjsW7vHpjv(+=(7l5J^@p_*i z&H>L852Y|Kq0J9I+(+~{{*Z+Xj$czk)(pu}rSyk_kip}!+;26@2M*8pv^&63JUuJO z;YX_Zy9RJsfznOyI|Li;ZEWCG_aj7<{<0^>d_Bw7LcSY~YL79du9abm&g(F@G#=GG zog@D#y9r<>_$wG-g<8XT2|o*&WJ>F2lg{lt&loMrZ#nzcK}3VP=xpti3A|GRtl;mZ z-(R+g)`2Jfa`noEvQ;BblIr(ejA7=_doUa35Yfxd6?5!6u&Q|)i~6M*%c`gK5s1S+ zmV1u7^`L+p)A)SLo`?wujjoP8%{=RYIZyAwE9p*LZrhw-i{(7r8Q|YA>pm}seYr*c z8}D4%oGOKYpA}w{?3!C9Emptn^@|3%0#ZiZ0WDQMdTOeej)ZxFux-R-qePOR{eK^c-7N%+6Z?(^Yy=SF8f8xg{{hoej^hJB9^SPh6;DoOH z+n(Oho?k#vl>FBB`B^Xb?I4ehJGKORo+0w!`!&;kLbg>bIm2gF;@cBXY#P>~{UV*D zlf4=}ak`U@y5H(2@@U=P_pnR(Qh!RJy8%UZ$e&#Wj^Xsk-|oI*!MU!ReSsy}yBIvq z7nJGXSf6KTP#dZ5dC}kcIx7C|le9;(g6ro?c7Z$V_1B$fO=uYOI>Q&Jc0nzB*qKw% zLdu*7f~Icj$OxA2S4b)yPuxZ#&~2C)X|_irldtbJjOA_5yiNNSjxyzakWV!X)IS(`E zmn_>u+&QOWgle;NPbGz0GiH}0mgE7$FM#mCjUymQfmvx=O^c;!ncy7o^)x4psJncz zQ(fkRs!x%UN>|_B*JsjO^~y~5Ig@^UsyE^T{1#bsn&RQDaqMqMzShjBzF`{V>6>{; zwM$;&%-6oub#AsEgx?>i98c5bcTL|)Y_Wu~I=6`6K49CBpV1~_9_efPElR5v94=UP z79_+-d+GK|d|mZxw$tCm81k(MC^zdL`(??B0Ly)T-qy}(9IBh1S zW^1OXd^tf`sA>0fTR*531;~`h^yQ*sUykiSmFzd^Rk{G1?R-cZ%HUX6{KWf{-9}zk zybrq~P9~{)m@5fY8~Z3jy*Io8lH$tASn!vDOtX26r>CRl*&83HDix5=tSi#}`z_ve zoPh@0oBm)77BAD= zxs3;gY?hy+3Bs-NSv{3A*55G}HVFplFU|p)g0xEBnIb z_H%c$YTaTLy^qaD*ZK?X@LzXNJ%6a@QZ6t;qaH$PaPm~5WTw;<=Tr7!^tWs7 zq>#Q}`@X#9;M&rqF5FasZ_ejW*t;(M*99-`x6-4fW>MkE+mTy#Tb%u4Tpp|?BRGMG ziT+|;m^YXr?4xF7R{YsA$tz~5b!u;`b8jO>HNu|~D zOs%Fi*k#d==!IIw*POX4Q(t~#@$2^h<78wQ<3*a-+x-I)Z&^f}al4Q?|41^=4A0Yn z782*Ee7Y#*UMDxTvxQPmMG%YT4`eI~S(~r~9yP!bwqo`6PG*S=(6 zB8wzs=Dt<%(W218fSqEFjG|J7Zl7Fa7uLByFCXLLEg>ERCe4ClVL+h+^7QiK%A+nq z0V0zi6=FRFe*k$o>74z>;}I_XCdx5#iCYv25Wn=U^lUXNrEms!EV(c7o3@mefy4sn z5kpyRxEIQ~_?V~wXkWY(4)Z)^^!}=@)^i<+*%X}d@c zV)KdZ_a*5*)F(w#wQ&;DeMsMr1aGP5lMt+QC0E9eY=crLbuV$TuUgM+`(i#w3aG4h z+@7*5_T}=MDy=9#o&f2J62Fez`SR!Zh19GLCfLX0l+FK`d#YU#n8UG99zHF?R|4C= zv3@=ilwQv87hj9%_-IIn7ViA{#JIICf5wL(_jq3>qaJm=G{>ee`S?B&R8VjYY{Os6 zyYQVkh;24n_w`btP?)UDxIn!Af;SDsdi8LJPo3X?7X3ULf_w*@{MvSV^33GzSUHEU zhvq}i!i046Wx2R?EeqwZmKqk-u&nusTYKzf-7R&=y3mMUWqyEPs~NgttY7XD*IW

HexV(s?{q~ZxK<7tJrb;gcKlB@;({;^^E8&;- z&Jf5fzbIV1q+WKNFp-H+UP=lwoBj~jF`UfhZ| zXwnYwzfe|#^yhON?`^!?^ck)cS)Jr2^iBoc8;Mrx<>~Q!9I@AeSCOb@u+<CG%HO~KG za+dd{jAHKJ{boB;;l^{?L41#7BjjZtKkrG2Hj5Vs!%-S)ssu4p1KK zZ{SKjCFK|q@6x@RqCxMEN-Yvet$+o6W%(&QxHzBAfq0DEJHBMo(tf$B^l0roVA(({ z$41v4G@1BHop{Ibw(Fe~v;F)>%oeWS;C^6hm%KX9yB!fq@KZhVvmdE3kI)2-q(-Vn zZ8fiNkR=~dmbQ4@iWXQ9`0U^X6zI9|jl4Mg=FwvJME7S*8duma;nypFKln&$rmFuQ zuXp(jJ7y(5vhDWrEUUdtKf?WLhnel?Fhmuu6RK)CO}AK-NX#d?@B^*2lJqD5(rKCZN< z=@iORxOtwpM~?VPFOz(|hjL{Q)^LtCx<*$QdaWo3tQi%>B?Hn0Nk-h zo=Ks>_XH2hjjbGHx)>NRiIaT0{Ln*$?JfzI1B$tPM3q*Ni zryyOCnjUSzpZ5sHMOqF`J^k8W^k<_tUc`?O$e+Xq)ThbC7VbigEnby>Zf%*H>BIDm98SbJcBwiMJTyC>mu$Vp<@Kfe!+^yOkHOain?In-QC?05 zl8&xw|B=Ym&(do_KJsOBEYhKvYcub8lx+gL>19y&H60-9d9NG~DVqCAsKpj8#tMo7)$NZ?_yyhYK84u|EOYgpfZrH`#rD zm<TJ?yq{N>) ztH!B-E4!6Dp#dRbdgiGnuT?QS*eivjQQ>wdn`dNgEUk}iS1<>lpp-Z;0? zEizEiT&ZA!X^q^Zt=hiM0LTs>>pVS#!yrA2ef6fE_@^-rYF`ZE`XSX(=1zABND!15 z#OQs416~)XR^k)_5cEG1o}{0YVki$HIw6Fx7thDJ8kY|H@ji^(`>!?4)(%N=#K(v4 zHLI`j-~6kHue$I{?rjws>E_?Cz`ZPq^1)lFCld z@BC4CD!_FqHrC~jt|T!qsk-Bnpw7JC=Xg7^a}(KNPExp$N6B8SKd&0hzk4vWGY7U8 zmqn@xn-#*$F4)a}%?C%+zU`{u~o2tPQ=ZaEU?>YmFu9hBQNrT6fCr|~A6PiejhvgWk zXRM8K&*|T-x7EbK9|C zL$c7S|MLM1TU!E!EWD3i1rtk&zkN>}G}s&^6r+Af7?v_4Ly(ZPRL8S)^`cDA$Oz3o zf3Qmz7{Lk_vSTsdpi|$7;9%80C!nA}{`z2f{^auSGKw6;8%FI0+c(W%L#Sv8bvt-e zhwa%BL{!_UU%vrn$^3V@y&wE_L8C{-m)gq@t9shc-Y zkfX9^VU)h0dMeECGB5MZr_j`1^=zwXgr{>2k`ruvTKTMTXW(svmoDm4b-647#Kbm_ zD)y;O4-?%|KeQHtsJ@t?Y)pNGq&d61ZY#D;NyI+Rn}Z*QZ@v@chTI>~m-6h%c^;-WyWFszq1p>w@N*Ag=y z;*CUGM+IY7n}0^eY5V>dc$(8xwk!e(j&2e|D}smlo&h z&e7vXG10ELz?@uL3z@sbN*HY79<&P(8avD*q2hxD3^ zNY$AdIV%tourz(273MvVSdrtE2VYWb`-7@xFK>1x4|<9?T#gI+=(R%gs74r2DqSp4 zdjzqaIpXepoP|D%T?SFgBbyytwq8i44QnC|T&urciD&Rj06DGgr!Pn&+u-t>&O2^V z*4O0(l8PN?he>)*{__g+T7d@4jR}wUkpNoT^Bv-h4fk)xFhAUtaGO)UEcTJ#J;I8rbT2pFx-?Ur5u}w zm7l||E>e&myuh2EudUz0TAOhg(JCt10NDUXOsw5bRwS4~rqto;ye9G~8Amjqswgn1 zY$X(>$SX=$KXKN?U(Jn*@rJCzN}At(0Q2JQWm>=!C=Jk-hIkfuPjYj=J=N>Jry9B8 zXVHvv^0LN<%=^!C`yqMiqy5G)6*xDLcZYpar+9J8?aE8gAWP}X$N3d5u72&qMiHil zJ@emE~{?M~n<^r$D)vM)3t+XwGZ?X-G}TseTW5D9tI_uOrhT(&!TFU8qUD zbnxx;Z^Ay#l1ELSZjLoZ=a&TuhNNv@;=|DX)0&l=7+^KGA_r)+k`<2F8%biH_KY-0ed%rN^W2?z!``|4k&0EdVlfq zjEgC<2?ua=e?EL#<2ui-mQk=g`DN4o#-VoC(-V(M>$^JyhGss_`!vyp*5_Uc3M|K2 ziIaP>|DCW1M{;$%GAo6e`+63YYXXd={kByElu(L@KG-oDGp-A#XP(miCa&a_ay~>)cF)jWDBiE z&8O_!vi)svOS{BmwLMxWbeX}X1tR{u-tHGH*y`ve>1_pV9P z$YkW7FPu(ATx-{IOKD_;I+2Z2cr{ei!?{SAf}`-wvDe^i#&L(*MOlFi#Mbh_9R z5&raq`=Ofn`TjYcDEleA0Z><>Iiv-s==B8r z|9Y&6^x?N~x&R7&POWSoM%i>#Kl#hAKk25f{mM=&GbV|FuGxh;ACDm2GJCr7soqTT zES;u9U!sx^r&W1WZkct8&&}Iw<0bz5qN?R}1FiusJb5_kyLSxACp*S16T!6vZ(D+Q z96Co{!ONXDeNU3m`|bi?Ql+7vi^h_V1^GMQF~^IsiA@Y*Vt?5K zY&p98gaIAE%TLwgSGgdb$iLr@f%REjYR5hVSuNE56CM6c>#ArHCo;JCSjbtk&*M6y zmh&>w_G`VK_2nM^++h_q`p#Y48#TqC`;3ozv3rM}-$(4;e;Xrg8#F$Pmasq38ydYi zf%rDkUM75@2#L>vS$tpDU!oq9I}7VxbZAO`_0xh(k@GTsxL2QrD_PLnA{Jx$K}AL@ zPk6g~WYbJsw14v3^58#J9~j>GE+0&yDUXZ>iqJXwgn8$79 zST~q;`sn4fgVvECwf5{xlpxC=rZ^3F#pk z<%PKKTd++yk&!PpJwGhRqT*=(i;Cu3^nacXWm zG!y2_$c|FIo0^L~Y!i!gf%t-6GC~Wv_Xi-!q!Q4P} zNBSo^6$vxqn)QvVR%*ojcq1hC4y(px(X552SxS$?TLEf8d3_-hhs(-v0_~=Jk4ux_ zrCoBR%#WJ$`!33H2tP=s$Fo?C%U$=(C_mCmu`e3?2fpzov}4t7HHH4KJ9##dZto&l zTp`K_V&z!Gi_PtV` zv(x%a-k5+W`vs=ma3VP85eqV(a6m_peZU2@$#fIDRR#nH_Dem?jgaSNpA&u3#-vJS zGs3R-q($D^dz^OWqT5>_`sMX<`+Zmo0a|#~eYo?7$25MPat=S9gncV?j@F`~;EL#k zBIROji|jlF#y7ekzrKog<2q%gzdYASN)C50j#KuaeUOct{eGNbM_X+U5sG{HMy9wF zJ|!V5cxXc)54noe3|me#jl$G+V^U#qeV!c`^{?EvvgjSsv?0+Pq@qNQaeD@m zzIVtD^71+VNb3?g&n6f0qHM33^{~R=&#+j`n(WF-#8VAU`_7Ce^~uNAFS1Idqi)g^%1A<9(ZVo!+;B|u+Tz~i7u2bz zI|?Qg#0-wIXd8$N=}!s_8;Kv7d&%kP5PkV_wKd|;LgIv}n^?(AFx4RiSq0BJ=g)MV z_{A!syox^%U@k0;4Z`OBCB~#s2Y=Bo>}I`Z&o540IAHTGBf7#6|9*fi=V2S_dT$ezfAJL*F1vv5pj)AtUO0Q9*!<>ZT5!< zZrH#fa4WXwm=Mkji5q(T@ubE&bOC z2;DnwE9rhwwnhss`+Q4_RF7;fypgAS@wIl%t*FfFy@Che3F>;M9N|D`sLt&RA`Jc* zVjjb{{SJt~fpPR;NAkNsx;o@d6GrfM;Xy=fj-RLl<<|f^l$TG>A@%+1^e`(J4!hyy z(pls!K3k-9SM~^TPqV>rh^$e}XFlWSp#XrwY|w@r2N)aP5>vBpBWf$$Ppdeq*~0 zK@^Uu-ObD{^ymhE@f!6BS0vvD&9(iX9y!d7q~6p5Rn*190Z$(^_d{HQXo}wZYDoa${I*x%)uclOR`- zk#%xR(8gr5RW%DLX!2smFndhn1ATclJ`K-!_shf)llQTNO*m6jFXz-a%FC?Cy^9Kh zXe@W-xso?bxiXW#R-Zier`thA)FLB^UH6=GCKdsYTwZ8jnxB0J3vHx2pB8zHs_*$` zR0FtHwE78e6sb0rf@eN|)Qy9N3O{y$S^VMx`cN40yrjTT}JS_zz|qY{ zaN)#BbJUA){pRi}zd-{NfnfsFBLk*CFEqne}vXhclN5J#|I{bmjrV)O{XL zXx*7Yzn5qf(u=?pK=3jJ4ggAy+gH{HWQEy&+pl_tei{7GcQxCX?q?u2B!jnDQ@V?v zvFr?4`W^_gAMXpw{7inQwP>+sw%e71bu$Avz-y3hPH7#M1>W)2sX@d0#)j2BJ0gP1 zl8%&4=3PS4MP}*2;cuyrJ4iOdOO!txm6Yb6^DHwnM3>2a;qKA6PeXs4=jjjVpi&OH zAgRX{tM48~{YoQD=ynwvOGP)Tiwr_BsQ7M{3;JR9yZB1O(W}uG98&uINMZ!G zETmla6uR?y~GSCRJ8V*yK3thaQkAgsffk#``QAjQ<+?tVl z1l?gRaC`w{3Hig-VyA7NXk*wRzR>=LU2EY0gN$=8BE^NKmkxfS_>X1e^v8npA#s<+ z=w`}oO9upQ1o6PxCAg{S<>2iXLp}R%ZQ4y$#dS%)^*$!FJ;HJz<6y7w1Uog7e7YF% zHTtTs6PZbYaAU9(Q&?A&3V}q$dVMsTT8<6l@W(5&``3xGK%h@_ZqR#oS0wUF#nE?$ zM#`pwRl+$Wrf&{*WzTjTUJ+0?G{$x>XZf`K{sBwDe2kw#|H}RvlqkvgG`c^JjJu!W zZ;bTC=AO-f`fkaMokwU~>07T$A-5Ez_0#%ZyV?Ws!KsiV@wt2%hk0J(klrZs%Mz!3 z!?6K=l&-DhHF!`E&M=_2dD9m#Gg^^v-uu=nnu@`t8V=(yK(u>CldEP%J-KnQ@!TOPN$R z3QMy&^DoqZ)b@-U?XTPA^^+*Dkj>?SMLtoPd(rHBJb?5+4>?Q_AI}zFS^ce?-!DKkC4cizZH2QKo!kRLW!&j* zC~VZ6_y8AL?}`G$rd#<1KvQ2P<#tX_31RtjdjM`?Mfr3Ti1FJ`(`A)jLh!*7d$Ji5>76|g z!`=b^K9^d(6IOc*Z_bK&|D{^TLqoQys~rn_HUiAd+Wk)Bp%{PIUe_#(xD79_4L`{m z;G(^Un^8NTOl)U;vyi!nX2pE~4uL( zYt%-#dM^r5Pr*$tMu4c3n8vW=bz%nf17+Pl_?~FQ%iM=JVr%iR)cQ3-M>O9hZ&|`o z5l^rH9|l|K{MFw-c+^M*zla-$U_RWBuk$g?&gc3>?g#m^+1ckvKU)^8AhH6dvob9= zt&RM}o#4e(XeuI7dTcq&W)Xjr66u1T9Z4|F;gcQ0$Dg8{dzSlUvr?}O z&zbzzYa>e)XA&Sp`Ttqu7yzzV~HU?YtQQ2M#u;j&E)`hn468j&XZ8`;7!es&EXD*}m}@g7gs>HDg$aK|f}7={N0n#L-K zVR6_p1SwW0ogsZgl<=$K;LvgBH@T~4K;O75r8@pu9x~-xg@SeE*gWFC9kHx2KENW@ z1i&V@(;DSNmFxr3%x(sgUknv?h*C>Yc#+@550l~ZF07fFE{MlBxLi)mS14<@nu_Ux zZsAMrH^Q4OJl+-Vo*`8QPk6^q|K*cI!G;+~1rV3K(2S!`xmv|}IxoIxDcl1+vmto& zoRD6;SAt1W_`1fZH!x8NxIMbb#mk^}SCP8bbWFvv0(1>i)nt#Crv{*r-o(Kr8ZdzzzX}afT6qJ^dM9{)>-2V9ESeYng+}ir_iU zG1SQOp7-bJ_Q4f&d8XyFp{1Iwqo`jb>D#>Rw{ix}AM`}&grBJ+D^(4;wz_s=C9~1L z1NkKN_tS)+9l1`MRx0XF%7-H=KYGCXyNrPR0q{xS-5UkLk3HTt&IPNQEcHkcfys`C z^S19N_Q}M+Y0}Uk$!=E&Nd*e%HjDVPX@GRMuDm_Fm# z;iamSUb)40hZB>C((8ntn+B439Qf0FXXYxgC*PnjR%Psp_7#f|*T-X;D!zstDt-mq zgMqr->S`n(Lg>Sp^DY)mo8YuG_rt^{?&UR<3Ps^mb(aHnPjcWe-~3OPtXXUTK@>+$rx@&<{!{_>-8@xct0HcIQ=pYeRYGjyl2 zzfTQ{NV+Xqyo?!({>3RBob_7_XK>2kM!zbDlsK$u=QnG7{3%NnH{G54K>JR&Ca8>P zb1jO3MVBDI((Tsl7yLvoIiK%%!!}SG*3u>9sj>L*O2xH}@*5*Gdr@>45tn%Cr}S|9 zi;v~f2vcs@($a&`whycGS$9nFC`h6idB%ljBkjrS`qkiTDxQWYisa?d8+55i22@_K zz7(-kbL@hQB4;P*3tkO%h5Vl&JjReO&*|r)S!!G7n5+cSuv*G!&*hVW)sKbAW zvXdU6CUv-rAm&n}8-4p~#P$+@hkKu=_XMC=7_*~~F`h<8@Uk}pWmp!p_Mr+Ne&LdD z5G@?{oz#My@m}~*uV@Dt^G?+{$@pB(UJF0%CgP4?zI~)o(0-TcL6kAH?%LIx(3md$ z#6CDn3ygRJYTE~u{C)qmc)ypG)SB+aVg9)J<>weY>Ukf_$qMw6!l6%(btY6GWjbld zV^;zk2~k@Y>X+aQ7ZXe_>knNp&Ley;*rv+4eWX}mJ!%w&)k4BV>XH6?-B*qN`sP%P zRT}-3lKqAxOn|)uAOzj{J37?;bUOYv-alPo^?n-0{Jn>t6dD5ez@vO9Z+~A0bW8-| z`^7B-W^$CVWvCZ&QOzw{AZJ68-kCt?6Q8Fm5T4B_&^mBCwzQ3Lzb%9 z!HksJ`yApYIqWRIgN+6@4GZX)N~G407^E#Ksly>%X4{ zPK|cVYWBQ*_to~BZeL3#gvFzkq)kwgaz6~)_ldz7;khTDfhm{Q6YL>|VYk~BKdUoI z2upwh{zc}?+wi*^k;BQtY_ryV8Q0!kB$@PK;`1(!Km88Rv_{dp696Ml{RvvKakDlz z@1uEN(ysr8Low7s!ok$o22dhIi{jQo!gaEJ|8Tk-;qwTZ@?a9#5cQWE_Tql-p0vhN zV^Si2sBGPzPITYH+|hc7T%%5Bm=Wv5K49GoeJAlfRsXtG_nk)(0Lu4PUB_rHKWM*} zHt*52RgH+DQOYQ?2$1ncZbsU3AMlHXojuzi?l=jUe`xnFTyqV8tj& z_JQQyZ{BNty!W@moC=^@-f&&Kz>xuZU?)Z*$kz=B_-B;s)I=RV<8-O^&&UwC7&0If z%$Ytr!lSY}jGhw-JEI7nV_&Uiqz1(VX&1cma*~qt9UQBge?QX()m>dsvKaya9E-Rl zp)fxDBPJI#hdz!fS#~XK4#~^tjlNpUcXg}D)V*2ZZ`a?-6-%8xnlAEvZL0e3K>6@4 z^57DWzuP|_sQ`LESPXj~N6CS^ZqMps2@eHck*oDsv7m|-Xsu8In*unHhgYYUe(gfe z3v=Q?|J=!mF6yp7EXQ!(r>XZO2a^~8V-*8p&hS^hb{N`wA-YaU-@UExse1<*|2$tA z)i_mZ`L_?^{LcKImhbK2JRr5CaH7QoKI`}fORl`%V8k@O2xO0Z)t5}d$3y>&? z+&Ay1oc6l{s@Kc1`5l5Ou_e!OXN~yan#WwsIe7vw&_FR_e0*mA&>@U_S;f3&SgU_) z=CapeAJ<0+2^)wV%oknCvv}3;0j{YF+Uk0BIFhqox=Wl4uw_tySV{O&ZS*x|TPB#B| zN{f11jT=7`M<#wiMTmBC`W*fl5BeO6elvC<;6!9ba|2a9BK&>DfRSHTA`^CMj6uBk z?`Znej5rvWwtXe;A0H6@Gx1U%)!A5nte&nat?A&bl9_$J#?lvPB5$pLdeU+*Fjgy} zTi#K?`UUNp^U?PHE~{UC$sVf%Ws*ZJZYZ&ENt<;OjX6+`LR?9=r@^YO?D{`podH@9-by?? zf`|VCmjKlh*{)w-JrIXU;fO_-Qi?vBgj+mbFx@!hl~-NnhXYPczwor#e9)fI=iT%3 z5rgF;PEJ#s=hJ~jVcwgsLLGWkrS+*R{St$;ufoOU9sWBU zkbA7$VPcs~gWLTDDzvcgP7xIG$+u8E9ku!EQU4szzw+HZQKuNWQ*tXh;_a-Q&lAVM z{)VJu)`GuC%OwVXeFmv{LXPk34F-7<6kgubHz;j5&zm#-ZJKU(_!~VV>a^D0h{4p^ zYK%t7?vW%Kc364{S3-Ad{Si(d`%pXzOJ!@La9P;mIUfnn`({ZnUDD^5y^byn>YDo% z-65a)t0xQ8;#okDH{zr5M1qOySfW*1*mwV{G2F?N>$UYlQpDqv*=US-3ohOuYBl(m zSXBD^MJqZ1aa(*NiPu%?)-z8(LLG?1hxk$}&lzOt^{2WM;X4et)%_GO>+Sm9%mVF^ zQU1<~^$bhLXHSBkv~hoW2<1KKtMzjM`g#;&czGtp1J+{=ff{7BU4O5|cKk=hHoVo` zP~o!XBlV&FSREypm$J^?_w11+!pzbT0?Zhqx*qGN%2o5}?wTO}h(tQE*&s}8{d$R$ zz6r;yf5hmhd|gfliz!nlAJ9JniNt#Z7yKL8B4JK|SAqlYBbWL`*td+%rMFL?6BugS~iLk1v`IsR`q%jO}o zZ_v4^70{)i_?6;`g~i16cUF7;pg#X3Dk#5Oj*a^Hx?TDv>+tOFQN?#Cwh{(xAciGl{H>_@9@@w(?YHqm{+P!1 zBfY#IT9l7?-Q9>!9;X0Sg#yX&jnQHOT3}>2hC@V@6W@D$<*LMotJk%Cx$4lVMv3LGYK-gAt-GhY5FKq2)!GsCH|@8MQ< zJ<{lSR?o+(eVbsO%ALT~)9a(?&imnn!$`Ep;nCQfXs)+m+O$tcMuc|L0NmB*@YKkQ z&_39dtkeN^JyQqehja{OR2gXN2Yx=XC7*ppQfE~R`<~T8CaGWt8f6mjD<`~MT1RX&2>CS5~#)c;5 z_B;HZ@N2|Ihy@F_hx|?rAXg*29NlVSP|J^Rqh_{q>Q^b){LNDb)7RjI4k z=k@KlI`=|~>l;gK3g5g%KCPWoAIbB8@Dy)C-VlJ~n#a-M6CwYaUU{SqrO1AI7^QysVqb(00Z-M(ucr-FANJ9- zZ~x!W!y;t9trV2a`2Y9m#f=0R0}M#d`e>&=WXw2E+SFGUlTTm+FP!m4p_P}p=WrMf zQg%N8m5@#eSUrSL9u@7noy|6do)nRyMUPAW{^%F%v!pdN-qciThnlEA^L9FxmRi$L&2qC*|<>PBy@dDA_gE?>3z_ zvQ$apsLfpVeYt*^f_!S_U%%Sd864meZv&edxqs*t0>46=GWe7_mvSep!C{q)utHHz z-uYnY>_lD7;H^Pj}cm7X`I;NsODvF8C>6HmvRbE_}@ z^VG)kYOOCz9xuy@{+Abe5L zxxTt1VVNaL)%#fxZdX+qYy8yzBk4-JRfEFtUn28ILX->{^Nk{u44HrZeVn`2S!W7~ zZSQw@2FU4GH}wWZ+&?|D;ff-M%KHNC@R}F+pE9&i+vUJ=NOLC*E!S<+>Hz)H=VyK# z*N(VxfBG&LSULueQn;@3WfqRy+jaI_-UEHPkjIRr&jbd&YEK|U;^gUN&$%K# zpf4W?EB9yU~x#7mTe{L96gSk|OiG)b>?5I=c2EFu|y5_!ddr zV60OO5ijx3zvXT`G+MJb9TDi%^SM9#-_Pd4*VGFgVOi7c4lrB)icW9CK`p3Q^a4sr z6d!OUZ`dQe{iwrZUkJIJH0t^s$fwhWdn??KHtnC{G;ZgQuU2gFO!iGiHrP@~k&~lnLd`kO0xdZ0jae{(vIj@Ic$d+aHXOEl!bsj0(sReQ!7UK0e;Bm4ma#XnzLw6*`@XyCex( z;|341t^SzTd!nOOl5hdXFscl~hpJDS9_*l14|g~N#>VkvCs-4XQ}ZyE+DWZ*jjE?{`|vt^oWP0;GFYwGp$tA=4UBTtFzJg%}a_aSh_h-A^N<&OR)RA{CSlBJ8ESfWywYb*8Hvd`oC-#J zf2(t5IfzqKcx@0YcuAHCwYkUqXP~*fZoYV^?{o_T1S_`?4Sw{2k_A~j*jZrHqCqF= zG1m=&eeILGxaZlnYf}S(WKJx)pQsZr2`&b~KEJ5yU#seQ_MWEVr$~!&@*J#AaEl}h z)c)Z58f|gD90_k%qsM>QPiEu~2uo*;F7D4BOEDr4ix|b~=3nsr@mR^BKqj%krtCuk?dzhG5u|y! z2jL^&0b{a*j$&9qZGqmOavYqf#b^lGN+$++-0tU3WVW)N0`Dd;APz;zy`)~C7Ui&T-j<63hIGNeR@Ym)XZ2C> z_3dx1VEx5FIh)eCDXVCU4h9tsU%=kkicy~7x-a+@BH#mpb+xGT+p;#d>5hI8efdri zD#{lV;wJlZYls$~nA)2S6~q+M1g*3DvKsV7ypu88^!5a@si~H7t3Gu91qle?e^*#) zR!;)p-ITUO=55h5*>UctLYwNke0&^tvP^qAqIk_6_77R*m*sfSL#8195L#++J^W$+ zU)WfZ1POi9kIKM_*yVMLJ1O{NnEfQ@TOGN)+ek2nf6@DZBiA=N_9J0!-zbr2R>dFd zZch^?(S!YI6ab<#y|5wNL}yrwz(vxqm(uUL%9m%En*VUK#~p8~ip-q}4tueiKEWkA z)&(pTDjoe@3EE2+7?gg_PvgdI#&A>Xi_gCswhpwa&OLjdoiqCa8`q2o&yOcvj}u=# zz`7As&{Oi)ueqOQ+H}))=9)wBSEB#c;r83%B_L}=%$wsHC2@ezy``Rb*HrbgO?2h( zvdk1y!NGAELT^l-!9bM--3z?Rm%7Z@yQ}r5DcJc|w(*nOI%|V-6B97{ym-aJg!j$7 z&^G-Dg9!3o3s^8UB=Rx3g7am3WzC?EdnkQMPScqtV9km@)TAc{>nfnWT-1PZDUTtK ztqd^qA7omu>3)^T(=c03&`!FjC*f^yW7k8#YWYTda+;b#h$6v^twYkd{v_`$r?sQ# zFj}!gO4UY~BphmV6R?$FnbBT$&~dd@?#mhXjuK+omn<~JxoGYk8*S%YQaTw3nfSnk zz+hq1-yQ{>9@8167B*j|88M$UqMRKqJ6VZU7(P{1PPjeWLvnzb@@c=FVa&iZ(0u7I z3iXAI*=NS#jMiwJ10F4a6(?3Iy)ju4*SF^tac&1e?DXApS|Zi2+taOO3p8FpepjFo6wY;OM{Fr z>Gqqc@OF5eAqIp)yeo*F-9OB!-ynCvnp$0X(bAo$zLl#btf`guHHLJD;?ngtyT_nd zOR9N)e~Fk^;b}|tMTS3$JPdDy8-S<<6tzbet%uH7sif~SE@ZWsjGvZSZdxBD?pQCi zS6w^seD3Xw2n6hktMmyeZrjUJ)9v!9!y67_@VWs?-lr)Mj*;;FHu-_}$|c)#ao)}{ zj$%0Y2mLk)RYB-i8(L2_zlSg#_DfACS+%RdnOiCr(3Z z^O+z#)8|^>!;9B&1y1`51tE>C#dJF<(C8&#D!9ol3!ZkzK8zK{HSmnrpv}xYfZ0H! zg!9}o)!zjqbdI<2nQ<5~stv>Mzef7dNb9{M^grJOl`V1)E5kzGO7Exe^A)`XEzIBZ zqc<=YOVcQtBS&7l2VVl$dk`y^XH}`P_b2$?)b2|J>kCg$$?8FH?zWvqrGnk3@d43Wj(W0l z^dA%}kc`TJ*WW(zk0eHhG$qm@{&OoWWgAZ;Xg3%51K%GxYlPkQ6c5lwGW)CUlLUWy zMRr`@&s6%o`dl~iY@G`S=p%Ot#G+=NJi(X;hwhzhBxg%B9!60%VBYRnJ*?id`aKbe z7((7F?KLoouTwr|SKvgD9LchHZ(i-^()Uj|=n!w)^!6uxk{7IElJSF-czD>d*3nEq ziDI;mxOz|MoJhv3*-8|uevvWjVr4*O?b=4q3~mkEhK9(?&-~~c%==6)+%sUY@ylf& zw-9h8l^?h5oX_OS`&zY|G^$z{jd$eaw~u>BK~8{Q`uKhf~rZ>#|=6Il#4tujjHzf3ns9IF!Kb0rd-U(BS0yz z9OIOLc1d*Il&5==-5;1AN@b=8=khO$N8%@+%CMx=Dp*q09V_S@zhJs^VArzvDD#*C z*^jfy*V1*gb*#cHAh@Rn?@J2d_RqH z-t>1^XUVjQ`<2I+&aqH#;6?jgtm1W&JcyV-TOr`~#A!rzhB;Z%o5_P~aZQ}Oz%C#$ z5czmZhRj|dGqI!$%0V{|`ZKA41TdHgS=k!sNFXg=+StK??0w2qEBY@U2e?lpow2V} zWnbDJcUhk;o+lu;Aqx&{BOSn}&cJiozT$pS@^7LKn>9dW4xc?OPvziOKV+-V1wz;% zj;h@M`Ad5Io)5wn=<7n~i^W{28i5PP>30&_O5P9sB%?kd$f5JGfi+2g zs8qp@_-K5k>(uz`!`VtIMgA!D?oaq&(gRwNyF9~}$V6q+(m*AsZtQ>Nb5L{)Fl@t? z6ePmtOF9cy&#l>aEjlofHu06VVG_}`UPd`i@`jgo3SSTAlXj}dhA8ENcfa8oDWXHb z;1nQ+_`*BjwWphj>q;I(^2J zC21aHdk>M@pPtSKCMZr{U3^KMgUYIKs8OEe_Mk|9WiBbK?qw8cECfXPoIhbsU=rD% zj^D*adlicJxA&_k&Gc0)f6b@7zs)w>rK?XqzhF$c-|tCX*<@oQS)>6PPtL9NjMv|4 z+4ix!`LW;$;2F6zKP#H*w0n7j+(Yttd$YZdz|5O{1Kwd3fq!0wS0-=A>nv-e@o6N2 zJ+#U+K^M`8j^L`oSkk(`^XV7ABCNZA3O_7r!@ZFA-~nK~{So)`dO?%-Ixx61s;qYG z`AF1U8I^`l>xp?7Ui%qnE6pDW2E$z~Ud-gd;vWC4-HLHJMLLw*2o_4KJgp!+nM8ff ze*^1q7XflVqghg~#xs(8zW4wN_T@BmXE}rrFT%Ec#2?4ksXDKohH$#Mq=!dEPZ&_$>*8sySkTl!B)V4s|jB9pfwKl&zlY zy1OZ;!3PHPoJKvU{0d97CDJF8qbDTqigiI#3<{SJExO-W!`lbfJ@^Bzu)hNO%0n{X z3Jc%Pr0DMgE1U|aTIp<$GVsUyqQ$P47j@a6FAk1w{Q+9zhdT&!4Vqc_=jZw-S|(Y0 zh95YmIL=NiZJki6LWI?NQ1?BzztsP~ltUT#Yl|AkLq6MoRyBOd$|BXjuksZn3#!UXLrI!x$+Q3*8OBoJK%COt5LvuQb zB{ujL*09uszru$`HJ02iUzjHM)dIv4jypBE0$21u11`w?vpB+Ahkz7{Q>FVoSgeB_ z`^TN;*y(;D=GtJnNpU<^dOyUfSH;M>{^Z7P1Gt9YefY0uh(ry^(TMV2$>dHaB%VPk zw=u9F8nUT!`UKOQDiktp9wJ0h3){p!-zq9rhb@m&wKqS z_VE)z4KlnNNo7_5re$)Q_R}R&U;CsABZ}}T+XFTed6{bxLGI|5kzaN1Kcqv^DIvO8 zpN~CQR_DLjW{@uIH|;t+JXZJehx&24U*Oo3#?>Y1|0E#K@Up+a*(cEGXLGY&vo&9s zlviUY;UzwMjf$V6QStgd@TV34`rz??T;7y{R$=+LRB5PA5ya()J`jiRm7UuCB4;1= z(C7pNulBhC=?9b;_Bm-JrhS^<_62=N1j~Y5xal2qqv1cN4-_T+D1syK#!P`uuh;OQ zn?_H3LD4>($eVrE7^czNz~KG3DQJkt4W3JT^Rh3FEf`V~^R=kenO=i@XQrrEpLAA? z+KB)`CWw$HlB>HbDygZ^ey4pemgqR%q3^5FqbPW7ppvqlw(EmpGs%=c-J%t0yzM%H!sw~{Ul<*Am4?Hw#33K}JI@kMjx!9V z4p?nI>=+7&@$!V;pHIJOsa`-vmfd|=U4BiSJv2s6Z;+y3Ca1*XlN+P3e;?dsoeuAiS)D z@(#((hsowXFs}TuJxr5Ln)@>{*+)PS{kG`skchsgNBF+-54)N;Y|4E7k^P=dp}_)~)0B zz)(|6Tb>E2Gh@SNQcYJv)#5>>#?+&T8@#pv4H` z;il+C!0)=Fw4GLUj$AtwjwQECw&5~od$vOU`q*O60@wQ8WpLp#KHQ>yd21Wg@qX?>K<@%$$M9JCR<>1jAtn|IPw z;a#(tXV-=mY`e(Z zRo+PT4TiHHcijh&)SKA~+nNEspyYm#IAmagyneps77LO4NN`@tpIg+(-0SlI?|QceJ8fk1)G$M8?3BdP`wh*blqTlM5e=ijt03 z8vt;S)B7ecNXrwyaJF79Jr0t_^W>@G-p|>SS!%TE$`V=4I25WfTGU6gGCn7XJrX&h z=m9U8>Y{#VA@m?1WWEh38zs|sau1~MX5@IzIb*pK8-UkPa82PPv~GMyewICt=8e+@ zh!Lw_e4`gn+2e5Y*~jboyurg0WmI2+%G(m=C zMz14C@_qS&Z8m8oaOQX`Q}K4uZTY=N*bu2rtD5wANZ?oCr5NLC^~fz&?cG0D388`d z$nj|{HeLa+`g+{5^rEyu2Y3lNIVT|LvNQ3d)vBxs$D)6}WpP9Ej+^6@aOUt1JQOps z0dgWZf&o8`6p&rYL)EA`Mc>Vu7+JhLV*4%r($GD=rH1=H(6W>jW1(_OTwuba{Y2GS5&XYk z{}O%RJ>frTrRw@^(M+E8j?@^U3_}^u7Qzi*kvT;~@dS#FE3!d42rW9qSEiD#Eh6b@ z+Y^R$fkIjehy@Bnma)eBqTczi(B$^t+~d`UE;$UGZE8;sk1B71zgSH@6HcDgtZ?`>7TLS`5RAL-0oyh!_I+PcGFFk_UA?~%>XFCgZ8G=Ti%sTwfsy4f zX0Nl>v{$9iYvOtH;J`-(-?T7FejtGV7BpscPC8?ua}(iicC$bNNmC<2Nk|6LQ_K9>t2!z7$UlgZhq^S$9|op`eicWl*&R%67gf? z#VasSG!a#2U{S2h$H5dM`-?NyJ;>4&nC(IkcjbfEv5(rrZm;s^j~Z%~S6-6Fu5WPX z%^qeQw`>>Cje9DO`tYXGBe@5QBUo<`@CV_TlfMKo;FrVQ4c|=D9#*`J%GAEq4s=s* zQ(Lt;hh%>mGJ_~JNvbjwV-IJB-lK{yz@dJ=J+JLqAV2PQ8j@a`9FYSz#KVi088}oPDFSgkurOte*EcgVa$gD12Uq%UO zG_06gdrn$(9uwlh7@qckTDVm27m&mMi`tsGw?_4XGSHV#)kk;tr!b!)c|2f&gz3qK z{Hf?x^`orPZytJbtYPdtF-TB%0+HZ@_lKh~j<-qMA%IQ%ViKxI9jG6Z-)b%gf6`OevoI-Y}q7Mc+G&w!4R2ytRSBjEg+lBIxOMAX#|?cUZ(Xr?bF*E z&Wbm8S2|Z;>1wnQRP#t(^%L<}?>!zSPqTXBe z3FTtNZ{XDm6b$(VdVD`SS^nmGN~XM)_-=&|!$fi-^`T{`SMQhpNV-kiJ6c-?^6+(DSNdXNG+i*&3sNsBNXI3L~x=q9@)}VMY?ax;C#m!gu zrW@{?dR3*6y)i_6v+&pFFdy$$4o~7g3tkD#(TmYP!m>T}G7gZvpg|rw6RzBR~ z?|$jk!YW>%D|xN6%B9@~%61%lpoz+HuQ6G)q*QxHN}bwC7(@Dj8&-(@tpZSQe>~s9 zdIPc0oo;jzewF1M#>D(;rRL!unyXJ?6P)d+Lc>e1b_lz~f6El5x6mBEXICHSOdc!b zk7=2c+2lOG&DG1N8HI{Z@)eDFkxYm0tv!Iug3tSA2Dw}+pZ0ht$eiw&uOPf1BO~%> z#z}k-O$YP%GN|bmTVUiQ&-ar|0ScpyvvB()g?(c80L|}(?~otx$}Ne^tz+;`3Y&M0og-iqyY}ITZGIXo$p*!H&E&v>w|PTeuQ7 z_G`$)yiC0sY|{eP9}+aK;DRfL9K=XSA4-kA;A?BDZJl>Ce4AGl03GFcep3bleUlk(ulY{5+( zq38V|@{gaaIx*&3MBboH$jI-lw~JRP7|>Et16GAurZVq0QR{Vobhq1&-UaieeyzGG z3SXl*=MQlNN>X?uC^|peEnyG*t&tnVL=e~rR4bcIIOz$N3vLL(Psr6nv?(_hw1O6w z+Iia^8$l8)YL(+Dc*%8`TW;r80vJz@3Wo0O_XlDi(6y<4`bUv}ay2?Bw^cypy}RH_ zJ8z8(aaxMZocfkEnLvoOd zp7E}>0X@z7RUBpP(-iRA464*ocM337%{ge6Wz7XSzFXBULhZ>(bK1a3Ow`Z zN%QQ1*#9|ldxT(F{%^8uxMEdN{pxQY;Hp5jKOEp$F?7tmdx${|wQe6hL~Jh5oQEHs zE1zRFS}q9NDvcIDl7YU644c_Kbh?Qyz7v}AO2k)x=+N4F%0Aq=;hyxCmWdYwIyCs; zQ(y09-Hp|XaC5+uFOj8iq%TS9iPm{dR$BY50+R8sa{aEO=9& z&((W+EYwD@7R#FV0n?a?>GX=x`u40Aaf_6Q(G516seH(%h6dm67ab3zmDil|=AL22 zHI~~Oap>KT^)Kh2QIWvm3iL0$Tk^{z7b@exAvq=IO0@7psUNSX4YmB_@A>g#_AzVl zkJlH(5POPH`Xl-Fe0%w%?ZDRi3Pd?H3MhDFK)nRVG{p7fzCW#l-_6YxD9wVsdsvNk zR9!+9#nAre}^N3h)9ANO{!kGX5N@Th>s$ZEVEa{~;luPmp) zSPReshW6{vOyo?8HCu6dW>P{WWH z;#iya#U~t|Z3p=^0|;;|zAEoZ{O<^m9|R?uv?T`ryXCB)pv2j^SPH3fACV|!KR$sK zsM6&o!nmG_n=Bl$JM$(9{DAf%qLFpGQDE+Cw=30Iw~{1Vb-*kM8OD8f<6P+q~ywpgAh?U8@G^J56FIyU9ltC+{&@nr0z39?m!O=}75P?LyJf`NsV2kMA>;*7Yc9Mc$NzDaXSqT=&o+HHeiFvXnNhEC!DP#rlnhYHD#BghHR{K^Gbk1Ryp@_C=U$#OM+73HKa`|sNTH9(Cyhr)rKcU9`;$CJ~&}Lu)*~K zA!`5NjY_XP4n4mBHkiX2uzA1sXlDJK!i`-NU}>z*F_#W(pq zIS^!$9DeQtzbc33GR1mQ)X(dc4eF%Mzb!-+cHS7EXnBxQ!?kTo*u)y{`#l~mu41QW zjmtq|%qo#>?EKdQ0N}^FQMm+d7kpLTEeoCWzi1= z?|lU@Z!rk;U1wP68T+^SlzK15=ON_;v|wQtLPiKEDpvYf3{Qy6S82UfQIlOWYe;|a#MOiV>dV{escPyvC*T|WYKlD+;^4FAzrUL z>V^0v+dj0JMy?;AXJ_kdv4JiXrTqx?b!LOTtZ>gmqlW}Bk7`ODyt=2fPWe0SK2V>; zM_IS$^G{Z(rQt3ykPaA{| zCH%mf;VW#x)YYzEo%nR!Boeg0;&V3M?xO#7aqs}H&e={QeB|VI_o#-G-wgcgAlw#O z7mlb8N7tL`V)DgdlRfWw*@rY=d(+I$7@2E$H+sISeoD#%QB*P5Z5ml z=TK3^9%W^0&hmGWC75jKyna^?7SAkWf;wPXckk%yMl)v8Yz_lUu3bI)i3&9#|58kD4qTfqm*VDMqmqnwTG$C&JMn;D@ z`#AUOIoXrDnT3*dG3IIKDXJXb?hlO((HXJfZc;>HoQ;L_RRQZPf9-wFi;qnmMYroX zb`4(J_#IP6KsOk^GEz0}4yHjyM|O{CTbKv(FRS3AN;A?ij4cuQoH(EHdhw zds!5=B{cgk==4NX(3!Y-)_q9uVCg=kM*F1oD?Mbg65!?g9iqIOV?eng{fO=D| z7s+>>7$Rc5iOl zm4#l& zpDIG_5ih)0#fFUYzTSA-b6THEK9>8%WiGEH7`-l0wj!orOY2@$_dmt@knHYf)|86&Iu0Vo zY0K`urS4}AHL1}?hdd<~3eUo3w@Z+`zS3!(-@fB))qeB7vCN`=^@MUs1D^@&3P>w+ zqxH>;h$H9_$!)nVv9T8xu`Vcg=L#C|@$o%=82CQQ8Tj?X{;{@H+#00i*pAvKyZ$hL z$7`lUx8Rzc!#}wOX^B-7%mP42u*Kz)oyzg&>o+fDng}!`9LIr?X` zm8gjzY9Fnm;)uF}0FQays}S0)27fk3|2)6C2X%SRmGDbStMiEd_p{ID2j+VvS;l(@ zB9#2`{k!E43nLTGIG>I7^Ol=1lAg==pmiGY)=!vxptycrBmdpf5l%~@kFkm^C`EMFF8F&Tjl_Y#< z))lxpJjn54hmV@YzKgalZ(nByUY!YU|YXXag?Uu~eWq$-9 zGC~-_p)7O1nuy827q%`=c!5lg(c#a#=oe+NT|%LnIb0hm1LIP)=r>BB3Jq^TY%ATo zE%JZz0(=FQeD(7;9R-)O0U+)VT8p+hKA4jYFipZJ{amiE?M!TsG3@oL^zh32ue+}% z2xl6Xd|*xuVWSM@sGwSJ?c)ufRnb0B_T}~`Xz?w&(A~q1yMJbk$MehR?)on1yVqas zxshoi!L5USnj1cN8un9KwxJq;(+s==$kUgbdw5)726Tdo%L-A8sXE%igM@)Ge^3^J z^Eg(xKjzo-YnU)>KO7*Yi?=)4nh!g1C@!kLiY{U+jVy0@gazjB}I zw&+BYTm2wTfA&7(MKPcDQIu}d6z?G#_V}tvu?W|(#UJXA*W&KdrO>m!m+bv|1T1i5 zdfc7cu6TYI_XXonr+_7o4`QpUSmrnKxta_DZKWs!b z(SABtn$-7*;(}yXosVnml2_;a)~Vs?{8A5CG`jq&2PVpCZjT=rY;JJeYU5!bsjm3G zy)5H5OAF?pH2FXN{)1Wg*9ftzkG?ZtrS|Bg+YxJvv>0gQXStqNW{q@R6*83YJN(ka z;_~)$2}r@?o`Pn)KbgdfE5AZVDpZ%VeZ5ar&}q>Yzk3TGm~>#16Jd3na0Qx3b6QC& znf>y8UZ*pF3Iwa1QAPr*YYx+-Tf6c%**?%^d143HSS_sI9lx9cjExU&+;EO7I-UKOS`#UOT+GBrs{zy+}>h%4nNm&9;<2|p_Eo$yEOh>P& z=BLws46!eZ`puz{i@iDsrWB|kbdY^R!R@Mq;b;DA5EBzhN{-_aqF=+atj$wcg#<#$ zlL7>r4Q9aYr}&o&S?%<3_uh+iR(OPC>PdXMk>v@5@}-9}#07`o@JS}7yZn*(NEg8W zez}<4nH_)ojsaxjQn;?VHz(w6XAR+8972MJtY~WrPM>~X2(ew8Ze926!08(~?v9?d z`mF@0dh+Vnqo+SrrF>}bS*yWN)pi~_caNNC6CfHk4bLCF1$->r3Z+jw=HetmIMhbB zuXJyQ{cdi%4=S1id5=17{_=B*?^G z)Z4ZNAZ(wGL?|fdyX}Ts-Mte22A?u@gof#UVer-Sw|Srael`zT*->zzK0Go25B}a4 z`K7DP@xVTFdk+tu@2OsHpB!5cm7>jvh30bfO79-M=_|?tjrDfEdU!9Sj;h;W%rr?CGrw zA*5#$zR06d*~~ck*ze0eiT^eJJ~v2@$P8wWi$y6<$Ryzc(B*B@Sz<#w))9ikOnQ2J zI06qnok1qLRyN$~pfd$dZ1~Ab?e6r)sc&@iebl(|WSQ6YN>g|LyEv#BQ!OFu@h*xE z;YV-91BdtaAaV-SnqvH(Yvlyq=F5W_2c7|dz`8~E-~CR9Yp!%TM}4F3EZM6?lu`!a zmxwmmOa-M@2&mT`w;QvEDztMnG%xA`fwYIln?WVSy<1jonp@*1tWHs*r=O2Dn@`W; z(H@|QxvlRLoma$JiB6`Xk^3dF8h>iaskibS9kl}F30|o9yg|*CTdu7@pVTJ`b*NEMGzWSZpMDc zU{3-x(qs$y`Mx{;LBsXAIJw)+ihWIG$sv?wX!X7kJ){={R{aw8!;#%ZJ2KclcBE4yq7pdnMQ`cjJBSKDX_3o;HdTXy3UqA2Wxm zvd%KGM(B_1&Ei-`T_CuW-)uKE+;>SR`_w$I1LZ|{Sb!0#Go%F-;o0X<~wR&AB#K|FJl}f5`1s%(UQ|;9^M<)+)v7C zsfPd|d3cH2_5pXHzydxddY{`2~o<8Q~Ru1}!XH%BGv&ocib^=c`hdsPQ0rk5h3~RQE0^z8jDNqJ z%CD?;Pl|SI`qz&D#u=iSOYplqEyVaQ+6Pm_&R)nlq`_I;)DYsAL>xA@r*+>j*tTg5 zxlddpJG^sy&W@9oA603&O25qbV=?WMKMeEeOi_-(0yh}Jsogg?PTx%Sq)&xhYG!JJ z7?U@2$xHP`+{&pqJMXqiWbJpE+HEDwk{(y>7YkqzX1)+rmjb*P+<$djMdkzRAU{`C zJ?_75v%xUtEN86eEvN`cXw#jef&dE_oGwrx-<5f@l_az;+|ht>*%!h%^2+ZE-P637 z_CReOdy?enQyj8%DeplcIfo=VpUbJof%`=j6bH;z?64$?=`OYL_Zd5hNq&uu(!)7v z7?dB>*o2Q_ttguQl4;yp+U-W4Qw#ZXg>yyiW z2gsbrLolZ^uOXBh^2NzGDBEu4nfF|1h80HKJ^2tK*M}JR8DGyc^>)w!gn}pJGDm8^hxx zm>!j8MdJ55tRAS8Np~!sY{dLnHzoGx1UB%hoX4o*OdWc+d~M(%Ix`im1DvhBR?iu( zFSCxm^&xWZ#C3RAF&Iv^m`waM43GI!j@ee6m3>X0H~GGQ#C_@wAIpuxRQMurYp{D(@rA}F!Y(wfN_}ZDE~N!# zr7JM~3!WM{@$WL_Cn{ah>WK^AAc2Qzv zR_$@SoNOX?QsD-Hs;IHwY0&a0i&GzPbwsqamFw(NquJo$&^Y5!m+InTSMCfB$N)2B zV}|tk4gWdDrm-IGY!Apa{zPwFDh_t&q{?>hb|U)|bK)~rw7i2$bPb3EjrA~9N*-GZ z`^=F?Py?k#K=n1lb?@SL;=Omt@iHH8s?yxC2{!G7oV2dEX=>d)%P$Gf#Tx-eLe#*2 zF_U)4T&(~H(33ipn9J?7eJN`6KcJ zyao*@>5y7+freQ6%xWs9Uo*1USk@ovn7yGLqAgj631n#uirK(zC;i zVP6t1i^U{;_XsXVnNrE&uvdwstX-hb1fMd@1hrQEq-JQ(-{T#oL_vbquyi!JMtXYz z7**l^bZSd-%2^FJJFxpBo)y%X_6b=P2@{{7y0gDi--j9i`X(M?oH$3fuym2n&Q4$ zo(9s{ZMJ^bWW)8ehWUGEJ9>|r9h@shczNwQ?LUp2Uf z%$~qLo2i^gbTH^)xnsN}vlZCm!a5U1t_Rm@Zm^><R+FqfPc6V@Tv{{v1A3un3eu<0s+lM7AdZLcJk&`9a*Zx|@FA2 zQ^x^!QP6i-691Tc^Z0lEx;{{WmY+&nuxp{ZD*g4RNVS;EnGq_?J-O$~Br_g$CUa(z z$()%ac!40Gt)dnXMPb3NOINK{v6OmL1zPHXwpvzYQNU_Fihxy7i|lhg?ryh_$37nW z?>-)%?~!~a$zrmVINu|40!ianeJM+)JUE?+pU3)jQlp>A$j zo9ijKa#tX3T+gCllj7TrSxx6org&N+mWTP+ z(2ULEHYvA+rrUEAqE!`h2+7@OKi98gQWq1k>9$q0En;(D-EKl{>x;$lcJNj(`OBlx zmAW@nzp5VKRby!B#?WE${95} z19l2(vIu>lVOS8?z1eGrEaNC}#!u58H1wevsoZ(X0o;BF*{^#}9Ay-_Z18+D8t#j| z9Inf%mb!Qv5V;9a<|Rs>ayML1iCV1PTWtr+X|UW4XTqDQ)Aycu0PSy8TgVm+fB;iI z;xMIzv?nVMrbO(y$=U=hhKi3+ zgL64v!Dj}q=*)aNiTNpKUWTE;F%yyLl3JjJvEuUbWrhO_d#D82@JpdlfHh}OAX}PR z#c%WzyUhE->qvO4_L#1C2iCWXQ_9ulk@A+AMl?eRc^?;rfA%3vuo`yni>e<;@bq|B zpygsBm-mS^fgH6uX8R)=z3t&dPm6x2RgZMEO{yJ8qgYiG%ObWzZl-v4AwXPsu{Nf} zP#9C%u^8xQ^W4fQrEOWPWW&53M*XT-U*XD=gmJvA>{&lL7{MB9Nj>D$xyc%JIgx|R z(8#Mx(R*kklS0Fn++x)Xbrx#6 zkc=3k*B#Yykr?P5rXAjFjOY_jt<>N8!hl`0+`1chl>DTqqIgY&y6!6&CY;l1= zjX@a`@3^RUbFs>J8L6~*?##=&2Fq|t%-X|{=7a>xn5ci|yY+mnq^-H&SMzaY9@N!8oe#t$(3zrx1w!oV%Z&uh zQoQ=uZst)6YEZtR40bu}K=iCkK|a>wWHYQT;i&F~?Ri%({5g}#atah_gpPWQPf0v( zn~T2En3IAZ61dXL4V=5MZG>uMbm4xi>`#@R&K~%2_=Tq)xNPS-y0ZnYaB?KCsj3=# z`Mj7jYPYy!4s-gs(bJoo@`E}wDl&NAcr&x9hmz9S22DoaYynY>QhZZ|>+f|D-wQ&= z!B@s!>>iW>*hY#9f`BknQC>$&90>70mMG0r5Krg6eLVc)*3mLJ6 zyYry1B3z*-H(K;4%?NCsWt$xH7D_h!oT?-VSRbv{DJ{tl5b=a$5??h7eerPT*oBp4 zy?Qe!dJju&sfC#Lc-+M9WCQ1q!)~SskaJ&0SaXFr+Oy}l9N$IG62ho+P{N{@Go=Ix z6yuXd3n!m(%e^;+S+U*>5ygXQdT#PbV~*hsh-Z9aU(ezwp_H^J>R~_Yj@k8YULpWh z@yMQG^@WO&AFLa6sXBU+a^U$D^e`l?uwyB57A>`^Jvr8CM@}w{h%okucdj(G-B98g z8RtCJpnQ~&vm*gth(lt|O%(=tO%3NJx@w$=52IWVZ9&zBZlX{v*OT$gELoPBX1hGJcd~Goa#-eFz~iC#;c}P{IFtZA!d}O#$6 z8gSuKqU}+_6qCN>sq4i(MdhK+g)y}b zh75BUYVaSrVj5=T+NP@Rxb}_y=%JwzHY*?~6bO#=Ao}A#+gR8#V7+&pnoh-G6zlpX zn4d}397p@97r4;LN-pF1GIBU#UMu{%pe_d(GE!)$+gMPAkhh7qP)@}7l+@TMU;TMnM5xQ<|1hOu|)I?W~^LbKO!}(U+SpnR=hb^kE z4!7-Q>>9I15o668#;)wuw>BO^Mgx|AS8{8Mj0;RtGZLm&=~}~eige>4V%Tx3u5eGY z?OEmUS|Q)23ng4^r)fr1Tmfw&h77P5DGSg|Yi-C&gp6g}nR;$GFXGNqcqHQY*mH;P zB~9U;Mol#w1`LF^o}P!Rv+$06c^e1qL{nx)yb0`Xa-0uKPUh9~Wh)c$3KiG-tdrAX zzPA?EwOE(?%i4oY2o>>i+xT@+0}T)By4y-QH_ojQJ*u0RbX{%uYd&Z&wPi2wCN#%r zhB3O;)e1GF!5@upuf#63E@9X240BCte3`a8#S`Mm6|%6lomo5M?4Y}h6Pg|E0oW&~ zR7?0kb&m5)l?{P`c>grQ@2AlHV;okPoJe3UEb{^c!E}E`+;?EWtZ0DR+z-di=f;$W zAgXMZ;)R@>W**!p;X)4slBJo^ZWhDUHm4PXnozO69EdWd__pX5G1G7hV<-Eour+zww=s%^$uLz?*0kjYP_{Nc z@5Zf=2+n3=4oGeRXCZ7t*tAemv`L@?zV*gb&DiSU+(gc;uQ=D-F8o?)IGWIhMfd~* zyeqK>YN#FNCZt_7vuC z_VVPoWrGAJ@aHDCP$*?O=5Nz50QarL=Xh)*Z8u({9^87^*zKt6#`^=ADexSxq`iY= zFFM;I&cS5jhQATx32&@Pl4~Ig>|Ac_(zf)jy^*CgU93*`*_A)tLsy}u3#SROI0;J~ z0#|3S)f)S#0TZto?bcm0$5pNy*F@z~__ae#5=WxXxlA)xKZeW*n%9QoF69fuxkUuc zb|4)gz!G!P@dB-zOB`R#Y7Og}cDCJb1=wwDH!imVLr<<+;`|VgiFw1>6E-A{ncRjk>^>X8V>uxU9Ua?VZ45<-Dn3 zhzx2RvlxO92Gs9p`{ofVKv2OYPaM)KX2%_+Mu~ehG_|- zEv8JO1*xE2!eKU_Jp5(k%MA}jP&Tp;6UXgMwO0>*l(0Ah1*Up>doi`q*pQmU3Q)XP zCnB+gLr^tSr_)+hwHph<%6V5FuLV@h*&#n4pMwS|;QhG37=+lICHixmiNHkBLQ2TJ zKI2E4Kww2uNQYW9?fftNXHzepFzVDTRbRH*rO?t6Z<>`or3g7dqophrh{*3?L~iW^ znH@6+AEkH2#HKIEK7h^QkOYS7(Ok&uStMZ#@W;v>Li1~QhTX|kWXEe!yq&6iSSs+N z>-NZWOmk}UoHoQwwmrLEyNbDW3DM!Psu;&E19FmYT`e`B(G*0Z{lK_WATY8PaHC*2 zIkUEQ&0m)F4b<`QcBPLx91(F^%KY4^SGWl?EP;~TAq`Ez&*08}5+_Wjv8u9Lry=kT_juTp z=!GKz5$*Wrj)}b9;_?7H5}1{zO%^1*l+HwXzU#txZfnQ<_x**e5q&(bj+EJLT}+==T- z!H@uTFGWq+B4i4>J>D{^Zuo7`k(7_2EJScgOUHUmo@@!~zS53r`or4K*TXJh9*k8g znvtSHQS96R%4x+(mP6cfn1s2fl|Aqe;74@PuxfOhg=l86UGX5Q)q}FMQpPo%Uq~1b zY4lYO3KgpN_czbuJrc+en00knKhB(pw4TDR`zfLmFbo!6pr8 zIWZFh%WbvT1eHlKvx8JT05(yk3v(Ft1^MaRtgh>kb5%l%p>7o!GT}+NGV*m>5hdTM zL_`m<6G*F+iK;IS<$~%9f9@_ssdRki zyzPdhhfBo!O=FHVCrOtIO`3YmSWyp$YkNWQr(r5yFKGyx)_8uIw9y}7W`be`39T|&xVl29QvC8T`AbnQXI(xUN3@$dxu0&%<*BTpqYKLV9Yt2Odys}~&-!FqWk&&SnZDPs3cX(v zM++V(G^KXcURjOcz@==(VQ?30pNXqx+>YZDEZ)R%KVGe3)GED>f}re*f*i#%56~Bp z`;-oEkzX_Inr^ec$1)>`C&JpfTn0TKJYsBl9xp-QB~}M%8XukbcF6WcE)+|$1E?;? zU=!5IeeTVa9v|-W^g&N17BEvICd<9{E{kw*Da}*?XeX5??qqUbtg+AK#*~wBofXHK zE_RoBvO^qdgsgKeE4$)m%f1#v2BPB9dK5!aXtC))GV_jy!!W+x?J|WnKj4r6oH7A5 z^NT5b0vnh~2ZXk2-|_fLhu?i8%zidJ$Ep7j%JAa>~h&&Q# z-BUvlORaEw9Pu=+7P?4quGUxE(0Mp$!69*$Pgv84faDhJ>I9?e4ZuyV13%|&f7ydvAmTr=4P8oN75~T zR?2deEA2vGwc^?x71NncUYK3sZ@0_)iP^`RW>SkJh92!OvoYWlRXiJ4p9?1&s;v~L zf8#lbvQh?_0$+~m@uEo*P8WCWSP6S0+MtIH7iLsO zayS#$%;s(m!K$LkM{LXP0U$HyHUxu^M__i_EjV~hlYk$)2Nyq`+!2|<-cFV-@>cdC z&_71kY3%RklZ8E;6O9VX9HrcBb0<|9dKl~8cI?%7M>CNzisz$nJh-8Np|Dg*MVu!z z8aF5A!Qjijm?tUN4*B^BoRW4dPYb?YCOSk*n&}FbqJe4C6MnUaf!Jhm+r=BMPVJp8 zLGxA08{Q)A^QqZT7e(5%i)$$GiEg$NXVCrwuKBu|!rKX%2l!_A3vy!6hqu_c87*Vm zIEv;F&kqeco}hv)nAuV~%Gj!UJ@!bzK_(8R7YccxLzM(Q7j5E?{hpoH3EN1+SJ=^?6l2XW_3`KqD2i$L&Inyqd zddX7L%hoF-qz{%#r`?K+xRO3vA+)}jwaKT!!XJ&a$!=pOeLghQgm?@HSQA)>UQty+#IG9OO_j!+ws5` zQtoC=DdBB(k7F4RU9j2kK_k=LYSWb_hW_m^Y*8Tze`WmZZGp%SuagPaikH)BqM0kL zw!r*TCyKVNH!!@;$S0%5i-JAn`z}@#bLVZggM3j;?e=m*X}A3;7~+!}eYV2_g<*)rd00eZOz{Tcp2b#_*w0n{&p`n<-FEuc*smGt{-(}bNA|$ zT`xBKxwi0UQ+g= z&RU^MAm0!0IwFt4p?9JOQQdKAgTsF72gx$wMj8h_<}Q@3V!Q|g3~!2@bWAO>%TkV{ z<%E{ZI#&HKX<#?gjn*0H&D+D|v>8(-WDNvwJ}__<;B-)$*D$Pv>HWM5w;B^i1$Tbu9qNk|Qy3*yPBX z7kDea4X5jDeHpe@;v(?9Gi`D<>!Cv!UJ}Fh)yZ}x&X1Ih_J?Or9c{9w%iC^yr}|E} zkqp7eR;SM!g%Vhp2D%POt7fK*941j_sKs9m%R)gG5VJG%tKy2PDh zUt>!3CN$G#s*cJHip2fG-xUoU;K$`&IoZ6rF?XalY&9!jLY2W6RL0WO5)3vubG|gr?f12=;$gkv>FajAV`M`*&Q~Ou&#X&?{*Ib@B)0xb#P3j@GAVq%yqkLG z;VQR4bS9g~u$k+?*%F{Ax- zPa`{xxheXL%VlXAR=Ay>hJlBl4R5(c=3C9=TyHOV+d2u8yJI0KhFjE%XL>x3xUG^@ z(>kLXkX6q9K7%I#D5b;@b~Sc6C%yQ1V)R9Gn8`P1*YSyLU$~=AjG=dUA171rgv$}` z)MCB4)mM<=E?Cr+7K@0o7{0h~Dq9fk0Q(23?dpgI5e-<=xx1YrE>;o8D;J2`GC*mt)NVZ$|zNin)jsuO9zXTU}|(}u#L*-sT%3c(k;)&r<5bHD(nwGe~Vel9qp z?fuip&2z#TvT^sGiMQ>2?FIX*J!JaR!lx`-tfz^m@^W91ey1F+eFo<~W0ZqK=?+`w z$}Ne7hhRpn#{OC}I&b8Le%a0mpaD*pPeQHCq=~$Q&?TG_+;fNWf>f=^rAx(%CRI!i zpI5^p9oWWl%h6$oU$Lc35q-^-eG5OR9ok>eIZBelR3IyJZc#TI1bmBD%=WSrLFNnM zB%pNVe$vx$E}zr!O5=)QKOVNY8}z>16@7vJCq10;QG_;EZkxkx$HVhT?dfGBg-j-L z_kAQ`sIN}&ec)+Gfq;-XFT&Z}&`=sWkM`Vcs{;l%AtnMq6eljf8%N(6CNJuGqfO!a z6Nc>a+j*6oR`8d?2NYGYkykWkyQXF*R^o%QZCw3~`JvbgP#YY><T)*;U(Y;3<{M;x6oFo(&< zoj2@VaXbP{etPXOiwOgpN@J+m%&75<2zLQ{-i=P}ea#>a@XNSYoOaI-p&0bBWc1Xp z8!Gi3Tc%daD9$4p5^r8!Q5Uwfk%2G9mL6{FnUtddgzmz|6>#PPRAiHRaWnWtEao#k zUu)t-jhzLGg59A-cZ{RA28xUEg*dN`9!}Y54nyvFdKi^V8`R7$H~I_2U?<0ZS?;8`{oeA&^DsOC8@(DDky_`gHxqd(j z2iH;O$;p1oE$eVw^f7>NiQH`JO>;CA%9@-`R|Dfkp*2;W2YIgWz2+)4oC&P+FvGJ< zcSC7$VKa3n6nqIwQg&wFwlTA^^ROtXvDkUHVrttXQOb2>MS$Rm_UXt{J-glOW-ZBCJ5pG}mD?L4|^g*gZAlYhjz1{OEvj98}+8J&& ztl%7#b(5XO8)R)o(y-wuK@M$T<6h?z4(dWjxlSP}dJ{VZ1j8BHGB{?rN@T7C>ylH; zJ1hD1oL!F3V-9b)o8%V=_#Mw1JXjT|c%QWj&Xyc>!qH|AH6bQFBLU^V8rK$FBhqK8pkHpcd*1AnDLQ$;4u~bBFO_0~eiOg)nQ_IuV$j zBQ)uO(5&X?Jwds1Vg}szVbxR9T{|AFIW;n=*^tMt&xW-Dwt|zI8pTdyyU{C*9>FXu z8~?0k#*m#w`;icFd3jNx{D7y?OZKkv${n2_O6h0Dog_zE?oE^tPiGPeXQRV#n#qb7 zTTZXf>MZE)v)w6cE9{&Li3G{;e!PuY69onOG#Qfk)Qu=_OD!KXrn%4%D-puy{c?Md zff_TX-BbvhD*>w?{$3kW$4l4H6(j{VGm&aFH@$Pu{I${*`fN{)MbQl#YG)@`I9L-5 zp=uW=xBU|g##ftW4tGWF)Ugj9S_4l@SY0A!*y^nvgGb6anOguKWJEAJfKrU7BrH4+ zrs7F^tp^sBVBHP=KB7l3G7QYJ&Co{~)8nz#FiLS@9BMfvtM`+Psl1u)&HyzAcndc% z)ByZ6**U>!u8g8?#5Ol>9vB`4JGKi+7!zW(utcb^8v!X?d6AA5r;95IeSW&GQxGwZ zJA~`Zw%ssyP$qmPw6(~w9y*Trgq_grA@$K|RMDMXD4^h82#%Xrb9+C!DUIQYTUiE> zHJzksBA2_wJIiD8fww$%#W?o+IZS|F`ZOKx#9U?A-dRiozI5!s_5WRS>9&Q ziQkJx*ZTpU6=E$rC{~oDq!aFhbG8WpIoKXza>L)FQ$v<5LJTlI)7jSKXjIX zmgY-|yM^#vpoz)4_9kU@^80wfRLk5@6=cWvf{%h=aTK_!PtK4zL78Y@O&&0bz^P1@ z;em(Ucy}J}^s17?OL{)Z`TfL>j22SNIO*#yyns74F;6!YGADearjmA>?B|0!lF(;R z7Q5mw{XuIkE7z1gl_^B7Mv9aV=d{tCf+l!MOeXLqv@OUWmckMS zMjm~bwUESSE4tbp;H#nBTwkF<)H#BAop05;MKt4&_oKT%JB~afeHEryIB% z7NO)H>5E`UeH8Bc4Ycr(1{)x~TTO8QJOM|N!<>?JVg|(z0(yQF#gR+rnqMQ(ruSgT zvTN>6-uAx4_e&T`oPnRi_vWvwJ~?LDe4WYu*ijamukGocI>FgUlp~fG#SMQ#-6vg~ zPjNdbI%$W#o_f8&e0AouIUd8kfG>-+l?i~^S2ZzDxr!(9FencrmFLRSP0&ELJnpQV zR5lATV6PsN>=(+xzBJL<5S>!4WXGM+jom81WyRC&(NmYimC}o%2?bANhs-eXN;BGB z$N2AP`_N8XcTicK&8{~W;&MkZp@KVqn$lLXJrTq*+?>pz5@6jnZM{X5RWe&+!X5=1 zPVRMob@v-)!i=(LbHju#P;yf@lQU>xUTymJ4vy*DN}0MXv(HDh(}-u(XhOO(DMh#L!)PN3@fJ~u1xQz%s7B4+*bR+5Dx93F4T`BLd2=lHhiA_TY zL-8Znd1juSD0f5y=(p_J9CZb)p#t=)H2a1YIi!7Wt^@Mvr_Rlv|DGi9+Yj9`d@+qo9$kqM%Z-Q_EYJWY1N!i1TZM00I-pQNr<`S6*WxS}cP zbAeEgeiiKEU9=Obbunu&uF#TjZw_CzvgOH2$*(o)1_St-s>+@?LH3zj-oj0?+%34c z=>5XI1r&^q0-(4`gDcTgpARW`HZ+`v@YL#8tz_w>rv_`k0$*GTjd9?J!kE0~4#3-E zgjyS7TN}anpq;9k34}tloUJx=P!K^v1Zssj0Z>i|b}Y!T#Qj=IE}PjzvRrhAx6TOxk0&6dQ}GD&n?Gce3{|B%qJK z8--0S->*m*ycG6Jx0rLGcxXlBnOcub5aLn!gjcSYvQ!<_$3jJ3+*EfcMl4n{+Bq8# zQBto-XU@j}L^wrOfcRoAw?UbTXnfdHwGiZjpVcd%6|Pxjdb54aisJ(hY;3;T&r`mH z@^g{G5FncMv@pr$b7p=!a!tN%h-jNxaL-;_i0}mk_AhOC*!VE?rNsSwR^}RiI6$pz zeN3|@>$@f(=6RM;$&_+Qj*Y9#LC5?*lLJB72@RIhhh_>Q|2)J z?IpbYz|bY6dDdy-K9=^P`9lR_*bhx2uG?k(72&$ZlD8fD%CV^sC~)9AQ125HIEFdJh!%gp9rpJw6$y1T3wCUCLT+4*?c~`tWv$>)!qI+;`hotjpp|GntmDSgfxn`{( zjP)~|A9EuRMyd+QR%$bA_@16Bb8C6k%u9V*HOr{WZ@rykga za=l0~6vT$5xIe;9DP59F`0?4Wkf&k9O2)L7>%~#UdUuV8G_d9i)a<5KCGo(1GFPT9 zVC2LHM3`OZa4j7D-9~!Qh`d10dJPrjc&r8WI*Os;!~y)!mD?bIm4qzF+|1KBhGvv} z87xoj;u!9iG6^X+hqip#TF$1)$(D7@-nn}>^A?%kzP)!rVcL_nGF1~T)>+a(!G?Bn zHurZb12tu*N4&1w<2kB|ibf`xBs*{+u`_PR-7>cVAGuA?Dx9!~$?iI&LD2!4x8#AmKOQC6m%vNYn#clVA;C0uK| z# z&|O3&c&yAq8(r7XCV*j8bFy#BEyVau(kXRn9KuTKa4J>i6@5@N4uW=S@TY7} zq+2-YcG%Q~);STEVT2IbvA$kWt!T%$OFq8u?Nb`TqLE$SQ+c%>K-0?`HBB%?t%X|` zi36-#(rR8EDlj>e3%bAVj(3oHb(XIzb>@xp1Ec^BO~j*uXd)Ydn1y>fZ0K%gllM(} zT}*9pyIDrbG%2MU56&qy8q2xBaHarYhBlYG7#5;-3Q`|tD_RZGgqisU&NlYfdA8Mq z>oVDcRel+d4*=T)xw$3pf#B7`2yTTLf}qV<+O_R0w`NwG<_C^Sy(+EPNE&Ht@l5IG zbCKW)wFiiRHJBPe3fcy_L(ow7J$h*mgMQ23*X(q17Zc ztvRu-T1ACpq)47f@(DxT9&L|Wvm-boGV`_y)| zR4(muvls8;rqv{MW(*@g!dR_iXSsqE_{KYJVA{jW9zUVN#$HjZdfW_AHMwxNkX|&y z5jEOQw)~zOT;2t93a_iSDxtFvpQLaUImw&?DUg?|IW*&sBl~{O_u-E7h58Vu2y5E2 zRj>33W4Xk-vsE#i_@P1VT6P6`H4hWhM0Q)A9GF4E)EMF0ozP?#&hn`B=lk(?*LrON zFoE91dbI2+U)j#4P}?IZVcUs~(g6+~-UzWQm|3$>FJMa<1ud>)#TdIV63wn7lDQqB zGDlGT_}*Qi{HZMT0U;ezY<{Wz6h$6l$n>V2$+<(Mu3W67Art5ef+Ip9{Er=R8Oj8stW)7;4V&gfSY%am;kCnsuUj=2hN37!FV; zOp=LsJ|6AGmKssR_wV4*Tpdx(hB{xJv`}|-)0CM_j?RiqZ+n*Cj-im~OrqIty0KBJ z;xU&gHVe}to>1#9)M8)ciPb46$lXrALBSd9!7(gmu17Co<g&j3)mF~LC}}vS zUN)P<-q8<$g?sIFdxmm!6^<7}`LuR>Z<7HHv7u(G zh-u1dNK^0=ZKweDd4=OatuMG-MPzzO>7a)cUZ*Te3|)sLyRmJ}vEUw*o&a=zMx zaSg%x9rPTlb5=X%SWWVa>oW4T3kwW;Wx<@vrQ0ZhQ1i}aL$d}9xU<$FqT;?!jk2eAITW!j99IhtLLWawy5gD>Sl%m(6*Qc3rIk$zysylPI z*ek;0XBUo#vTug09yLPaq`~mmBjWyiH!RKM%WI=E_Li&3qU&4IW4DAcE6>K}fpK>| zpggt)#ujgu3vDzi$9rY2g^a13<;;~w7KG}_redl|DNU_hDT6!+TW+912~Fj4X`y)6 zge3=+zQU{ZMb)_1$A9%Wm$+;`4M^_7)dyQ@{RpeYDhXVc769nVb2 zQou1nARpwqygMXxY^{!T+gp1?7u4LYtqZI_@|zpXPCIIsu4wgkxzXE{91*&s?N83a zp56oJtPYhp{6L3NbX&3acG7v{v*K(|u2CohAH*1U-3H2E3MgZ+)WhAfJ%ABMfZp#? zp;=FY`x?kjTt;H4M($~H-py-RjEPw7Zz$h07KNL%i5>jj;yr&~!x=*B#Td z7rHx>JhhJDN2WiJ_r?eMHgZpn(I@EMuubaQgy*@PHSPfNtgf`#o0*gHT3Z|@Fp_Gm zHH5cP$5`)ux0UWYY3Yv(gcO#VTb-gpfPR@Ale+=n0?f`%M@V2G6*f_(IHLR5i8NdZ zvk5UK$yIa=6PNY!kiA?1`aPV$?3&F-UV{o5gKt9Gs5guDy+*Ozm!HXF02uJ7~bdbfX83?KHBM(zsR0rp2M)ecobi z5_bf6DZ+Bvb(h%?W}qW0M9Ww-9Ki!$X%(IB^Mf|5w@?gMHR0gds54)+VZgg<_L9S_ z`{XjSY71!qRUWS+EQC0Eh$jO5q|8@EiYYP&ML0o664-*6XwW5DpP*`xV%bv;dT(UQ ztF6&M?(J$=ajbJ~Y886Pi%sB<$@>t&KC|Bh+XHwA0dVXn6Dh;yhx8%6GvE) zx>Gb7woCiX|JSoh23-)-lEaLSiH>Ou<4T=8zg2Jby4db$c`^ibMtjtuih;sMxln1B zgJR9F5W%1iq6Qm+U1rcVlJ{*Cs7kPFkl`rMFkkB-Det4pVJMYp;_3{bHRl;>9M4?y zKx}7#pAH=WV$lPRzY&IOTg5}|%HE9uPPHb%`07FW zzdTup2Avc|2ho3VHOCN^ZtpA&qm-_oIxV?~%ai1{Weu!-&5>fYC>MCQE+*6A^>8Z5 zsCk`LP^`N8t8*#!csAHh7_O-#j3p=&Y_Bdl$X$4Q(9B>KBKmG8ST|NXubqS!#~9-c zkEXReNU;s$rr~U%rdxCS^r7_03M;4~A}D^)^aYfEOkW=QyFkVj8fE)%zL``u+=gn} zKQ)ruE((fG9eUXBfeX}>i|2Hg0B)F~K`ZE>%Eg(vRg4cB@kCdG3mO<$yb(Go8Fq2E zF1?LIlG>dn;)!UrHh#g&=L-lYWFPPDl&dqy@7R7AP|EQ%2zv>f=E8%8XQ6tv9wMZ5 zIh(B4SDT)O2Rf`b@j)2L(SVI<%w^ad@Z}qc~N0hU432e%g7&7($=t<;2Jij8pK)sfQGNb8EArX{aGr)(`7L z>KDVb=G+a71I%L?9VKB!SyMbZiqveYjeJT-Z)!X#2pBQe)QP!I8`z3-7Z3M zu}gT4j2V4)SmS*JoSx!qDwJgL06)joPETo+BbYnlKRt6j0KS%L*>Hx#z}`1d)v+g&0PBjfOoI5T zjm=WqlDk^4u_dRLO7QFPimif4#M4nH6-08iGLCm@TD#;>9-qb58d|9hXPA&A+r;LE zL$h?AAdnJ9mZM%KhkmqA(bpxQKHXFi8O^96-qU@Db9?9F>(__ePuD6uyS}g4iL0Z! z;$2esT2A1x*ho=R_ZzB`<$>QRNE0JGOm3s$q@AHECzka{l-O_(7(pY_^g4kS9!`npEprVH*vZ+^J< z{(jR#cty*0aj*^#1G#>=qL`a;JJl%-k`kDIV=OM5MEM> z1kXPp!GZSFR}5Xs0@g-_R_b6-NRLKAttWnk?n=DI^Uer=8FzXZ5+}H(tISFsVmyph z0^oFmzOHbC1@!`5pnFPAa9AtD)EqV;7U-p7%$!dgKME$K0#B;((L+$2@knCKZt}qK zqAqv|en#mH^|OlGSduAmJNwY$Z7KYj2B)>8G`jk8M()@I-HqFE!^Rt zXvZu%b<;GaAGC&s0WPGwgd2is=#=Th9z4xS+ln zF9ae+xNE~l{>T(V6N0;~FYutcFho``#umit4nU1^iPAXyZz{LIeKtJ z*vfdBaJ+EQ1=ilwag_}-V@+KqM;R-iavq5*>`lWGDoKzma$VeiVQ4QaF*%yb3Wu{- za3ux2PMFVkWFJjI8{M z0pG@4%Z0<#t3Xj?4k_fn!3rg_rM7zjbUx_63`4K#Si8a)$AACgCyblC-d`5d2m)y5 zbcCCsY^UoZ<3%HbZ8~ng9uv4r3WL+k=i5sq@5MHz_2HVIXDFGEYH>%dBnos@uLfnGNbdypnVlg9V1!|$-7>|w@CC3=YwGrU~TDRCat*Q*{@+=5E=u4EAu zx3f!pG0s2_)%VLv&^R19G19|ajEkI@$0Y5}E|xZ-P|7ogb=!f)yzd?+2T{Es?!z-y zjAd}RkzqO?=3*x-?qk!yjSzATlUNGa-Sy1LLy@GlG&lsUg$3PDc3X1F`uRqi=_4ei z{k7Nl6FFSBfYey{s7sh{Lcp@d@Ll6Ef3i$%dK({SlfxE)xdH+r{(ev|eduWdZqA9- zW_4d+0TPJPmrU4@ZdT!NFLlzG@LYcx?|3cIOjD=EOdIDC$YM3T9|j!ec^E<^;k%K1 zSsC4N$3t)Fezi@s5mnzf&=D-~uIoJ+L1S~B!+;TX!Vn-^k(`0$0Gsieu!ePxOAc05 zvy61BnX55>SZPYO?p#vUhiS0EnnO4!EDfuM{jhv$v+&IHOCEPhNhY5~N}ojz+fA7H zNeu}J7zI2$K3(CN6yc%yli&KzkNdc%f812!?dzBR-j_V_YHxn!E5G}@pYhlWe*XF2 z@=w0{6JPp?FZ`6>`^4A3H1EIn$G_xVZ~C4;|G@e8yLWwG{;p5?l;f8@{x5yk*RK;O^{aoV`J;Dy&9i^&-PU^=;*Wp!kH6x#KH7fW>p$n^ z@}p0G%F7?op77Y?KKbKc_SMq!{`$v%$78E+d)hnx@?SjsKY#m#$9?nU9bfa`9r<+W z36E8u_>|B2<;8#Z4v(!q{G|W(Zur$BPx<)iYlJ7vm~Z)ie9EIwf7!P@=kfpDM+nmM zKKZ+!{DN=(+5hWI{^D)l_t-meR{!lIUhw3ny!@@tlwKE-!`c4d&*SvS|DT=S^AhFP zpZl>t`D?%Vv)}&IC%^D3Kl-Qd{ZDWB#<$b&`r@y7|2IDOGwwh7W4P__dKNBzTjEOo z&aZ#k=e_C~PkHGR9`|>uM{l1>AO6w$Rd0LS+dlH)pZ@$G_^OY6<#RsxuO9#A-~OM! z{mVvAdvyFgzb8I?@gL&w!b9^#k3QqEr=-t+<$GWJ)c5_!AN<@;{Ve-ypZ7}ROTOeE z_V2kp@%-Z-Wt{K(;+Oe9^|kN){IB|xPx`*M{LbI`uJ8Wt=fCpbe&vV%;19;n|D)r3 zop=ApjVylj51kL~e_;2MFOYut6&O-q@JxJ{?%(~xSN-%WA9>N&eD&X`9_8Qiu|NN_ z5B=u1pWpYt{?i}($&Y;K{Xg-}@BH!)PoMK&KloEGeDcqJ8~sUddefV(|M^Yt`u@|e zGS9);P5$ine()!r_QtRO{2zPTOFsSbw9mNx##6raXCZL*OE09G-(392pMBt8{-=NU zkH7vSuaSQ5-OW4S#{Sxuf6e|IxWD|8zxwGv`B&I?fAwe0U-^je_IEPHyFceUKl2N} z{LLR>KlgLz&zZmPzx;ywnSbk<&-{c}ed+y~1VOy~)vtcp8?EpD+Q+}-__@P{4TcN* z)^Gp(S3T<~k9^7tzU-}U{GlJRU;a(c|G>XcU;c*QdhJ(z#xtM!%oqNfmp|=8jo1DI z-C$aCj{_TJEgFpBa-}=Tc{E9#Q_4hpg_uuxG?suQSKl)97>nC1Mzl{H_ z$GF#i<)6Os`}Jpj-J>sk+V>jA`TNBDKfK`^zwqz;=@-2BMSuM{^Iv&O_qo6MbKmi~ z@BZ4yx+m?PQN88&f9%gb_{+&_-}{>8=RTqPlYjOd4`btlPao#ylZLtZ*^m2)-+1H~ zUo!o+RQ^;VeB^ta&;7t#e)n1Y*M8*q&hPwtU-9u5VfWC;h^UKH;yA>fg}5aWnla>hInE%fI@;cYfj5zvx9z_{?AY;q$LO z>!nZrlHxJ;cRu#xAN`|W{Y$?01Hp@5dbp$hsK7tQ_{5SuL)tkS!eg{tAdE}E{{?<4C z&DXs{ee7}H@mD_nd!P1%*^S8Xzef^uh?nB07`ak%l;7R}f zi_Sm#;&1!5PyK6ubN_Pg{BOoT|3yFQKlS*0jG!02Wcw`l(I@-3VqZ6U-9LNw%bur7 zPygcgeb?J3#;5-JNB{WOo;udv^S0-{{bk(`J>eH-^1I$czVkVM`=u}c=gVSA`BD1mulc|i z{N*qI1Lc4GkAHRdk&k`m^M7yr-XD9zH~jnm^4tIZ#mxWkNz+ez|Np_%TgOH9h1_Y*(o%{6fm!<`SeXg6xR5ikw%LCM88O~O#cv0d7v!Fl;#?yJz0B7ea^;foM zYKSXK9?6@^06+Lc0DS+_Zr8AZGO}gVi{$;ML$iNN1_AdkV_@$l0jj{P8flI6e9fv| z?M}bmQhJQ>#J;!#kkxJ8z;JHu_}VvUt#vUS=%E}Y2tu7 z7wO9oJrHV}?T5;yR}BLWHwsySz}Y;`Z@=dL zhK)@+uyd{xW5AYQwR85?I2ZrV^=iA1>yVw#V_7oIq#^8e5FEyP0f5>@+hH}5)i?b( z5F8CsaD4Rr=U}2d^*+H3?0yHAIeQmaI>pfIpbpZ0m*(i!N8p(oV9p5$O{ACij|7&8 z)OsNH@6jU@fI2#+Ll}YDr4zgO?w_8Tu6vBlq4=8sYOJ)lpf_6>i~u7I0#3KXkZq`7 z7O9b@zP=1O(Pd3gmCgA8>6riezkrrMziuiGzBd%p9vb0=sG}j8m^8eY!j~D1H=LfC zIRn0$YQfk8+Ya4<6N0fNRp7PvOgqf}-RoJPYjS||8n9(DSqh%{2!?xc+u_0CVK`%X zem){s$7$#*bS#uK-4y|$2H+XQwR(Qcc-9jsbr1$<4MtWgK1 zkh#_lj;c8E09~P--m)Fr1be@R*W$*rPQ{ ztz`14%uKhu0$7Kqz47eOC2s+gh71ttMUocY{0@5k_x{T9OT}^PZgxLph>9cubanFE zEK~Du~6kivpbuuIT8Qgd-rKt^?;JBg zH0=7d5_^0mZoMeJw;K^tjgERhM--(<4?X*_1<|OO`I$47eC@)|yVm}Va&@mKDRbg& zjhGEV@6}wp?wD{yj<~19!riCowRK*z;6(tdvRb|xtgS2FR=@Sm{Mw`%{Xfy_yj_~(yzkcFoRK%}( zt~TwpoT}gW6ju}|-daaW$TD)o_}%CHyL(M*B5^~x8D-b_hKtKpCetqbV70xuR>9`| z`>1<>n~>LZoJURS!;6qpLE+N^q!9RR%&4WCNZ0`D2V9n)*#MsHC5!?nMHdY04Bm^n z#}*R4|L!ZiFLD^`UVqZ!(^ILYZi647IDjs zhB>JW-G(CNG*s2P>2ED|<7V^EkXI)U!1$sSbsZifB#Jbpo?e2*gLh}Qew33yhVBa^ z04jD#?b1wSFhd<49^9KMD%j)Q)s!NstZ+i+C zR*NR#8oa+cW90^by zd6(QeCg%Ghy~J_&-aL};H3k$};`*#+vnS3oR7xv9(wUiGm{wh+53<{yYdy*Tqg8y8 z$s8FOf$>}6Gda{RItln_8ju8c`d`WY%i{U zx67b^HUe~sLrguQAoP~qbY7S5r8gAfgN&+9Q(eYY< z+lPEqlvW|lD?1wcou)}QYT;4FuBt2X@;@zCRzO`H|q%~-fk zM?u=-W5Bzc6%RVQm4^?-1vN(1YQP1cQH3N#5~P;h4H#%>P}lAP{o>%P4v8K9V}41x ziR~NDujQ==h3>w#OLvQvsV;ZXoNWqN@9Xqs-lPD3n(O+zi}q!l&*8i(vK}wCay+#t zofu>dd8PA1bIX<7)#(ml+XldM!a6_Pga$FZ6{p6W=`{A;2p`|q6r%?Y#i!ul@}t)* zAKiY{+fefdHB!w8l>JtGTD`dOTI=wOm9tqX{w6-tt=XBUJlba1G34xk4(xaFRm(v+ z+lHqw`IU5^l%5H@RpvKC6m~-;+;{%;0!-Wq|rKOyY+W zqv3g&fr0kyF^;!Ls}u$`c=4!+f8kg!&Y#yJO!jf2EFm{J zmI2WjKSUpwIhAFquh1~-_BZ>RL=2Kl;2-}}+A{NBZsL!lMN0!EuKT8aS%Z0?d|pn- z>3)St96)w_zwGq@hvPrqm1yI*E@UjCGykM;RM~j|y2yyi_$?~exnDN;!W)T+%E!5A z$R2Z@fG|ScY^2N%{uIXv8nnNFzvP$&)Dhm$0cHDMDtt)(>Grc&0#M}<0?_^{M2iRf z!~p$?Os5pG$tdHMqF_cgn;1&YY@E|eeFvL(I7*DiRYvfKTV97D0(BgyA_$cqMp>zd4ZWgh=cXob69(H8Ak}c8LOF>2@3Bak;2v@oJqs_J?;v3&C-? zMos?!b4;(ZtzxuRGy-;Bm@;Q8@=3=c5q`JjJq7N^~>%!A>#LvKz0wdgfV1 zcsS|qo^#WWy~q_o-+uMya#RzXR8(h!ifhf!N|KVEK$_p0jQa- zUf+9<`xUXvxURPpUg^FvZ{cH{=OrEo=DdZui`+!s1Htk0X_m?sfiIFaK2iIpdo{9f z{1{}^lA|3xvb$(LpafHS&oR)n&&G9}`_J;sLPPGbCUMS<6fhHdRTFd`Gl50~{%_Ab zzeY=bq--#Qwe|uYOrY+GnvPX@(RQ%znQMB6jiwjj(|QnmH!}!t`d&1^N^BNq2vevK zBlbwK`X9N<6*(Z1z$$|?@YwN)?TsrQXRF0@AygvAXwuJvaUrmM=Sh`b>}hhQ&T$TLO7l=NU&Nx)$)Z}DT&g}D*V z+Wb4NF363!{jl0H{y1lYSivZ(Z8p&KhI4=BFDGSvQJuQ_&R4+`%M1Gg)9B(QI9e|m z;I{~hV%?37*9-8BKSYykDyL80aS}*7Xv2Jgt?5$h}mVJ zi&GJ+`Lf#a$1n8A83*OHGyA|!s6UoU^Li5fw1q&M z>$@b7j>zd_lyt2KxmA&2<_?uOxliVDD_^hSp`c);J zpKUKTy9VX>7Ay2E3qX@YIVZNeVEfJP`c;YaVB!L5kD+2qyW(&$7Hg6(@YDgvB}Rzm z&#->Y!jn}t@Erd)8nZ*xyC3AOPx0W6T$*}#+*rHo4M(`%EFg^uYLS02T z;qdRFFV{t~F%1Vs!d(HTK#c=vX|x0^lHg@rbo7u#1QlxZ!0121;~2grLEI8*XQshn z%NR}we6^jL71DC>gD*X{`ZjYF#m3hL^3VV(Ga6eCljX;Ge2BNyHuzf!ZkR=fr^FDT z-nAZ_+e0iVsohd*L0?602%NzvIcRX}fgVp@PN95E6;r(1a2@Y=-SueRdC3PA`HUQ3 zyeAv%JP{7dLY>!rxb@KgG~P%SL_9|Dn88AY-bra&j4(SyGqZM|SDnS!OD>=x56ft^ zcf)f=^*ATyt8~&kjfr2t%38AsnD37cC^1a$3Xmh-IK#~^KIX^O$qA$E@A#|yQ0hsi zexD=VT?P9re*Fu^F{l;6Ktn%)l{HaB`g5_UsCDi~g^8x{X{k@sp5^};W^ zmP}(Y*wnYV?~zNC;e=BsUlN38=;REqXtC)i6rX+K5Hvbm9yrW5*`goEW4AKev{KcU z0gRr&AQRn$7aupb7y&UQ&89n?4p0zGOQz zNm0;H*J&VtqEb|+zaz9qZxE2pj^z5;Y`INauxK=Avyi*VklIiGq&g!L@!wVHUZiY3 zm&hqe3C3qLqh;eWh1(d<&@C41a-vf-{eQCnEVI6B92`W$UDC8*ha7;>x)waq)kO`$ z%D#?ly#G#CARkZkP1QLSIdWo}#WE^tiC(hOr@`gfeRU4}!OmLo@pvn%v zBwjGpGCBh^RX;7F6VDcZfSPP{@tq!*8UG91@a0ouJt@&uwS@nd@_Z^6I3Jch`WJ=F z3%Nk{pUoCFAqa#!PAZu|`=~APYO;)&XSzIo?%g)%`BC@8Racx4+RY3*IB-ZDTWFtL zg8dW+?A18=%ycDLM(|X~!ki<}F^DFswm2ETfoorHWS4%UEV5YRoI63%!7w#4!D8!F zK!~A^g%WsWP9jEYp<=|Aw6TLJ$Tqci6X_MW58TdLJTH~4Xc`E9g{S)Zot1n0RK!V? zqbHK3HhB7=e6e0Yn^LOl?t?cVDf)|4gWj`f{*6qg(L0jP6Z-;=v^%(~ObE<{jL^im zzhkDeuVF^0Jt<3pv3~0=%Dbt0E*a9V6`NAfJgJd&s|>@jDFn;`Wr_}Z-4*ztuC5+j zU;h?R1bQ~yf=%-Q3vzOLrpie0@_5yVVP*%Vrp{^z{)0X~2HpG(r0r_n=&b*h_&Q*= z-RP(4`}`EW33lmt`8r@S0(4iRtfAFV`Zw@q)yMKFAnptEzXlFK@qMc>0@%eeB0CMr zN=k@1n`*VQYiea(s3|W31z+x@G4@v#RyjImS{S zWEUzTIBeamgbPAf$Ghjbmud+^v1+H`n21^FOS&ebh&+wUkx} zLX_s0A$L6e34kbz?IrbcWIuS$K{`+aFQo%Xfr~|Ip`M&Y4(Y((CjaB9#H?*mzkL&* z{a;|uE`PV$HO)R(hpEhrBO|&=Q(XOaZ;r0N*G7-GoALT>o~&{)q#?i_7(a^mo|*%8 ziM#?zB10m3B46UWM43btDq&Bw4>!jH)h6w=HlxIqX5FTbACBsV;GYPn=Dtm7tgVz?vrTeeXd*0?!l) zXZ!?@qZ@>>>KWrp#bTgvmr(7q1=|7w@&=Jjf>D(^F zJGxnj;P)IUZM(753VG=V<>LH4VVAE`P@Z{_-~hpp$<(&gG1mVSb|?t{akZSNVTzF4 zPnCcg5uIY7Qc594C~KRAC7;Qfi_ygZ*0{sLYS;P?7_NiQf#>O^r1|bd7QE=+vpsI%oS8VW06f~aw3Uss=BA= z{{g(Gmq90+o15W8k+9gD3RoE+@bqQLYwl91fY}wu0qxaZ63w7w5R^z$$K{HdEZ%Av z`0-d%>I?)jupcTieVx6?oWR1V9pBHQ+#r)~UQdfy>6iWtLV~^dl(&iw)CpS?!Ksww<0)g+bhMdx z^7-5IktNdu^{A{%SUsSW70%!>Cwuh3T^RQtYf}jOA@^*?zTi-PR=3?4r^3B@QApPJ z3JP+JJhn$tZvl7k?702JawLVdW#^mYC&u!kfsCHX@&O6AwnK$4d&M6BiC;rody5wQ zxROCwwmEYEv)*`il5T&r#|oC6Gs!Y214<{M^WAUua@jZ5@Yy6|FXwQOkhw%#0rGqK ztc5lc2G;TXewf%9_gAb*$3o`1_WRJJdJR4pp*+p}cqmSdl&P}3EnEzTP{D5y9@~;zy83q)g+}cqB+&RQ*0Y2lK2z+s$`i=l^%=02da|3|x28^fQ;+EHvWM*m_2Ppc)dZvCh z6;)e+@+N5Nzt2c3E_1Uu_LVn7lq6{Ml_HMvzo)<98F4b73l$nc{IZ!HRZ4ld%=|lw zjmG>rARfI{4>S61?nh&P0UZfU;V75hGTe3pk zGrv%~1lUiH@0giMbSMPiDg4X8&l?22CFxx%sHlBB!>X-ZwC#_Q5~ZBP zym=E%*fT4|cYgIBbf5Dki7Fv45hG%q7ZWjwh)@7QCfj5~`6?dAq)hqOf!g}cx9uaj z=WfyB5IV*D_PFga-k*f-h-(1aR13$Ebq$oED1KbVha8x-veG~>e55lRP9`%FmbY1+ zGjrMr>ddEp)d(NhD5(!ka)&4gn3I_y=Lb3!Jl=Efv4+JJ=ySYjY2O}bygg*lR(aRA z>rkka$_<)2{&%p zrCk-b)J;h%WaUUYR`Hw(JPVn|z`1E=3MZ%Jgld^c_JE4r1o#YLtizQNze>aAs`)0S zh~db~RRd*x)RVF$oFcdox*CXZmVT2b*?W%V$jbwV_*52pP)z$#ao5fZb)!+Eo#oQ_o}hb=MM90AG6pOvp$!j7X*G&f)h^PNY7H(V$#ZgGggor$Wf5SQU1!)tuc)qeC*hpAJS``Ttz<)m*ED!wfmK~ zmpgN4a~ z60n0k(Os4r&_%qDUJNkboc!j3(U)ylHyX;4sFV!esav$${>+9qQ4s9LQHvV3Z2DjB z;kmI~_c}gx_{pP(#c2y?y89Z@gFm+cKMj(G(df8iWl`P=3ZouAlS`Rjw9wLujg;y0 zUwoiKatvtOAv<(}L4#+Fs`S6R6ERi({@ifQiQV8|Y^@I+E zn?GJ(h1~A>7No0a;?UtmzD2an@*)OAj?iam+<`t3Ef5Gp-ab8?oB{SbrZau|HoJN~4a%^}QuX#nG#m*rAUC(Tp7GzqH*#eO9vUg|0 zje*P=o#Y9LSpZ&R<3QUcj$-D$&J*-go1Hm-^$uN_4PhIfhzxn>sBk-jJBFHb!nXjw~eq zEAM)YpkO^%5nkvAvz(TAuKGjPN$$8%2|_#?`-8R4cHG7oxxA+tfZ7HFAwO+gN>o{` z*mj|5gpeKiR^$T?o^A^CUw*q;5v?A(_jV#Yx`*q%VN{>r@h5{2P)n$WMM(Ng4OnVp ziYi>38ND+7UwAs+5p_vC=(tEpQE}iWa!DO%x=MI2Y1Dqkr3AwXn*;II8ywZ-a7(l- zfOpL$trr1$TzMYXk0}ea@c!f$&?LsQBRpSLU5zRt=+axtzdYHUi|Zdjgt3|-6*l`K zOe4O2lR1BD@yv}po$%`yvEMU5?r|PHTD9}Pj%J*Fn*~3l2hGd)$hzbp0zcozQdu!E3Xc&=iU^f6a+;b@mj}ly}Za)^b2+!Y!_DxguIxmbFdnJJY zHR8S|r$vVZ0baO6SXdRO7+Ud$Esu*`PE%26y4(Sw0HG8pmnM;hq$vwyzJ5; zagHWetGev8vla623pTw`&YHEM98k7Az^Fg!>FZKSIYy0zizm7{`8rM2IYCdRxHG$ph{%0wj^XBLWmW8d z7qh(NzZD=%f;i3yPNDP#!X}@HH3|`Xe*;0L#0ux>LPZ+Z=oGfFa!Frf2Ks-0}& z)Wj`-U@>j9b(7Q95Ajv~A=W~G+W|gX;$`KibZDbY?!fxtS{YL!Y1(-*152tG7%z5Q z`ZxVBT6E&DA5qGJu)6LEF71k3C-thnt@$S`bz^7w)bXrt9MmH<%Fugt_c>M!c2x5x zJo_IieDLkm0hSu8B|NGuoxBY679jNbkS%oR<`Yi~48O zQh}+ue#}_8MiQ4Wh$cVcNIQfUg?~qTyp0OfW#{7VVa?C!aG%=`28MSxfD)1)+8$K$ zAH88pP6<;$e#Bk8_#?RZ(BEA8V^rEw*XQz^Fm~8P4go$mnOSY{@$Q12&P6eCn8Kw+ zvQQ|GzeJR9r^(8nxIFI!C=8-1ty7d4tik(qVAj~se))d8!fB673}^mcV=qo|T*XAh zPH=p-qTHBxJ|;ZoQM)(k$gpzJ2s2|fq|%z;eY}d?`y|ELszsxS-xuZT_FlOklE^#; z3u#5yXcXqSgywEJYEZAd@wwC9Xt9KZWU7WLMjSG|kLt?4>qJAD^M>?-Ymh!$!#0v2 zWu=V>KRLPNWUEZr{?)!%kj^ZQkrVum#FSj8`X-`cYj}TlquV(F#4}v8mI2xi@f(UC zq}l~Xt+qN>t)4-aUQz@pNJv`}q&gwth@2tFM^QPWGnG6Ad4P4soIr+$ zkgkOPx5DhhOXVozb~)azMJu!^IG|VgvvKCAL?@H^cN@Q@^D#j~_zDZ#n(YP=ns19$ zL_+ch6!A+Gj{Gm~|J#Xi3LP;ZXiJSa_i$tNOLc+&?zE--SaRVkgs7YBP}-3Isn00s zLtI~K2ctag2+*K*jt87XM6>)R0HPNN9xH)>AEk<6|9RP!eMvAL)azBjX|o`;$Y#kU zUt9e~=La4O`S33le=3*E6(TYy>MIfp%T>XJ6q@F-sET+c`EI`GA_ zs%KF_7;ir*$I(y(3AwQ2944Yhta3KwhLWVpBHNJ`mTTm!S<85+Y;c7STMr%{D%F*+ z`?`UK>gNb0Pf7=KV;Csc*s$sS3nN)u;0Huosq+@jrg)T5N=Zl_<73vC#aLs6E_#jH z^CD*#)tZ!*a|Jz0A%Z06?>96R@{0x(4=H7<|EGTvCivjY;ed1W(kx)^;ld=|kCXUR zjRT{MKcM)avMdK`b=>qmy4dt5hEdb5fu4BR-`2yqm6_T{_kp-!>a0V{_$)IWJYFZhZb+V@lxF%M#b>^P z%(V7leQ=onYR9tp*#4BOC1%tg$mfPn%$8~tEDa<9xg7xr{N(F0d7%d)j_|!_fKCOM<5h9iXlRkg`R6PF z3Js^ZQuc|#bg{2LRKT9yXvm#zLr1qa8{|J33CVh}2*yT;?1X6>Zuq7UzHC+N2Tgt+ zxksHQ-4lde5gm2yzn|QMA)u!VunhE@-Jx^~ccWr9>Gm9}o4Y03Hos`s&lNuI@%$di z!Ankl%31CWZ%rNO)2ZkJeh>~AXR7-*G5y>M^}ctiDwVjl&B?X<+lE?C_`o=VCxVCg zS52Itf9GG(R1~X}AE3rrZ4Snc%Y{j9m*jjD1|W*s_`{#Z@#7K>vD;~7u8oa|*Mq>c z%p51;VBj_y#wg_1MRbG59J*dAL77N*cvXF*!Mr(-5x4&(DXG0K)Epw5Sz1*VM&;?6 zXuMZD^NYX+y^~KhMeg~5w1Q}=yDn^uHxB$@s~R$kKaLVBWBRH5YrhG^aigE9Vp<%t zW0XmU7E!`BU`ijE92d0}@~9#C(s|7PU3Sfj!YbM-MWiqcl~F{jH@*otWhN25)ywbkT8~Gg1_a(`^_EUe!dM?@fnF<002d{NU0 zLgw~u6KPNKAv-o0Hk{W_;TTn0GD{u|Lg?Powe-tAD0l3KDMI>Os)A=M2sDH@QU{qB zu9ACNe|IbkwlqEtU6xq&`7?Aa$8Zl$t?t~{F@z_Z#w|824TQiHwJLurA*w?~A$ZRovj3Y*;0()L97M8^c2)JiF z>gJ6|u2pQru>FIAx8d3$w`{OK_fPz3y&H2DVsO z1jfWAX}ZMGwtq3j@t(B-OYh8QMXvLoOmpX*@HufHhgkL_j91}!f$P0vB2psRE))nm`H|m=@)T#Crb|Y)R1#SY$`5D(;J3k{ZCW$pL<#ACk1b0*KTdze;27E z57VenM*D6wh=VZml7TkS5cwGHhRAlU9YwNN_cu9_`uBSI=AKBDL!ybpP)Zj>A$CSE z{elQZ*~3v?dlR2Nfw2wkbcfDU?o!3_w1Z8#*-)wcu&#NU^@kcamredaq@+D+f&`|G z_lqlCHi5KLLu&s1z-VBcWOYWO(-G(*{ZGUkF>y8)4y*BA$F@J5>)FkonEl(qHTMrkB=qu5T4=CPkUeX}Oq&iM z96ncECnpw{VTR7xcMfctycS&fUtgWBsye@6LU*Yys{Se+aS62Hb0|j!o#hnMwH5-J zVVwN|DgtTG!+$M0B}h9tG#+!|VMfYJ4*zXnT~PZS>MW)3CssA__}j|LFDlAn%Lur3 zm@ptEh39)QE(p1t+89uo*5voUv|~4EYtR|ssHmt2mtfrd-sJQv6bQd=?e1b?k{=#< zx3}PaNl%X)8&d(Abxc6bMP3Mm;mM;pQXGEMQXq{Nz19a3_vq4}vFyPl8XpEDK-(mG z>-D?D4m;)1OHS59_#wJ7!9m;HdReoOs8y!t`s(jh9M>ky-sQ`Q?|%ua``Jm_j`AaM zi5;;@HIwBvx6iS09wD`h(DRI?{(HwljbFeRU)L=hle-j1<^_>ln7ecWvlW(;xsrQ8 zOq&LX^D2e{=8BGv4*FYJ%|^!sPN%gFgROk69P#ZGtsecFejE{Yc9!()@IWA+PE)y? zzX~$1ZVL=25-XO}Gj04_Yr1jde)ruv5zUhnSvwk#WJuaM=AHrcK!wf2;}l5X&{$oP zsV(`Sd3B{>?x}aXwFSAA#G~Fs@GM3Obt^BvANS3vbHjcL$bAw(l$^UKO8q~3rv_}b zF!b8;hWRxV>nhCF3^(uBu*(uJB7@?Bi4T?7{T@9Qg#Z>XryBZ$8z;g#>Po9v1y8xK z#oFVCHaFb5PXE)x8=+r%J%Xgg@$b$fBlkCq^Gy`YeXnw=LB%0oxoO?vI_<{7hM_tB z2do>P3&ujfphWfM#oPh2JMH;AS+x(dG++!(f=$TgSU;pM(v+L@vdfz>3rA6LSii~U z)zkGc7fVfJ8_c~wTW;6CXM022BnMt?*8lI7$zG{P2yxgPpf@5V{Qdl2H;@Dx`1o^a zCUR{n@`6c2okLxPvw~@PyQ+BxETW2A324hOXvnypiIycmd#XDPDO0 z)u`DABs3C)Ej6(_>tr5vl>`+`>Y;oUNyjuMC_&8;1s0RB@E>ktuMv>`VL3&0Si9}G zbaGM>ou*kpizjCG-}6_qzmBGzOX@0sjP@aRpL?3Qrn$g=-U6BV_xXZ}>fHJ2o@39? zRWH|;BFZ}Bxu9A{KI+fH7m$f~5Itm}Cnh0@CS*}Llg!UIEbcQf(}L|k3%$e~Yo(Zt z2^~}T1gefR-A`9s7U2ap(Oax3QuTee41=sw&T^xKL3RjmXF=3xA7JuDqZYK;e*I_p zYp38nT$ zMn7~!SOh0^4tNn0kM6N>q+tfzccCC*MB+N3(`pYnm2oD5HpUEY8aC{+_w+a^+EzDt z?s#eP2&%4!rRAG^u1j_+oE~!n))oKZI|G>KS22zt+N$^SWUhimQbGbvCG{8r32QWg zqTjAsr9hx7q5FCQ;K&;V!c|Y(Ovq;%9W2BWorAmG99KSAz0If_F!E#$#8tHA+R{va@e3PWs*x)HlwX&nUV9?20a3kk++6u@DBlOKhU&t2 z@m#&p9p>lfdNkH_&}%pv%Meu4 z&rm=kB^;+P-bex5tq%X6%T~5Is|kWU`rQpXr^KdwF4J=h3(sShB%dM#uNz#31A%a5 zA0q719&2RBS)j_cuUExcxtV&mU&1$IoQd5$lX-}~_a2DR_keg#`u^T6|9&F&?g{kR zAvyX=15=DQ*u3BPVjxc=2F?Hp5mK2xc~glQb|I;++^yO%LYCBZG*BG_tJF^?l=$E+ zV#J|a$^q}-Z~}GP#?3}EAB+8_Fiy%9 zrJcHO9~y@88p5Ng1&f@gv|*XcNvso}C$fen=f2!tjVkqbyMVC2Dne?Pt4gb?NWAjH z;WAm{(D<~Io(ys4@GL*y72br_gZ$3TuD}0rF@T%4o4NCmAc8ZnUw$--YTvu|Ka;%# z?db1yo;OVA_j}Uj>3c7}MyKT9NCd-`=iCiFNX=m8N9Nmr074Y9^eFulCvuEST&z!I zm`e@JN0VZq;zh_&u?}iX9i)EycJLK7`NfRG_4AOQg9E}4x&uV`qp#YE$b%ijXNk;A zFp3(xer(PBj)X?~5)8U@fHA9^CJhlzaGJN!%<;uinJcJoK$aa~>=RTn@WMwuk#g@D zr$1czW)`{~&O|szVeInGBGFz=HsTUl^y%X@=<=t^C%AS`E)19iq5)o8@OWB_{Koq3 zku9%$4XXEX2`cVQ;)#ZtX<2HO82`kmKfbVYITAc-YPX}!?dIy2kp!~EZ1k<>V#A^*GjUqcSy zhIjXtoy2fXM(x?1t-6^eJfuG%})k)s{5hQR-k`c*bFcMyjLH_~Hc+tLw)oIF%HWRIv#S(gAfCxnAo!^osnrXzh zss*5DjB{cY0b6)&{p|Vq|93pI0{INTee8T9e?47jDRu6-f?0z$N&v+TE0<2BGhgQq zYbu+i8kSNfaBV>O&Zn`O36U+3i^Z490)l6WnNr{HEpJ~T^^mDgr1K^*7-r8(5xJu# z@V0a`Dg_&RMfc3I1r%K9uBw*A4YnqKMjMTgJaHu3h_1=+zyhP_XXu5tuRRboHtK5Y z5$07FD=nhHvE?#(W<#-}ky?fPq?Dzxy?2V=M#Ogy3{zk=74fs#o_q}Gl<(~|w0hW3 zjSAi9Y+DcE9qh55?|q38HqY`i_4F@e}i3 zK2J34GD&cL3Wv;U$U`0LDFj_`AC6xy$R-InFY#F<77l;uf=Fg+4q?Kr1<2h_jub&2 zaJN^qj1YM1g}5H2nrprJbwLh&bFNCuqjhy#q^rjy&VN05VPtY=6EXkG>jHoApmQtC zP|B)R8j0}xP@Nz?q2C${tHGvPYPi4uJg(V~WUR0D0&jMqN0VZ3jpo74Y)1VZ^zSdz z?ub6qAOTAI@ccK5g0&Z0A{HwxknCUx{=4G3Jhq0$DA($?d<-BUEVV_F8cpHyDBbNN z_m=vb2ztcT1eSuEozPNXEu~M#9l`l%IkH7LI|m^xn;a5%padOi5zAsuPW-f{9*q#D zStO91Xsnuh-(P%$q~Gu}*ihblLDw;a)Xo?$s&HoW2qMZ8bWVfk3ygtN0}(5n{)pF~ zFE3*fT!+unxLAcyL@>+UPD&hm5;Ei5`oTa9aa&~Fa}mV?K2A)0-?49cVaoh-?CI|V z1Td1L1o$>|b#?D?OF-Wd;>Sd&lRw{F;yU5EapB885MS#Vx%Qix{Y5akCWeZ?kg0Af zD}W3MB`-}w4r)E7p1TMjzcwF*VI6dh9yMQ+Y+cr$UAxGsLS&B36tgc*|AeQ?`boiF zFwyOFXJsUnE#q-Bb1Uo%3qBjuv~xwcVjK{uk>U|OaGjc#Q7r)m@*58Rv;m2vGMFM> zb^O>C@`~@0e$4&?5tMjgoU6<8z!~R=t)ia*bKd+W#B$N;iiJz~MSDL2)hc%xQ>GXT z&K%M9kLB<3Eqb#zdLS4ycj~@}aLB9#yEi7Wb6q`CztaH) z0|NsB!`s9qAt5<8*k%)_Wku2UZo41`ns%WS(cJg5zn;%m*V|a zvCeS&>DboxHk7TBkJWXhWy%?%B;$PmiXYgo{yu0mxY$K4%5y(t-*~~LTY)`LWYcnB zrkr4;&N{(ol@FZEg!uQ-6wf{F{SJN!(&!h<&F|Ib25q|Vw{LON5}_?)Dlnf>hqE^8 zmsA8H3PzbYlpvbR1k!c_s1#(B$7(S0}6%g^gk5l8Kub(>daeMxzJvxY8Om65O8HJ zmA{?UPK6pNcTjlm)XH2cP1ABQQxFlQ##X+}Gt7*{8kX){g|7O2I5mhvpTqebe6B0W z^&_{zR6j=e@h2-ikDr^KB;v>04H4RQZttTF+V=mCrn6v(Yw4Ob?(XjHo&iE|hr!)F zxDx^dcXu7!-QC^Y-Ggfg76^B8zW4rx-rc)buT}Nb*%GA;okA)=|NSRY^6JLMhD#Pd zIjPtBuLRWzu%fYV?944vq)((3UIU+fvwQ)S#)!|1$|bmRhGy*if%AtXN6*ZauBG3S z%^kf7Pw@#UOTXmok3)gMxu8VdU$Nvdf-@<2rIrph+HwDhBz|I)-pn|*QGMB)YMg&+ z$_SUAMX=pza6XZsSl|REQ|4K!6dh!h`OXNlWMQ=y6-Pj>Md7g`F*YhxQREL-uBU>^)xgGnV+=sqKC?Z#<1L4ucgym@SRn+t#w-@G)Pk1GOgxp zJh17rWkphrIS-4OOHGYiaptWk4vy48Wo0$PA3xp%dknJ<19ZXu=D$+^Er(OYV#_BZ z>79bwVY8%MPq^{-*I|!-mnM%m5gNy3mHw<79=Z*CYf4Hla0B2DJbi|_jO0{ICj5ub z*$gQj_rq-ZtkMu5x{uOhmH2aI!k`p9qTN>L(3L~J&j;A~&-h~+!~pVhVMAbH0iL(Y z)W~A4;n?G1-P55rd`J6niROTUpEWMX((Uh&Zc*)~sp>oot$9IeCvHiyPbYy&6-1f> z+6n?&KKBR;BwHG7$vy8Ln2AYh9Hv8Kd60Jj9Q4kS)XrYEv~rc!&MwyIyc#Hx*y4>? z@hRp*J4nQ@Md>PD4P%T?Gl6%AhSTnCD4hT35! z+Xu>;7kwkp%XykwG{~II49%yyo%mj@BmsUOUsCDW--NDk;BBTd7@FOFVOV#g0bHE$ zuK8~miiSt~O*xUZvYj|PHNbx!SmCP4{`VX9kmYL^#EE3)gsttl*Z)eNeT>qLK=J3_ z9kxT%hu41vJ7S5+H)t#>JtF$V(S>M!R{tzH^jqBi)d!8f_pigrzVkCx<_w_1n`Q1F zxyH)+{^x1*-+-UviNtaCjtWm!O)u7ZVZfhLX{uTpQ(;G!M#nA&i}T>9Zl$2=Iew0@ zfMv1B5HI@1M9k2EjA7u|kpeLdP`<)6BJkex{Zr32Il6Q*3y{QCEY}=mvIzmTSfCSi zJ5gaR9$ajnS<>jCJhQeUVS9~I&Y1Uo+GJAJJ-J2fEJ)R`#iGwPjN=ZYH&gh8?YnI| z==>vkP32somPW|t5(zDNlcS^)_5yvw$@3ew2hRE&^>Q>#A*rA|h#=8=Akf|&;O$A` zGC}(6Bo2E{ia8@b2Kphu%yo{&D+_|jze7L4f*Dg(c1N;_u`c5*@%(ZqMS$vsa*+_4 zWfe0z_k~bKQ7%}F5V{na_qRt^t2y--?H1BwUQLs6F!_bI$Cn~8`d)H`yrlbRI)>ETvOoC>|8C6%=U5AfD`-RTD%~$uc)v%* zdPS&1Ix?Z_%a6qVZbb1d-N8AImVwbLeEwO%T+wGS%kFkkfjrw`Tv;jB-lkY8Qme*M z?MEeLNfh5LNSub}QhH$#Co|hoI^((j_nR$A4Xj()+%w3D1S4$WYNj$(`Wt zp(0IMcrQ>g#7R+Gg!ayLpmNn@9A&~WhFWe&Rz6VEUAMPI^z7NMEr#0~ zcjhqe(OgbK{_?QFeUIgK8Qj@?GR8Ygk}q}4p$`)hAknzM34yBFFX3B(NZRGwG$>%x zbd8g@?iO2W`#DwfaOV4elO(6`MaNIO{+Z%o9LHxTn7OpjeY~Gavp;=RJixK35!fj! zl;iubm(6FO`Gbgq0d$t{fF6_uY$di29jvc6S|O($ft^#Poce{FncxTTQ-@%L8f*kM zcIml4HXMzqL4##6(NK?@_FdS@sc271bSre6c;$1CMD*{sa*S9jTT1A=r#{2H zrPOp}_6>~}aqksSFU-;F^!o|_foX3?try&}MaJ>me(=4B&zZ-y%JswC+0>0Yu+dUI zkx4Ope3!9s0$fR6d(t?YHTKlc(F>RUO!K0yuc-mH?bwCV%vKAy8&ah-Ws+o&b4kVh z5!3K~s#c!YM2IKacJ@|<;8y)ZWF!2aBt!k+sH}4EAnJrFUs{Re&sJ1EP^ras6rqXE z*|fp1!q7G$1+1hG?4NmSZ4bGwfJMd&C;u4WVe0Cb-Sn^*-D+sJeejC~1=h$SnUR6T zfeGh)N4`{2Ad(d#cCBo(B=0QFnodO6Fe>cBqMpn0lO|JFz8+?U7#knA)`sc2(G#(}Rqi1KjTLU)$X1WIZ;Hxllus$ygy=Cb@8CO>C2q_}Tt1{M018jb1pvVw@e^8_5hl-V> zl(#&$%+F|PsVTv9#sa^ri7Q+`A^c$I&)-se9OExHvGWp2{1XSOP-C8`%KzELn^;ci ze`_>kd(^w@iws`N{@_18Su~`XX`&Udz&#S-Q6KQ-2n2?q9*6wdcjCGqi%2jy=G4z5vYlDqF;cKYdv)7sq>Y05Dm@D;9#v0Lcwuv!#^A^^(` z7G-#UzMX6}GTzPECS#?p=7p(LlA8qAHu%QNqQp$+&36b^Rfg(l?3-)|Kv~&{Hq(iL z-W;g%A16mg;p~WsRX4pKXek;gG2uz+`OSEOyY0kiwm%jl65N+=>y2->;Efd&uxZq= zN}W7vkL~|^$$-I-d-uEb`{kqawi|BI9gnZ6O8Sp;KQZUPI24Gy<-qo>OuaxvgG3aS zTt@8;T-~|vhoAM);{=R!6M>)aBoa<$dT;SalMcA@ItuZwx50*jIIxay#4Q4B+Y^g5 z?scl?0DKmj2}hQq>w|#zusSJd2oV5EglN6GJ{_5yK?=2KjUp#Ze@&^2SnMOLD`{bK zUbsMQGgd(IqCdO+?I%2v^SR@EAW8!{*vf15I-T2_Z)d|)+ytDDS)_h2lxP3Ce^z<3 zQk^9eJaxcs(myo&R$zjqSP=^UukN>g>U^T8w8h^S@ZhMM+|KQgLNZR(R5ytS57J(F z7cRB_wQa-XKpsEdC_Vh{G1V=srX$ATuE-$is;6gW9@{mfp9m3gFA5YvmQ(4J3uQ2i zL^h1h1?jYsJh@;@mDHbMPkO^P!284E=DQ(ZGlXUO-nXIi(WBDZ-ATMgWppwDN1G$Zh%-TPi1~5T`&8DDe0obHJ^wiX7+8>Kh zIG2;L;lqratk~}*ps?y<;C^bfx(SIY`5(%nWP99#^3Q~5ozPNA%;fp>c$3Tqkq0~I zzWd=`A^rQ#W3qy(3}KCBLyRZFexolZIU!&a6~(7dN^csa9>cwGS03~pmoxo+$k$-` z!D(Xle;U3&r!uT+kJvDf|C}l8U^=9sBBe;8+qU~^gd5!ytTZxTghH)hH%tcA_k*ak z-wJN>&SN5kaDkL0QwI;Tet)q;LP835OXTDY+}#%MY`%z-bRnDh$yAh4?95LV$tF30 zMHfM`F=iTX4$CP~dhRch``GlrHIvqYuID`F8W@oe9&8{f4tk;K=+2K92IfK*(dVIv z*)==OqpQs@#gM-92ABjb7LnI_gnc|RXVnL{WyLVo=2|_}u_%C~@~CVSfb-GjZyVcb zR@q)}u3sQ%OMli!7fQj>QVaCygsQ8%9W4Yi+WA0btO-BQcK9*R1*ZRJ&8b@%cd@b3 z{Z|0N(Ul~qVYd?=-^dNp#ntr=Y&m>!TP&2uTUh8Y9=+B_Nq5afckb{!C)o0x8A=tQ z%SFZf-)gCai+o$Kq)`G-aPF%9f-zDL+Icb{ZMKe6D$#<>!xm&IP+7JFK2~#KCKD?n zniUckoKF(QD}A)pITKbyEWzec9IaWl49@pT4$b0mefND`5U4AAXj6F^x2%Q%6K1?j zi^En1>$QZyxK$@1DJg1WLqG*TmIQLqi6c(OSGE`d37=3p*rN2jL9gjo?xV>@T}UJT+CR`}HKru&xxPHYu;`MF#|!k>Odc7PO6MdE`rWGyAKR zQmm^iQ%KJlHz1eW!UYN%i&Y1-pXyhF73%9B?clZXge1UkHjj`4=?`^-8x5xm!*PK2 zV}yTi*St6x>i^q4Y7#B^Y90rQsWNrX@OZN707t)c^h*35r;wK%U`jqUc5)21wI8-o11-D@_L=2_e*Y00&b zNf4$r;JY!wW4Jy%`vaQf!K@W$Q?Z}l!@h~;nhW9i{N;3M{3bobl9scBOP|AwZ*pOyjw$x>N# z4!F!$ySU14Ko432eUV(WfTjVAsy1RWa1gpd%}vWn`#^Lw1j8qUrs!~~8)7}1t) zEc%^_tSr$cw$FiWI=VEg=5_zGy`y?__A@R|Z&_hGgUE;i9xs@=6-?!{KPse*@f= zp}gn_w_XOoz!KKe{Pls7sRyLFSqbl*dN+2GS8w~j2|j1o;tjt5;%AuL0YQO4g9L!?7$H!s@=GCy}U50s=ZHy1P=R2CV3~1T) z$lm$Dk2^2%B+6>|%&iZM*!S3I^B=PQ+r_`u`HdVbMbgT(1}Dp7e}`_p*^2q=%L!aK zz?ng7sjB|JuU~HQJXx9*Ct@!O>Gk^}DsiJDFPmd0{L@AH{ZMZc%{V*sAYtRM-}1nX zB3#>|Vp?+Y(%W!zBmMWy%K{T#nLA!z~Y&6LMDpV=cEb=hOPmjX)3)vdyIcfRTkT_!2?GnpDm56n5SDUNdiz zQS~c_B7$skWr8%- zY@{C`pHW#;M@7X(rUijXrX_FZ^o@e#ZMRwPHDJLTLWn(ar#ps+_k zKOth77t_xUjL7^ueJN;{S0Ny7$ITBUWssiJbpfO-JRzy}$(u@!IBu$Bta9=LhXBKI zxlzJMf&tDAdNs zi*$OJ%qawaUpJLQg8|#njGowsOMn-UOY$q&18m1oTfDC-NlM!!s9UbghKoBGU!!&y zIWV$mQwuX_0W=9(CYG1bpJ|c(%uh!bDhqV;xZr?P(1M?ULA^>*Qg5fH;nu7{L$c(u zrv2G(3As^44Le37_E~U)oT@(l`?#d%BnOXv#IF!tlBp%rbqqgsVuj~Rb3&UKR%ale zr-pvuw_{0d39yqQw40^?K^w+j!8l-tB~a#Th&IAfrbHQ1CnTLl-8M(d_etF54Qw!7 z&Lwkod4XhMvX_@1DgvX;)}Ni~Gwt*D!KX0=rEkBRn$~7lXLH9fs}#9BSPsph2Uvcm zGA}PLqhLr%NYn+(Rg}2db%l{48maz<;Z)VkD*k?a>zEU&&t$oI)UtdFN@6JKw{u4} z_88Mx=!t29i`LciE%r~+DGh3&AkXx9P0})&J1C1V{m5W`c7GmoANt<^|Fr`3JCOp66`c^-cxrZlA?*l z<%2{dynl*};Z)#*jL>VrQ?M1_RZW0UihT@Irx_S2l9TX~CvcKunA=xw!JCA8$zS<8 zQd&AOm#Jl+O96X*dIiZ1)241Jl50%Zz^piz72wcg3Yy~XGh!5J$|ccDs&L{`LXJ|@ z{&fA5MN0r1pyKkJ$HD7Uj7LMd9@@~= zx^(|h@87P!QP`7UAA3N(Pe0%|OTM22fU zm_yH=Llq&qjo~rS?aH$FifJ-&Zrdn8Bn5%q)g1$|ieP;>DCDf-!4d^YL&OSh2KUV5 zHr!w1e4mF#w(tVGs&C8Ckfr_2Gy=0b=xD5*r|x&>i>x!#Duhun#I}#cnp-^*z3cBf zP7R<#S2jFIW;CKtev!uB>kQ03J*MoNC0?NxqHY#X9_;pc$eV_ z@sWZmNDV5>i%NVY;Z;*EX46KN{K8fo!?u-JYiy0iGp>vPJw$Rok z-)4{DyIbpz?bNu!{q}}Tg)#*P!>L3Uki+vV@$?Q6xc@K=t~t|pFzU~JY#k-jxkt+N zS{>F}?1@huwFv2Re&@URCUQPMsIlRku_Q}(sQjBcZLh_V@GtaT)HWZ#^*sOhXS&Lh zfv)`tB&NGyMY6u$YF|79oVJ18dC*EqO7S$%!oWmAS~IIwAS`f8JP>)B@Ikla z%A7YNKUsU8UL=sg2=;R^pNxc{1IGI3E`Q9^;XQp9!*C4IgQy5s;l#>SH@ zuUoR8#8yg(kbW?VjEYU73Iu`K$l#@M!U14@3Ta3!64PLb#V%dVLaeBjq*xa_+LB^P zEjU?~dWj2iU1_P-sulCb`x~AQB6Q)jvHEF^2 z-px%M|1Z3QEEv{EUeYnZdO!(|6q{qN0qZn(%uEeTN5|CAm-S)FZzW8QAKhoW5>jDS- z{N&cSSAMbe5}y4-I_i*)FFbk34{W3F@Kq;Opzt?*d#G}6=AU#fnBbalF0inN1;SW* zQb?E;QISCL!I*mXiJKi(TR(pRleo=^a=jD?}Q0dj-aG9}CXQ$EQ57FIGjMvYC>DKF>S)2Im!y-2uGY+T$YO=VgRbP9xNQJe3cH3}@su{o)ijLm< ziY=RN;Z*x$N#Wq(<#$wI?eAkM^hMn(5`B{U*{sdNz{1w=_}z;}bJC;j!9)3Co9bCHlDY3R->f;Ot3kN2~modV0Vm)wOZ?BCcJYd@XjFBr7W!(rmF^(7{R zs9w2A@wJt@&Bf!bX2#6>)jeIy;C;rvPItPDjX7}G+`KpTcY>*YGJ$3idZs&gD|f5 zln6|&0I^a|#zSzeBU#9AVL;4EZNL&R0sjTMl(KUKDZBhi_Rm#22fG!i^j^~`&=kbw zyw}$cmsO;kotE~Atyq92th4)^&1z$_*}=B24E)~({&(}1UV*+J3Nw89fz&@JowqBT zW4C(Orq$tLnb+u_bcosVQ)6|@PWc$0op5h|zrRDpo%DTYKDn)U-K~UVC*9d*>K3p` zhHj_}4U7@}YPNS|*G}!E+v;FI`bUB)+viXe6CL#YRytyKEbclDSz0*)I8IyL%Rz6Y zsBOCv0CrhoH|mu$1do3;9wjZq*A%s1Nq4= zpbBMxY!sXXoe&PbZ-};WfCPj8jCsv3HfjkGO2OjvNk2|)m^taVKuOY__UNRs8G!p$ zx^gy%F)UXkB=l#U1+3%3i0<4dw5SbXL#1LB)@`dDDV$_kdQD2JK7wB{f)x@f0SVP8 zd59MZQUZ5IsA@H#Nsj3yuzYxlj0})bI5@*&Z_xIz@tsG2TvmLK2OSdfZ&~#+fPiCj zjW;blJy=}YPdrU9RlMrnauq7%dl&r?UlF>K(04W$^wh7c6QFYAiy#><4)vUp zh4z#q-~?A=u_qDsvZSU|FL4LXJV_zt4H*hg*%x}y%|fy=bWckSBv^AIY$-Q1XdH9OzOXVR8E4iWMcF z&rd6bHX%`WyoTrVBCFVQ3>wjn(|W#j>gLGTyr50m8;wuk`!NhKQ;OHjR@{j{^oW$Vfz~2T&~PCrF1w zxfI>~;oRl?Ynk+6!%Q|``%SS$nBa1VNMY*dB2gojWf%^UOV1>Uim(m>Od#ios-92H z8Jn_6Tuk|aT9|H4FkK<$+a>@HI|F3zvE$=P(BX%&MbuFaiQlu zctJx0Ie!^CL6=T`e>EEEsD>Xe zkXZPJgoZW(9uYy^*T~DrI7PTGeC4U~nwih777_r~1fQP*zGpM`RKzM>mK51@;apc$ zbd0>H{X4xShi?3R5gD&5>LPl2=xbA%snyAY1w|mOuO9TP4z|_1)0azfq&kv|$ zw%~JtgV35?IQWJd2s_ih=p#l2nngAYF)=JGDoz$n<|#|&Au38WTY7FQQ>=&x8deTs zjZdoNl_|*ci6s54vnDfF+$zfPaaC0$f_ftX5*g9lNI>AUL=!Q<{qlGrw7U6!8;kL# z?+eK2g;H15&tcG{z0(ky+o>CZK9dPb3CHpen1_;XKL%!?#%4M8v@h!v!Q5Hp{=ftG z(#?MmGl#V%vrAUtF{VmONpa0BVu8=4aEyEA^TcQ0yx7T?D?z&bR_W1**lAA8F8)2Y z<>bL%lb8I!tGkNEb!81*h$NNKha{h5RhH9of6-cTT{$A}a(+6hMTu5eKt2AajE{4- zHD5MztBPdQ?F+ky0a%BNGuZsO(8F~Ba}AgAv!QHHrlRz%X=JZL!cNu73@Zbxmda@W zzaSq}qf1110D4abtL7;qc~!<4MWUs#0>|GmhS2GOucbiSp?KIoUZ#If0bRW>JZ33m zAT9#c2!yj2i|1nrBB|jpGlg9S0!2O$aN5k+!Capq8V?eU*7D#q1mv~X^vKWB}mkuTUKW1+>gA-JIgnrSQHnJO-?#umDmb89iYwH)$hre(s|%3 zCwkKN3~zF0p94V@;^Mg(K(4_) zLqHUzEUe^)ekY|X%HIUGa&NfC9{X^{%NhoVaUv(qlMRVcl4T1JklP8NV(*@Dos_gM zM_B6$)C-#>w1DI!C95&N#hyj{mIhxacR{!B`M=ugtzcB|C!INK1GC>Z!$$W#UC{33 zZAB^O>)HRC`E2a@s1Yv3W*%)&L*=A==Gp`@fbIyug-s_Gi_$L?02 zr7JxwwZlbT)~}2)4pX2RFvIpXm1u>40~c+ZgTWl|CPhB48SP5Ievpe8;-8iuJ$S_8JbD#{2H~ zlJfml!h?Q^#9re0oEJ-jrX&Ct7v#ytu6NL20XUx z|1!r|C3U`T)7(KF=C0^i+0v34B0&19TfnssyoO*aeFYOzdm5`90dBrnF9oHGtBbOV z%J=oY2=renV>eyHHHsiys$`75h4Kr;ZfCOe)?TmRR=jj8zE^tko}2n!1B-^dz5QE zWq~qO=4*dY61>TAi?DG+P^IR#$)%O?`;i<+b0tQ4Tn{UY?^A19#^P>u?AK(g$QI24 zZs@;9ZHZ$|O+RX$k3F&QlnBCc^?)YldDk**43ee}{KcVWD`RBOS7K-`6E+#Ml+!xh zB>gTd`W&Nd{_VZ}b>iaUdxwWH$xSS78G5-S*Dd(FR~r3T8mXbJ zTk9Bh{_UyHwhlxuIdBp&BR2ua@( zB$yl-5~0AzuPZ~KSNa>ewpN3Hgk&jx!qlDV=r;9mod0+`lyNE7)$*bgt72_dcr`|2 z8hwEsqgMW%MFRh*T0%Ajk0_{|?OysG#ip2ms2f!?3X`fHCdf4C*4xI{08ra((8%Kg z`5hWbo9YuUl&WSWtR_7VWl{(R0*8qR&tC;*iS`lyoqb=9bkP z@)u7r@NvU+yD{-y%>c0z*XUK2fmGt(qo4vEq2qG9a z+#%ID=^K6Kbk(*EJ2TvY?*XY%b}>O%?PZ)Xd|0VY??9IQCL1^UK` z%wNkx!om*IjC@Vxj*@pJ`l7I=KeUJ<0uqgOz>G*ANwjvt+Kx<3qth5^EAA|1!%Xz7 z;enMae461?8A2OdoA```aWRb;z0Jfy{yhm@{8DyHW7~T6U(KB*S<|5me&}7FE6JB! z5LxiJ3k}Z*ydE#dnL72YnNpB2WbgK8BuM1hZM7`%C)=^0%wFC4i@U(B`mcK@9rKRrpQ)17-0uQtZc{0CK5g{D0J8!+2g?>EV}vx;D41%J;Jx>$gugGV5L~! z_G2Ov`3d*LY>PA^3?~R=KIAlLslCM!T->=a2`b3RUaWzE5fc*)_f$HFjrmH475haD zEUbZ_IYj6=2(@%HpwWFZ`b_N_7NXTzR8S`WERSE&n~|O#bhRdQ)cQa+d193DIllVU z*Gg|+o?CY}ocdNH8L<8X66_Fx{`|N`?FmkqBzc^0-%IU{8zu8@@@+Phpg5Me}-tGnZV>{xA zA)%k$?3t3~7*gcIhq3Ul5x%9_I>V7LcaeyDu5M@}epbx+Ovv6f*QEd#VUok|3I|R{ zAXPh|!*xMgZRVvt(iQa38WG=@MOsWqXE-x9h*%k`tih7kv=eu*#tnu-3U1qh;bVpd zS{5b{K1z8ZadHD8D~AJ*j?@WIK#6T;w$m=f&VF7ZX{jmu=3a!c>R#*bqWa{A%cqQ( z5ggw|aPUy$jL{7;!v@39#fnwAf0pxi68ct2EURj>7wU)M`wBp32i<#l$4WC|AMVIP zJ5g35d>RVbFTAo+(Vu=nr)ttAm?jNz22p(zGyo)Tr9 zPrwS$ZgxlE6O9$^rV=0d@%2Fc*>T+{|pW|V+Hb8 z_3)s3yxEM{?tIGckQyZTY)ad_p$kWIypNvpXv-T`#L9|%CzXmQtJxEo&(-L zUHckO^w_;^t%YDjgdm{akAnCc=L@ZjfZaMUc%65t*A??kndLoDs>1I&Kndx_l;GS%oVz zr~1rSjt}Q?XQ6;7JD4;^NNYMeG}NFBYLr6Uf3VO~E+5?7Op4c0_12l#ez;AO3)bc+ z!T)S-s(vx`e6}XJbgBrh%xC^Yo75}I&^%KYA`~7_-%9I3&RF6Mn40b0R`Yq)Gg@Fx zb=K2^3#6RM+=4W4sxz?Kp)Q7$BtR`M7u~EFurk3pEZ2AGS7E~wp7DW2?{EE7(dlaE z_-4Bj&UgL0b~AhJU}6Hv=kL0l-BuH>ZgmbMRl7cts?iM*c2LxKxiZu7?JdnNE8#WgoW!?2he~ZhQ zm|J|bhm@v$t9(@P+pZk?VV=zoeKMPCrQxCe-fBLMRoY1faR*N5 z<)C$j!lKc*?Nv6Aj@|<2hYtE5q}V7b`fi?SNTYKV0;4h~sJzJ{PzMKa35Zw%L~E_6 z()Euug?2>-^l0Xm6SYV`1_}`=8+V&PpY2#50%GM3HxaIDmWuec(CLZK%H#L`Iy(~( zVfVS!oKEsH3leLj9N*sEfiDXBLJe!SAu7&4MELR&V@%6?QPAZw6SZ~7zMW78nPiMH zVoZ3ZJEu9%Ld^(_-)Y0q9z|!zAl|&Vn%R<>Xj(W#LM~NJv8yhJ7pSN3BlsU0@_((q z{>><9RfbS1Cc)(eO~+Om9on_n@jY@qsLGi%tSJ|M@=q5G9QSHW8ULJKMS_rw(6+0? zlH5CVroazwv1V~cAsS=-m^R#c+{e}~9(snO>vgE@pupuEj>K%S*J0V_r}h9uGn8|4QoXl6}5j4{?Ik|Hq4ib7S{ z#9~5|Pk1?WU`}^i>32SE%{;vlW4GLIMZdX|grzqD&gk-Mn{X(YvSzTRbh+t(IJt}l`K#$VYb;!!M zp2OdtYzYQ}MPcr4uNdpilZ8+N&elM+xe}u2PEx`Q1Chap(wv`x1wW<_;XSL|-Ze)1 zbHX%ArHJ~d*t|4f^&!$%Q}RPGk*|1tbQB00xi<$BA&R4=s$+LYQ~ff`6{7KBIDSQV zRBO@^x5h?qPiffcLZ8w8U^U!5NB1+-EDer|2au!F?1}lpvRGmxBPWuGjYms4o`IXg@y)UXQ#(uZ)rj{|8@&p?SvOfD{)a^?KZO0DYOx)sF>W|Klq2~B1T9| zaRS6BAH1-^sXh%2u6L74#0gosVc`7Vk?VO{iK?lC;%|l0ZCK)PL;ES8g!}z=UZ7@$ zoY^fEh$5@Q)bdrs>pgeOJGjsjDduk0kE0{Y(*3=h7=Z5qPa-!n z=hs_`u8+S+P7Y7ie#UJs!fk)rtooec!oOzFyo=fFqRB z>#vQP6E^rm*ug&~KS}g@*u5c7sB7jNPE;7x=dgez7To;w-;L=CWo(6Yv4m8RbIc;K z^O&mP#*(tKgq2PQ*uw^}K(ON?D=iFU!;O|&mfsqG47cp(?$M$!nv3j(0AFSij{I9} z))-v^#iW z+;~{Y_3%J91CH20F$qU;t#@`rCld`R);9VFqmU)2>{^m8gWP2jt)zDRMy<-NI%-_2@GGaF$_>V&0mdu>Mu}`n48dC zU}l3V&SfB6XLEj_ddRzgAKkv-4Ky$g&TRrq58^yuQa%}Tz5Jg6unRO11+S2I-YTvs>cERjittSAeGzu z`~FEs45wF;S>bk+xLslNZ)`u{(6>4vTBC^vK@fj$6v+UrgNq;9p;|izQPX;l`K$i< z1bj`O5W{poJuj2J6rb+GLY0zJJ~~Qdu;|Qyt>+ zNpuPj`Zy&RjV6kw|M*QpMO8@rz?-GG)?>}9S^bJt&cEz=o#6*&oVK$_oH|?+o<QITV7O!$cIrEdFb|oA* z>*pQ8D*8QAr(H5&4GLEYa>08tD4*SKEmJ$XT9)>*i!+`EgMv*YpfgNb#16g$*Ngef zR&K0r;f3xM79~faABRt}>GenpV%?b?W~5Cf9wLAY26C*^A#(H^JUhjlUPOR_xUznY zsD2SS&|qTla{h;krbf&(z1rd7w1v(2B97tNztkWF2IaZ8tljckl4sB&s-N-m${fI$nr9N}M#tIh6?CsylS zmS?p;e(@=E+w(=bs&cN{z>y@jzqqQ{^BpSNvzB>eH-D9Tuz<8WlF?Djk zH)rew1*S=QY{PSIu#yD>TQaoIFGcG6z}?;5ld^Lzd-)=B{7AhxT9z~317V~}HBdq3bF;k!suFNp;~V~}3Q%?iJw zyWCGW&q6DG(kH_Tk7$h^jaaneG<($dJSoXDa#w2!-!&{5j%F+PiTjHBg)E-mBS zJS|rH*V{Fh?{XC9wM7>a9f}Wc|I$_ky(6<7dUYTba+c?5NTt@x6~T|O#PN(zeCM=l z5)?A??gTzzJ8+cT@y7&|jVkc=inP&Qq|BXhzi`d8(@_jnnUR}Sd}DNrLz8>-LyA7A zjQz*I&WYEqHo)xJWs{s#Sd{U$P8S?iO#S5TQbWqx!MKVUHtXP4WVC_VR7I+|-FTFr zBLZYo3;bw=4>s}XBA0kn&R#Jd_(uQhR?o6np6?S3OyQe(+cycCxALmQD|!DLpyi=N zD%=QOvb^j{pxj0&T13E@p`9;fDaj6*3uuzTlyb0BYIJ{9%{rZ*1uumN8rmZHHpf5} z6*&rfUghccElhtO z5oKDjDH`X%`n7oZ)l*~}$w@$2C1jrZ_3&70H?%d*vGLEuc$fdl$M0|Y z6X5jd+#mh-3jf4cTBdLeX=f4iIU?59jFlaQM@}}$_@7M%VCc@=a!vZz2?|t0rBTxP@?Z0UT9P0(WB*2cdny?`3e*=2 zvC0K)ARoRC)#=mQ3?boasvp!l`idiRGkWZV>ri!B;zm-K2WB;WDP114c3a@3sObTNsVhBD-hJW^16Z_DJqg#rQ1<`5y?YGQsWrJT#3^XhvAZlRt>{AXszxLGVpvDSq@t`0moNl< z_kKW;#He$cTtTGeQwPWs!OAL8g94^nAmqnVgxi-1{fU zBkkFp*`eUHg~{CU`8CaKD7pH)rVjyxH|eSivpDYkHPeaek4+o+c#0X8n7E+nuQs^7 z(tUZFBAuf3I7il>ugQFDr^)aODEgJtrJ^S$v$5%J#prj;$Y_hgPil{Osjy+YTro_P zd}tGFW`RGtXLVPN7+WGxz)w75)hA%Q=TCGkcu;Dzq(VCTHn~mcN(DP3|c4)uJpDHg0Y^VR7kbMAf}7#)R{Ye$mmhRZi7FyTARUtSuJh)!OH zE9^%|*}&fRLN)G_b(}jqaThlI-Aar>uosid=M-8rvjNIzHGXIB%rYP&AsLYSE1T_e zz9&jhQXaabK5MF~vHb)~J65mFX)=L>P|XLksxD^3A;OGh@_u8bY)~nxV8;RnjvoKG zL4lqEil_HI=_=UH5HNz~^=S zWNczpj4iERj{cLA&DD%M`^^+#-qt`0vsS~ozyxdo)8_{B^?Eb-&Tk&qTjSbg7sba% zNB%q&2w|VWrc13KYtvrK&W>7;JhI>~+J+y6zq`oU7g4(d)lUqm|rVqy6B_^$9!s~7;y z&CEtSEGZZ)^hV%QCNhLVE;|t8Z^GW0v6gRmP)M^z%L&NJl2T4zfRO$zKdB9&L zL$OYe)8&=q0|QTQUuNM#esZ2(UMMds280qw#1d3haO&X_sf4jgVu=KLy@BaXkxdj` z3v_*O-gH7JZWH7%uF^k|p=xzyE!gC7khJ`7Gf(t~*OgLs)+{!I8Hwf4^_+g40Ve^b^zy@kQSmGRoEm}5 z;;I@v_wzYaX}LTQnOJ}ocMnH&kY7EYXR~74sT8c(mtxnIYWd_*(*N@5y)d?acb2b2 zjS~Nh%1ZF?SI1CNYho{?5j`VtG${)|q84!h+e>@6}$%?_z0U#gY z*&}=6?TyEoQaMQ~Fgb#?%dzmzIZSx9u>fXJPykbGcP2-$=%#*n;|1_AU8P4}QL$`277BQC_XZvWH)4xI8!jBZdz_ zLSj0z(c$wfnYuUSy$MAu2b1=vRH||JefJ|XErW$)<9l?$%J)CStuyDMNB2mqeE)sa z*emk5kh{I0#bRNVoh;=51fGnnu!WA1{-z3HA5S?5c$>{ul$2}gDpF}XZs7FSxc>i& zM?oyqmMvRYuG9AI+aZ-ov2o+ZYdYtNa+*l+^XaFbz9yI^{<>(^tB$^&>VeZ9EM2w) z8-DtUeUb6GJ@j`#KmgLy(_jm|8o)`0;Nak9Ee;&Z&)at+ID~(!7UbvW!a@wmbqJj3 z_!Uwy9vvHnXg@gzW+1@M^Cj4nP-xfbqC8$3ZjAQBoIwFBai1D_+I@038yOY#pt+^_ z6xx8n(cYLpBplvKuBwihy{(Cb*m|xAS`%5h2r+Y5H*EMV*=4h4X5}IhW9cn@@!i2B z)aZ1~2=>OFQRo@ri`DxRP-~zNE)SfZ$3nY~6Uh-cHm7m~Zm+t!DI&>`z5Dmz{MmCD zK4J(wJv|{70qMy}kjlN$Ev`FYGb1JO0s=z9U^N>N6dH_z%q*0a7DFr&qTjHQP^df^ zds9|cgiXI}!mpe6V%oHcSajP+NF;K6zkVZfa*Gfd5sa}T`{2Q+KgHwAZpE0`Qy*?3q~k-UrM*o@-oQrj3v}RrgvryA@)yg%HAMGT6ZrcR%o{jn1qW6$*u$ zacbYg*1gsho`Ho67vj6`zGFI2*J8CDRnL(sI2jfbTXrqAW(6>*a)}2{y2M>rv}mEz z2ZqsT#?L?h3{zk{e1=>Z#z~Q|4nzC)L||Ybl9N-IE>veX`ikw@vnL7)3s@yqZ4V07 zk+s70(db;NBw{>rQxu{DsM3j|EmmwjU(R%#xVlEpO0aL32kyTy3KDxo93_swzB3Kw zdb4X>qRqxa8_(X-4Iy3}aH0_BTTI7^le8enWCa&hpS47^lq4ET;mP{{DWrkn9$~bT;#JPwm{b9sBp~ z$GCAf!pGYiN|lN!fJ=#GvRdF56u_}CQZf6Rn8WnMa|n;^hD&Epqu0O@kgJps2t>Ga z@jQOsxCJLpp26*NW zT4n)0U9%Z`_8ewfV0`WxT~7p@C?v-NCzV=_yYIaZ-+%oTjAje&S-J$Dee^L4u`Rl1 zA-?+JOO%(FGhax)GL!$%BEUq98>gI4*PM`fOLF3#^|QrT`8vHdu0TPdkb@MB-J!bH z?`L<9t3LxIkV%HXRB1=~P}hP;CW%{89urkP4;nNGAt52mbMIPeE&-?fBkQ12shD76 z<3Asw>PFtp8>V7 z1_2%v#uXwYED}i>#aO#`9Rh+vanHip=-t&HUMeX}W(#tQtMJq2L)f%wCrcM#*DqB? z+Q5JuS;Ej*$Vi-lIf;aY5%oG9`xu}^a-CMk#zqO;v<=GRVjhupX_fjrfVv4`ws6ZS zM9JhZ>|sC-JrPi%HTa*odxb)pUw!o@`t)(@ICa*u*uCA3n*kEeq(**{-+c28-gx7U zt7^|eA01?3Ov&sdZpn}Dx&%%|$2TA-H~=QQQ73=eczGq#ict3$4gaCjSyHB50GoBA zZ#K?tjjNce|C`S$aO~~)=;GIGc#%+!69K0=(9G9s4u!MwJpt7gNz??h6pByxB|DZMni- z29yu6e*O1Y{`^ZAcgxMVlz0x_K0XK!4~3^%358V3D($?y)KIHEq4H3&DjfnG6y%pG zkgP~3S3M|WVuCwf&S>)tqU{;%1@#Qu@x7SE;9DmU@)Ou_gMJ* zdBbKkGZk{3&VaLL6JauPIZQM@+BWB>$$=;`8z$gH-f|SSqir!kUeZLhU*8M@vFn5twTwjpF^`r4neiJcHq|n@_PoIu^yScaI zo`Fu90Y_kR=+Gf%98A|ZwlH^zfokh$NyvJcr&6m0ZS5St*QS6N;dcNgxvmP@~a8Zxz5(CV*8SWtC5Q zqk-iWc&g-#il_V`quC0jTmqX#0Hf6cy`fg8_^P_JHP2$fyg4AjL}E~=(aVnmPXhe;=bt!m_&B=U zvD^)u8qFvGm;@SZ7Bl;p zDag;Y7m!$yot1^G+!BP60w+p5CSI@e&eM} zc<)N~F~)$Ci2*07th89H5HqVMdNy$%1_E&5HkPNv(hllvjQ9_}I*l+k7VclXk2SxH z7<7|?w!?+&sPTYI#Bu<+5FMZIM2r(v)wzLFTb~H-{#RoLoB>rJ4tqD4#9>d}yuxj_8m^C5}iP@zX7#)b;QVNh)R*mUHx*;jI3^fJ| zq#_$e_K3i#-XI624meFC;1r4NS1?pJW5x`|IBla)U7Q;@UCwRPQNW2+ zIXY;8(U|IVoYp*pKtEr`0yJ*48Znhcr4@*o=VqK5&kx<_Yu0{)*I#=F8cj8B7(NU} zy&lCyMey`ynSc7pKmggQmyS>nl{} z+F@R?UL6ITntCTX0H@W@LN4WAc6P$S;rPf%+5&^ghS&u!)-g_Q0ZeX+2pD|*^_O_( zzbl~E>tHb((0@RGNM$mlCtrk2E@z=mdWb5Na!4f-#_Z^HwWzMHMR9Q%1R@y=vsG18 zqf2ZzgocG7;mm1NSJ&7j45W;4CQw4`5G8k0Ra$vPIoqB@B4v3-qzlF6Em01WnI(l2 zc=Gc0K~+^HJCBs-B$diwHXC6wm?0Dknc*;voz6bVB@jDA>(jQBN)?PI6PNTY6vE5f z8&#E+?910~0M#I;lVh+b=ZOpT(KZOY(Y3`hPBbQ^l60I_xf!P`_9Sud=yGPj6<|Vk zNmKwvx=#e61`i(0)X01H?#*~Q>6v@ra1?ey)BqZSU>C@~F zfu$)^rZ8=$u&}TehwsYxF6a2$yKc+M;SGQj={UXDB5)!dr(j4N8e=77Cbt6R-KtR=s908W~86>JkH$+Jl8m z|NQ+VD<&B_d^G;Ha2_hFs`25w|Al{W5MpAwp?~k5c;n5t5Ys&l(OqJpsjk4`BZo0` z_y~A-`XDp;0+LfxaKp&qxcjcV@y?sCBQv)Ew@#aaf&Kd7n^j*hh5DG-7z`ac3Tsz? zfuPVZL`6j-Ix-SJ{O~R2-?DpOiV;- zYAW-gBrQh*OSGKc^8})pHBwj@6W#39s~4+~8!=);o5Fr=9bae6k+W^O2%L5?I*k{= zI`PiycH8~9*6fn_yieQ*_bh7D*E+_ z$CqEOX8DzqCr?1v=y1IL)=Kp5-2-FCj)7QU!dw6S1oP+5Mnrfx)Jhpve)Jh;&$$iJ zF|qLV^u#?&AA(*_k`|m(B`a*POAZjDL<|)roD+B=#)*XwiFLAZe=C)o907feyPJCk zuJswXR)GmWZ`bPhTn0`{moCBAU$15l3qC)9zBVHw!a+VV2p@=mAyd&SIvjl>{IU0Z z2FR3rT)#-Dq+%Ssn2*e&O7xEM$GOZBW)eCuCI}aEOEGy+S7wz#p}d655~$^3T*@zR z0XVILz*x(ud19RE^B6ksGOY(rB!DTq?v%qjZ)V!J<#qul*f20Q7_*1R;Xmt-LuWLh zdze3yBY14u0KE9aQB-TWmmUwC7A}~J%*+hz+0#@2la#}g)0ziP#7L2z2)S^7^wCE+ zd-g2Wu3d{slP2MzhaO^1O-x$emrm@Vam7OdJ7XLPGsXCU#iCK(xpq7J9jP{|9$t}=Mqar zEYlA^evfzG{eZD7Job>|)U;m4ox+p&|FI(;IB4jF{iYktCo#Pe9X>}~`G_+ZoKU8pFp zz~aRVQCgITpMTxUggYO3^dX%6{Ur7sI)(TiF_<-b4pJ^9;p?xz#gM^$F=yTaSo9h^ z^~@{KYDwsoW|0b3D7Q&$uejtGCt}#@tM=-B5(r>XrJ)-*weOkWUhB%wz_kiYu0P=9 zB*#gcxD)r^yNpxKwu=q$RU|~auUoes=HR~Y8#)alkpxx}(jl6g(lZ4X(tBnq!@L@~ z*lL4?<(*J+rHv(}(AOO^QE(_5c6J%@jFZ@+V>&HCfx!(t$U5uNBj8k6Sil%3t56E< zb>>yqS@Y7~?Y0Xz*=+13xcHWV`2OH|X!KNZX@g3kz>~KR#p^#EhgPp=78@LJdJc>3 zoR9SMbf-E_t^%jb%uEJKh>m{bkw@^s2OnVFx^>K{d*sNG42TdodG*y-*>sQ&3H?l9 zivSM4E`gU>vu0uW^5uB><(FAs`q{Bje_Fu7TBNfze=Kj2?Y3(cdg#S}0=otV-nxZ*L!_8t&^)QV$A<#1e?b zG8WdNoT!0=`r+pv*P*hq3PFK>cP~ z+jrr7QZfb&?2lQqren>w>v8_vdCZn&FbkNhP%AXYAOqNY6;efg{JEiJJn;^`ztE>VaONehfGbkHf|`DTi|}sHL~` z#}9{-P^&XSt&m~in0RbHor=8DT2_I{tncihI%1rf6TtNG@j-H0W`j^2$^P(Obv)xl zs=7ST;DHBC69KX(o_K=g8d0M-J~d*R8iS+80EU1Ot=||pHJ<+F`ZWev1l))LTd`tA z1J^x=OY zR{KFNm$JMkp-95?pF+b!ps6aumQ7ojIA-5I@wolATXFGXBG&!*D~8@M5;LZc$EsD| zpt4ef36mzFd$&le{$>r*GxM=**%EZ=5`yo(TZiOJX}I^^r4ZOmSiR;4R8`gD@qavw z>Z&sA-FFlktqu>|zXSvzLDaWaIZ|+)f zH}?!&%QN5xPVGB8O}*+q*n-^Bss_NR;`FcR*()A8y^hiKoN%1|xncv$oR`H6y`sR0 zl*1#VqOg5?>&oF2UZlh|dJz(HL=QU;4^Pgxly{+RW&TLViI*eb1u$(gulCKldo4}? zvyH%srY+K6jXTHo#-C^%gRcMe}Sb-|7o)c@bGfoQ^%mXn-`}XZ; zv(5wT;NT#}kTeL@HS((CffI$@h*_e>11G91`SQyznPd0<{rfR==uoyFzVR#&&+fPi zocMi`{Q=)7#OI8ea!d|y4mdf65!;ePPSt2{zx@VQty;~JrAaS|;RvRcB!FBhMo^GH zj7AH~6$=guz^xNU;+wTU<6>$qOQa_4BeFE1Bx;#d#v}twW;0;3VC;>farZrUBIVL0 ztXTOeZksg=qetC<<3|o-&G#Gd{PO4E@9T|Czx={Nb#J}%2E;-uUVZg-WM}8&^DjO@ zQGPc5{eN#lCY9oiw_ihbRRvys^-Tl@1mXW)c>y^&8F+E|>$vg8kyx_q9vs}a2Ood7 z8vl6wVf63c7nhRGVZ}$Q@Yv%Iqi?^ys3|YTBagqpSWE8XiUUJj+>Xm(qUt|l(0E@w zKEINeNg$?;t_ydLllvieJ!*$c8~I1U+X-k(!+9r9^EDNYNQEnk*2C#f(-bPfarc8M5FI3n8R17(`6@ znc*3m02UkhL>cRqtr_FA9&<>?DY9kdaAKOMI*7st1ehF|C(g-S4uAgu2A*1D$=m{% zF5LqzcWMuCBEasckU=REGojR~S{?koRP1`R*leiQ=-BU>3c68;jBl4?!Mxe<_xD9@ zEmu|NDBjA-W6vZYX6|xGJbYPb*-<&XG2`U;Zz`oFO91jDBT!C2io$m!?zm*h5|+E< z7#4FCI5h@3t};%I87Tflw3l(BV}0X|SMk-?YuUX_Q%d&`%^#gR7D}5mhAZ>8nxRyC zK`N-mk>AeY)Y%Lc&=&|rkjW&>?xfDv#IBjtEhYlv$K8Mvr_SL*awY~3?2WkCNbEm! z0=aobm^O7hJk(0;J#ZXlW!0E{+eAnuLTuQy8qYR8>}B$L?cnY_2h}o@zDb+%^%3Nf&YQ%q7Hj3CE}rLvZZ)Nt{bc!@#~h(YH@G9RKYMGII*hr&l+` z$4BGz?-!7op2Oq~NE?cBu?RddjdA-2Bj;HsV(R3aP-p$KgTNG7Q?2^)bM$g2hr9eN zaCf|VGvEkJ4ySCzflI&E4MrhR;^z2S7!WzC)d6lx_!hrs9cs{TP}GgMwNJ|_0R)!5 zJ@Gz_W_^QoWBlWB=M9ft-@u7*t*n>w@yI5Eb< zUhl+|ne0pe=YPR1VPvQsIHj(B2EN{&OaQZ9@Q@oOU5k{TS6)?%uJe{dr1ooKxxxb_ z>Q8x0+1c53IZgzO=y!Dekxc<5kQ0z1;6x82Vs|bVIMMisxgxg98RJAbPDhR$VauD# zaUv#)&&%S$934+eTV zuSI@IHS6mi7!0A!05Sq61#cGCWA_;+-!3HoH#%=N&U23CJKA^^ZoBrDv z{^)cV^M?E#-GZ9;UObw*1N$y+bh_@i9=Fx8N6tEYee5mdl&3mf_of~*vG?1PY}s|` zRmTJ{moCOTZ@+6d*yQ4L^#Yi@a`+4k?GcG8jUEP*33rU{jn8(R!JLtC*nKvKC05g; zYSGR8@b#XvsM6>d?ezEQL-EV;OVAliD6iGQV7B4j34O5jbULz1YS|a9g*|2|k(^_k zZol;w#yC;65^wt1c=q*rEdzDV8ed{e6+ywlA+2gl5O5;pR5JP9wrekHiuCjw4%z1X2rlaVkR51|-c=PrlH!=DkU z&KM`sA|Y@@jRz|9v$I5Q$HeRQ04HLm2rSWcO_g#FJn#VXVnp#RJ!3-dIzn5_tl z>H>?g21XNSgF;oXyfbB;XB=wo4z7Xv;5VciFsL?&U^j@r`$H&2>|WBd0bIXM~h5k~or z^xR;UF7{kd-s(lACdTQ@x_q~5?6z|c$2|iLW`GAyzM~DO)RsA&otS{0xO3Q}&CcA4 z{m-L9Q{r^Fk17BU-SmpnW!3r$yuat^X15#e6NBtM920e20w*0YPD>W!op=7*0HpB1 zi4;PG5rY`xG_rRLrr*$wX}Ns1{S3-ACM+4>8)wpsm;vjVv|{v&_QMVF5%5wEv{*KwKenDuMRqCC)dT3Tw zR-n4Ns>NG{UI2lC!OVNBwMM!%)iqTpE~|p3$27NBU27B8!t!>vKtPJp+z#u!>efDokv9yfQG4{b3aB|FXx{O1< z>{SU=5qKj1sFs?m{aV@v15U60AHM&7y+b7}tCQupJz{z6iH?Lj2rn%fBZfIPedWMRz zOJV}lWd6&=8L2BVQ=B!6eYvTn zWJ+-i^#6qxnt+3Xg8AF<1-bz(7PDZ0Df&1$ox|JmrM@iSWVNyq(V*xM>`Tdq-eiGF zDZ`NHb~uz;ga#oH+U6X->Lq4?Sz26(FhwOg`nw~qybeDf%!aGG2LsEg=~?K^G){kg z;6%(3Euv7pwefd!y$b`U2K?iV*Rf{ZZ%`|hm~%@6+WRO`Qe(izQ>CaVuVCy8E1@$C z%b7g_D)e0;bJF%5!{FtiL`@B~_w&dUZc@UTA5k;K;FHw?rP2jvGqFS*+{k1ukji-X z8f%m^P+^ak^ppw$E*8k;Lg~P`>-vG0@k5fuK^vOGL&%KMWX3aVwfKwpUB@$3~QdZVExPpqUMt(O@aiRE|&gG zps%p7KyVIMLK`~`7N>K#!ymNfD_#sZF&>GM?I~Z(Y+-KAMw11DW7}a;-$?xHr$eaI z8_>IR5GD_b#K-H8LQ~JRZ1#~WZ#}U9|JO?ne|Nd<6i9pbNPl@x_l1u!Ot2y-TjG)@YooCOz; zyKOQ~A3uTAvuD_T=sH+doq@ZE)Bm(HdV%xw7B6^2 z)D#Sln%wGOv_<1|gB})jTaLob5GtgV4OlpD2%q1ui7ppDR+(=Zv*#eow z1ty`Jg+%0DZYq>&>OcmVZb?5uVbMb-mm@Hc{G~+YMAI>*H`=nYQWo^t+T!Qu&jg*c zT$pic%&N0UddNZ!$VNI=Y|sr(#^MaQw7C84{@!caQCXANHg$ zr+IqYzjJgCtUs6vO+!=QRIuhXywzgfed7riYqYrS-Tg>P&1zDryHO%n+A#DE zZAzuOcmMSkp6soIr@U!iB<-M5Yrz`_mDv2pAJA#Zri9778Hf=Xrw*MWAa~J2XW;fF zqzw{*kBC-?Y2sf#D^w~uj0Q8CXGnBTpoiN4aE+8sN9V!WC|6fvl*n2{!T^;@serb@ zz>ZJrP^pd>BcqW7+%yM~7E8j`r|opiJe7YgXue@#y@Ga&bJtcjzfean0jJcYL?kCs zpm-y2;$3wzq4Y@mcY(XRE57~qTPJXG=u_rg>8~;Z4Td_bKD-P?)j3U0DJrNZ=JkK* zqNjPeU3Ii$0#AF=Hh`=UXd!LWnAn*J^^Lsfaj(}34gsg4{p;ArL$008#n)HVcAC7a`WPo`H_0f}^ zj8hvvwHE_UZb}(C1$v=YXTqT9_9(8bMSMyD6C&R`t|xxjn}QkwP7)W~IkGD@97%_! zUdI5t7`ZaE;CuY%;o+^G<<8_%>`%&rch}*ND%Ca}OwZ0i7!q^g)b2K1`VFxu*^cC= z96^}6w$<}peMW|DX*$%^H!y%vSyqDF>`Vq;0)vB@KwK&@!f58YCC)hU?>7Nr5#(?^ z6YpkYdMOg26N|(C&Vdr`OAIccbqN#+GY0RllK>_oXT0b}%H-T8fMpj7nk7*%&X_Sq zUUPkws2Ok6O>x1vOim>|Jtj<=g0$phBqb&az==n$P@pmGQ?w)y=ag^1{RXkIu{Xqh zcAn&4YXqpVBP=ZJqUCt|vu@49?Q*W{aMpJGnL@foU`o$L=+%+?*EzD}Rb}Ga{qM0E z_^u((qN8twBb%{xvMW-t;@}4iG%X(bH;1>oUMo5ToXU^XNvR6B%G`+O&yL`xjcMbWmSk&)Uyv(i9Ca zFU1hBi5}jOpl)>4Tzh;B*%DXO^N%fCr`z z>WY(@x!9dt$jU?(!2olC@mIV&r+1sq)46f$Bd|4FiXxu@$jrz2rxLQidVRsu^LIN5~YtR0UuO=cl+Ks=W4;$<_Rq@S}-f~|Zf>XBH9 zOv>48vD=TWC8k5!8(0YQ6$!q@eX%Y)VNz@QCuh0LW+Ns{o{F=H2}nvz7D{zuB@daF9w`!jpl+c6Lry11R`}}sugk=%@(GmQ>zppc8cULnz{y<1Ys}P5nPOM+I^-R z@uzc~j8hA@mTCG@kE5f!s?{66E=>VT=m6yB7a~8u2xTStIDFs`^J}_gcwg z&L*BlQX-Y=2rO~n#9hP%=F7?x3B0_#K#WsNOw5)2!Z`PK(~kgk!-_eV6k|pX^brve z%tFN8M#Mf{fPPLv-xPO5HYP1ukI=wTSDI+dOY1!R@WZW!jJE|iy~RZ4X1sXYa-rkY zvDaPGg0nh3+i{Z=-ZG56C1#2-9{ux54yVpd&S&f!MimRQ^$epro}-bwIM zHvLZ0wN>lPc;|!{+I0xQruDxfGyNQUsp6U<2}X?{hwRL37_`->rx+aYMhxmaV-^C; zhf5eG0#A&6;{R5wiCkSWPMk6sDW{2X;-xwQOH3SYGzv{6Jc@-n zb2;Ngr8*~Yy3xM_*ZTaa_faMRGf@EFMAQE@@| z_Nj4b?@Q4vd?~D`$6X(8!>-f$uu7x|zx_3CM?hs<7YWP4``fG`ZMeD{e^V-Jzw^%9 z=oJx&5vp|fxpQWPmRf@a|M;U2(hl9RXWLekmXVoe~lfuxQaD+kRWR%C-Qfe{OmNCW{fz-}*7+QtFItT*Pz( z`bqQTf^+3(u=3D{=WIcm0`o=#sbL z?z#4n;7p4!4#O}m%I8#ssE79geeM_a7G9UupZfg8=;0z}B zkHXdy8JIIX7GG^iV7Yb87Y>|6jZ?0maaxN`!M-f0mrM+8aV%GQbeiqY&CL~>Y7GiY zE71@$#R;6+Fy5C1oLHj)v#A!!D!hq+t7dq4#ny~KA-^kMM$hiCkXj9R`nE`f`nw{x zyaDfSIEy-+iRo4Hk;&r#03ZNKL_t(?@{5G5I>EW@i!$+;0rH2 zha*Q5Fn8V@MARKdh>sk(W%c-QM=^$vpN!qxHlwJJbYlw(Q$P-srHwHLp5uLt8vr7^FFmbkwYbcq1+l3ook^v`yCa!Jb<#yVZ%6hae ziN;N4lTEbE+{PK3L^+wf^N)$=goXCY&V&7oyQ7=U2GDn%3~xz)^~911SpCxuB&HWL z;6&%n3@{Bwc3wQ|lFnBScMo@b_wCn+j&?FmH~zQa+Fk(x3z1c_FRj_Hs}6q%F{7?E;B+O0@RxjXb{kwU zv1tN{j*dckd6`hEo5s5Dx31%6Cstjpuu2(l6-k&QoJy;Ki>QG7 za3oWMv`n%iXxRX>t=D)XZ%@GK`RAX7L{o&fW{1PW&XStTm&>e`Q#IpjcE^@L}56wG6cNddh0FFHq95YOh!Mynx(FPZFvj^ zlOE4a{0K@}V;aYW*fct)tg;jq_G=&S(i-C=#!fjpwpU|42Z0l3oId~j3r@)k6A*Qi zgolSCKR+K*A>?;Zx6T;fvlA=VE#G*YO)CAPLa;k22air3z-F-I>{9%8I2FDgZus|I zBk{`WJ;*MtXXQLcfD@JKTnzP0yxE#__>~?k0!{@5`8;n=rb2z}6j+r!9N4*B`Up4z zoW#VzCS9$i8r zZ}M{L9O8@DpP7SFLpzjL)j*@s;LyQCC@d^vV{JAW*><9Fri+V=eW#i3i0O?ulOwWF ztdouj$}P;gKs3K(zH!V2ys=|X}=00OTp?^fRjCoM){q@oV5fFuk^KCXnzg>r+Cz!+KlPbrwBAW z?XIy~jzpv+I+Jzi4WEHC7^9?=%h}|nH=1}LD@|5bF!yj5sf^L~+@;A18M*rkuEQ-E zP_|a8lbW>5P>)={#f+(|IdGhDqM%~RbWoxpcB->f*MS9jxYN~JIAstZ-L-c|Q=mKzEcol#U=2B}nz1G~2|TY{Ol-vNb8 zj?9F;c;x>^pbDWVEvrIxO%3Ar#v?N;PtcQ5YzcQ6Ck-LZB`UQmFPn+RYyyMG7%J8= zNx+OERVZYa*dHFFBId1dPbk5jKx~t1qHVWAE|W3v#KXY}@JL}Y7~tyW247z<%$q+O zu`yBXXRw+P>Rpf5-uw~=6S84oV2Qk&c&Uz0ui>PmEN$*6V;{+n;|G>aNwywx3k&a0eQH!9702QrcU-r8i0_*p-J^`Iki)SY+ zg-Y(quEPY|(mm~9#JivcIT(jk&jUWgVKQbIbW@8MJWvIJM;tU3}X!#&$ST7liFQ4IC^$0-j2GX4Ujx@K@sMA3TuL{vSeP?89f#N^gI>?F z^!)sMuwcP#L`6ohd4;m-LOpBn@*AJyU_uT9PNE>3I{8@Sig2zpM^LHG$v9p7v*TRj z<{W{4Z+!|{V?CZ3{{hqr-jLIhwu*jcUvhI4IEhva*E@K<1s|u)D6FWlb)3|s#G`oM zS|*m{-Y0f0;6gGv3ADXqhr)l*Y;ujG8OkPiApadJwICDiEurkOmXu7be~4Q1ahg4O z0yDteym|9Q4KT07M^v;UNKH${#;w~?=QO}<)39C)IH_b3c&O#5)>{!5;*G+pdX#9i zP)V)0dtyJV+MR?3trmBT?13NRQ}D>-epnZug6y(7UYBuzacbQ;JP<=-{?{2N6ADvL zT##|vR_2dPgAacFWdj=O>rqovi;)wiL2A|_H9ZYdeFa{4d={z^imI9hRBI}+XV-3| zXXY?)WHwQx3K(-FmCN{?L1YsXTXTB=#wJ^N_Z=<7>WFUQ3I%nxQCP3Nx{7DnF#~b2 zbjPd-ct9}e$(i*5eMVU6j`T`^UT0usLSmfe&!2^u=xAo9N}9S5Hw|8S^K%?d%C}|J z@$)9F7VoO#=jH-$@^Sj^TSP?>=yxv85%}L4f%pG>8Wi91^!WGTs&I!0bVU0EaWtsp zNaZ`R?3PiQgddK4jEKN)xP8E*Y_*m&PJcVP&liIBAmiLVJ1(Zo72? zl9H1IJwhXsPH$NS1x2v5>k7Ytv)LP(h^io}Kd7TlH|9ucAlTr~j=Ou1O0Kl15$L|s8CszOP17`aq!Mjo8X}f`y4JLe+ z5rVADH0+N*$o!iKuypIu3sJF=3}6&xB;e`$$3Y{BKvi`EDl03nd*?1>p3CErC(J{D z+XD~_WS{_Dxq^WnVux7An_%}u-E?d!u~M!a*FG^@0giv{tZWmP;X565~WVCn@~>eKB{=3}#@-`ZUcZgm~2ArPn{f(G(7xXnPhQY$DqQ-qpu^ zs-!OP^z_1a-#dZRm7Oh|d%Kn+kW-Py4%f-=(!u}xe?Ef-LoJ>f_a5Aoo~(TM*kg}j z*|KF#bblf!5=)2|0#4041uLPk*)WD+ZiYjjY!NDvbmfP}1)OS-n!ffF%K zVGc#ET+#tsS@}HRylcNLSZ3mt-IxD_8p~t4fY1q5(5IWC&2{Lzo#!xtc6Thu>b#?gLbI)R6 zOb8~oFNLpbV|+qYgAw1KQDa|95zZtgFvgcyAi@s>DCBaAR*|4%pgZ39+Zf#GP3do@Z$obf%J}iJ7y|D^baemHL_0J*GU9XLPwp@aYw(ir4uyE#3Y@i zXjj0@F9~ch{gjZ0M^*yVb;mO8c-bu=fPm9<#Kpz3^D!HB2zIT&%Wr&%V=4JII|9)H zfmkM{lVSnFQh0iJI)PK0W(McR*Lwuo;^Xwewr5eVufdb!-i7-mG*6|MCgR5LMq>qVl}D2fc~+&Vf@Dem#)dV$@DsE?s1tGFQ9=7nq?|$}wkX zI6?zFkXu%Zwfi!lHF3Il2a+rzu~xM*A~?=dq@b|r#O6F)hD znG(Z*dCnd8dE#Y3A75`wn=+p183{NUbPZ_dR)H7({v}SF$!DE3onv$y-q*I{q_J%_ zMuUlMJB_Wzw(T^=gpIAnp4hhA#&*fve%rm_qDIvjT-qd4(l;?-nO8(H%5!CwYYxrkN`#J zszSVumJ=FY>?3N$R&3}98a5;F3Ro7YUIm6+0N;|63?klc2qWQBwCuhBk`vWet`fjY zNoJ6Pi)pScc-iFQVqz*;*<9&$!HGT>nkVtZ#|igROUK1?pD_Y;N4F+6Jv0pyG85%HgdB3nU^ zG8^ZK)#%l`*UPWW^o>o}1%Tjqy-N4AoG6-`)-NMv`Dd*6tiL_Vy1owBJ8mcRYU)nrenH` zcqJJb$ydbW6gmdvm41oR6^sn{A^*za~c) z%Met|YCZzh4;CZZ_oUXFYalzD1;4{YkvRUR!W-4yRf9SrAz+vaeO_MaV5E2ggJ6;5_H`#HZec6mPC`_Y`3H0vyqe~X zA%05h!M1P4?jYJZ0iDAWF4*=}S!tUYa)8d}M4Q9;S8X>>&-Y+rs%*B&6=ER74}E(Z zp6tyfQ?Q=JqEL2uu;sg!!402`A_};K*@^Ge9(*fKW8g9+KJ^T+!80<%*a7fW5MWSbT zO#4{gWwR;fN#^p+?Td=otj2%2CW|P)n$@)9mTMs9_yTN-M=A6oInXpS{)?ma36|u6a0BhWg|%oJmb%!fnaQKdTy)1?%gEGIxD(JhPdaS zJ9vzV0X?}`Eww9wYoPW8H^E7&R%K*=JwI?*V=0;Th4#AiM>DOTo(v5?E3tqVOz^pw zN>WO6jICe@ba#P^dnm|O^sV+>%nq@e?b?Od$`2s3ZyX(Y9}}zdvfme-F%YFnSuPHA zyYnyWGpb6nnwcXOrRamn9>rcTCSQ&|+`=GWwk`My7eS&8v$78v&Ox#waeZ6VvRG?7 zT%ef8jq>VwDXFDZ3Xw}F@1Eu+LNd+NPe)4_qaXsKE&X4}jSI-RTpNRgf+J>Q;X zCRq%mj)ef4QcQHGmrJF z85&M!mmdibo3yY0)O@_2#w)Zb?<+3e32CkB9ek|D0NjJX)yVt5YSe^Q*bae0cbX@D z#sLlvz?A%ZF3ZlyKy&vJ2G0X5u=EVaVdwbEHN0N`oG3E1CM5(bM@$7{N!EhGBf%CZ zcp4f3##38X&S-d8*uv^AWP-Kl>7*TQ)VAV2S@Voh_kjLU(oq(cP`QeT)*Q@UQl+74 z$mFa02Qdj>N2VPo{EBeR-)dV>gLPis4wu|{6|T3-QoCL?!oMxQ*V_)+9^JuZPU411 zyNBoZl0iZFfB!W;MirT90RgRKnwIxB|0+CVqD>oXf#?gXay7rQs9i!@+Tm&kR3}Kz zSAlq1FbAKd(d8A&XK!D0Fn&1W>{2XF{y_D7YAiemw{sMCJyM^-%255lu@eXW;Y`$n z`&pUG!_B20Y~iOglS*c;(yEd8g$3AJG$Qs*npeB3K6(&z-UrdPyFT=V!^tcXMI+ASJk`_1lCZ-qy6e zrmq%!ASep;HFfCCfdQm}>MR@`{cd;znGo7w?g_z-pA4j2YJ^)?@z&|{u;>)e?lakG z$(m(|N6R>{^`L#h0lXhaQty3>8&RYe^TYY6mbbo0_dKRTy=-@K?b~XzJHIUuE)z9Q z_p}NC=J>_Y6jt_2)e1zd!g|XXk)CU+7ee!Dg7a*dh!?Q(-<)CYb+H2Bj93o-#Oa&x z#JkD!jzyv$_sichGoNx8T+giwer5XF2>Xs%ZnIM;cw%e2M@Aen-Y7=9Y>B#8y`bp! z^v}R~vP`xf7hT>>L(bJxTZEx_p44LfdqIf~j>(Plqe^2YPKz#TO+w?h<6F_Ma!^gt z-&A1+WM-&YHpRj-;OxI3q&i!z*o$JPTmZ$FPJ4}P?rL<}0Csv&fj21ZXx2Zw!j{nvET;7!u;PZA3c2u3> ztbxUj0YqSNTSCpGC0RbDRMjfj0dLV2`1!hnFX+R0D`Z;%@}jw%zcHvQXzam8OMHR% z+kzt5cBgVW32%QVb@S>xZ7C9uQy)BL#{XsuaJjviaYZZpLd9AKVZDMP1Z^co=?>W* zz5$hMon53Y&K?=QJsn1@h19+G#nN-oRGiIGg1Ct9iKrlP;At%%?CB2aR7>~| zA)rb<(N9@6nNE#9!Y3R*Ly*{7S|XN6lMA<5DBV-2gvcFD5IM$ryLTh>xov=-=q2x4AY>pQo`nA%I&1`+13gAMCVM2}Sd25pY{Y1&r zHa7^|*b#8L#Psu)w(_E%3Dm1(mt*&RrZ>-@uuw=D0}b|mAikiiZ0XCg~%n(SK1TkxqRKlKbIhKc7a6=6@r#l9!$AwzIe*!F>g-1-HO)E%jSGp=8U7rt9gAbX58jnXNABXI?h5=L0?66`LoqD;wxp(?wFVtOaaatl&5xh z-mcT8A-aZ()x)SS7va1-NKPE3XMKW?o8jO&OxG8g!str*jOj^;1;Rxfp-@Y)!X%2m z5u|hf#p+O&rh3A>S{9XYi&6R-(V#L$xgUh+xJO8y?KtjIU*x!2W(lVzACL2qB2Au` z7rZP!n4ez9w`3TX-%5fO))t#q+uVt4#~>EgG!L)vil1Y&p#Tm3^BY2GR`{-c-@}J% zJMgYSA=h33reFQ^iHHy?2`8WKM7TWYa7|}=p!JC_V3ZUcFua?#ybnpN>o`r1_qUxg zTuiu_2}!P=3w5hk-4NE{YD8dEWv3=H=}dhlX}=Aabry-LL*iw{`Ess3kmJkL-w0g# zV0CUtu!-r?gy;GSCKGjy$z)6SO)2&Z=8&5N*4556_A;iqXw5I!#%~g9Ub*jkXXc{p zQ#zpLW>zqyeH`WLXytW-+o;PG8q$3>BT;OgEM4^-K9 z=E5c9|EL{qu0EzJ%Vb7L94>B1h*m0c=*iBjy?F~{K=kw;_0PEIXfcZtxb)rHD>6l$=%eCccdg8g{y0oJz!@9xxgw? z))3dz2G6VNg0V50cC19i)rL_EBpvvw0I1~81F|1ADj!>}CP8^$>UQD3I}n6|#QE#X z6ZuWW{Z(};hIRtwh6|h*oX%!N%}aqMOmXFmMblixW1~7nwcRfTMQsoqSz-{3@kLIx z(zc5P*OY`t67o<`G)28wb@Si9Ym<=3R}@ThpZumOund>02~v_*$guXKua^@543z>g zoiMHP@#%+@#TIqfTrR3{la6a(aN}|~aeP}H#g&v$`GuW7uxb#>bLq6d5;)xys%=%K zf!#K}1VV7rKden)bQwHb7Gde2XfUHTJQu;e_C>d*a?1^x3J@OJx#7NxjyZ7?X14#b5OL`fDejr>~UtV2I;{rh) z2Oz*!RNt6T)$~8&ZG_zPfU7z0ICVQaPH3fny8sxJtoVvhQ>R@!ijx+;C$I9t3LazA ze3nuAg}#+39H9%jHylf!^BRk%HPKDSJw~-4FF}B7cMI(^sMIvI?+yg_&BDIl6 zEb%sIK^K{9mZ<-HeQ&V>W_iuCB^axu{_%VRjkkRb;P*y-Qd|a*cSj9mo;FGjT8I-> zJ!_i91=ASZ%%nq>;3g-{rmz{nFb^|AM7iXgTCNh@%6Mpj&5lM?=cb965@2qNX^dQoRE2g2>?YtdF#{aAZ!{wkc2cE&Iv zze|}`?AZ%B$}bJH-YkyZ!`3@iuztl8`3A2B;{=mW7mPs}3lYKva+om3{C5h1#DQ14 zu*TV5j@Zf8%m% z-#1n|Qq+cvNS{8Y(@Mg)RO10v#;t(D11f#kva10)xmuq17-b61cFeY8ulx~pT%;Ur zg4S?Zk>@*~d3+6O8I}rRo768riv3qClymlo9 zRiYLQ$)T|;F+-GPW?E}#M)%p^mZBsK^*4oIIcb`z^*ZHFGlV3T5uxVMn?qC-l|mX_ z3dEO{qVxs+&XcH_jtU>_-22l`sX&Gw9gs{h`FmG5N7?uXR5W`H7=vz?gm2d$5%HD4HbuUvkWnN7>#5l4reWERD#V%sG zFAGg?^fG%T>HXf|N|mRPV4oh#EBkI6k~(inVs$ekhfPUo7iMvJdB4mkaFFvJ<7quB zGUi~!FBfrOZ|@lFr&kiKTPbR8hAJLT7;rpYhE#)%KqU%#BIztxIEI~}MNL?J$G+VU z+Z6rSAIze-rjcPPX7|TjV4M5Y-(()|l4X}YRgX@R^MT5<#SU`y8{&VI8Kj1Rc3n#; z@HO3n5f~4LWG}3i5mNFofOY_a-CiD-Vh`vI5{fJ&{#NKvd>weZTbp62{?~_kkVM;Im4Z{gIM2lMMOfD=@HyEDoelRrOUdqAS z-b~xTv^Wuqr%!_d@U;E}m;>qS=s?_rI1?K4y|`QZ3;OPw7lC|a=8EOfrH0*&6D56u zP84yg*ZmQ>)}{R8-$^SL9QvaiWB}SR*WI1F8zgk9S~Y(IjH|0I_`yUhMok{5HkIQ{ zelncr88EhV*6&j^j?&N#mp=p0G>1qdIJ}(Tfx7xp7s> z7s+gcVcz+qRHvVkt8pa!$cHX56xs~nlmbxU`>U#89setAKXhIIxA+ZZmj?b7p>pTKHHNtP2J}3Ujfzgt$7dMW}bn;_Y$rQ@JV^{n7 zClj31;o-QEu&JNdM4yf?i3Bx=oGIsy45%>-XPH(r*r5AzNLoAbU%%78{gLcz#n_1d zppjIPm2~8caLExMK4tQeIFomy= zWI^<7a6-_QjjgrhMre1aNI_CRKx22NUhRx3s#R8}!){lDSz;*rVqJTGYo**3p*iFj z*aN*hv9*?swM|hqTzJ!22qF`C$i&q==r=XQw1HRvgSwe99N}6)Ck{QxERC48P%5@k zZGaq?yFxV)(SBm2@J`5p9O6&GKnkm4c*pbDut~8yM6`j*?y;{`7*P2rx=d_uAsL4c z?Y~?55P z(vp)0eOF1<)@byHhl68pQFC_2DE1ZOa|=__OROAc(4sBgQCC2=IHOOKgMo!BDr)@6 z%blXf(eeY!%#Je?U;f`or6n-b%?=F>t*yPixUmt67BSHB*&9SYw(2LvYW4Ro&g?0Q zVnk?wv{Y{M?2AU_?akf537HlzL0PQ7S8ng;M1qK3&_dw;j)b#2=>^FHW=OXfNzZWV zz`@fqC?o2}3SN_g#4fev()Ak;W2M@DA#Wq;`^y6^Oj^99Gbe+_fSmG7P>F%|Q!->} z9G}UkTDWI*eXEe@NFOb=&o^^jIEQ-rmp0`1ACcM)WWkEk^LvLC!+qtbI#-uF;B&SY zCGNouaB%sWYHKOJvnqOU<=;__3X3g;WSYPO+H~=}gp$YU((qH&!#vlp3o}-(Y9P{hw z>CN=PdW)!9Od50cnQ{+KZH0n6-91=B4sx694XA=k|b4hFVSF?TD(pt^$N-6fm_~C7tI-Tq61W^!M;Ssl9DC4_p|> z>U0fOk3ul;u%`V$r26~Bdl|l*aKmmN~#^1Ffu%46lnQ0aH~zg#*u*HY=4bWn7P zasmvf?=b~^5PFC{3n?vP#T5}h{)iAcb>zlU5QWZdiLtYF2sZmraRWys<&-dv!fR=q zpYHTVD8Ux|z>jtm80*^KfLz+Q4Tnw?Ful3j<&SqVIwJe`&bcGkcZ!tb!N6Ui?=++h zRmjWxLgh?hT$-QE)2p5SdOXI!nyvW^S-H>Vy3O#3{eu%1^)vw(-7Z645QRP=>7N_J zrK{lmiH@l@Pjrs3I;b2HPSttPo)yaaIM33y6^?xLA(tIBKacsgGqBNc(&NBvxui)% zjsLl9n412BP~J{Imbr_`nQf>WSbiJ-F+Jf1`h!fmN(K#gFXiJy%U!(_C+W!&)S3wY zaXW;V$z-|N;6zHzwzp!$BSx8Qa2F z91moGn5Zb0On@`8$K_^p*e^F^{8==xlX##G9JD)m1{IgjM%ciP@s)YB-!bs452QCj z!68757){{V^GIOUT#h_aq)Cl^OL<7hoa2~cZBOw#^rj7mVF@GlAyoaqO|yr88fcjF zzmv7y5mqf98{TT|3VPT!LCtq^0iUePzVOj{51Hk*bzcR0RV@Y}nIu@qnTS@2IC3Gn zjA$z`ycVx$2ni|H*k%Q#=iO>RQYs~8H<9w`Br3u)o_QqRer$h{3XIQ}rc(8d;E=p` zV~`$2>?8ukz1_uQ;}&u&u;v=fj<{S=@le>*)n`lx!5axwWOQYarGrLs{}{QU$~1;` zX2oT}@r)PD4fyB;Fu?ve)=z=(xFQCFcZs2ugM1vMu!s^FJ{sf!~k{FD#i1Hqin+pq%5UW304kjYsJF(KEcMoX-=V z{BhR^F)tWX(q;w*_}JzG z(@G(ivKib?79knZFg3Y!&8;j8tY&IwkKJd9Xugh5iLP8Ul+RnMXqSbrS&Mj?n0`;PW zC!Zbuud}&>KlSpYqdcu5XPDZrz6S7K8@buj{^sCbeYoZb@B(nUo@KcUMYn=-e9biC=SQ`bf?0xa9(M znU0ot@e^n8qoxB4XLY9lDVk9{DWc6EB>8(i9Z~J zWKm%5BFIiIQESFxB79sRc#3~mLns~E6xf$C+XP&jR&_qP{`+G#OX2!=B9qSsiq9Qc zG~f7(-;ziPEDsWp&dJ0 z*G7VL@9GbJNg!k(0d}#rzQ}j?U(P3+YuAy(Egfak2LS0^+r&Pe*U#{`N+u@ozLDFN zb5|2*1^Dc{+k?~v;^;S=F9l;8?glN$n`E5}zl0;RRa8x562pIrHhniA-(5`rLs@#k z@gp-P7tC|3E}S?eTt3JN4vC9Jx(XN4Sg|-Xn(nLVNwMsLeEUP~gF2hz%LiGjX{oUx z;~iRO2+Jl9sb3IK&cmj1c$(CyZ;?ej7C$s&KlL^w4a+3adV%oIUgRScy<+_sli5XOftggz)R<2jzAZdg>Z(Ym|A4!9I70Pn|l*IMt}xW3lc9Z5q? z+6%%PV!jtX2dEqkCz#&6H^eP5IAf{H&d(d@c^@s{6*X8##~ZohizlSBz6g`_Ml^lpt#LyKlz;7C08yIr0EAiR;(EjNuv~wP$P#*`==u02;*T znToAaH}mtN1#dfKvXf(~!%Get&Rze7a|4-Eksw zg0R{fN=wR2Hfp=eT_fIp+cclcyZ`ByFmP*vlPg|X1jSgGTH~S(Kep0R+tMbun6z7k_`8;)10;hDM-~&Eb#Xp?uYtz8f)AZTd z?GX)ukp={*v?DnUUa+E^Hp_1D3b5v(zK-mCk^@We7qtylsp4#Zh- zILMQCRbfS?sTP7kr+au}BveHO!Pkm%@y84HtH*nZ`D2MioA@?&4KiHxykzw_^|A$a z7a32OXW!zsW@5(WbJN4=Oeb7e@nKaledHfL$zlvCA#uFNPcY~;sc_=G#WO!M__gW` z&ta4@Zo=JbeHXz08t~iVh8A!ij-yQo_7$=vX^ijruu97wTWq%5{zn9)Avm2g1=^Xc z)GTU$QZ-BzW?0IX36nH6!V4Qnz>O}_|Hh?RsxU2T3D1KaR5W$O%F1L2+G$8ihpBrr zW(2E&zk@7Rx$q)8%idsU;#9t-Ufth!(~|KqC~Ik?_KPqtY0;k)(G8xQRd${=I6~!y z9oDs05wmFZNw|}K+pYasSS<=~#<+jAj5>|O^G4xNEMcdSVy(%XNz-V_nuVgj7WuZG zF>#hCiJXGq_8%2E%jvt!gq@b!@H4mE5L^I~OKb*&coG{(Ws;%tP-F~gP*_qPk}~|li#+&A zKQ+U#=zij}IlF3p)8Ye+;)O#9*f?e>ExL z4%Z)clTXVgw04&&*K`4Sp!Th~{hG3I7qlIqt?p_=e2)EXn7m84VkGy)jldCumMy`e?ZSzu$b?I4t)CRV@P(Z!;|* ztpzKx?1uA>zvsd2Ot1C8#cUV>={5lkO-Y>d39k)?1KAwP1P@SRL_~R#6njvAAQBWt zF2sxX4Q^<_n%iV23+kzJ!dak-Sk%z=?i@2}9FFRP+ZBDHls`o~0kp|sr#xzcMFv?W z1Rg}0-8$D>AG=liruxVb^7tC zFau)ufDf|AFbQYjd(0)}t*HqC-!ry`;}HN;Is8Ph;WR-I)Cfr(o$X-7ZkqSErN!l< zTEmH1*ajKy5l2(AYI9Qh!PM(5^xe~NpPDbxHaIc>#r+?UDKb%MKgBCF8p?4`45<{c z&S&g68ZUUS^V(%BR60AvS*UxDno*FelkS7-^2uDUmrvcwYwFB+Gr(Ch)p7DK@|eyk zwJ~ zaZ#)A-)P4E4T6uSmqNOrf$Eap?dE`~n`#0DCHF>mvNAT3;#hgpf5sI5PG8=f%vnqe z1{~iONkI;G9x**!^Ip6D`A7M=Cbl`#SD??Tb2`#BLe14Z@B4;Npj>*IR5& zwdk%c(;azfk`cR0iT4R_+UEYj!S|ErXe>Iry(~8eQ{LK=MOP?|yH~JlGq22`$o>l$ z`c2qYYroQsgKht#u1yj>_+2S?6E?+xB=Pwc?>|hyClr!^;CQwE!xQY7MPA}^NA9|M z4u+Y!XW}i8RCQbJd(yNn4UVD%kgO> zhe8gCb`MS?Wz}h^9`y;kx&>7Yl1FHc)s*34d>)9R&U1LE82RzchU0_#3nVXvp#OW6 z7Z=p8F2hRe@)^qgVamq8rxadSB!@ z+BQKiebhbsuZ$((8&CFCov*B(;GfnphtK&HtTCzK4HJ(lz9Y4Z zB^31Smd5N;w+$G9r&%fl8?phva%&-Sdy9v51;3XuwX0SZd?3(cM9wSDudLn8l+qosAlErIaNKR)q zqtJ|A^{lP?Rdgq;PzczcQcP1V6J-0c`&9tYfTocuqlA^Q6f!iyP0?K*lW}r}Pq*@? zrOp1%so9ZifG@i?9Fq1~GoDnC@EBY+IDviOr{rSJrrkSjU-aL!_Ijm>&XGq;xTr+G zYdS-qFtKCx_7rG8qp^OPHI`tlw+k&LA?&Z|gx_tq40-Yx2H#)R(M>-BFI&`HmcMO0 z3mxIG&&U8xjU{sGRrm>^59|i#t#+Mt2Z}2-4V@r7BR|~EM`F`#vRcSSjy^7P8OJ|| z{|2U}Les{le*w*Ui`#NP{5uMLR}ic@H32!AlZ_X@TyUth7|XGxh2)!A(q=>6yVULsX57Vtd|SOqAa+aup{)XWv`FB2WB3<`#Qp_x!4wniCNC ztvI_(DQQ`?F>#ou(0@pR#pr;U-=$f7On~cV&t>^dH+rtc2J5u*rt zrTB%ZJI$y3&U7%frWq+Lru7~10v{aZ00ZI`@F=@Q+Xow3ilig^GnY?U{x>Q%%ypKF zj{LaOQs{DLQu{fx3d%O^WSRTJj!vOJfP>+b%}Y(_t_#igeTN2@7%4MS!MPIO}v`K~Fl4A!y= z26!lh)^5dy1;rnXMW*@R;zka1d?_kb#6w@?M6Vf5Lpm-;%bUqPVi!19aF)m$g7sbc zZ_R_~1=K1>adTH*G|1+H{Jb?XCnW7(`Q#zqDyeN6)GrHD)B`DK@W$fa>EC$hNVLHn z`Dpk<_mP)(3v0FxavnM~zM8x&TTJMqzk9<9>J?`^jxWqd_-Bc^Aue`nDPdr`*5g9I zjU`)KH*+NwA9{!xyKObs)8yujmw_I<=UA*$zpI3cw=ggE`o4eATK_h&bX8EzHw@q% z+Oy9l&m}Ty{jUe6>+eOtG4Zp(c-IU8?dar+i~0{4=mmU4R^TJ@5r-;M<}R!+8pdr` zOCv@zyYblc1yiCA$A=+_Sb+$0MEV&l20Cq}+dPB;&}ID$n)N#vW)d7wC*loqPrrt~ z`f-bLktn}BrUt7jSQG9Zz_uuah&E7oU1m^?GF1xHY0wcGM|hlsfkR3RzLAxIDI50P zX6K3ga*OFb9#<_A!I$!=f0Rc8I>>^Kdl^^oNtq%$Z_3Fj#@9sE4XcIbt}2BqHEx9|kh?5{oq!jz}y&#|q&$1kHT=Ck$Xq^dra~s42VK2wAE% zH^Zva>UNi%sla4-%=-E|_@d2s7y(Dp=;AWxeIc*n1&0V!?JH6hoSCU~^+Igp)%wNW z>Ax+Is;Oc65tr<>cb}-+&Bm~HzTOZXz5nA>u}jj(ZVzvY9TvPf<5jE-2hV}~4|}`9 z6`;Q)_duY|n5NU{g(@J}1%9;*SJm}S-JCuRG_edR@n8P}`GbiJ<6%$_!reW1J{qzW zIiH-Agpd{YkB0H>9U5G#@W6zoOqg;6^szs3oU;O@bjBm!=}mu?i(einr<;r>>FL5I zH0S$wf*TBnhQSKQ3E(hAzTkzaYj7G+R}8oo|62@-o2T9s+EtZ+@o@Ee!@NN?_8;&( zT60DyeRvc8|JcT9WpQKpw>~k zZP)382Mlc$jtd^%Bq?DizqEU#R#~K`X?TuY^sDgNVkIOkds?j=>>?ulMgAf#!B+-`fsc21LcK{yOO2y{{}P%f?cDNSO|f>}4o6A7JpL7&-UHv{ zi8CgJz&$Z8yX`KVl#%;>qR*E~&0S-*qw9tB%j<`YOHnK96G|3785dFRR(5pYZ!q9n zC{@@&!tWlO9fZZMdDpHkKU<^6EpE4Js1a?DnxWfe)JyJao159r%iW+~3 z(GTSW2Ew)~Wy7`S_G15Terw!F!&bfq# zjeBgL%|H7CkvOa`4s~ge|9;7)WV$~6v*!o@oyygeM&pB0$g`!1scZ@PLLN*v$BcEV{oAduqJhPcRd0D5J&5 z+U_!_PVe)063(($CDVCATW!NI4G+rQ`K5~`_|`S3w^%N z{>3lc^EilHnDq$`#_To0YjNpxw$9U0;Pnh^wcD4dOVA+M;{h4kX3O_6vNe(s4mm66 zQphOcv-%@zO1K%_tX5-`%}oS(JHV6o?G0MjT)AT7X^V$+D0>IZcsjS;>!JN{dV->B zx^=kt7T0A)W`spsm(J1?hXX80M2fwMTcXO=gtzEZ9eY)R!bwqav5HY$ct0!LHgqXPN2qXz$JNMQHRa|y4-^ra zg|U+z+x$%x`rI~Ac(xC6+*uH7Yo4*UiCsve-0ZY=IG9*xBHcjhC6gO&7G?K(JRFpv zac+|f?%4}owV$Zei%o#sc55(~>3~;zMnriA9ZQNSMy@5oRP2mKB_35b37`{GWRj3L%YZY?Z}lKPC(SB!BCzyr zEJ#+p)a-toEXhbGVs(^lliPu9`j=Jz&I~;7+S-}EnAo67-JJ1ws?BO!0QASIdnUmT z%p6%7QOpKk@5<{tEHu-XT*<=*CCjES8{D-6uVhT(K*I#GK>g6!+1aYv_O9I5V?%%IwaLEFB zb$in{t$t{X3E7Mu>C8SnrnU9 zTWVFM5|>GOyJJmCeba#K*GEYai=fAnHna6W@VMX&6}0-1TXx`QR^Aa5U=o9h2Fliy zZ!n&d3zHsherf5lG$;KWJ^?LRuV{wN~DC<|pfJRkn1EDVdJe*0JL+Z#DahC!!? zXqlq;=#z!Q$Z>GAjZ9)tOs+Gd)Ac?5l<#)`HPrhiV8{N2S{bwG!+opm)Nu z0YP9nH+E?2a5R&194(RpE(3bmVouZp$Cf=!ON6%TAQxR#e$4IdG`8Pa~6NN zG$KSi4uug3Qnzo4^<*o{RLVb)@7(PRI-6RErf}GWX$P z>##xKt0o>MX3TzLm5iY*mr@Uv(l(*I8)nSO+iUM9KR+1`)NP*2uN{dBJ2iMZ6xtWN zp%|Q}xx|1lF#5hxGUoPglE8zB)9J?W4*D$Y;9EQv26VbcsX_C`##f7D39aIh*M;ap zEjbLL3aLz~ehI#NAEfb0eiJs{tE1w?{bQ><$g%XzGt`|^@5BLiD5zGbU}me&u#ojz z9o`Fi^WnJb*Po$D01~m&ikT#_5Qk|p>I>`H2u%Y6l)p(|5PzpwmRoBV!6)caYxXb@yW}bWCBkMDI7wAW*iWfOE^~Si% z!y10zbL0fO4@hhkQ7V*btLqKEgAq#jZV1bI-G1(Ga%J=B5?u1Z9A7w0Tkx|8!@t^- ze+7>CdV2?omydpWnJ_;Ds1FNK{s2axc2B@pOIIqHN9xi`%M`>UlmGnXSZtZt~|5b%ya+wybhGz8dhx$#OJw1mz_Qc6lo zX_qbJ9@&#rS$xPem;#QjD7tQ5wN>=Ak*dB)D%ogdaAU^O-f(6|ecAC}t67}Fpz!1v z!XVoI9bQ9c$S^Scyx5L((eVj<4Ugu>BO9X(`LpJHxM<}f)$cVhV|$$`0ols% zN!_m+$S2iilq0?m&l)y@$y%9u0Ror%FW z=B#_zCAG~nQKIvwYu>MQZ86~J0d|tIe*FUp(AX}uQkcD^K7LQHHB$tQBuAw8OB@V> zFS6C2$bhCDpHlo!0SU>rEeyIG?RYHjCFes73feGA0!mH~LLDi`;V76~hDyn@{>9#v zQ);E5OZ$OLaH4(qJ!eR%`|A9BOcNdprTfxtQu`kS2`}@12ybq%+6NM0;dJ!dxJ-BL zol7ykwv)iNS%IGIs6=CoV+vSjj;Fs1o)`4};5CL+gZxCxYfv--VKP3YF6U;k!s6F{ zvTsSCX!!gdtMl{oYWao&apL9x_>$^P{5{3X?%mglH4j6&8 zLT?EbJMN1eAkEIEz@h9@6s4qKR(W(&dQ2}*smFlPEc3un3hCpmi|d*)J>BuasL^A4 zTR9(@!C^GT^EG`MA`JL_siTDpo@m7u+SpW&1=+TRQII>eQeBO;e@Yro5eTq7d_j(# zx+Y3+#ffY<--pM~0iYmB`w;$m_5Y~{xXy;k^oadJ*_0>;ovu2%;+KqEzDkOO@|deCrtFbsJ0I`TzA*YYCWO8 zl=`c%O5cP-KbENxlFJXzbcKuM7}s&jyUc?wp7dI?$Ad1km%r0X<@1V1U1KE2f;ODG z51+fc#wvWxJgT$7AYDL4P+yJ2u2k2Fkl-WUpXJ=)mrw@#Q~qB-Z6vo|B>_808*#I+y{XRJ4= zv$G}fr0NC&Jyr=8bZrX$B0U~4A zUCi9@{}SZ-S(mp%$v)j#l?*D*RgLy%a^mJI=N28VWOJE*?ZJFWS0;@hVY{(oe>Wn7fq_dN_q_s}3YbeF&Y64E)+-5>%|LrY0BbeA*; zL$}gBNJtCP-5@0@AmMX)e}Dg1&v|j)U;A^eefC*OPDd5n4 zNC{A;E1SD9VV-pd3&|H=9X;!5%bRsARZ6h=Fq&`H?t3yLa%1Bzt*<=1>bnv2eQ|ep zm)=`1uxhICnt2=q1b~>B5#2Qc5(L|FYcujjQ&+AZ9`XCTMmcFA1+V9Spxa5c-+cTY zeRe}RBfP!4rSFTi-n)kTqw0%BqOHppP0b07ku!Uus#kD0wz96Luo`z&(HArP&cKT? zkQS_M)H!s0`~4C!>oy6M3i$26%KS2~F5Ti67vc5KD$jHK6PJXy z%H^)VO}f6_-d0e&?5Y#7yfKsgw?dRRmEfe*zf!IF|84cXJLB`=i@`_dBdYI1F*ZcE z_2w57hc{OD_w^6XZ8rwqD&+CGVB%P%`jWASjINBWcik0*>3GDqE~yTyqMGlMKrkB< zNvmN(ImT6qNDfQ0Afj@Dq~XgjF4~D|IrXd@5Dfw=j{O4axzQo|g!#oYzim6u3u< zu`NAXzW(niF-DS7ab+tNl3yG|x5|1MUZhQ;w=2X?%d(ny+asef0Lw1IZtA4TvCoNk zWo>R=xKOfh;NGT~vP-i}?l+lRPVM~LWTPFYb?K?2=TlPM$My-xmsy^@ytiD~*A}nD zxRS+_s|{3U2w2_^v;z+nX>?aOBI^2zcM%Omx*O+WnOBfZbc z{x7n=z#wk8Z2JhjIegE=cjW1f#hZ14cV{&)U}`IL@4^T{uWm{HT`W+aVjjGWjCiDi znLMx9!!|SbHhB6S3<@LDsd+CN|M55tS9l?PmrddbQ*h(g&;I_vuI>lgI~Iv&*aR+g z8p+8~2*dpRocp@$RGeC!M7+IU&WWS@eHq7WRO4jYyUS~*U`ZsQP#lFkmj@#s4~lLy z>yFM_-XGPb#*_t%=Hh`9LV5;zzli(d;c!_82kcn2Iv-N@{_3;Oy&MD7=)mfk$6kdS z(%nv^1mObPd0y|1*DdPzwtJ%ZmjyAm8*1A>KO5+YdAY02pu{I+OzZCn>RbG9J*Mws zdv?uVb*RT-JDXR#^@Lre&)We8V$J*m`vwvGLY{*^qy2#vDu*MM1<_`wCjTo`Y7#>m zwe`g+3+uL%uSewShOk7o2ePVUp1Rh`z?cPQpy z!vW>k^jDq8u64Uyr9>my7dFBd@|~#BS6r?m3`xK&j3Z7iuIol3b^ zuUPr^DQ@=kuWR3i4kX}W|68kU=p&+$NS;yA$nU!Mbciq4w!?exYyyAqj59QT-WYUU z>9XK8^xK{*@I@Diemo*8_w0Q+#Vc$-?(D$EV=Lz)W`nyziZhuN>r9r-*^ma&q|Qx% zkEj5y(tXaK{G89ko@kQv(F)o?fVsHtzjMD#zv7`u&*Xj%E78lJakd8Korz88^QK(m z#{Fr_hF<~g)M8!Z9Oh-(;sgQ$IdkqKh_~(Ecl(j1+r7J6mv-JkiRGiiR*HxWMCu)%1kbkSs>P1LP zwu;HWEp2oIR^`m#vmYFR!`Uq8cH{JpsMF=Djv5Buw(Dvm<)$}_lE)$xmt5?47eIuM zFX!SyM=XZRM4H*u0$1UA^^HTpKf9N-l1zeDAZ4o>fxRfU@FqreyeMlMTw3W|>PTUlMkC?0X*h9$(}3Mwg$(h&4?h zjsVQcKsz#MI!S|2sf|6UYW7Uwn$k1B_D>bq(eG1>fO9^-rt96^PPyknh`l$3-2^ow zN$yY&wOIgVK$fJ9wt4H1b8pgUu{O`lpV)}l6c{iN%Biu+}n`xJ2>f&jH zn+UAR^{j8l%~{^t);B@-%{r5j$FB;3Xx0^s5#yVT5XkmQ(vu9$ha%3{N%Xwwf z=#>|{L8TX$jbJmELs@@k0pQ+{&+3nVnYbrh*!+m^w$0MCQq<8BN!r(Cj&vM8>jV-Q z;+RZNydE-3(TH9y^C$#CsnY|xE zJ29l^`pP2uM=)zDF%}xGNc>kHCm^QFAyEc&BdKKvMa$fRQ3{U5$uTeTy1I%J$W!C; zK!_$HOQd{tW^>77&>dleu6yD&*np~T-bu?yLjwANmcIWmO98(oHz(mB&%*n`xO%`0 z_1_BZq(-gMEopf=&#B#=+Ph=7Wbu7$Ek1_R(|zMY|G%Vdt}EUpvY?vR(@9_7bN@bC zO$-DKMa6IV^l1PjMq@1=my$sePE|`%{37(`UV+KNOqlN7sy|xFdqy~`O`z^)Z;e|? z2Vpz|PC+)-)VCi}l#+hTDjT&sNN zng*PkZ-3LXG=7d~nbHo}BqH)*NFxK{+u?OM-b0}pG!I9Jg0xKMWBc{7~D z-2hDcd-HYBq5Ne>#vp@5_bO}1QO`awY;xTAj->CWZvyVszl@KLj){ln^2fgA>HA{s z$QRZ7HaxY7xF0Pm*1}pX}Iop4h5)1R9RY+ds77_k;Y`--?N?& zO>V@dAw!{pUlD!`h=z8e{x_w%=oBSP$9y?H@4JSAfZ$9-{3vETx~7lau)En~%ZH zGrLKrt~P&6r}vT|z`H@lMKaFYQ)zo|3d*QK8o?NeeW2EU7}^^y>TrBPlS>mLpT)Ut z_u9f+ry5nLokUw(`?26SYCi?V-o=H0w9gB^2Z&R)pZR4Bs`lr;onLZ>ej(-hx=+?K z7^ZLZ_9ex)3ED)y(j3m%zpoa=sU}3rf1XyS^0KiI|2mb}0I`#hXQ&iwtApriH@Re6 zmuM?o&LaAqqD}bvw{aXH0cAA0(d>dTu|&TuxABAM`iQdPhYb<2?q%f@@+h8b@Ao+P zdzYg<{4jJ3A84C4ReUziGP%WCtRliO{yQ)|k=U!mu(1_1@C$`tI64rk^t1jmAXe!> ztOyCWy|U*aQnz!M_Zu7Qzf|J1$rzcKP`$l>$$od|@!Q1`FskL~GKn5(Al6`@NE$e{ z*I+0>#zy}A#7}wJ@ksr{pO{^3eo1_rMf8LU7MqyZb2P)|f2)vJRb8DowxvdeDGn>C zlPDd>!lzm zh``1hChGtE)|R*;dBEyZ$Q*mYpFzU8kKWo^xN7aR6mit3Y8cISg2px3$rN!E-Jp#e zDH8s7!6XT%m@l_me8lTA4Q>8DKG3%+{T63pG9k;rMviVUxDGu3mvZ`(`kvkuV3nQp z$lNVFK<7^<@2J?-e0SEZiEMO^yMx0Oho>98@aX~&NpJk-wUI{x8d*Np4}X+jfRppK zoUU!Xy^k7ghY7QpqnK=Fb-vZwu_dU07BrO|Dcd!0t0xH4G9-Is26G|(uF8FT6UjzD z>wp6c{d$S4EHB3u<$6xRjVT2KhpKna;HME_C#ws1+JOyTPRJ=ab6kb51hN#8yP4J+ zxN5fb>ea=Nu*DH5#bpEy7}q7Eu!+rdLh>jw)Yzg#Wn=!Di9PvyHH!26y3elb=T@+u z=tK#&K`g{&#Zy!FcNbC22|W(2hj4`}1PU7fkwF?YH&6??kV6 z--Ye4b_$4{plZ;26mASN@UJCEy=AcVIPT8At7V2JoGxzutSZ&Rc8PLnkDhUN7EZ^F z%#~<;Ed?q&A5fZ9I*ceICTKumtA^=t3rMieY9?9EJ`;!RP)pbHPo-?$9*MQKa~#rk zFUZB{C0bYOxzJrJwpf~_iIhTKri5nj8u?L7+x^xN#^H1>@l%TU*Bi@;qUJK*9eL*7 ztmoY!H9z$tA{@*tt%CEXg=agv@(kg2nREAl7FQPqkPDB18BzSP(-?T zwlCe9OTd-PP-AL-cG^cY-Kg=ar*vRbg$}qg=&0kXay>A|8CC+<{d&ne?ewf+iKAna zPKX4Mn9EBBO33A)?Dug+Un}K7#KTzFLR9^qi{(PJ4cAgx)wPWDLTV*{7cnPv9Amyt zAbpt^&&FLN`V`#a#FLkth{8E94#T)RE8AFqbxW8Mu9&G38xoT#0mPk70+PMmR%*Dd z@a46G2KE_Uer%fJ{7rdFsBZlE6fnPdBZywKx!~k6EmqLRgsUaxg~OXeJ)HZ*|xTG`rb+4O+bz=5NZ}_M&HO4oYD=;mvi$*hNCrho+r`$S6tmq+y;V_Bv2m0G zL&XC8NZ3jG%&=D&c?f;q&U5b7OpY9<6K%pPbwLFW8L@pwimGVBy@W z<^4{1%U;sFh8z#0a~TR?2QQ; zjf7e8Ec1C^=ynp4hgF_$=RxA6 zaSc|h#P|38qtn!yBh?Pb0ynOPzc%9d6sG6I5L!4Mk&>Aa@uXR0XueTy^XJOlaLPv4 z2_fV-xjenBk6^*zwCli^mqB63y}xW6(HmomY-Z{J_F$z2b}zcXqwV=2VsFng)Y5YI z5d8Ute4bIdih>9<+G=zqj$Kqb%FrSxU(xsZ9=6c*w{N)0-yI_2Eyv5(*Bz>Xn$3#!)`~KjwMO&Vdd)l%^*ZFAkombE3yjmIgutx;%UqljpVDjP zk1y%`g@07PzsNGD)LLKcr$M`!p@f0w-N3JPg-b8P%hIfyS5gd@;Dc{7ASsqRTmsjR z6tSu_Oe!(T`*x+Z^3m6XyZvhHo*;y#-!X!S(b@UsEVA(Aiwv!N0FnmD&J6-B51~1f zrh;Kp4d|k*oILpt8v$A>xsT^k5x2BpG-+DG0e|9e;dfJT$yZV>)bF)7EMkt1;*vp9 z%Wh$wwJ}(Dy~twj6#-^joN@$j*Eg?)gY@;%XAEW69235XBnxIJJ(AOxzrb%>uxm9M zrJTc+Wq_@&Zve;fro0Oj_nBa5MRKYUd$8nEKE-k=V!Okq5D9p=66tIWe_>-11XJxU zsyWTPTlc1~HMcjY7)KmiwY~^)6h6zB#t{^RLEipg5x(tS5`lWO)9NDD!)Kd>XeE3| z%&GCP$~++5c$2$^qagOzTT-CH1BSf#tr!r*P$!NwQlxEpk+6Fdx6BOlPoSO$I$Qa$ zEK}B&%;Q@!c3hR7Q0AA~CL%N|0Y39VK3&8VxT58j){KF5PY99elL7zD9^8TJ$ic0ZCi=Qo>@G1I z&jtr>Lh_(UAoPOFK`9&e2P-f0EH=ivj{m6VacrkU9#FgPk==&^%b?nn9rp9@^0o*J zykS=6-X`jykEe5`d}F0=Mr9FmrC8G-QXOX0^)Ni^*|i zFbfH#=AYY>va89=&(8~jttdw^KccXK*b_{Ev^0`!%$c#7G{qz9<$gjOtV|&i715B_*fX*bKfmM@gic4TYiv16p z2yV90j&{6GzI2=ONF9R>yWh}x!G|Y;a%kj!j;GHcv_1~uXqPK56Pa2|QXX0dU7vsu zh=NWZWF@l=!L|{yGEH&1DXrA~rNQ&g^WBDc;Hd3QL`r>Y5-1Fh07KEF2mWmJG6Jzo zZqp5xcF4(BYnv)`32vriAnk3t5HqWh2;H+4wNh9`?|tdr;wSl=JP^1F`1-z&zY1pX z?PU91MLUTbgbF;{ySf)|ZhSBPoVW?0Y5*v2uC0=igz&B6stQlwE;UDn2W^j8C{v?# zb~b&Sd=~fR#rRf*<1sRG2V?yE!a{aBDB-{m`fBWJCx7~uiUqkxwTV$j;x0C%zC*3g zUS5`uKZH|RPY)kyqc-$Ym$9l4?unM2VTP_K(S{+=4ksN28Cf@p3p{7ScasWYSYIoQ z^ZjiR6@EPZr=g9ShBQ`2I*9*M0pHMxWxfr|^VpnwpMlAa;|}k^1*Xm+R(L?s``0w>J0{x+iLEN*~;*X#^yHZ$&|ooPmW3;be&e~$_1 z?7M!<4Xc>_7Jeb#Rk(p=-SHnx5F&=wb$s*Laf(?fZC6ZIPYW8k_uuCG=OPY5&3`(; zeDZCe2=Rw4R`_CXfY8g!Yjd-IFd3O3d$WsW9Gx~%nOd0~3xKt;F_rdN%PVUl0UiAy zYad%Ix<(GWM@{ ze%-aLh%~<3RuG%d@WmF1mI>2P>TT@2MqbwL6J}3PC?w_ttVuvya9&Qv4nIlzTB)C; z*ix~0lfe%yEw7Dp*)~JQ05`?9I~UZTaxQt)ZhUgj9&wC~N3uNk^ryq=oP41OL^Jp{ zl1gQ0i;X+3VS+9rjPe_F=;dS6Q$$=P;YijgKiz08PLsmzSK;fD#;@>yjg&YJZ7hqR zTzb9EwQ$JNDX}V2B?h~{AwmF-Oz%kRvuoZ~aV3`^cp&YwbA3xe8oLod4=SeN$iP(^ z(-~G|7SM>SvwxyC^{u$M6mP5mn5(dg zrzc66MiD=w%Z<8VWTg-A=H|);w6};axs5jc-5MyK2b1|Vkb8Tgro*V+HfK*;u_

e~$5c35dE(=d zm*BRY=;m0!)Duy>PDH^#tr_S!i_nL@mA!JF%D;jXHx9SaW!TlLoIfHcnJfD1T`>)N_~QA_7^IgoT62boFOMyMEzzBSSJkcXy4rrG8lUe zo1=J+BLD20B7>O#9>}=3c-e`hig}pKux$(h)kIl0 zp+=iGog<+Qj3U9mF1+HQF>=P{cs_aDgF`T$DLr z-8ul}nRNbV>b|-4vAUR4jQMR;R0>=0;ff|OtOb|wye%YMgkO$^cp%u=%EG%@83$Qu zDf2sG^j{c#xzP-1__hiW>vl;S8?F-c!l^z?IMM67JZI0GrM&arOEx|x)K)k-zdl`G zLpt))Z#2;N{$1k+=HoGtF##%d1zTHEB#tc=Of3Ot=!ve7d))_AEWQk8N%8l_9`V#9 zp+S_~TKyjgpJOS;HIWPm1o@Gyv>EmFxeg8wN+@hsZQi5*OD-b*$d*kDMDrzXA6 zgc@K^BD|SDI+fG9wO+G8=VWD5z8nqOHahFDr3>LSrGaN&HEmxS_9$pRWp~_^;*d~? zkW{Ia^Y5Z~_vg>^WpB30A4ATvOVPO(BOUYbyuFZ;g}RQH$!*(j6CsTy-XQe)j@)0o zB$NN%kpf1<4)bExmXC;$YN-?d50sSMLFP%zPw(_r=m5( zZtt!GlKjDmkXP!#m z5p;B5krQ#+wQ!M>&n0BzCZ}osfM>XqPII)S-@4ml43A412801ru#TlliAXtM))4XDad3b%?Uu&K8fV1Uzhj5(AQ^73lwcW&&nYLqW*x6>*= z_7gBR%wHNi0^bTyeej~{7HeF5v84OWQ5ko0b+rHs8G%{Sld+54_Hs?vn*uOglZY`I zj}U0Le%*vcR?G68Tu6{UM+A+R&i|R$`<#Ir_GtbAyC<`x%#9u%nCq+ln7k6qzTWIG z|KBnTvS~9}egnM5(gTYBp`7TLxM%@zXfnJ#oF*J!D7-K7Z|C}tZ z$hF+NxtUsZESAXn8~usp9nC9(Q*6C4LD3A-J~HiuuVoX&Ih~AIoWyjbgXD!9yVk8M zTIQM*U{Ux7uEVCxK0$cgAdY9OxDVB#7(hF?Vw0b2az@xwzKlMi0v?(BM|~-rDGp8xr7ew5wom~}CDA}P zZNl}9cQ_fE`FUhqAOw-vR%K!Bi$x=*ZLhRm`hlbWPzf}2aF`7-1#u*?H~Oy5P>9qe z5EjBkf}d9k!6b+^KbsvTvaIwFZ1i5i+0RPLO3F#};mocqQ4>Mf63vm`W-*E+EDGpg zSw35*ZHnsfx49p^Zyk6kQB(T4?!U~c)?`*rSbe_THo12k76afk*%_h&h_)Yd2s_jx z5_p*Jld{joR@K&q&f8-EGn1M!36J4vdf?B~6~tr%`t}ryYy!`dT~k_FuyOw-!SC zfIwIbmtpP_%fP>Cw-h{}l`1EM8G%t<49bF!>}ie)x@c)tU?zn1%jfxNU)lZMFh6#t#$NiioO(Rl|MV}o(EQS9t%tPLiAb7Q6cmd~zX{XAH*1u2v z-_4XBIKO!lIXdw1km$D_-4=72`)=#U!3du!I-3~=L}vp3$gLIWoh~}q66ndaoZ#08 zXth*>OxIUJ)93&45hEUhnIiu0^PhzDC1AfM?Axn9Aqzf& z=+oV^zfw2KqRVQ6)$5W7?wuV9UW4tx>>)>1!FG8fc%*7}82x&Ontx9NhRgJz24)0)br(m_X+T$fqQc@^AAD^Z)#?f8OBmPlTL9ZO{-I zBVCrhnszl@T-=Svz`z@lfjfMs8lQs}ri=2`zWg()ESQ`*;196_bNKYP=@|8BHLJ1# z-%46}2LDmTJap9YlRx5MT9*F-m*xOn!hPS{+#Q9m2OQg?{DyR9X`UWrB!f{tE;+Fz(!F79vtVeerI9x`J8F18(MoMz!J|eL zEBN=jJFS_;rEmzwuB$bYQ&13xMR}7SR&wqOdU;blWov=hZf#M0?PE3{+88r)6JOJ} zpiWX};CIhN=nnlFUs|_Eq!%X4k9mGAcwj~#}n8esVkmvgJDBeOB< z^0fxc&z|9v;80UtOPx_{E40Y7rZFn;+M=gHNXx#^bdGmd^;qIbS{4Q%j?L2bd6abg z7(0K@M~P07wY^SG%}MlzI26x2)f-zuk&gXg7~{LX!v#TyV@A(Z zn4w_&IGjFT1e?%+dieU%yK~O)NlpcE;_9hP_|eeB68k1d zCc7>rJ9~tGGD4p|UWioXO04o25)LM}K7A_oJaOaix-Lo@J5*Cs6ZjpJk87|lcgS_! z8@uS2Mg?zH>aIB4oL}c|Hbh_>2m}__^c>_%$h_OTTmq0!)C{>X9lohY7`p@k1$tGx z9^F^ie~gTr6rNbBm?0guI;$Ipih40 z#9@`uh7K~x`2-3S@z$+pmxGV%YN)4wod#X zH-%T$iZN2yt^f4TW7*o)H&+9B3-5ZjS8Tm&7T(d;BWno+PZ@^405khkw;jgKAIR)H zsG$~)vK|U39H7&SzU+DZ$0YkVX?Zek0&4ZqgSaVEiN`cl2CW#`2_h4_8;4*xJs6<%~L0 zfH;XWPyWBUdb3V>(;nybI-k|UG)w}`cHQ;)?XEBE$F8aYH`2*6FBkuIK3~$8u;iu@ zo31xvUNq&Ad0?kS!jLX(T94mm^qw^L5gVxW-^JBf<0HYcE}2#xe!M z1EQE$@i``q8E6P6kHH~|ooB;z3LQ{oWl0lLQ_Kj+jOW6fo-nFLqZvUEh4(x`&$fGp zUWANucIe!q7SX_u`NlZEAU7P+L0b400H=UcNx)KbwT`|5IZrH4B73FDqyGL$sZ3Vc zZ7_27dm~A?Wk;8W;Ip`h8TWSvalf2~YlLvvJmE34g@4F)_TW!`YBo`E9<3&;UYjZJNLh{Of z6Yd-A)Se=&KLM@j!m1NCs8b_>M`Ree@15HG%!yD=d_{fzNx)Txn(>?(Pv%e6hQoDJ zllRs_xmGYZRxL`o3EKdJ*rXQ;;*3uo46Q%yLA%lfLl>@om2A70h528qsEkZJ$(o{}373;p5?npI0;ga-JBQelVUBo;qvued%2`Hz7lWg||}< z)w^A0sOvzQX_EOsb!Xfe$F{cm%O4jV(qwzTS=1@ojml zgO#sV79m&s<5m8Fr}ru^Qk64pv$cAdQGCq2q(5{Gs1m*vS2wIiY`d>lPk!W(icqN( zs9X5XuN>C(p^zD{&sUm<(@$kjPy3z3qgW%h zG+?|(hQFzFQl7kdo%BN0o0K9^eaKXjf3qFyykAmsYAg2#COXF}K5?`jNZ@=b2K=SU z&lQhIcJ08Hez%A`(luVgPp7L1lP{`hp=?~XBp(+A#OZaoL~SLY2KPR0IPWERyEE#4 zQ9}1&t|;DgU#>O696b` z1B4j50%awKM&Ug-QCqT?Oj_&G+-o!JKM@@EUnNEt26>8xq9 z*T>=oV#Y9Gt;a=>W8!~CCD8|Af)=HqW|qc`)rH>@7pm>f=Ltqpu|gRhrx4mG9W zq$rvpB#weiJhcWhbD<6{j6f4QXDu3_f6AWOvkXTtLyVr}L$Qv(cP@p`riO;1Iyk;j z)C?l^VhIt)-oxfdO(Q3b_?5QJv_oq+ZQro97qmB>!}A2Q*=-w{Ur=`|vyl_?_wj~G z!ppuQL+IXXNCA+x4d$duppUU8tCl&tq|dkR%uo+r+*Wcs%;y+6w&h<}-MN#}zjgR1 zn}_+m7KiFZ)zIL1PRE3~7R@=0&dAJi;2cCiU4-RgU-Y^;u!aLeKL^!cw;*6rIrWCi2I7mME3K zn!otbU>)Aosmr&VONu|r^4`W^gI{;bbSL%bE#7%%Er6kae;sPvPYn-SH7{S*6KV7_ zv=$7^)j$GuO_F|;L-}}ENtgg7z?*V{;jLA*Jl@LidHZt%!oTjM-)hY#x^Sw-zD$vc5yCwYZ}_t=TN}$)B!42k8e^ zrG&9F{bETO8HOL}F)I1DjQFB`R!y>Os3me?+Fwg-P2KfW0J45(od4R3@(DjRd)f|s zB|TAZSma=uaKq_O^0^i-KpU`Lofrpk!F=6bV&}v8ID)f!sLm>9sH;2lfrL?8w(z5! z`!|TVBq%1G;{(Y)zr!f>csB9|cFV-)9U2VyYjT zUOYak3m7>EouK{PS%L9xBUSOI|A2(ICq|Ox(QzK=CcS7Uia!qRH@UyMUKW1pzPEO; z)sO?ZV?ZE7xl1@n8vP|y?5LW4XPH$Iq9{r;6o{kA1X!ub6ewkL{a+$-Z)Kd;9X|S1 zTjBcM>M6;CLH(3WL|vSufa9!!y~jy@RVhJbQ&X&Bo}33oQ-X@dvMMwTDJmMBpkC-6 zQ&@mhwHprF5wa37*7~-HnPL=wKKV4E^;4m|v3V}hb_+ET&->^PAMDtaWs#Nj{ifZ1 zf0qigG(6DbDEXCMSflo=w@0TjQ$>tzDX2vazY&xW!7MD~uyS+uaw0o1`cm(F_O+*6 z#_zXMUiKJ@DfdrGNoMtUXW?`CKW>knXHIz>s5sF})Z#y$-L6GwFBxkL#zkmRcY7Si z&9G{);nf+;W20q1yoLQg0%9j^XwN^9|7dzI<;lW3talG58`<44oqs$618JS!oG@zA z5V=f(Rmz0WD__BJaOAALg`0(_3y43DB#k-^-=;3pZ)dj@D>^;_(R|np)3X8D*$Ao~ zFBgd!0}asCiGOr(5|TRuLf?0-U9oLzuC`Bk;+$iKf|aYfFa#vOVghwa(PnnBHV?+9 zoj~ybhQTy&QF53n+Rs-VD~0Deg&_9wqOln;AL}qqRg;V&A)G4bnBGQEF$p4X<=?vI zfu4JDv5W;wnUB7|f1c#GS2i%fB<)LQ z*%#Pm$>P3PtN{T$t%3Saw2=xt{eO%HVO1aKmD0#D=6gyhJe3feN4K_&S+Ss^WO=Sn zJBxP*@Rj1o=QZ{_qFF-PargH2q`mV13sOKf zBgOv`qV&JV8lO@TKm%wy{6W-@+{LCJJ`esIi=~>Pf&|)XUR=>h@`r6h*z=g1IT$QKPye+LY#_P^v&?~pW~4gtWZ$#wWHZEwMaj<(JzcHI;;1h7 z(wp7_HmIam;85Y_!jI7HP>c(CKs261pj? zFD`y++`l~#pYxtJ+1$kjJ|ThegmuhTb{=TzXHSVd+T~D;90!@lz1@-DH;!b(nFxdY z9C9Du!vrHCCc1Yrd2t`VHpA*Z0A&sVkI(@Wpo+D;p0Y@iWTj&VaJGXlq=cmZRZ(qm zpo`+27CMm$y4BABHGpssXr(8~Kmm-U>5#DZElJME$Y$4Z@-sp~(oCz%4_>q*wMtp* z5$p#^$o*19tua<&`S|m3x|qK=!zl&1^(qmOwz?Okduch>RAr{|Y|I5g0sL2tcmRQ1 zNQ7ee2REa~BC-2hJQf2fJ0WpkBtia6Nr78Rl4uG$bz!RKd0ojwYh~p>20S+Ycga&F z&o^(Xb4)~#9*0;)D7tJ-HV$7n;WbJWd&PIGHO2>7D)`-8Bud_7a=H9X6-gRO3NO*) zh6auUD!e*)0>NPkzp&>sguz2o#U0Nw&(cP;i|L+pvou@-r>Jvax(#FCX2kC|@(_6$eH5F8LEG`0F zH8qPp-Vjc|dGifZ^2GmDvsCxkKWk~Bl^tF30(<9!X)mSwz1-Rk6Px9s=ti{^v=Ddf z#2Z=#s8PrbTq|?Aaix~WX4>@`Gp`O_hS>m^g1{v&GcCXzT+jzW_6r= zD=X5Qls(cc%DCCS5qqUS9BXEN2_u&Q8N(4T$Mrd)STH-8KEW14grmw)F?t<8xBG5w z)7&C!vg6@UhUEum;?4+3++fI=Jk@0;yWM*S7N~c;Kl9d z1McwuWQ_O*==Y4!=oz0g?s98|HTARbSsB94C+sf^!XVbPKn>E*l+u=7p7RrB^rT_% zhLE#vJ`YUjB>~1zNHzN-agR~)aWyAwJ8?e(pJV$&PYX4;nUL&q)}h5BVwe}>u%Q{A zpa4GIdzc}o9Y3kN7QgS7oL*iYh|Lh+Zt;?h8>EIgN#Te)XN!2U4Gauu>F9(3qaWp1 zGG*)IBLHLl;)$#xJq`i4_2(4Yf41ZJWrxlc?9Gv?mWi?-X|6Zk$pk#|ntl?nnKuR8 zI^c3__Q9bZG1!gPG|!*eLMAikguama@0Z?^J2;%1{x0sdBxzJZ%N;yc0`M?6&wi9ph_W*T&+^dq_?U^0E%NcO*dQO+KQZy$RlQIq==QtE1oTk6cM1Ex@ za5!rkuxe~*(X{-i)UZ-C`9Nl)o~64Htsm&=&1>;s)3Yaf+qu&@={LdncdWosmqOKU zny6v4Uc+uM`5S4n(S#P)ZVlTBGKN$|Q`4IS!9n!|Oa%j%$V+tbAc-_kkTY zo6+o5Xi%*f5bzJu1d&mpcj|4WRFRTmrK<|Ca1lQ}ql=57hQ;5EZOWPlP_D0JMTfVO z9|{>+H!mA0mt>Lj(cO|;yM6mGoIxb^Lg5FgMMPn*BUslb1zp~-7rW5}uU#W7hdK44 z@T8nsrL2p&P_vEmKj05YYAbQFfY^d;!y02KKS4muumg_MY2J!vT@cLCGL!6Jn_snI z!4k0_$69lElXJTSU^WC9W`s_?2+Y9J`S>ssy2pdBq~kV`qAeDzXtabJzdj}}Ps~vs z9RE0W?eVq9eXU9Vz4CQjk0hlRLT9~xXvfP&@F(hwJKR6c?$_V4A4pYaL7_m-SOt(s z)RTD#XJ-tlXIiP|hU@D}h-;f-9)N%U6fZMyB{ZEUtM$JUa|MfL_$scz6)RD-iD6fEX`5NW1d zIc{H`HmBcNXbk)t=5G@*U+y!@wy6I@YWnj33y4{Ow5{snlCwb1Y``3w1PgY(v>=vX zs7_L%1pRxf1k8`M5`lkD^EG0N&U<_r&<`_hzgtF(ZLD~(L)TxIJJ6IJ;~%R;w3;37 zr9-#vs+5fk+tqbD1BATiIo#upo{+kf7h6!ElI zw_Pvx^*KW%>rN_&hGcdpf{f|#_&99BX?T5=>wdratAH^k)cNvr;pTo}|GRCkB|tBr z!d(sf5e-od2i0nCx&3X5;EeF}nFRkP3>+mG(RaH4veN0^)iybg>U#xh7cnd<4-XKs zy}ZKmD9Zf*+B@@qsQNaJYX}u)ER`bb&B#`m7-I>IeMSr_BFmkM5@QK7wkU?iGRAIX z$u`_%L_&yglPzT#G{R6xCi}iTr@QC=51t>N^TYY&oL|m4*Xw((?{!`8&!=0MT0BMz z51)_`x!;?87aQO;(>soHsExzSFT4TLlR-oNJ8wFT z-+a8vN@*5P@=J_Wk&!-e@pYI`YlLlui5x$)R7LRLPY*E~NHLqWv&`INv%CeF={B!1zrF(o`AL|V(kinj@^)-k z+u2rAO0bTGAw^b#PM^$zYnF7Fb`S*T;Cp`UIw;TUvTpKe#Oif3O7&>~N^ZNtI8{@2T{Xgz3F ze@;#_(In!>Bg@_S)&Xt|UY<&hN(FLK?axY6rvDxC5jX^%zDXMeAkh{N>5DKZR%!~F z#p{U3zH6PozWTf`l__p~)OjgVTdB*m1)Mgcr|%B~T32Hqd(h?pU}wgIk;6ExikyD#M%DCS5{)ql=4j!7R?zT77N#mA;Z}&UJnHi z_w+=3IyYTl=#EwxZrqlU?rG$$zhw{znF#dJ1qrF%#_MZHelM`eEx*mMa<-Jf-|&hr z7@2pj8LKaprxatTHmJAVzD?}1&yL8d9jQiK#3rdfHsDP8P-bqy(b+jbzqRz9lrIhJ zaQ+T+d?X_DJAd@#4ulj>up$sIO4b-5-%uxl{R+5$o>6|p@Ob!k+_~3tndpKI#LjZa z6{sdI=5BZ!YKiheg76_bGQpvxn=c>wXesvyLaDvP>by%T!JFPTwzgBdTPs9>m9jct z(#k*Va|#o~@yh_p{_;s>2j>-G?9uEt4~l_*Aqx5gsY;#P`8Mzj^#|E}C@#uEfDi<1 z>zoq$BFrX~#0T)D7LkC0Ov`g!1c=d%Yr&4>~!o~Qwd+IKFF?fi;3K<55YM)(?3abJ`R}-DuCs&JBca0@oLs) zXP>olyzl8<5F%=7pqgDNboUBAM$Fs_L%Qc-ya;>?>M-!@*(6Yt$^_ZR8{luN!_R{SQ(kR!TvirB0QV|!LbB-etenYklYShg#50@3U;t| z4VB}tW7Wh^6UKUIwxB{8hm}uZA*6U~m^B~xE{jzvO+t-L)}bfJaDM*j*PC!jv=pp> zIdgxxEYYme+d*C|BjYiohG=T|UaN?Ck53D5#sp}OmaK6LwdaV9`n&4^ByIq@3B;}m zp#Zz$9_s1-025p@f1DAMoM?G8VMT9Mba1r89TjvUetr#S^z=2?knWb0!LL{rLsnPJ zT5T@eux(}h&W!=E0S3}QQO3sX?RZ*m(wL0By3Ng-N5;MJJj<8Ju`~}e#FqrK@Zr%Q z!=k!{gXYGD+i_9^CVb!NXWzKFtAT(k28rR8rya{QXld<`r_+x$aV{y*H$nH1mAxXB zl@L&D#2pv@m>5F{S|aw2tMW$Wa?U84<-#{|{&7!eEf3yzXkDK|#;aa!W zd&cj-k6~IVU1^-fp9`Pq#G2vM8T7*@cbq`XnMKQ@$SG_uGb9Sm$%)yCD!_2zAb6K42)ID@eR>PUR zf%xigG}z}0@DvZ###)#7(t%6N_zo8-cjWOc`z*3YgED!oA7h4tVxb@8Y~2)|l3%Wr zq$A~1$oV1$-?1_X)8-9#YFyO=^M?bk6v3=diS52>(brGkT!T%Wvi9*GKDA573r(d(=pC7K{*Q5Q!r9*f| zX#J^nqec5M40Z?c$oh`?>ahH_5I*OZ2c#gB@TeM_{*d^}v3dcmC9_li`pm+1Ds0@{d%HVX zW~X#_1k2I@2Gu|3W+k};gsvu7~mMvC$h9pdwj}LE58n7J#9#-PHUPTCHS-m5KTLK6U z;H1|H;wVnUr;S1M{<-5#8Cy%20yIwY|Cj%lujP$65kd7y**nC|1{|h_7RU+%=ZOCR Ddxy2f diff --git a/extras/Images/ebay.jpg b/extras/Images/ebay.jpg deleted file mode 100644 index 1189dcb021d724cac3008c99ffd6520064a550cf..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 20098 zcmeFYWptb|vL@VSj+vR6*^Zf+sm;vH5Xa2S%*@P8F~`ht%xuRT+c9is=FaTwxBKV& zw`b2)zvpfBBdLy{s=A~qeXM=#08nHlWh4P$U|;}g&_PZH%Ktn2|KtpSBYl2Ksmw^E z#=8E;_(FJ>X1gbrX#R7s5Wz}9-Co`iRc*pdXBw}Tp4PDbWwRTN9 zOqn!3_nia((F|-)hC@e7Zd4~`ooi}J!4wx*;)rKmWv<`sc5Y(rAWvVDfvp~)WS|Uc z!y`9IJ|8;2Gh-XZ{Mp~8hKtZcJb-#d(X?ZfUhFq0C;#{nF+}d-9Bkr9WxhF#WGnk z*$b8Z!53>(F7dQX`7*I;0RvzF004oQCv<)%c6ZJlD>e3bW9gux?`)1B{%@o9{|9rJoVui z>HJRS`Op4Ofmy$)GMe(wuRmDhNG5!Uujvcs7{M|()~P!S`{ z$-35*Ne(mpETL&iX!DK6N3#StC3%2=cvR}9(~TAY0Kigt3n&_{9xseFWv?%#=eKn> zy3YFcbT0aa+dx?2O$?WIr8Zq{y$A~UdN(k9-lw0OifAgeJ7JjC?pbNZFiK-;FH)bf zNX?)s-Y;$LKJ1QKmX|>1tuN;{3*^QGt&!~njdO{424FI? zEhTFCkpr=nW2t7{GVKW`&Y_5t5Bw|FUa4J2L(7y#A+*biz0T@XCrD~hg#mPc0??EI zU;#9cfGAZO<*KBXe?X!H_V(0{`1D?XOaJ#YfVlI&ga037g^`g)xzL(S{U10l85x&p zMYUFRtS^P)ZPS0$<>|QdJ6pq~LyKN=6s#7O8q&i{8?m?FTSxyvrHte{a5$2@^_xBx z_J^Wp{pa$!T#0|Rg+R0@0NlxVUjZj9q8y zqaJlO=>5)Opn*@-C+d0orXqa@8#NPjnoVy^>3#0Y-Fu!n3cl5oWNVmKg#qSGxtU*n z2BK$cK76d-ch@S4fW_2JD9mHvS-zEA7{~j0yIPGC5YIUieArb{K!e28^R}oWy^k)X zGoLQSC06EqxAI%SJ@#;sj?fMSl-E$}UW<%N<Q?Et}C!=Z;$=r#72aa~2rILoi8vuS113nWJ4)9Mu|6 z(rt<|sRd4Due_AAXj5TMbll@ue8aGKRrNCJRRPaj70Q znHrcg_!Q-bB(BG=zj(bw`=qBKuN`N*Pp<>Pd+R9?PHJ25SnIaQ=)5hb8OA-XwBGth zpJftAlTB+|e8}hqLup&)?Q7?3R+GXj=PIqQgDaEVJQw%yjF0PJ9lw}8@-W`F@Byfu z(!l(~N;P9>wtjvQ9#Ply61V41(sL$1Gb}-i+IiO7X?uwj6f2S2j*pB6G*q30CA#ZmybF!0 zn!fOxHpQB)!;15COz8 z4&n>MYl@*7?7ng15fOwY?9eq4aEd6zR!wuz1zi@J%|kHa=gCGG#MyB+W+TPeke)Wi zR~su0H}a*2Uq;)eo^)KrF*aS3 zV&L|+?)!!r@sEiX;&VtQG(AQH|H`)e-DE!;fgeA=7tLF>02#5OCH|S=T^mzxsJ*^n z+udN3aNKQu`(mMCy3&J=Fq3Hi>Fe2f74vrZ(}jzd$Nj|!TWr=3IEp_caKdqau97!J z$u5m>35_-s@80xR7wTmKN2XE4XFdsgDpUR}*wjZmxf$Y9=EC779)JK9i^NlYV7V{oQ=Eu14<@0=a>}Vmx4Vfz>M6ofl2aV zO?qSqi?|(L=$7DsvEWsPtI?Tx!%tr3DQ>ZRk3JeKDeY|8X5s)#$1hefMZJzKnBAed z_l$evvj8vpPGvKuJP*2QqeV1oyhK>Vv@)x1HH2CfhXwkl3pE*QA(chRmJHoK#_P15 zr)GSE(x|nzfGEkt4Gr`e{AG6Q@6I0 zt!)x<#_og_8ywkp2<9#I#H3mJ~Qk1m%J0qHv z?8me*6K4hzY459=S!Y3niT3j_PzjZg7jttTOpbchfDPJ2l_!M_S+4G8p=221>kG0q z-K3_+*7caX?-v*dLhaLc-K4I@fPS0r(=%i1cvV%8X&U^klx%8CV=IR6+BASxH%75+ zVm81y9iUKSbUNLajbvkDt0}+Xqn{Sp`EyLfUK;naOZ5n9QrNT__vl|neSQ1Ov5SY@ zF}3ze5uM5v<`n0jOU7lQ-%iDFQ6vXG0I!SR(S=;Wud3^=x_;3!JvRNSD)XRv{&iGb z%e*9BeN2&N@ZRP7u(aMS{O+={;l1z!Hzx3TOUy_1bkwS?F1s$f9IDZ%ZVI!{(xX9I ziv)`xRgIWZx9IsyzHoAwULh5BjNF?1*z)Bn_g>xNk564!T^-g*?%Vngr-SU9pNUII z?|F3Z({WLZJuL^rODW-HZp8BK?4do0rsI<5_ZJ8!Y&Nzyb4muwR)qx4k&8$E`zCDG zxv{CN9u8_@*QW~g_GG(ik55I-)ZVi&rEpZtW;d=KtTf;6yl_I8via{o1|Bh&n;U7o;uKCt0{KwIC8t}UvQWTcl zR(+_1^0P4Onx#jpt7fZowkNmF{CdiLcQZ>eU(uJ(^`ot=uY&X+00I9W)9>LPW+SsD zk4-}DOcYyl0XnDn>*cuGfW#()hiy3zs&H=;zGBDhI$Gi-Z-w>9^}z=s&FEj2?x-E( z$Q?r5QJX&%CWV(^9uHe5-+p`bYsTXQ4nhW}o=RcM%*wg@kV-1fZmFqz?X=>X z^%5xJEqfdi6t~wP)WCb9y93d(q@~KSk8TK{7%0Ri4ii^ybtfDtI~NoA##Z>*@48`} zfuH3QD_MS#$B|3k$c;dB?3tKD^U)~HbC}Wq2W+Vq7f1)tnZbJyn9KJShOcYR7A1UUC-s~-01hy#l@+G?vM%HIh;03a)Z7IYQ`4h8`-BK~PZ zfXoOma8xuDQdS5O7Ia}{GByzvBjW<6f0z#tU|>RE9{{@5bqUN@(b7MZwBnQMK3^5q z%IT{q7b|{bb~V9Ga+}$IqsQzxw0JT%|IF6Blu&ZhXwAzZM%9V=Lnt;lnHDYdS`y7y z`-L@p%QPJ^Z9_Y0YoC;Q3=eQLeJGkmslr}B#;Vd?D?)hltqoalK968D6e9xLrC8n zUrn7p_I+v85JtgZU%57}kcgkx%wS2!EHm|jk$Mo5c@T<{@trkEMMjMw#2$S;(Pz>c z#qEet~jLU$xv;Rl%o$uVociZ=5_3-nwM-iu?$^rr;wya z!crS?+S>89Le%48#H)G#e4AB1rjC8#yEvmVsg$uhDJ!V`88jnVtj5WG;ld_IT2B5Tg~uR`!?VxZ++lhG%EIcp!Hmf^C5`i+xp27 zN^4IKM$>W=v4xUh^ShfvWE{;I3egpGzauB3j`~JUG709_JhL2gZ6tBLPs=P8!>x1n z*?iK?h&KCb=2?@gT-ukjXG*hLAB4x}A3s@BeNB2L-bh)OrjOgHi=oO&e2V(D$=Au) zgufWg-i~*JYhs>o6IWbbg0f50#p$75z;j+lML(vfC&PbV9iK9ysOF4oe6QsOYEY0A7G)1z!gzCG96qF5_wCh7%`eo#m2J<&WZR>yGej1w>R?=pGX>QH;j z+K`PX4RYpqzi!8dkz{&d`OR0{ z>-9+dnd6ayLo9Bz;U;|$QG(%^l5n<}JhHwOqse>t1Shna6Pe?riNHg~j-pTc+j5&% z<5Fy&JdNX*Y5}S=Ycn-N;n4{Rj3`Mf*kT?e>CKZyi zh^o2-aR@7$6k&)_7!@=Q&b#hj|JSY&S_rgjlvd1aRdWSTgND8iy*%-jU6|$W6s`k% zTcx!PBiW5WE>U|$J zI&-bQ>KA6KXVfPDsJ;GPP1g6gAi;OsSYT-SiE`(b6kEi=SD-}-v9 z!;{i`>b?*fWAxHkrnvbbPr$ElC_A4!OCV}?Knp=&tN3QavnuQ6P-)!npybb=gDTkbv$(l3UCar|W zbQdRoQkQLB7@J=)*JW<&Pn**=m83I%$K&$r9kuM6L)bMgLY0tSN_2D8!+))0U&Gp* zBa>7%`vhjm_>+LUz%_Om`ep)qvy4}CR=50qXja$KjH+*w`3KxEe}91bOf8ugRpSGp zCk>s1)Kj(b+oOZ9Ds&;4Omol|hSD^H&Fi?vdND(F6Ghl?KMv z>BPEalR%AOvCAl;XRm6YiO2o23;0g%v-uVCi`q`3H!$RPZ3K{mHtx_J&tJn8f2WR+ zgl9NAP!oz@Zw!9%SIvder}oyOAukZ$V;am#K3x1zc)M=F*ShpsboY2OwpI1C)oPvC z@I|CrYO_~FY{n(gis7FvJOWi}$ReuX62 zAFuoX1P`g$-W=p-b)+Ld%iCL8jl58U&(QWFpukZXO)gSP9({*gAhhDy3V>8HBmNYi zca1;wzQ`^vJwK)vDxKZ%>vh640^mqDCZWW0Ir8gDGnNnO;P9QAoWgG@=7o%Az6oX~ z%3OAc=*xo{fo`b}R)c7U>0t+Ei3V3&r~7XfT#-})YelS}WV@^GLG0dmN4Bh;4}jIL zP_{}6?l>|{hMsMPvat31s7d#>p0R?@nEXh)P#iOhV^@(C(!Ul4wK;A0p8H+qsgQ|2 z0DgulgSGgRj~aMB=^b9x=W4_*n+tc$BWfVsfGN19deKbh=)*y?T=k;%HWbaK8I>tD zy&sj{_|v3W?eq4DX7xNLuRK)4yPRaejlp*+A}C004sv6oz95&2G!8y0xWIq^5l2 zb2bf-#nYGbQl`agQQ5*j*N8&#BUD+J-mI$5D9+Gy?r0o%1yhiIwsf-Y~Wt>nT+$cSM{x<#*^D)SF|?SmAR4n zx_lzjvtuWhP6;|vkTg(imwP8er@NDN`o|2Pp!NeSVryL3?x3o_^uqRMz7S{Fsd$%F zmsQUwEWImRo$bhZU@R!k|JD@V^3TjMB&&(~`Pc50QWdWlocp|A=+0JNj} zS9bkSReqX<&~SaeTkjbtRVVz~+zC@~tErHO%d(wEn(8ct+pS zP+4~U)gZlz_>OBY`c~=~f7r(!ul@56A9VS|39HOEkHw6IE0z`q0--4$ZVd_=kl%+ zdWKQ$k!Z)X*-F712iwyl)n`$0jooEI2ghjqF_~#mM<|NEF(0UWRHR2Sl7&y__Y3l-UWE6T1*Pj7P4meLZHf0LcMzYFGArL zORS3MH1}J_QQL?MiCC{B9(s(Xpp6`cno+&-#7>K~a|M`cb?4uo9H)P}UC&s_V>yCP zn(9XoGFHppLW z&42g`&nG2cNt+Ktvtpb-rv<@|aED}P;>&`AVp@M<_FQKY_Ym%6JQMy>#VN7}k`vv$TX(A5>45>gX%aA70wfgDeQ||7vX$OCaTM+AsEe@3$?rp^D12<Mb?9Ajh8TGr@dJBtPUz>kguYfV6?3!@AE^dZ$9NBTpo|Y<#7ycm#``3h;%s zJBRI#L7VY(n;!toc0r9VmQRee;&K!nzdTQ%#&VAXb=mjYEJy8nHK&&CzG#kkRdZFaRnkE65OaMj;7IENmRSW|y;1(3E(;;jzb=a& zBuT?1%cWl{s^E9k^MNKkzb^UUOs{gToBDTjLIwt!bN=`rWyA?R+M1fqf89%;Avp6w z2ez%k#+5ruGAf3kRo@CMTy7l1wEU*lf|GzV9ViMpio}G8l`1JsPt58%d3;DXNvGxz ze3rc#LXz{$mXpU2Na}nmQccr<(5m0$tnzge2;Met3Hw>p&dbNC^H?i7Q*d8hTJ%jH+R(j6A@?0R{F z<{WTIM_|>&A#JdDu0^vsrJp251tgI_i?fK8N~}%Y4UDjuuyziz5Sx(bV{^u)yhnWc zwDgxPPJ4Hxbgkn_0?ClxdanRSCP~jNGy3Mf8#b@WNY}AN2!rbuK6cG0JVq8( zun6KNx89^Wf&}O4UPz(BV80kKi0QnM#kJ^FeoTX#V%iR>GPZhkB|Mh24EYe$-?Pny z5V`p%j%38FT8UmErfy+Q)G`^)lXv5GZ>qJ4GgKUhTzyU%0m}IP+?K(QL1+tv-Birk zNCxSA9G{R5A9csB!K`dF87FOUgOnL{A%kgZNaZ%U8A}Z0xNo-gdF9mAPP6URbR;9C zWRIJ)C(#zoE{Bga#%xjG(3(W`91t6|f8A-k&Er3OanA}ou_!(iQrk{Hr%fYR4inEJ z-N`~fF~Wlhw+-o}N9)UHw`waknsee`)r^f-PE(?=MeU2UTaCUPj9;?p z3dgsvXuNqf2!cnnW*N;7(Ab#!)iT{ty1(I=c3V}Y3yN=BF{!rc_dG|Bz86|enf4iF zYzL0qk+bnbe7WJ!hXI|4F$$WX(yeSG!t1wNFG^>)M|jU@1zKVCtWzy%a^o+V##NL+ zaQV!BO87*B$MKa@_B9yn5|c(&j&i}X-BHGeb^cC_d>MY~Ab5oDQMcGZ>Q;h)~n^nHR zAqr(ANrzW0Dxb-<01pmlMV^g1`rJ zT>C#I_8qaD?xc#~JE=+KG!sYs0fz=Q?K%hl^* zeGX=Tk6d`p^@T{aw9R?V7Ret-wIrTd0{Bd^8=}uTBHrmyDVZuhOF$otCA6g&l!thR zFs^WZZG)BQ@i57YIk?K<8Bq?l+8sj@N_E)BR7RHwakI|vAzg)=s`kB0X>Q@-Jq2Z!dh-ox??VM`dgF&WGSNydRz7sa3A9J0uf&B z%=ehA#ES1j#UM=l#6s;o0!L%xa0?x}QQ0K6(>Ey5e$wFU*!i2{rUr$LeV4gH?MIn0 z#6y~`s;a*U@__Q1foRgY2ok2pkzFgps^U;cLM-g6l$dqC0Z4sn6CNG-i5e|}b^Tjm zI|CZ3tJmBr)@BMU%*Hn72mvS$5lG0<2!5mYjG`Jl&_OCT_v4(KRz5p?x)+jj#9LHY zqIZlxJJSslCJ$tn@8mV@>m^I~VfkA^9Qz+R^o^|?@+8$J8{QSe|FkD+NI^~3#P@Pq zgw<8@U5`-UJbaUD`l?4QuAv3jLy)7@B&527o?&79n9A3b%VE^oxQSpt!<^0kwkuGb zXh6ZeybnGAlrJH%Fd8vhhFqvHw!nUw3w(hHwWGO} zzJ8ue*+c{aaGs+V>HgHIUnoC2sNBBbPhvf2XA=e&Nq6F zsznxBM=*DFITGAD=6^gE+`SVFyaW8WKL&+5@jCo!=OO&*;L^eq)%SMXRN(0v*hj%I z^J=l;^Ia)Oy<)UnxrwFrW`9y8p1FEknH?tzLpYUA%S5`kz3>h@I%bw}H`SFh7SF#c zp~Exy$wq}1lxR}EGL?EJs`e8$9Kyx}Gj6R0567S@k9~Xw7NqFAj*$oFKLBo-#-i9* zZMSUET_1p>{3yGOus+eRN%=>XPde{xmh}>dk!(~SfC2ALf=|+KS|dg{*bR!Nmy@ua z86@qh{oXzW+sUeBgBJlDZTO&YyY-F0S|>8PEz54E{*nW4ezHs}Ij2zeW09$jfZhaeqjq}KJuBQsx~JT6e4mV-BdYm9-I(`7Cfbu|3+j^GbZMPL!LoQ7P9$PD2uo~< z718uNlKejH_W?lrQ>i=d+4lk9iC{1}T<+m~&EP^jyVyt4GgFNJCYbbVi**#rPWc7)m^JcW?$KQ%}wJc-r(}8JEL#>kSprb2_`k z*yrnaD)LWIF`n?Lz;j@Qb)6{fHz#bq!c^^!Kg#U}t7vg+m{nALxQBNf4;NQwoxQtN zoRwb6E>}$S1O!!rD!+cyY~^0tc<%xep3fOfIK5`a)bt>)kM}U!cIP_H`IfYVYNoVh z(|_S#g%a3{hugxn>}LCa0MK*g;8bc_Eo~M!tHlILM3+%7cJ!G3Xv^S{dQ=m3F}IAe zp3s+vEUp1?~Hv2kftZnL>jr{4NQ#Qs}jRa}j6rPQBz30NyR;y~VX2Ie+}wjh%e4 zrN30vm72DIsZ$DHW7Rz#KDB7Vk8>Ifb^N(#-Y};ly2T|%^3U+M>}G?r1ZPQ+rA`Wu zh@;9)=Vb*Fe7sYh5UenZfDZsarLLcOd`Ng_0M+YJ=sA5;P+;q(i!m&oE^|!Z=Z^HL zT7Ja_@)SG@4l6`#u(9`aUBnR2D3T$EhM`hNn1C zm+**fb+3Afjb$Yj`!QCF%8vrh+^p%myBY^L(Y=sWo9_f6ObApET~Z(JVr zo;ru1KaXL$vaJmKYhnJWrND8%Zum>W`wcHRd#`G#KL%S;Qc_b>{44+0e}#nu{+{!q zB*{?x_w)bu45X)-{bPVIv;WIlGgGILx5!X_VN2ii#(|uD_zQ?yvS}%JiBKpRMUvtRPb4+St*I*{4#Hz2eA$zS)D|g{ zq=c!Wu-7B3Yy)+gzw9gA0@oa{i0_A0D{>6ZpT>WNe%NM;)=JPe!LGoGa9f*!FMb-pbA{fOuxdXm}rO+G2Zf6!6 z2xmW7kde=#rC3jE*|RbOw#6SM9!Q)Q zw~>}6z)brW2r9)g$>s<)7C@7q4RAg9pSai(U zY71$2o3M>*Zo0JhJ%}?a5{9BQS+IW9{`cX2HU1nU&Zt&)s%j64n(^R3S5oFgNAD~cBY%p)!dgc|0=MTQc5eUno`P)9R6_A zi&pyeWRsmI6L(o6au{dPI1t=X)JjL&SfyBzn{?X0C9ZfkHgW|WEo>8$4$j(H9swoW ze@qSndY;xueZ+~;DNlyTtg!jvSs@l{B>p?x&upj5Hpa4hSxh43y0LB__PTz#ioNoZE2=(l`eV!zzL#PufY z9-&~hdzxXhIxlf#LNvRVSf0Z}4I(uq$3R7ur}IBJp1+ z=_s&16K`{fWRp8YjK?BC4QU|IscAoLd{c<+QmohC3$fECX^@|<|6;a5Jigxby^S04 z2RbViyR86fFnZBGnL>*C&poNYUn#r`@uk0Z5-gN(+1G$Z`-D`)iD|Wzh3AE@ZlW6~ znT@1f>TOh+{l~os(Aw0Dqlx6K-Y3gAx8EowbR-MGw(BB%N-+zwwIaOm=KH_jNTtHo zVXRBC_W5v_dqNLmCoSmU`A?%45p~KYGNRGGhYxH@z(vs%HGk2mC$G0lf+f>WCi5eS z2*L%)p8#7urD()JVNhZJV39ektl{umB2R0z8fkILoGy4Sto^Kb6t=H)O%{>5lYG*- z3b4(%@SB+(f`tpgd{~+*Lzx#u4{ox-fzJ#x7T8gvpP?|S{M3#_bBCMsU zkGE3XuzHv|kG?Q7W>EV`F%&-Zv;Bj%Jj=<#Kkc0g$WM? zQXwjN`7M&dD$(tb%jye`TMLiX1fzDCopr&qz_)A`7KUxwBn(KD7JIV@jG%pe!ji0I zxVudVMX~WtOUe~(Yn(`#Dk*JR96c6 zYT)r&+mJ=RjuPhWW41G;Qt@h+)Mi#FzT-&fRA7h5h!CZcC8-bb$22VKJ)HUTA9h;a z(^$zB*TjXrL1c;RkZSxH>(oaJ&XZ+e!NQ> zg@neZt$73rHhAI|=?fR#AUJgLAi@-AXSPRPz2c3MOjOKdVU`ja;1q4c4B;<(vM~(h zp|=#)H7+MLjM&-n-Duf+xHd|`u}$|YAX7~Ez@pw$rE{$SU8p}!5pm07%GTW6Tv|wE zu_#dCN2V!|XGgI``TQWOL=?_Wlx4FX5j6QIA=Ftm3JD?e9RJ`ZB_wp_#@YTcdre%J zEednc!9G}HlapQ7qIqPf2ek)Rn$DtPMQKHhJwBnrLPBuYTrY|tRqcQ9sD@qLpWCbG-{rb#xC(tXUY=Tm4%f_D*?W+~A!H z6ReQ4$2?u}2xF^cJCoyai5r5j8l*H2)?Fl>IUwsJ|u)1qO7X)B~xP+$N-Ln1@9KMa@I3@064AT$xU>C4d+(&29WX8L4XgH% z@ECVE4MOa{;7QgY_BAS1=g^$B{TW?~8}K(aKTL-$+E%`YI;KgsE;GS!pDWgPfVV0T z_QK7nJMoufAPI)G3TV7UpaWoVF>BXOPT}c)H5b!VOMbF1%gW3i-8<7v!f1$su1PaN zMJpp;!E(16kRVVMboeRLq=f&uG*4KH2B=wD!DHplJTj|#u9W7hLEUnTta}jqV_aXr z=yTEH5)}?%;Oj8_u+bCF)_SVC6Es92(x;)o7I04u`h!ob(2XNR=r+*{(FK?3yEy#j zd>)!#B8VKmUgA|Zek~E`Ir^TM7t(<2*wtf!cvkSsAyN*1EC|Z_RWZv>G63rEQ|P>u zoX;deIUoE~gVR?QQG1+Q*$Q|LiQyWNOV6L-8H;WV1--j~^^B9g@qGCpb!fFfj}~Rq z8kVYY>0)uZZF06@=~jPbH}G{}pYoS){e9K?eo~S|OjA&wexaOd@`RF`E?GARYqZS1 zg=peJ^P5Mdi}Po*)dyfj13PH91?P6;fp800P6<9YWJ zDQ}olM77JOgx^rLGrr;(4ofe0oi!m!7?yZ95I7X;i;A}* zY;G-v{q+H;NTw1((s7Cvi=das1k54t*SggIU|n{0LhHdzqmK|xdtyp>h*CrgDyV|a z&|8^?ECO^cM`snps)zajY))E?8K(QtPoawMjx1BRAn5I(;UdF!WBG=VGWy)oSJwgq zVUQ6N<(4=H!PmnX)$zndx0o zx9!<}4oR(+#!$IzkyMJBG8tmj+ql|U7hkBN)$X3gKudrtO4Chu5d$4ii!Sml-glrO zjDv0pJM_Pi#A+ECyY1Sa((0np5|-Me$tkniXZajPX@1(Q%bB-co@$w#suD03e`MT{ zB0I`OdqV9fh|86p0feHuCo3PW>ZlmcSY%Avz=kYUt9uX#CO!{RdPLdpxCalMN~o;e zyt>n=(2vxVD6K%&Z(dNS^O4GUP%O#ez7Gan<=wDJD#?B#Cfx?!xwKVj!gG1PlgX9U zYa<0~@)Q{cTU*&R0NB8OgsNB5a4>BxuV%n@8V_nrcDuHK=YSPX)C%d2PIf@ zAVTQWH@xO$PkD`bHvtz|hOiVkeu8=ITj*h507N&stt|Fkt?N|e#?l)W7a)y0`Vs(L zTw)FlUH&0W`tb7);jK6!P#1OCq7;Uhz~Kx`IE&!6t23z@8z<+~yFxY}GJ#({19spy z$$#8wQe=5jU(18X9-EyarDI{YS#ul_$vM6?68bq)os0NbJ8FBEwppiR)slN=Seizw z3%8UGglOYJc-ROr*GtlhHs_^wTx<0uWT+o!Gg5Yae+q(BfXG2KW9<7aO_wr67sNTL0ytl@Y6Cvs-yR^+~a3m3v@0ELv%z-`-E~*O$kGq3p;DvLu zPXG^UL8eE%fg%|kn7ovj!rM7TABg0jEE8(VjUXYYrc>omHy~Xug3}mJtA`V?$TCcH z>Gul3OIyAt(qbNsQg6oC_yA--nq|yrP1eAZmeC(^H{di+b`8@A;B?yOGER)tv=l-3 zt{u^r+Q21vkgJRQ+`-_$!t%FrNi73gvrQpuvq^^M)9C|uC@R{0KjNom1a~7kE6>eyw?#H9jVDb z21o>32clrJs1<+Nai{1A#_s1dx5Q18jb|wh?5=zrEVwGT<2T?%Mw!hQcW1hIbcG$# zaQXnS!|SiU9l|pkzs~UT38msaq@vu%B*PV6W?aa7;3HRFApc=%79AtN0;c}vH1D0m zi$WMlJOKVUViXMvm!t;y6G}q}P_F#lrV|dqW_X2SNs~W)Tg00VHz8qM!dTumoP#XN z`f~K6a)Qu$d$+C{yfRkLwbgrsc!Sz#ZQzMwZVoa(P$-Gm#)8+*`@T0ZS@xJVoMJs8s?m7S~$R*$I9kiO3IL5p3Eamz}ddYZ5*8IZh7b-lOpXVo2 zP8Pw>ns;zVU^=^V>$dqLBs9isKg!^}{Y79@yE=S^hb~UG56YLuhz8x+ zBeKk9Bz!c)^bt>d_xIEbI_$Y?mtRLO&XUs$PYq^gMAq`T&Kn-&&9n_bSH^Hw#XU4z z*XmhPn<37*)Rth~12m(+Og*AkNOj#yMenwuQ0azFMpaoHT%d*mVe1%}z6`UqpuTZL z+tnHw4d9e)*wg!~Q;mE9CtEBE`2e{K2tGMX-XW1wG0+rhEX|z4VbjWNGnhxElog4h z>XLtMNK#X&Qj>KpyO!rfrf~Y?_7hLukv3N!h3UFA(3pNH=t?IqFOhRxT}MpEwfyZ5 zj2L^?Qbix_LA<6pL;ueRjqI24(sni77}6D9v$u|bKzE4QwyJ)%=JD-&D*XEBT@w4L zyrfr5`s6ZB_f+>b79v2%w6mbmt5i9C={I4TToURd9KR`Lr2LrpmU-yvc=LJ-=0$k1 z?Lta!;)LKS0Wzw9bG=4)kI9edc`+cPjS=4i-qWV!uE3j=pw^o{@g zp60DiIvvFU;FGpk1;M*3XAzKv#_sPbd>M>bYDR;m`~tjM$UtC91_=xgd94L@BSncR z{sz)#b^)HQH#q@1Y+MB~WU~tQs*NX(0AV~Zk$b66`DM!$JtEcTCOcfk?Z~v|4fe<) zH)afjO{%}yys7eSN`v^mg7ZY%-}9-J@}ZaVsm4(fe^-q(beE+xH!){ErKP0@qkpQI zwytxR7nHw<$_aH1aR5lX8E4OMaTUp8d0NhocPK>xi*YVME@brYu zQ2@FM>puWlqZvubqcgbguOkn{KQr?Bn^&k`1aAbsI@So&|6J5otD7Ah{{RRF8O8qA z;JV`?|Iui25YU{$J+kYtKo2Jw{v=gpD~26?2+tarwcRzPP(?4WGO@XhV8d?Y`Ti_j zQN~pl_8f6!-&XfBSi`@8iR&$SA+BPLH%`EmI4sK_Iy2L}^2y86u`w^N!~iAre*}yK zbNhcKtuf$Y3QIK{6fPjQL5EvcR>WB?a5LqWr`l2Nc3>AgY*ET(F1J1FLjKGinTl@E z2Wzx*DHDsT-T>Pv8MMpJT?tDA(3%jaw&QT%M=Hc{TN_22Zow9x)F5i}_KX1*Up#%- zFDvIU!rGgVtZ-C=8Wm@>#Fb^m89XXp)J7qpIuB43FT7Sj2^9ie#G7E z&VtQb#ou~`AQa?03tthjK?tChQKc~l>QjJvo+2zkc_U1{F#!z#p=biH7-fV8RLQ#6 z%vbNUDfoSY_Kv)fUzzM&Y`57h@e-n76Ey}*h?i1|>O$r-xT&10lot`s$cKAh2k|N{ z4?^rn3)#jw;s};$^{4`A6jjxx^}Hl4bWu}nT1V_SM~EejZrqN8A4DxX4M*!{L4E>V zU_xbDsloD#;^Z2gAGDoN&85`_O-{1O(WEtT#vYuFy&I9 zo#fv%yB}euD0_-kHwIyizL&JffEtux%(t2xI+gf8#Dtp}tU$6ZDYc+ucw`ElT`$Bj z^rDPX_1>jGHw!ST?0rRvE=q#T+j{5snAo!x>H2`S-qS8yBL{ZHnGL0NR`2#Omh?T6 z;d?$KMBd{&uMyFy>`T}k-$(b0~;gr0us?#K^&_z zhoKEyC&hqaa^R_MG$1230Mn*Pm&M>9h_`Fl`!q+#)emO>05bCVmEKc$a=l@jKwj`F z2uj(dmfd6fCwwXd9GPs`+;D75(J%X~YO1KeFb(byZk34jt)EkN)I_bUOtW;GNV^! zDax!Wt17?cMxPV|J`b^m@aQ%%GqGGtA6~$cP*o<%DH~(J4$gW Z#G{YCzKGcms6arpKk$_+{{TfF|Jn7M@NxhE diff --git a/extras/Images/ebay2.jpg b/extras/Images/ebay2.jpg deleted file mode 100644 index 87ed238ce7a9f8ef398804e5f2c869c2baaf26bb..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 123479 zcmeFZ1yEdF)F9Xd2mt~F0>NqACAdR?-~j>zcL?t8k`P=vc+gI8cXubaLvV-S-Dm?% zGyVNDHM9HI&hF04R&CAy|L@hg)$jFv=iPIU-FwdIe){vY33#O>rzi(NK>+|zkSE}2 z1t0@JM@2(JLq$h6=;-LrF!czSvJ`1*x@3k#2kjEYW7N=`{l`;nfJo0nfuSX5k6 zT3c7&(Ad=6(%ReCKQK7-dw67Kc5Z%Q@z2uo*7nZs-u}Vg!z1X$<<<4gE$r_8AG%Ng zsQ;NPWc!~9`&V?~Bk6jEWD6R`KXjoy^F{(HJ{md=_j3X%bqq7t*R(ueUJyzr{Hp1} zq~q0q5ShD8W4)p0+hTzJL)yPk_WzEsum4k&{a3>N8(qtQm#8R6=Aq&PBmobc(ab-e z{RjNV9Q=n2{D%zuhYb9O4E)=a0dZzPZX&3N4^Xc`<|OC-4lnlycaog%5KtdYB3kxP z`CV^xEP}9o3iWRxutM0+Z|d2!EFnPszXF}dPxRdMRaaGgbXS|)=;ws$vVeaRK*szN zP29d8!5Lt_5J0?B1(Wx9#9D^);r|ZXH66$lGsU{;GhsnYrMc(^O$q3v@sMnVV_SP+ zX8{z&binD_*{m!*OKU*09?~Fk;E$0UMzGi?`qRpzg%!>GF4*4ABhT8ICom$|`isQF z$me%mQACGNfENhrKd>jjJNrMh0*l|jr+uV~?6=+%U!*)vhJps401@s!ZZ~M&^Yn?d zWp-1PwLob#)MG>ElZZS!jxxJ-8kF2w(hpeqkTV5g)J_c2N;}=CA$$_KA`$=7qE&yN zlRO*)#;TZ#(EIw$MYi^isS&)**%}XUp;fPBBcEJ{si}+ z+MbbMKZw$%^Z5+=Ss5Lv=!saZcC{ zmgwPr_lq14#&N+20_E3!G>HCX*)N998}+{F=Zp86C9x?YS`5!uRF^BdHc3sJtx|b` zU;DOc$Xv4}tVfxA%X};7?+a!QW{ipFo&b#j!bL~xIw?189+_6|O)e8`A70rHBT$+^ zG*jBnZ}@*sYpO*acB&ioyqhqfcwF_Yr0bV_1^3 z!-!`qI<5(09#LGoYAlB=zSQcsI9AWoz{(akJU<)oP`N#HIt0sIZJO#N2YA7=z?!DT6>q(BdDS5UF#b)0|(Bf-;j(+#0 z-r-*hngHWB;E^ACr)G?nXQX60`x3k@wQz2ID+;mq6Z$)0m#HF9@95;~n})U6yH#qw zr9lu&nV);Mkr@SRVp)}PA0u)}96 zG^p)?@tBC^MO|Pof)1Fllkt7%{pHZlTUzG?aIYIl@GlV?9F=CjVj-_o^Kv0n2w1o zOb&sg1v~Lu8X-sx$tAGYdH2>zrI()xHGcO}e~40X`esrVwo%ik6XpsTOEn@_ax~(5 zTsJVjJ@Ln+{^+MO){2xeN;r*$`*zH6nN>*T-QZrb9NvR?*&G~mXS9k6F48f__hKj1 zIQ$K0O_Fn3PQXOF z-{MTC7<7CxM1pc@-Uy=#)<0sk~2yyC{q1T9hi+0f$;v%=9u0JzIBh1{~5Lh*LSp%nw>it-vPh_UK1h?Zn zlW3(HN|2KcIEI3^BVynT(6_p_i`=88zex1&0IAocNA3nlL$(Ji5{x%K9{|Ya8+TiC zzan>%vjE)C(edqoVoUvn1{$-$3H&~4ujQZB%-i+IsqaTS>+Gg9iC0rhE3}|y=$}dG zGUrAE{A)?MHpxaCOTM`U8Dg_NSTd-Ti``= zRdMCDN6Hb=y1d>MrmQm*4yV#OEFNl=DEr3iN2)5Kb=;WrEwQ$(ts(kNFbaaoz^I~E z&sbqZYK38N4_;#&S7>`9Vws_LcvGXlQiM%m-ypxqI&~O311|8G{iT}LLkN0Jp0QJN z7-&~sk zbKTo}hZ<{5fwcsS+l(U~(ib^gZWTFkfvUX`91M)QJ~uY#o=;(&I%e_+9G76}o*mlz z6K7~MtDc%EYM^@4qS>9;=M5=Rt7~Wuw;hZxR;Ne%YOzD@QHA}O>U7%955?A>X&BC{ zZB5+xt(CmPS(V5WShn0r41YV_2{c+avQ6_&<1wZkM7WZmDAED&{C@3heC;HFdet#j z2{+fYCR=GYQe*07oterr)|W(7FsSA#XNYqZt-G0C##Y8cn_1?P@{A|JX`g1h`T`r8 z?l59Ixov`|pn>3sij&=W%jRV&1KUrLQ9`H`yH{daDb^#w?mbpHN{fR*R{hQY|v60j+C}>~ZzX!7D z{EDiQcFnFlwOrZP*2(zntLhk05wY*`HDJbeU8OK3FOc1260T421eim80yrKINLsuM zwuQwAJpt5-5#Q|pI-f*JZjm8+Hkg(=hi=4|?iwAIvhKHA)WS_(@~Hug)(vfm1?%`% z?c$kC-(e||bW=4nd=T3+PF|Sqn3TlG+OpXbI$_V;FJo>#T-q=m@)EtN%6S4ffMAdr z@zuqt;0UE12?n_Ebh}?;S()K_FGpSVyG`rk1bqvekp@g@(YnyEIxm*6e!5&-H=i`#k^zaMVHRt$$hFWy#Wl(m6&h*SqT zUj0j4yQaRb=ZBpyrn+jbO3ti8$832;pSk&65wU(l)R1Kp)U=JeZ2W1c_71ox&aa<6 zxP38xMjnvRE!VsD`}Yq2dQn)t7v!4+QCkyntH(!na;Cc&)_Ba@O>M$zt-v@Xf@wjI zNljq?UGPoLYrdZ=DMG~~IQqkknX304!JAoKJs?7#py04p8TsPnfg4eE!s+@iN<8s$ zIKISv7Eb`o;8V(Cp9r}Ps+=V9uPdrpA;hGI!~1Q%PXKE?46*(9bDj#*Q4FY+7}eVy zblpLC)9pmLoN2iRr-rn;!V%Xb9>|OOiaTK9$4dcypD=t;Vgt**OxI&ev{gT*x9PUE`2+o$aF6F=U z@v`r~`})cx46=2d4_9U}V9sPKDwnm28B>qDz)m=EQ{J4bQq;B{?+UpqE3`-JpGtiG z-`dOkUwX;1W#eU|cIb+sEUy$z{KvS&Sdo$|J{0qRo157G$Kb?^N-Jf5U#9O{bkZk* z08;)-wUb{vk^D#t1Acw=;ETPoW`|c|&OpDqNqHGa^NIje7YLZ|0tb2j|~o#28OW%?@x^guuet zj+jOe{rSsXCU`SHEl&+fmJdIG(p^-23*awaJ*1+Uy%rVDAU!?9pYGW;U7Xs0d~_z5 z42Bx7^!=Ky;Cm3-Gb*B2xLd{BW!n#u1qAiNoDh_nefL3m&eVx)F&+uJ6bIDWX@1aP zBp1ByZ@U8tmWBK44kI0{?`mZ}CxE-7Z(QRy;s6|k>hIA19RW%Y#hf6oti2<{*aQK| z$F`ckrOy@NrJCJ`>Z26yy-*dhb~hGnIntMSXk-BRPuSu%F;s9s?bQ)-9q?etvp&*z zal`#w6aZ(7ePp|Cz3idF2B~GI^@`x(a|5AVF|&(~0lyw7{=3JC}pUh-S&k7!Q-h$ic7H@F2)0O}R+{q_^!_u|k-4HG;I*spefBY7`wgL)GC@j0$6$Nw<~_y6DL>?7=z zVuw@u*6f=Bf;0E{uf@kyj#*vHQS`O)WZMcT4}HtE{DFRyGAfDF)T!KWm-X7P3f|nH zat6mxQG8Y7=>OFs8Ky`)z=hY0@wpUFY2Oke5W!cdNVc_<>E%8-lM_IhpE8s#1ox?E zAvRm0dCAl8uDZ>P4*em(>&Kt9^?Z_AtiZ7hDXIaa0pD&b%EakwJvc zcTpBc;rVJnAFV+hO=HPF{0Ci-Z~CuOI;iih!XWP@`vQmjj3=nm(*JfrvV2S-{CrP< zP8C+zP9J(oaQ)8i=4Y}?*UfM%Q|Br9l}bA%2q{ZwFnKIAYd>BAlzj7dSCLMS&h&R5 zb!bmf^gdj))V7g~qak}>S)QJyI-LJk{@Ut>k&4J&u<7QzZZ|~HWx1gqV*#PM!vELV zNUZxbc&O8VlR@x>OEA9V@t-Ha-|MPsPp-S?t51MMVuW0$#AB4??k0jZc(LXQFn#=cSDX>JG>^EfHeGxN&%{L}su7S7;B8fL2`TBOc@h&KGE zS03$u?WUNJ_3_!XV!{BY4Inp(HjNI6RWZj^N#S2`{L8)AXn;NoCSl7z{(c-lsPS1N z1HhdBdjJsn4qKK&9eI(*_wgUBd;oO?UC(h+LO{KGf)w>X_wrvdquAt6{`1Cv-p<4P zEFv;^7ta-O>Z%@GtY)ZVyG<)ub8xRiOp1+_v;7vSgXY74@Uy(nsb_jmNbif4r1O^(fWB0+i<{KL;ZGT^jAGmFJsKxYd$nh*FUIeh{ka$vg>nQ*F5K}!;{HLKI3sT(>lE)9rC+! zM3=UG)AJ71v`S#%v-;~W+77n&l2De$iQxJ8E~SymUe0MbTOPJoZ;(7h&VTej+)F3? z{4ZQm&iUsK^ZyDw>-_KAIr|ezWrS3dWv+H7BpC_5J_)|^o5EP)``1|p zP2HX7qOv3HR_%0wJb&5&G-kbF$pXGiFKIV*9n193@yszJN0B0R6ezGort$zeNM*Xq z!liM2Eff4gdgqd8XPqB9QM7GP#Hh!?cTF$*EGO@=OMkz7tEDBFbK*~pL?~#YGX^Jt z)7asC#oo$(KqFhEKA4e8@bdgG$TD+>Gd5OQceVCLsF-|5JclRaeZ_SW(E+}Xnof#L zdqS`1SN9JskeoV#H?c!+k9&G5!@iBo?(OSbTM-QIpNYZa*CVeipxH0(_yi?y{%EQV zTA|YQjXwdtpu*V(&SmGz3t4t-z>@t!{LhR!g@3cU*f$Cb;FJ|3xZsl#dix@xqY#r_ ze;e4G>tw_a;Qg6oZxVu7GkB`?2>^Q~+1su&DcUSNsXqZWY>M{^8+}gs+%88YROw6- z>3_IqCu%OeVyiBY7F%7W5%pT_ZFgZO1NbZV$tWCWdF^Uh=G zWmW1EV6y49>rxz4x(~d(3;g|{h9Fky7Ls@aMmzz6uSYj?0&YzfsRmx-O1E>OH2%rdrfP}9kZGc;fNc0o@Lcw^=$PC5~oUNyw+r7g6UMwS@ zjHA~e&s0g`_RRaAC%PXIxLHOK(?W9wj8Yh}0mkx%>> zL0nHtZA0)%@(_s*OC37xCb^v*6#Oq&5YlV(QWkw4 zTOmB*tPHwM>xvYghXX_#2vUMEM0AY2x_km`KoLZ{ESr<~^1zH~FnboJSRJTBW6|SL z=3Odt1Ez&{vZa@x`tf_7lh*te^Q541E%%or$-V`i{|KdKfNQLqm^jV7s$_2%Y*+Vt zCt-&qNUe%!FBto!V5j8lY2n3^FU@C3&UZ{%b5y*rlx@)${AHq21>bO|F$p%ZI|p+M z^}@9%XjE@>{OTPehPJI$R11`imKX>p^@HOVq9q(ziNt%_Kg!Q(>g)_;p1nQ9WHxCh zI8}s~Z8zvKrBB?^TbYlI`3~&v*SADZm#!*N6ltz7%A_Cj<(r?zg%?M$6_t?WmMpw;|Oi^i>@z-`(Bp9aU_Qs7yQ`ChuP> z;Fgkvh*WIj7i!7tRip~76qt-TjcNYYQ#ugd)rzt2(7t#)IdNFtmiUe^sd*luMfY$Iw!@ zjIxN7!n(lkhXbQgWZZVcaoMBZ_I8<-uJ2M?W&Eh-UrCsWz{V9ya`1{7f^ZgkG4`@C zf*NTudON*y?rnPHHEO*y*E@K-gI>?HtK}Lf+9in{4V@;rX-K}~KG%xsHhl}xOy;|A zhX3v}uYpAg4eHh!gVihFCe)wM+Ht?5P@k)w$J(SG$Sbt0>jS(NLzWm?$kW0vV|B^+cf33R9f zoygxl!it!N+6a878CH%Mh(?Z#Q6bl{I9$t?&7a8&q{smnK`OqW7|yHXKzpmC7Ds8k zlnF&X2rQuOHK(o=LULb@vCtwsLM*>?XFYh!f2pn9_Sc8AU34mI&E>|lZMn9Fy`-L5 z`Iq*c^1jgeAgxQ>w2~j!_82^9>Tc=o(*U!qMMWrhfH-bDPQ~N=)vC&8NJz!YW>6DJ zg}vn`I(`!QJim>C_OW6s{yhxg;j@&KR(Sjq;NxS_)u^M~_Bt1?8oNv52Jbkk_f|B= z6TpsxbT7_wijz*>v>>)+(0;FncG#09&DH()L5Eyr!p2I}#v`S*Cij)8+#8i7{+r>oHAp z=FU}A{EEY+c#ihcrDa?Lc1&*qsbXxa|5){!^#nD(VP4U!NL^~W*11iHb-I6$AhFD= zJ)sUM^A{VW5>#m`x4kKylKSkH;J!YCO`OLezCdED#dz~4ZrnzmnfYHqX8C7xjly~tGe z9R%D|Nz?C8XK4pSi;|Pv`h|mSOGh2O18p4+_SMCD#Xt@VsoCDnKA-LFAN&WTLU+gL zF;84)TGXPtZ~{c3FAZ><3}URBg!N1vtFD-4ieMIyhrSJ5kFs&ezPj~Qj;k2@b9cs_ z?{B#erT3Z)LR;oHEkehIE`*O&jB_I}&R@emKKqI{;y-h+*dXJ^qm}%fh1LP5a`k3A zgb^)t$j^SaQyze8tA^2XJ5F~%(sTP0YZuH{JxK{5o!nB5rnHV*b81{49HrxZ zarId{yU^XCb+JJEpU%XTB0`SDYQE_oooHHhBulp@+ZkQ zUyzgyu{)65A7nsH;?lfR5#pc(U}jP89}^S(E4NjCtZQLAuCdEHOq~L?jI4^9Gi>Pk zpQ|b4GOa5&-z46vf9HX~T43OfD1;4hl{b|UWs#8ysZD!aJ7bxI$ZBk ztIp7qW4CiR@I{c2LGTnV@)=ei34z0JAW`KE?vte|Fu{@P^Pr-cdcI?EIfP21*UU)Z zJ0bYtC_|5|QCYy!IK?f+T2faE=w~i$bj#{Ptr4A{uUrG)Ml=;(XNtM32nJ^+Jj+x&D>Fls4PUraE44PJTh3TM5zYixFH}S1VDp%f1cYgHDhJf+G+cnT;K|k>Hp? zOam@BbMKru(!YFmKEm-OftMD(URQ;lBdqIE_pfR?k7tbHbEBP(Tn>%(PX1S-jYQY~ z{f)MX>5<6=PRkRZk_#Re5coh4Jlq3+{{*N)=3ep^LL`R&)eh{LF!-}7jL9x3`tD&H z6mu>n<#|J7LOZxtYk`sKEOTlMtyH3(K4(On;L1N<*zY}0IiUHGIKypmx7d+jwxi)z z!TcI)+dIAd<-Z<#y)qeM z1eX{9`Q-?O?xr5?M?J?m13AwWtSox&@NNeJZMP-ybnRUn(*s%-&pw3i>q8`??>{WK z3=_>%Epu!{0Ukz;_fwuv3!p|5KnWVT^917P@ASbQ{~9XF#990P?S3&sx3AL$M>KgZ~6J`kTD5TaHF;k zIZpDo4VEJ5A7XWgN-Dx0OQzc;i$)p7YF!#P)6zj2?hEM^0SwT|uVP{WQk93*E4E3E zN+plm!JVQyqgs6r&s)|zTfvs9T@B7D;ER?Qb7pT*l z-hFVP7H)9ZDup(B)R$5yga5hQ!y8w?y8iQHx+|Px#{X?$% zF0PSXt3s}{>Z(OmfoQ1s?3Vmc6{e3)x1V>Y=P`#YQkf!Kq&sz(gby=L0vJ1AK$G3= zTnwc=4@3pmvHDRr7&{$mVZqzk_EMmJwyl`M`tg2_DOD2dCUMsB_z;e~i|qw2j-Cfd zp2d++<*ERI7TvgUb6Lp}MLjxm2ysAld6a)4ss)Ucp>?l0p}&dXnH{I?BY{=H)`0YyDB*i#!dTIz+;7s7DUNNS33AH|ll=IJ#ZaG8dMn zJny0McDRG|H*P3|k_|j{&VD}y47aO*pLi%5Ev?{UhaK%S^T$8u@nF?kQ6}47)uzQ6f=}8d z?TGJdF931v3z?dD>7VP4kN}3o{ID*^WptDD1#Tk~S&dW>v6VsQ6}=T|X0AVB_PtF4 z%T`Uc#c^_D=MM&8oo_@jrVU@MQx!~o;2k?fVQ0`6mET5T)+&(VL8pRlj^4fm6!zg$*8sjkU?eJ1zDNBDON7 zS#yiztVb$_Mxydyx33=#r34aEg z5d>}+7sbwk*jCy&w;_^Bm)_Pz{%ko3kg{!^xcWHhbx8udGXK1FV2(j(IxVFeUdetN zUJMmO15{=HM@?I_zo=&Cn|I!)gKyU#?ZY4x$X)h>v`>+0b6b7lieq)8WnK~n#^u1L zYTHjQ=Hullg$Dd#VuUmj-hl#Q?8ZFqAlAmN#chK|uLtK5rNnl3o8!`Dp`=+MIi)4S>6zR|- z?(u*%KaXO5k`YA2ltzh0>3*_B?_t8dSI z@3lWK8zE})%SAl17TuV1f00^DN*Vs}#w(kf`&(I9);lUQ?OfSz@1DEb1_OUoY3zL; zwf~Wm*oMAXJj_+F>3chiE84cF?w5p!Tj*~%j;9WS0D2yiD+k`1U$u93Dk&OM)HA1k z`4wdlvr62C)8ne8w#$U`2xnBxasI_Ic%goTv7^oVuXVcANTLy^zi|Y_?LZ6SnHD)2 z>9`Yrib~?5I^|FCNga;cG3U{t#eQ9!Yry>B+Xy*cyib)XEV%qH;suPn&?jcV``F$* z(lVCHSWQ-aga5K?G{Y!G z8C_~XIZ5+dqI~?m?%Zzw0Cw?_)PStVfckV4JN$D-jg{qP&gT^M^cIY{3$@Eq{ZbMs z#{<`ZMb48GtB4SG2FOCmV~u^K@w=^1KCd{?Tk8~whNDg)SVkwu)UO#whf2P`wZKr72cp?nOB>Vu5BlH(%7g(^?I@*PE|LZ07|`K+I>sCqk= zNtEytp8yh_5pg=Nje4r4_+@y8-Zla|up@h}E1jhg%Ld9R^Xb`YtDL?QeprWlGO?Fg zkU+bJqvD3-rk@8J{6_`nOzzSA8gZavIKJC?v5%@&N&!xuN;_EU%e{6)|6%#_II~iv zL)sO?QkEf=@#sECXIletDnKD2>o~iapSWuEa zprd4nI!7WoTJ9J0$u!Sv^2HX#h{At2G(016=I8%n+r9!={_{&PDRS_ zKi#`Yy86U%0d$q?fuZtHDsZ4z&@O%p2lbgek)mKVITxo6$$p~r0M92=ui_lpxXT<7 zlv9nU_n|K^*;!sH?6RVeV)=jCEipXXuAyFRm$;9(ae*?XF+fCv#%kevU9IBB>ex6V zAIrGbwNK@8KZCMc=z&s-m&|`vh3|n%ww7k~793MxC2e-89-&7Sz{f78$=Gkhl=cZw z^sByYqwv&t*E%0#*m=g`S@!ZhpXgWId{4Wm} zt}xs~yU|WAv*!^$mv7^_X%p8Y#B@U89z$@ZR5uK+ecSKfgR!p9iG9*~)5u;zL9cDS z2~c0-?JZuSh$i%6n3^^GJ}buZ5tP-g{jN^<2nAT<_M?ITzg%ZUc>JTb!I;D!=XS?Dyb**=Q z0af3|E=kQxyY>v|jxVxWNko)X{Lj7b>BcvD{l*fU*hm6g*aY?`Kg|N{+w@Kog7r?Lg#7qHGg`@`Q+#6l4WdcD$p=p-(+JX0S>Q%@`58@MBAuvHL z(AS6#5CWwCfT8gO`0hCQ=o-9hzjOX438DH=A%H*dk*Xf$M&)0Xv5*7_e;?RVk?q-) z-WciBZA{U!puTs9EzWMd)=TRVNsvalDBDY8ZF~2Z?Z_w4IO|boHz0zbYyx{25it+M zb2Mv$6eQRD#1k{yl_+ebS!f^Kl#I@uZx?ChA1mcN3GdhN^|-E5p|n46{bVUu|BK@+ zknwrDDd_KPE<0{LOUb+3<4BVCL92=mblEJfvz6fjXTx z50@`o?kQSR{*lAd_g&#EuOMK+P_Wuo@%XspI=Sq@`m6%~cRHEaFsW!VB(Q`^8N~5J z4xdti+WpJwOq75jRhSxTw4xI!m8~AeIk8=c&w#0uikT?d(q5Z_j`=Am$)P6Y<=O!L z<9h!}Tl0{9g{{Ax`_C56`r|u!KSsX8kuQ06#DId|k4ZJJx3;P?v#*1Yq zO+NKBIkfBj`gXi6@H1HJ$gwVQnW&0b<+tpJ%1^IEbS5)``7QcpK5~yMJN}Y)(4t#7JKaIE68bST`HQlw3@1EA)=#6!pEtF`Mryg-seSq+h#&HH zrk#16iFf(%V#vkJNOtr>R5)9W&=?$&g)D5e%o^187664SqhWwUCCHnGn_3);( zDxswBV8uvr_nUh5$r|wr-@`e@@qO4pe@6RF6Ue7I*%vh&0lT6tg}Lj2Wastojf9A>M0T;aro`CCPYtkaaHKtbo{HVJ2y*+9 z_3M1VHH}z65D&NFmw~~bCCssp%jKD|s##~kCqAVJb|_agT+#Y5rFb}B(as2bs%R7C z@e^5Cn{H?0qTIZ$AvRJom7&(~em@WOYc^T?j4}d6clDFK=3dm|(K;>EI(CU~ zTw{Mn$2`Z-%WJo41jDqj*|z?-BVSnz9kx7W9dSHMxW2%Z@Zov~_NG;VV}5|nELUYE zUBfpvx=EI9!xGYiWBpDhm<8p2QHfCx6k8_QL}5ZuDU?)rNdKsWj5{;-S3&*Me&Nvw ztCHV_ks3j`)hjkYRZ`;8p}J85?*Mu0&y3Hp6j$`y#XjI3Dw>(fD%2xw-T@RQ4`MrS zJX5yp>blnEl=n>py}y*%1cD%cB^ox}ly20mn@;KM8w1nLAZ0xW;Oy0snEy8Eu6=XD zPpwFtzK3>y?r9>oH15okN)iTjJp76ZnIYV$6vrV+iLV33_K=ms&0qSKPk6l0XI1*nygDyt@4dB?6hpNTy zOj%ZoI83Jc?l%p-d+7e`ZeT(l^inT?cZwrGKL5B$5Py;-?sPZgCkDm$!A_?Rkxyi? zmceS565%O|^M*6p*J7zaN&n%OneRl^_`WHk=&ASN{J~kw&@D_vr8O98A>U(*O;8wp z%kmn;4$KtV;s4U&i+=V5s5dNk0q_nV97k6<(7LkkpG`F~d(uxOB7uD3%G;JzA$)5DBeNgo7&@Rl&Hm};h6DAN zbFP|jzB#z^*0}b8>hyVT_`*Ja#`6}(8l@9oq<`*qGU}XCW-O51v=!Mk zNuTB=&h+#r^t|DrUl$&->w~#cRWTNp6sbC%&?bq*&BV5|tbWm}^AR1O0?vk)2&C~h zXL~8F+upsd8ndeey=h?AsVMkB7f#4{+P?NBty4a@zWFu04 zBdYwgij#x?y(62MvPrE;o2p5jNa)3W^RV-Fdt-ghv68)i9SJd@#e!vMo&Nq(&(AY) zvXoU%-vqlz*o6Ow90Cs2sqCMgfEvECRwb3O2Fe(i9!e8AlNQ~jn;)YfN!dFg*NxqY~e5$G;l3UiJ>#E5h z++a2AABlj)Lk9zo54oZwU&0x7+KL$E%kovTf#i2`rf+GACZNjcsS`+HhI6GhybWmv1G_e zA@SVl`MK1Q_%Xp~pPy&P$?MgTOZ~j?41N;M>_zc9Ei8jM2Rt(EomrO7dghS6}_*=Ylvy9{$nTX@28 zS8cNTis5lM1D%i2kT8Pvc7Jk2z#`-B_10qiwIr%cnLv_VqT!gJX!9zOyg1IMj>qC4 z8e^2bAqxuMyLVCUuuJ1N5=p7Fs(-H`Da18VH-Z_j&OFyPkUwOVJbhj0a|0xwtm=y9 z^w_|i46E}o{1y}I7(m5i|Gnw4Fo=5aeVV|68}%-T8JA6`--IHf-}#xbkH&3p5_#Ln ziz1DH{Gc&^tZk1qK~H**5=NI>=Q2C)Vf#SnbNkE>q4aWYXdzw`_U$k(@4|6tQE!|x zPgsNEM~Ut)a$}}D6=t>@fb*P*m$0ID>(gaCnRDp4B0)sXIxyEj$f!!_ptr~w*vrD5 z!qvctt?ot)tIIZ!{TeU*I@Czt_kj4jgaIfsI_>n$S84N>NO**>gV(7E6<*Zqn8(D4J#V(|Ri0j|<{gvoE?1+Y6)f0vnuXI;0GVEoW)$qn<4x>Tv$c;8PxCIG1?e`osRJ8=mk`f&E`F@XBD^5Thm~ zKfPK;_z~S5NPfL0+MgroXz;=6f#n;^>f4^0nbvB;0zO))*d)*V*?&}@yHzDNhnp^v? zNaSzW0TljJY|D!)y$I_xjrCqd3a9Lb89p!ULB-0LzKeGm`Mu8y$AF`yB>!YHsfr%NO}1D~HAxwf%tshXXiaEwKUN3@caNWu#Qs2PV(jEs3Mx z43za3RX1_bkwqY}g!mUgrK@*Rq(pZeej0h|v#Ea{+Qn@a3dj`kWtjr56=G^wn8Dxtrsr?@Zw*R|SV`tA?*DksH6Tr~qjtus2 zL;nOw3WY^I0gQ*90P+=pz$95hWRdNE0}LjpLjp3H`ic5-4|HI{r4-UzN_a+zYkvfc z$%3J34q}`QT~__bDv3cA8q&X?03rxGf@OAm5>>P#erCu%?xz>a23v4{-KT4QEBWi1 z=oEns8!s?=-?&bvY2j7|k|b5ctEPyCcx!(30bJ8nyc?+Xwh#~V^BL<*ajO%5wMe@LCt3G-38ny(u0_WUl_~SY-r+9xutN*lMq41k~n{($hsCunj{#FyyX$b3??US3E2k}%g7SaaHQ;v>`7oc=h}0f(#qCNxyIZd}uMfeFIUEAJLHB%4 zIBph)YWTRiZB&CsLLal2#XBlM>7sDOivOUW1@#TG1k zD}Rcw3s0?RX@JEm#}?H$f->aL@Oj-<{#Id#-BKN&7tH~j2e$9QWDZU+} zNQNt#FVEhZ&M`V5G@ds!)I?YZw^&s17zUP7>S}CLmif*ZMO%YD??cDelq7dkM#$VT zsVXa{APUl0JN$+lx_48KGybW)!C#?i#KjA4`g5GyPRwp`x7kKGb$)m|vs>4Sjgh z*{`g)IX3nCWxV?bf3N~v>@io2vH&hV)6P*Y6Kw5mi5ZoT(?XupOk~kxj0X$crsUbt zHW+BPk4UwW@QFpq3jOM@GieLC9Jtl@5ZOBqYrxOrp-i)TF45Us!tNpEKx8&=t*f>k zMc*x{u0P#7Qf^Y`b!Ej{UeXmvHNCSDk)fKoB@3krtwRg{_SLVQ}&q2{Zqp`|-PU zqATk*2>pA zJ8p}zrE4$hwzSSRnY3UM<$inrk%!#LXWV0*e#SghX<=`!l5bq+V`IY;KsI~2(SSuW z1$4aJUZ;}0rfZ78bxx+-v&`|ID(`asuSL{o;1xlGwMlO8FH^hR2QwWaX>RWOGs|o%n(=Yl$z%%; zfBNcc4Ot`c!Ij(^Vmzxx`pe6MAb0)|SpxjQZ5LL1#elDvTQ5i_?W&5`hwZ92R$ehS zrdxgkpQ9#Z+*SHAjnCa0Y7bT0fHB1^O6k9ZJ5N^w1-Zyi)BjI59849e>>u( z-gF;O1R_Mqt{^@m*Y?aKI`Zi;y&6TbBW#)@oQ8pwobn%#^b?vny}Ro4r>;Z-4td-Kv66jFeF#9l8R( zX+x|`B(Aou^>$E5yQ7GQruZoxw1&UMe)2;0S3kLY)d-PUmx`l7x62TH%bhy0dbZQt z6!RBY+9x&F(KjB{AV(w&;B{9=J!x-9*JbEh4=S0lX?Od-)>4kZL)gh=mTGyrLx0LY z@gT3Q5X-R3{_0YGr);YT7cb=jc0G#U(IWoNK@dZnGYPQHOnS zuCPjJ<~c7hxPFa~Hh=tG7i^3WQ{-NwZpD)eF*aEdgs<)n2rwvWS*3;F9b; zD$^)qvB7)VWv2G7x*a*%wv$seq;Ffjawgx=qq3(`dHUV=sy=VL>KzI{7o0eVwSME* z^zRZ%|6?-=P~fEW8Ea2-u1)I7WBStHTOXyo_$gUE_xcvCb+;M3u4~X+JZDb`Zn9~O`UhW4Evhfh^Dfc!cNPkodyW>$IoU#) z=b^^Cjc0SZMpgHjB@Cp6YM8aG+|A_>@*35MJc7cSjEf!(m&$)zJFvgR8d(Yj)VU>i z%wbia4w_cUTaKkw2rp*veEu>vPz3me?YlUXIofE|xO_p46}CG5YH*OiM?3xGk>kL3 z^fbitSn{mP2$QDKsyrMBed$kuCk;&7Cwe(GXJ?eIo+)wq!wlxnUT(jz**AIzFl}_^ zt~@U9U{)M)`}m{Xv8*#Q0Bhb1)nPVy58V8HnMLdu@hzaIG*tZ6`*{@91R2<+iH)8| zsE3x&z-ClnHysq`_-b)go)5ky2)LY% z87T-UKRQXb&n9zt!sY%&?fl}RTnrh0+`44#I1=_GE?^ea11CBSfhhk0d+Q~9p0yy8ScoeUR)){IP_v~b1G zSG`%Q+oC_IM#vF6fbu^yi25WPb!G$%sjg!mr{9#zPwzB-DckqH_5vPr4YCvc_ywlD zhHB5ZbE21k$Y!*&ZrW#^A5M{c(=Kg|R-RR5wDeW3=>~JVBBuHr)EUCE#QVPLeFY#_ zf2(q@(1Pcy z8Zb*lAhy{JzdaQylfCoCXX)N>r)c(~l0tL3UXGLyTyYu0cjWVQAvqjNay|3px+ro- zf4h9SRmgmZ%O0gqKaQaJAv{?1>DnObl>{4fynox=mQT%f@B}o^Szm)LK%UCCS&-TL zQs+65z`wx8hlA(i%^P3Hr1S|z|K9S`_uT$@K*t@%b#a9tW_~t-^pZEsyBVdj~s;K1ZuVn!YOL( z)xRo^e!kq4Au-;O{&3qC#q;WmGh=Yb_ixw-fCJaN_xCKb5b0@$0P@6RDJ)S(dQ1

RT_rPM)XW;)fx52H3+M_{9UFZ z3iU7C-E%ddxpVXL;p083CtP9(Y~SDnZ^~)C1 zIP8_MF+2}`Z7sCgMnm2@X1dsCrkM7aX#OUo$yvlq8HIYaj{Ug56Q)4F46`sJ(*Gvc zvgaesTW-dluz%~=JL6Jyll?mC8S@q~H_Z$mEobzNyc+$p`4!3F8CP@-eS^V8McwP4{}(z+w&vXVgnXYILr37@h< z`pUHsn?{pAdiKbrF9vX}re*hq%*4oXlozZJ9lHTHlT(aSB3oh?>L%?Pd`WA|qC4s= zAIdSKnm@IwL{+YP1)1<&LvqXt`_b`ynYr{Q;|Z95%->l4sU$PDTCb^%w65@~UghXk zBz)<=MU4Y20ju?~kknfc>}NBgBl68Did3!Y+oy-BE+4nj4%JYEJ-#Fun%I5-BT_b% zBusc=^GtfF;@MYXZ${?d741d(`i&f^1`Un5DWb%wy*^%#&CI|e_#Rv-kLp54<`Prk zEnN>$ICx*_HtOoZkt)IEDh1|jp+YOW;-Gq@{Sc{N-S9?DQss!O=pnv-;OlN)&g0>3 z=UdyUHUc#gWkg^wrXft<4lhn6>?4zsMd>Zr8KBka zZroSs01S?8x!`nlE#TnCgn`e0S4nq@@A)5U(79prJ-?{f@%mcw^29tKX<^%reJJto z-F&&K83}p4td-X)1&TTk@nFCNRE51YQ=GZ_73dk}YN3i|+tdsb@dG2~@TZ`$Pn0Eq zG6QTSn-*+KAMqJ1Dou?vCKz(^sy^8mDN|J>=eT~UPW~G^;p^qc;?rGWFWAQ(r&DVs z^E@lCujc;!rUl`iR)h%C*IAl}FycT~3vzshFAF2No=;-LrN2ym=bC3vKilm7)sC6e zrM7cs8h!yUWokDxdv74`oo=0iYK#p<4OE7S&PlHPpZOHEcDCcaUs|m$@E;wvywyk3 z;^O@JxF0)vg7};CcVfG^0&&*CpFO`2X2O#=7JDUt09U zQk$&(-EF!o%N9F;ozTS3IxU8=eeKEUnZS)@hs@1wi-+gHkwmAZKCDYMp+?>3-NOqWl(>xWNQnS0{CS#})q*vX?s?bsRkIObP-7xh_bXIz6w8*S~EYXpuP zo7d&(b}Ua`4u6PX0;n0*&gY^Vi{-*OQVv#j4C=F4?}|*3;_F^eWeW3v>BaYFdn!Hn0dkjS5bD^lui1!+2CcPVWBnQq_+t(Mrb5 z0Smh5TUTH^|8QKmWTNz^?(f8_%kwm@?u^_T-E?fMs_TD`K&DI*O-hA3D|2v@`~IjT z%57E3gxVV4WzU{fqjS2e%}n1p_1S+(wFy4O<5C~hMBVSp@V+$0W}zz&^!CD(;<#HI z8CbiVI(z+CzDv`r53~xAgi8Z?UYuUD#dmnLr=6Nh|7LTybdsEfd6sYH4;N(w%_X|N zwCs~9AMKmS0=xAtTq5-m@{lRzN_1+k#fwKqQ=`MHLpvwNnxE5S*ML}|?AfjVuvpq< z7VqC7d#hsd?9LW?aWb}=lJ3X*-bw+p*U;)`Q~T3&2sXU&0KGeGc&*4Nn^s+2>_VL* zMKmeajb;%zj=z*ir{!EGB(8+3bd2fiHQft4`q`cL0~>{pL(N8dBONVVFZ`c*HRt?n z#o=9V4(_FpXTn9d=6-a#jQ(3c)$yjRN7rdEQ(*2iR%zW{u94q`7_om@1$`uQ#?SYu z2G_UN{4=EuJ@S8Z1_u5ki0<#5{)_jWmF~Wr|BLzjw(wQFzlI?=2qnMHy_xsNcGjjz z`8-KL8XG-V5>-dU_30z$Wc{DZ*F|?j?}$6J0M8r?@x<@#^vcz8Z>A3XV-PuTl7H&! zL{i+r4Dbf@NA z$Q(pTxGaadTSMsU+`6v%<;psMC2JtPnQmt`8!{)7bISR2H)vxrxj&wj^~V-juyOZ` z?UR3tH-cQo0>G61{DW+4(E!}2-uTrR-o+71<#tvlhKG9W>Pr6LHPX6qLOb6u%xkA( zcB|RmJAW6^gs|9Dw6 z&l1Nkn@`}E)T79fd33>hdGAEnxKf3+{*dG=xmY>!xV}6g3`G<;VG~$S-*fnf zj@(2!JRdF;NdEbLp;9V_c4gC+gwG7z%q@g6ZXrbFAK;(N$|&+s}%18bsvRf z8Ir$s<5*~nFfd(jcn>HpE_?-4dgm2-2^B`eWgj^QU%EHhFZSm;y4d=Frn< z;%9FEVPRUwc8=Z#6aQh=Kp5<4!YZGB1EtZPGIwIUgOkQDe@q<`!C^Wx#HU zhIh6_?*8%>RNE|v^A{q9;c6cSJ@zIi{PT5LOi8x5W1DjqeLg?qeW@=OV;<=d?wCMs z_&NCaQ&U6pya=zH%5d<-J0l5&* zuYb5vTd>ieP;S{|`HDn=qUI_`Nx<--)RMW?Mz}6C2(Jo2OB?tuy?g>|K93_2y!}-IDvyC!-8Eqr8?h^idfz17bnc9nXKl)U(a^a^1`#S;Crc~QAUp<^HM&<4P~CT z&MVYy9Bu5mlRn|&bw({UD|Bsv9c=ys!5<|@d}%=<7WT4EP2J!Gw?4>-)vS~)kW73( zeLc{YKiG>|H1hVY2T1XdzH-Hz$;RU*)G_n53_RaO5Bv$S4a{A5enP(Xgo{a!+4YiA z;R(UC$8ElYCDUv7N?j3YPytxz-2_{Wzo|pEK;%2ygppv}5!84UfaODKpE1#0|GJFB z!H9!)Sk?qlT&ya&KY$qY1?SUyqMRhyHtf1;il3e#=jS;@+Ke0EDdtqh>(Z!<2}ajRW?2ByD&AjwauwED$l&mEo*y7S?w}Kp!A4cn@ z(|CEwr4;9lQluzU>%NvsE#_$46Qfu{APmSdP@A7=-4D)| z6sw zNSF=_(J=^<9Bh!+E$>)vqr0XJpF$qu{Ua$Jm3VYBU*+EDwp;VMRI`NuC=hG50>j*eD-_6n)M?Ib;509(DEiVoYG z_@t15Q+R6{K(xwNB}+N9{z-8L;Y>_%I^31#_3$rK#^}w}hRYRAojK3pEDOW>?9~(0 zaKqkJ-WAnR;8W*TCd>T2`2gDKiwEQ5%FILRGcvY{-wYpdyd*|Fa~LW;`~wkn>Co_i zQAgL$(o4^isd-1b8Qk#1H`-KGLzD*8 zJ&NIjfQeE68>7`j>0bp20+Bn9v~~&LgzbycOOrO)ZFgavQ2@8&i` zVGVsJjx#^|zFl|6y1m#YuXtgkQ&@uqMlQxuX$hidq!tZT6B3@Xm4mDY&{d_wdH1G- zK3|HcZfvmss)N>fy_3sQRO9eE^3+Odr(O9yXY8R{=*Ct<@o!l&c54<@Z1Umm(O%4p zD>93tZdJggx-a0GF~`AkIc568A>)A<-^BZUts(}eD3`>P(rD!%eKOJ*5_#C>t6YE4 z$#i>C$$ThToN<(LUCI=H&7e19nTZ>g6375wOuFo8Q@@lSy^H+;_pjRO@!oGty)Db~ z>|>kM0f9x1@C7(WizcIj%bvOokxas{xx9kRyETiYst?*xv%sco#H9zU;9mWlFL zs<2~fMUAKq_X%SCod?@)aNWVP{ok)x~ z?SKoZyzc0*I1@`D5b{ntz!-vxr4FlNbJ7%54p+_QCB>aJC$Vli>fJA&YC2u~hlO+h zrWHjK0#S5po^8v#W$KxfCgL=3=Amd|-^HWay2;FWYi{ndLa$jT_j}D?%%1LqDzb8W z%WhfRXi?$8#pm9ES+?aa@Q2znMgPRvA~fia+&{FmKXHqlsS>l=tA{AZ&Qt9JIYMd6 z;>G>+kjt^?Ir^kQqKaVw?y+t*xk{h!u?9~RXBXmfqsAP6-`Y~rG_hLx-Oa~Hd;q0# zhb`D*O&f)HJo5h|M^aiS%!@!nZ^uLGv-rAu;l(*6?@M!*mwP!s1ne#qc|;+*y8)7L zj9xiCHQG)3G(xF6J0}M6Ae<_O=Q(=0J*oX;_tSWt?~Cj=x4g+k{ox)hCPhh0quz{e zac_g`e`5z5S4Kl>w}R#C z(?!q4R>iWXV7vLauJ$mhbKnt-RaT%4CnudaC&Zr{up!iO4THp04|c4uo&QgJJ8|}Z z$J+j%&-@>=x4kj&sb`c=x*@LOXxBf!-=~+ zXX*p23cgPy{@qlR4wXsbaJw9&N^7rbVsW9|@A^zazgM1YrLcp%Aq;VB(qm(IF|22o z_aBy#FtnQTHV6#;Foi(p6xyQ}c#K6WLCn&%979f;J+n;jR7wZAx-e2-qP?SC%gHH+ zRJy|bK}boL1!WkSDLU`?n1pz!U;L`9cZbsacSIk+Bi(VSV7kMyfPa`vW%Z{uS8YOq z>H{$U)UrJFky@>$HJv83Sm|zPs_*z_KIh(c0^9MREO+YBdBnOXp@9jdHM^7#A#K-IC{$Z>FD-+M7E|!UCQ#W zG|jU&En+TY_O~xhS?ZRcZGjUv52C7h!C56)Lqh6F%JjG-O@7h9T!;;_Js6SZactY2 zsG8#2brZDuDFL<{_kKQdJ+ILQz|plUogWzEuf*)osuzC_4)?q|fSMoKpt{cn7}1o4|a&a9U8 z8sb#4t0iu2=|Y$tssam3867+-YRLPoNb8H>>#Z%6v5g>GtSPgm>i9fn!~0qjfWFU{ zb2bK%X?x=9MAz9}@`tR7&9)Mjn3{pzHDQmVE!KWF`Y8CEkr$1o6of)Eow&3a-Wx#Y+V)73Ru8vZvYnQU3mp!?HO&em6a!T_T!&$bE zXXpEtSayAAdpr=m_32KbLJIMC#$YG5PQ2reWnbdkHVsTl<4I+3tn=^gB>{AAe9m z_p`R2HlR>glKc{$+4qN?E6S7mUR89n-DS18Z zrR)r#aj)#MU!7O>9P-Eu3N?}SV;A|D%{0_}oU%vNdDY5g5eN+GW0syzxO|>AoBW;K zbYVYVri-=XcUzZ2oF+Yp6jVWnZ<2${FUIEN5T=*_E<_Ic@6X|t*DBpy`}nhALN98~ z7}#;IdWnN%Rbp9xsXa~5)R`QNPXaS#;G^(1a;IuUqDn9BZ^e6gz6;+uFtm8Ubej_tZ3&{!G0mIn00I6OU;#TE+uosafaJn+t_6v_j#f!qramJm$ z<|a2HAB$&4hc#=tuZdEuj^1BXWinI0&5^cA7wiEh21n;kDx1uV77carwokLKkTzg3 z!^%Yk6@>BmQ{=^K znq#0A&kF;S1He|!7KtKXR;4J<63NY&OBgw%)WQsBJ#nV%W8+s_*wb z`y=A71oNenj3S5Gy+feZ3-}p}Dm9LcwUax8Vbjdu!4mZM?- zdf79kd~^kFV%P`IjF#920crs0Xm6o`MH|_zInHEiPgun%a^2{da`?lN*Ursk+L-WS8E&;LH#YeoVJZ zLV1pVAtSH|T+q)#&}!u49JnDzcrfbcY}fE_qs8+D-rp*=qpJraAl_t{v4XP`7%ukY z0b!`u%^f2)Jp#`bP_&D-pjJngIjV=oAY#ntsASBy*SvR4d5`P7#kPzVTfHzmFt4yv z%Zc=hLE)u0f+J)2GTzg2HAnhktIJY1K}~@*`>R)y9d$>MKtWB>THMM43FOhldrDUY z2k_7fYB$-dQ{Q8VGm63lRr0g0gXA!!+UJVAF3yjdQseo$Ba?vX(n8;)jdX$6w}*rL zkcm2{!nglnNmR1_C{fu9x!lzkFE$RR<70C>bv@C3V_}zf$+TH%BKhWgkW0KO72|DL^qccqkZ|Uv z5Kl_CgI;X?8N-`{eR!rI6-0M?ZXSi?NSN+#mKoqE^dVR$USyov;Cels7*+dsZz{Ts zeJtp3y>cxqueo)eJy`FPk5`I|8BU6dCSm6;T`xE+!b1kw{m7p45%sJYen190-vF+@ zx*89dy$tJhRP9Hs);gj{dfrN--b40r>^kY5Y+}pwLP}AZeZIDl?JpeyIKqb=ar0Oc zUR!U^g8MWP764r`gZj*E&oddg-W%->?&|lJfBlkwelRnE$#5H1I&M;=#Erb}#L*p- z0dW)Qs-Gu5u=C3%I}mAp0yV~0sb+NsmC!LKCs#Pa943!(s^b9JN=N5<$HqHM27xtj zGgIy$tB+dkc%}XCb$Dkpo8!_LC;2v~UlLrzEkb+S>5$N9&qFAM!&O5{qe0*6o@$>U z%kd$Bsj|!>^>bx62M%$#2~|4{L>8sl^P2fuvr&ynK!FT=oXqotL%D-$e4N49Y}BTQ zj@6wZ$Hmor=}z=u_@QLui6d`scCtu!h8d?mD{X^v8m$aX`dLRfJyCyHt9SXn`|5j- zN1r4$x=p;yfcg__^g*)2kO-+IKfy~B&Vx%UrTRn5+l#84GK_$_doA0+O(k3Og6 za8WMJbsvyjEPF= zTgq!rO%6I>KIxi=->i!DtB1muj$9{yHhy+>84oh5gz7v$aLs;`GB$ZIm-<%8>Wxbb z!EOrVz5pd&8a+%i)KK&K+ot!cvQDF_W0zIa9J_ZhIZca*4gxI$Z(Kj-?;RBP9CG28 zOC4C_ujg_X*-j)vG~C|xi|kx2#z@ydlkb*Naom@IEvAbQJ7j9mB~jobHEvebegsw^ zN9u?N(XV$Bn^Xu=3r#78!H@1zG=XlQm0`eGMe(*%7SA}t+k)pxqUU@)>t{`Hfa>Jg z;acR7K11tX%L672;}wf5>LGIS0qM|l9k}S)4ZhlP`VTAB{RbL2Jv`M8d`LBAiJ)a7 zs@;9OftD#k0>G6~H*EWYF>eQb{^myl`eok!FZ`nauQb{J1LRmL#`Er{&gptFzE6*^ z9voC}x*rMfhHMcn#bMwV10Xk_4!b z1C8i@JONfhP#1BrFE_ zQnvHj3mqncDOA(_Kx&8Op85&z?+U+pRM-WOg7EZB)G+?h-dv|DxwXwrlILblkvaPI z=*pZTjop&0UMYI_1+nD(Z`0akvy7;SofO0Xr$KUU{90u|a8QYX9+3U0elJINQy}?` zQj2cPYL??fBZ@*kuG?I&eImcS@TTn{jMbY_BEjNtl5neqdYBa5dH z{`q6bd!IkbpQ8yvVE?3vyR$(d5Bcr9Xp;@xu#&w122e&^jrxwvNIZARr_ZE-&T=Dt z`)LgO4R$PtGQc)h#81nyZ7y|Om>gO6Rgr+? zRgEYeRX0zh?a%hrSUeG#0;vcyI(gXM%KlfEE`gm|OIK@bXpy2*tr|sH@<+P!6me{L z@g{p(@l!d80Bb3)C)2Ano)+l=@0S|0L0@-N=qy9Fi0J+2%`d~CfR73JpDAJ=FGM+k zu&ER0E{$(ao8S3nU;?6jvb$7MXkTY~dxMV84Je+g2Avnut}555cO5bQ5{SS^mKP!{ zA(GCaTeBAzt)TT5@A& zRj=!-0};>|VGBZq4Kvj_{-Z{hyupXlndo^nUXgct@#wRt@j^RMO;(WAtp5xDGY)Vs1P;&;H_&3g^@;u$Pa6N#WvTZaaXz7%JEv&)#5>0s4LBZt#Vwd-u@WWR$A0XH%!Y=N)YgH>Mp| z-^GTiZdt3avU2KF_~009=R}BzB8zrIzSqYR#*gj@iL#O2F2yO;jw=EW^Oi1LWQ%4^ z%Vwc88WHvoUPPtAxo%@q@DUN2{F`&WlGjYi{j%gBLs&R2I~(?|PG%WE>0CW%jr1UX^`Mlrg)Dq4TLgOybJXxV z?WpJHzanpDbo?066?$BnDN?mk1GUl&|LQxk0OLfNHd3PGBb%v@$EtI#!5EeH08iD; z=v_=upS-^>uzqO1D~@g^%KRcjNQ;r2#hs<~5)Q#nXK;>6|Ii2=v?S;k5Q25GaJVHb zMROUoPQ&lzXK+Z9trN>VSqhm zrv-IWCZEDa!5r+uWm1vnA5BvhzL&q@R+0*iJgXMjp9L+pk?l{Gytc@2wI!|il~IH{ z>qI%4bK*VfPn+{1fZ$%KBg`1Nnr~U%P#?i}EL>1~{lhQxQUk4a?3}R{i-afqrq>_8dt|J=r$C zuNmt-9*K}uB^z{3tW)x8uFlx%g7J@)dgRJm02W1k`k0>FkQ8klo<(qzeT`zm(*!voS2labt+-wDZ|Bl# z$Jb2APOaDoX7!521A5t7&w`aDsZ}G{!7Gv^zuC_TL;rY>i<;BgkF=ue{pLFI(eB36 zmoYl(^1MQ0t)$9tq;^{r+O*`RQkf`*;mx4QNEsNSyrhh-2APQPX1 z0@Byl)e5PwDK#}ZpYY+mH-LH)){E}HVE)=c-jUP-Tr2W{N>+}{B-{s%92t3XCMx&B zliMDC+TDi6`w@t(`2P&O57ARgw(D+7p3xG*p=c(}h*RA1hF0I}0u+i`Ht?0+_7C9= zv#jo$uJuqM$0GvBINB<%#3uJ0Y=CeYzgQLaC+FCi2ERXHK$sQ!(6vW=5hP`4CBt1@ zCXZ7L>}+eecN)4ng`WXd3vU@!NW8}~Eo^nAKys0uxr%89GBT7=GxtF^K0Q!rzLPp&c zCUM{UMAKo*y};O2c4TVIy$J}BFWnJ4kvQFB>mSXq;&kBbFjgrv=BpZP_iK1xrPE(o9g zasBB}{(-a;b?znt;Z1J_?Fk>URH)WgN{K*L^1yFMbQf`G%C<>*h@+0B$d^6wmdCh7|FEk$xtY|q|LXcO0Z zWo~!#ibUH~I*wDJ67-vVg$-U^lfSK~nClSXi#i|-R{vXh7kX_X^KQ4u2BLyI{UI&! z#n};)2&dQFXesrHUmR9;X8C5DH|EgaWrJk*Z7<;Oag>2x6gJ|nuBcfTo_76G*F%Rv zA(AtnW2X`QKW&ls--P_w5B_Badgtt0i2Z)!7tqk?FMCol@%i|u?mkv&)XE;kOu`t4 zDve4#rx^a2=8Kx&*IEi4eBJ399DHA9uMjTk-KXFO%)XYw?aZtEdsGJ7^c00WPhuY$ z&i-A>JIOo|6Z7M`jBdklLQ-JCmq7CSLyZaP7&aTy-gLlLhN`-kz{&lw+>LDNSHn`W z5V>62v0_%|U*jD$FWe&``crbne_t- ze4X0HpK6jFV2$iapB?{=r}W6(6j^QhTH*VHqHgMosJ9HJu|buv6=8O!rv6O}1&Ype z*l}RZ?l4M%M#d3Cyq^Fapr+bCKBWDI_L_XkOle4!yB_s-hPSK9{DOVU}>FjK?KY zbplCoD^p{5K8>!Zyw38>SOGN$-gCA;t&g1UdFMkPQtp;;%}$|lr`fmDxY{7;gqRhJ znH@)u_Zr+%6|Rya^BXci4qnSEyMh{zEB(Ixn8D)l6*x$)(QwUy8rdK^Dl^RKj|6cq zs4}+0o1-l!N6nV<*O0T>A&mM!5!F=T!p3bc;A5k$9e=w7r7gWzc14?ZM$S+^Z1OT= zi3F|M{`OD8xSFhWan?5>SPOMOhPb%OiVW;oVGUT6EeiC&C$J7Z&e-oPdn7{tr~=EG zI|BO1#siDYzwo_m)tP$jgw1#2mp+z4LnMCp2@njr(a*`sI*E;#ucULEk4`wBg^b9t zpvO-8B`N(1nMJqK2Y_SA|FEXQkc zz7*h9KY)H!w};MdB`xuGCjqtxT$Jxj=Ue0}n5d5C!Xk{LAIh(w=37FlBbD*dmsJVF zy^`hNz`Lg=Qz@M`Y?)NDx%1ppZ^9+5wi1H^RWCd6AsjUw)4ZqkCVdHXn|w+P3lo9{Y3%~H|4cIpoX&uiGHSqiNH!!D$ zC7d4-H5;vBGlTnZLAzx$G0MI!H7DabEQ zk)Ev}q2tdITQAmigE}!6OI60+Va(2m>Q|cIt`d|9qkJSwzbs7^{5_|i&9^pU<8ApO z{_nC}u;)jS3R{fcuJnoQLYZh{Ke;1(Wcx3!pI0t^(W)tX#`!)%E_o`*miJ#LXCCJaji#B#Ue~BUIy1X1Y zmbbY=GN8snDorYnnDutT!;=n%w`a>rqD?9w+%*%MGj$Cq0IZl74Tp3_^07a!$3UZX zao>+i?GFDep)s9y$5DEoXOqgGO^UhyjAhD2<_tv0>!9g+(WyO;FH!1;nj5_4JJy~A zFQemW+42a8xlfWe|6KTMs&z~YXGuDO)ZYbpXY3}$9!cr1(cN=m6fX~}84-@U)@ep8 ze%9Z%Tz{XotcA=qlSDxHQUYF03m?9|2uyjSt#8}plx8_IUt~}(_Fe_hclXU*H~6ZG z_t0__f&m}tqX-?SZ`&G@>1Nt>3EmFLUC+n0=|My`C=k%P-)@ATB6Rv?eMfPvka>{;S85-NklP2h9hoj(0qW5gTFGD(c?E17UAiacgguk3=9M8^-!L))XzDQcabv5*$cjur;>Hl(nzNpH4s zrZM$+{px*#t9anG%VL}j&hGlw)AvzR!GJA$;Rok2>^SaFzW$QWeJ8A0wPFb=8VAw+ zVJ)F0`}G;0pa*BchTTKIiXkQC)3#{42@l`>*dpzod5BNqxkY zZ{n-9+87vj;ZSs-(hS6CBg0ID*-YtH-4o20WieV{bA}kQV%x3mfo^q^8V{>5`}R; zQ*XiVW$twVaTkniLrT%jYk0IH$5z;C}qQw<+ggy*rCv*?1KF~5=X&PjKS%(Fc zJ-yn20iV8}$zV95Uwsc(VzW|Olv|h|ydvmIDN|W-Y}x5C9K{e6Z~*dQ2aq` z_#?Z16?30jG_DY$@)vW>Axu38M0@@3`4g3XbE)}fT;z`IyMHgKF2Jho@bq*8*!tJ~ zJIPqF1#!zD5>+?io}5mdH(Z(L7e&~+V{*m^5>7)Y^R@N?FN5_$Ins^`jd1t^jNZBj zUsgr+w!dsbd4~rgIOZ;feXOhqi839x`>~jRdRBRBcecEHH%MiNsb+Ld+BQ#kV%xG2 z#cefWWjZms0mgf#^WH!mozwQUlLM{qvP1QIt4buxM& zK^Y*nU_UCnM&vlf;4u=-{?*lNZ^rp~xPRG}Afo`WPw6GyNmX6>QeeZ_i%F_yh2s0G zFw68&wU3Gx?nc|l#@0nd>74@l>ein33-U4EQK}S28urpdnttn&h14MtZPd#Bifo~N ze2FtfC@kUAE~5t>XZ?vRG5T=~zS(0dZ}c@>C^ypaRB{*nj*b(SK_~LODyIG+=}Iv8 zyj$9u$^FO&I^ojvjYJG)%XPg6N#U&GPwwROntzIb)@zW1WQJ%PMLDvY|?l_`l2iF5f zpVH?^3f2T810U`^Wo{!&S^f<_k9EG}GLk(j1YN)1dJ)@JKIk*X%r^zYa4Ib45?bjt z8`+IbH&k%^#s}~Zb=9P9Yz3Zim57`g<8@<>L)fQ#UAc4?JyYf%=3P{nMgn00 zO%ku#nw^8qSr$1*ZMF$L#JLr7 zrC5Z=HXHf;ht(g91l*VyFMYGk@`?HBiq}QuNTr^_gs@ui*SUk$fJu zEmKP@UnDn5__6WXYZ< zx4%ZEB)hI3`m<ej^FEZv(#i0h1ZYx6!GqvDap6h(On)4*JU$elmO4Ww4FGtgXN3n>3zB`{Oki zVqytXKG4{`-Xm4x9Ax~t$jlt?^Km$kxMtl};(FBbUx~vb$-If~)58z#sZx-2Z6?jH z#MnCA0G@=FKg()TuWvNnBQM;$5$V!9h)D0fgGeU=(mM!9 zFQFr$OOqOU?=2MR5PA!}CkP=xh$sJZZocnad>3cVO(vPip1iYX@9g!i^*p}^O~ep> z@+&p<;__j;ck!q2&L;t#oSzs(bdpe@Yc*V~((~nKcq%9& z4PiWbJ92qHv&jEM)uCZmLz-;}&@W&s-;`pjq3r|KVGTlek3zCQ#V4>a`#;NWm&2RX zjc>+2C|?c{=|-K+hCHm|fB#&FA9VZ5Lqf?@(i{2hb2oXz-h{C1JLyC)7@~~YK>8;t zAQV(sleJ}TpWZQcnMhfjKDi0bJlSRF2`Z2yGl=rTzWz7Z(|-j&{ZH>71!6Nj7cBly zre}P&mC7*(3Gg4z^W58u^?Bpf^2}mgyqo?KwZJU*=eg^OhKY4-+6tzmF*mXU-L-=W z6)-MYZQ$UGA_HL}c8)U62m5%}0uQiCZ#1(x!#|w-Gi;(`i0eO`cm{ZqPcSB|%>wfX zf)Ts`qIo6r?unfK;RH>hwEp1`YS{h5ku?e4sK<~!xbpu0do~4x(i6C|*@&9`z2Dw2~7WIL7{Uni)fu!T1GfTHxg3-=+~oO0h%wACAl#&p(`p+t>~dDtI&R zq|*jLvXz?#gCcO3mHhWyVr@Sx@5)QFpLB0UW5>q_0GB&taNl=H@HVux(87nal6nGk zmW&(X5eaSrjAF>tKIckAjg=X)M$`n5C%wg?J&4?z`g>Vz z(wkS`Skeg=0%6#je-Ok*u=^sx`91SsLc%$=b+O~%DY&c0fy(<*Hr1H7#N50W` z$}@v~SKkDTjnJ$}nMf1kLrNj5&!EBZ!FctlCHcCZ$(>6Z=b;WDGIe^Z3qFwr`=mH{ z6~5|d!EpS%28Y4aU`lKbS^;2o!){88*zL+r0DJ#%miY&S`eqg3@x`M`9@knU-ZeY& z?IE~8zs<1&HLF8^u35Ag2EQ<-iptXFl(IBSNJ4`+(i5T3H+2k`Kf86z60!b=qsQFy zf-DSD?4C;-OoSCg^41~f(=4&3EBl2^#VLZ*vqGxAv;+4+&HEC8zVEJc7)u=|a2B$735PZ@2|#^|a=T+yZ&!-|!|$;ywdB-ksAD~r_@Z;m0xLB+nj zG1vOt^96B1TV`?K_BktP-Q}@L#j|&ot#xhnZh2nzMts4f7KR7d{kw3#1!*wAQ7n~| zv!+ZosP~WAh$;17hUI-&nTgyeNI{p=RNz&o`?B+fLv?%jMEJUqv@dhqz_(V(M|K;v3ErZ^5Yy{&X?XGr z9HHZw1Se&h8miQR6>Pgo)i!5}I8QPC_Dsn##*i#zHzPdFT52H9z-;T@07euZi8S>) z9WRazsEoO}@ehf)1rHcs_Y-+Jmq0Q&RuoKIgW~s;{;^{2 zLg{OtBvAE=IWgZ3m)yfq2Z(t2Y2rolHL?7*!NS{yNY%Cl&u6g&G}rnU%E}}GehW76 zpe^S;XtMpXeC*j{n&|!Cmz8REJyML*9l`*ZCR5kcnVzy44<0Y(1&Jv64AvVb9f^MB z8LOs01l!i_c4vOtGCb*0>}e$(7@?fIz~4W%1l>zV(jX>YX@sPVN65Y1bYd@7ls5ib zLG#Pm15B*)I(bYxS6VX1n>2xA3L}D6pB4l@k_v5eS~a*(e~QnvL*F=v!tHO%i$WU} zH^m29K3WHbYCCrwFlB>wd;6EPK`!nAY8n7-F0O=j7)99Diu6;*_e%%*)L+xmw0HgZ@C6xvzi#ECcA>O1><}1I4qf?q9>QLW7hM@xgZbzx}!k?wf}+A z3jqL{iM0mI9y*B4ZsTNiFfvF@OO4-9y&^x@y@;(S=#7iZ5tocCnk1}X9Nta6WM!-z zF8j@sL-24b=t5r-z5Ihx3275&lK-fm?X8A+8Z)J4@k(cf*k8yfU}F`rt5UvkyV`2w z!DQFef;%QDOPuy{u*CWG+H?LMh%)HtuUhM(om2gTiP=Fut>SWSVSa`)>WGEJcca%1 zr8}>iXN$}Z-7v5SH4)mzB}o3`6l&Yx-5P0QdCVB?`@H)TgjzrsLdyC4jG5uHWux<} z+hn45Dw6$___)iz{t8TaRjB1vy~|M7!P=tz+{XoEyYp7n7l@K0y z#J;jLmIa_x#>|MdZZT(5tJNEXsCi_!oU09k? z$r-|~JG~DV6(uIWE?8_IONWE_9kJB^y{6m2idSD^wt9ho=#+39eH-}K%D9l}Mz7rT zI~*?xN*nfqnii34LlxZ|axM|+)O4kB`FVqF9t(b-9M`|FKALnqk)j85vBD{%T|9Y+ zOou>v^ZnuuGlYfx?d$}HErbTbR@}c9l4Km2J92H86G=MXAg{r)Qy6lzGL)3Ld8#nP zs1JjRD>%>f*BugJJ**?$d}Ea~^V2 zidW(X?n?c4yG$&P2?%*D-f$=&PwSFur>Z4=z;$SnVsm4($aFqi3(e=lhQI-)7`VGf z=SuFG;RaLfc1F<4u-?a9Z->rIx*K|=ra3d;spZ}pl)-_&O7;}2{^Q}S$! z1Bu6-@SGgz-y}-}Z0H=D#+Sx5`mEVJjnmu*lf$Wsg%BiaCxJsodh8TIcI^_goHGiH zw@$F4kn6EHCsPlIj=3P#86!LJR&8A_U*rhiQ5GRRz`0FoY~zbh2N*-TpE$4j=k}em zroCY&P3yAAXjEfNug!4FDdAIsH2TyBXdpN|O-#MV1p;&tv@+|i&b92>-}#e(GP1>5 zhnAuWt;fN59Wvz_-u~8t(cE9FUfn2;%0#ywXgF?3I}$Nr$=czO_^~X}#F_rD64+#V zIYo91%-~E~weuZ}pmY#I;#&K>J&Nsq#eIk)e_=eD=ldS>B@!31iFHc!qu#>A9kMV-%X9E5Nd+W%i=i{8O)BV4fCZz&? zR)6u;_!WtlHzs&Bsb{roRXBC65$8mg4u1P* ziEqU@rTc5R&ej$SW4Vs@aCx!>j=F4bf8Do7MJ_dp4(Jx8MJ#uHh6V^0973ZVn}sJU ziz39waQfdr_e&PJ1V@&AR4?VqnXE0{_U|e&kjG=YG0>hXx8wU=I+Bw@`w!uQ!|a}lZH+G zofPEnZ(mmYy)bid3)+WG_8Vdu3WJJOmr)Dim8kvxT%Oj3hAHQ`Iyoj`rgWM>j(tfc zwVKv88jpLqs!8#FLRhEw)<#5i2Twl0;++q^sm zMZ$z*1k4P!ghRO+#9OKxv6Z)}Y*^RIo~X_(lxHAogJ{Vf1i(z6Z+auW0$A1F$P`$7@|B=N&NTN{3!YhO@maaw8uIiC}# z`(53$gZqJ$bQVKG%aenwZ3~=VgX}-2hCWNkL>}q~SXC>*z!a;;-p^&6s7mS2`idNmJU@Lm;)7)h!-66jNIklA>9QcX-7rw_i3`#HSYSwW*ii7hyvaupkH zX=Pu#9{@g%#|f(>HJs953w>nDfv+BuzoYj*9NZ2@4AcD8d>~eID-Td%Vs3guAJMtKplSpp11Nn{K=94=sz6WPdczpPx9fUh6^T5u^sBa z8qXDjx2U?|UR7K1&WDtG$q45vrv4Z5@7=@kMJKWMo!=9t~-RV30Y5?>s=po7{XofoY zdwy%17>#km>{xd8ubogocU3rRPbaPgw(D|Fd{bQ|z(uif`kb!+#p7X9T38*jqSouL zME?5HPF~~N)o)AZ>LwNZkmZ!zOu@tMr$JBbjVB`m9I64*08)nx?WMz7ejIBLDh3@R zijBvYsBSx>jzB*iYbdv{WD!=%|KZLTKSiP80xxqQt6kHlP2G13(b95Cx|z-#t}>4H6_ln+j@?i6bgfl(6}`{ClozT z5Yum%D+iFNc&%Q!;QQ#P2gi!>L~`*o(s0n3s4IbI*kUNZvr8$K7d*;V5EKQw1Y`34x4IBxQeutNb#TYwqk$oAI?Bgf^^LKy98ld z9gl&XJ7SL2-gQCUfNq_Up)NkuE#OUW8y5~*8atk|kn(+)rCWF|w9-UU9 zh6upMtU#`%!(d#CQB-CT-}Ng0jlnWG!lJi~Jc!ADLVmiXTAKY%yUR)%BM>O9?{6e~ zKYR5bZ!Qz`|J9rO-;TRk!90EN4~JPM_!uL-12_QPtRVkk1ux03yRWd^qzi!u)0n~F z3+Ev0?a;JwD_F5qF%exnujM0xaRTEL9O1 zo)QebWZj;@w0rr8$hayGlP3~_n?DmW9dN%KUB)T#W2y6=2A}Fs%`gsffSUZ7xccwE zFETHgK%SO&KrEtBD*FzbI)P!edBSRRN6sqM0pdXa!`Z5KKt%<7g^rnMl$seqR%NCz z%=5wcXz8Zu_>CA0^N^EO?agL$_Kx~?QcAL4h|xM*Gpey*(Rr?sW~s^`g_*f&!_8f3 z(A z*>$|<-uyXK+-KW@dznmvoj3=O+qZqr9n`ppR)NR(2oG#5A%?lXI_sQL@Yy9%9grNG z79BsA{)W2&y0Vui26CiS;abmmc}ZZiTOL)H;X@So z9w#nOWS=2NYFpjF&1$Zi2AEo({SQZM|F(+`47|OIPc8StbRlxz!s(0i51;)uTU!>f zTiG4Du{5o#cu2f@XQ1kFW385AS|5kiY8GK4ib97*MbkOTe!e-Y$PRRX5Xp5iv*~6V z^t-Mrlhu9|1G(PZke2@(|pmt}q@_GeG^4$@0jze$r3a?&h|6 z1Ov{_a`LsG)IMFn*Ut^B;|Sqcv>HtKA5L`oFT^tBuUx6zz`Nk3>Smcncy%TirT}|biq!gnyUp0w+hPp{`d>f~cx78oP{(XrZfPbj7gS^Z? zSt7X2?-ROV^m&{24p&NB^LCV8A0}<~em^{(HlV{^zx8O`!bL|g%U(ecC;CzbwifA6Ybvg6zJqT9fTDpv=OWx2K$IRV^V8?BI( z1OQHTTye2a98-H5`24#DT~OMi z(^cdbN%`rHtajf|HDhsGA;YjP@67f6rkTa-;HN>8-ok!qe}Xs>mFc`I_gD4HDm&Xu zf*}Z%Et~!RdpGPfPgra+qI%(puL!-h+toW)$iq?;6C&;Hd^I!TviYxL#!2mWBRsU3@s(_<6C1`?_w zDg05xXtt7}IR+SHrt}-`=DyTrp3n*D)WY1INLS>awiJK9_>*tT8^7?l2p+_cLK`vk zKIJZiJ`)>;wM_{Jp)hg%iO2FBVuk^yjyMBp2HHAz{Viy~F^6ic`Tyk6$}c5$zzg>Q^r^rQdN!mo@t zXG3SLQfZfVkYL;ZDPXVPb?g;>a|0rEhBDy|He^syu@a z;8y~sFRh+rIlZ(RbI1|&~)3sK2rWG>RlOG!!qSo`=v$|e;2 zn(YdgOj?pz2o3VzHk77LtDn7_C~**~%$)b3feCeQDY1%i=h;0P{FAjqs16ZKLvX-6 zCle&}96ZYpnwrGI>u$7HS6&2M_}NLN;f>wZ_e@&F3<5fNue4si0Tgd4HSge0fleZb zQ>k5J+K%k5GUwFK_IA{|_nf;L-@G2`A+!rixH6wQ(P>XsnuJyoE2#VbHIE0rIrwux zdg@Fud-`IKhHj!(RCB|WT4nKt_;q&a`1{_}1dX}*iVB;|2l@}?4&3#U4~BB({)pn% z3dZHPMz94#f6?OK&VOobj(D4}_Q|z--Snygb~HsR_**JW&`!0P zdZ>^-#jyzDF%rMdttx)qxk?x3hCudX zO^WX0-DWiyJ^y5}wL^@j%3{@N=GmFE>8~Oy_jbsWwBE7T zaN~0hd}AZZsYc)I*7)IY$PVzD9U7eea->Lc@FwNnkMLYPk#sdmvRHD~+i0-EO<;!| zURsOj269?}$P~BJ$;|QwLzKU7yIn{EWIxPa(dmn~G~@^!Yx+Fz_=UH&3)DF@dM3un zmD~>?X9H$Q{jAdcwU#mmNml~Yawah)VPkO)9Q}u9Pilu-h=%0!6MS}@%8g8@ZX#b* z(Tve4b-ZtzM4D|Nl}8%EO+m-ltUhOD@mjZ0i>Ix%TO?!v^B3)6xgi1oSH_b>>5urz z$1JE_#G@*x$o9;3iuAGmd#pPt=I>84^J#NVt6I82!d0S<|?y^R6x8J&OSyfk?HlgynYdX*g6P3T!<`MpV~Uwi5DPVdl5p z?sn^;TCOE6V6E*zOj>wRdXj~!g-IDJAmc0A0yYMSjm-)S+SK^QY-Ih~MI3|8;q?9e z6|Dt}A?hmSNAa>V`&{L%-sH#F1da~tB{;tRb-(#}b630Eb#4yhyW6^^OTqdYU2opj7v+g_yd;SVu;2)AzZt3{B$?}JU>guoNCusI8NEmW|X2ifwhEhZm9>msatSbLl4U#rM?O|`v_YI?xw z3avoXA<`f~33|bm*jFccrz9k4H0iHQ-BYegj%Anq#gALk4WfNm6L#;HGq^4{{7u{& zBm&0=J+;Nsbw`6D*Ji8-|l%G{0lh92frJvC+><9Nn2g?J|6ku}=}FSEqLPc) z6DHTGGAc67L2Yob?fK_%H_m=G*V{EIbEhW2%yIdNG1jP_fAR7EqH90=ub;cT?z{2P zhH!b2?zjur#f53X9fn4Oen~r6MhNF69R-rc$g9ZJMprdE8|NFJBLvMq2?5@+3rnL& zu`_@25A=t3%AaOX{%Xq~7`NJ*q$4`6H`lV0eVP!l1C{BK_`&#K#|xLJ4Lqs$4%D6v z%iX}@IV)d+PYydb>S7mwJh*r7WQ=iFnX5}Ns%$g;ol1N3PisF zA=^8kRr2?p+MLp1sd;G~`aL{5h#9e0?E3o#+c%pL$WlQtg}Q=}2d8JbHVN_i*)|dQQ&3u$ zc;bVSJF3+_U-gj?$3Ac064#?u^c##4WG_E0Ty? zUX^-{sy>)&mtBpp_)|@>HyvOZm?`6s&Q*c zLJwi0I^$Fwp3_0?sOBy15h`75y^3a>-UaYmZm$?%=ESj?i-e~1IYIf*?m;lQxsNbx zu&KbQv^S9UR=L*`FNPpfnxV?KI}|PBur>KyI?DO7WG?;Tc&QP^Lk_kl%;fkrBjAz( zTG;|hb$$IA=sbFoqO#_wVqdBK%o5P1HWXcDen_3q;7}Ks@O($O02{yb6i#0X&PWHy z;1PDWWR>r=2D)gr%r~lZY9EG~nu&U&)jwdf>WEljYJbcL&7LmLLw)c^4|)heD>R%R zf3*r9*@VSE(F?fq5bB_UcS#BlZUq=auhT!iM+^{rs5*kQR0ktlYv6j-d4+jI@#1%i z-RE5pu@+s(x5i!U)fZs0oumEANsvp4s~}uy!`Vyxp%^cQeM^AX1u5tGZDyMjk}how zXD^>Hoj2*;^iR!UZgr@_PuvNY<6I-5DoP}m7JD9)_GR7jS@%!krN_cNdcOcs>#Q+? zUd-{ulaBkgO&qT|d)UvUm6KV%?BZFA91)ZiWD+F2TeEuCQ|~uhlDX3z^vq>@SF$Yb zdx1#e+XpvFgPQYrJxV(zrth}te5>3A9PFV@TQTi6OSff}ood6WWQ3KJkLsb{rP}IH z2AfZUh!3xY^go*^+3gF|tUJ5DeXv6ku#m76z=g{5w!LmL4y;VSv7$JxsXXeeJpzny zT?GcsqdO_h+7l#8J=jEV0_7k1m4*ksN5!g7ZO+<+?DP`YSpNBZWqANFCg**wU;5Tg zJBK}QKylyY)U!f7q8WPGzCx2mWyz^Zu24^XMS|z^ObJm91o)OKS(P59AJ>z()l6~( z`{cG%ZqTAl7di~`AzPUzT-1Y4Nt#B#PrlZuGfK0@C24!d?>h+YTldY(A(|WSN{*LH2z^a6u zjz@bwzqQtk`)tdTV`-ke|CCTebH7C}o?@PDWw^EINMX-k!s4MvyKcl^)pp7h6ENsY zy3--AxsmUtZAZzoA9E6RL{l|DHQpn~U-QH}aTN(atHC-A^IrqrR2*j{1H{a$6KbT&T7oD`CMN)9rpqw0wqq zlq>%ECMqCQq72r73uA~2Vn7)$40TZ<-qnhoqAZ;Vh59t(41hlaC+7Dttf*-O{=fnh zKKMKM%Oaz%6H)SM(tZC^#HpQ1IM3M?n+rD&w{_q+OaHkyYpdk3aE4xJN80_<1isWf z_Ad_8kAY4DMNT8;{$At?CLf{eMq6fmVa8fY)C0c}w(7)6+hj5&WJlKxQPOG~sa-fU5v95V`k5_HCZ|MuM2t;|e>kUdsI zOKzo4j+uQZqdKHv-S}8^#IwP4#EQAtlSDa@M6o@WVv z=+^=5B(~`QA*l?!3FlS^fJ46JlnMoq^9kJjoqW!xUzG|#Q|lRUK2w4{4(@WuMK)Yx zrt{@E8^Eb<_8ap%@o0R|c?TO@V~C!0itFl_NO?wFC0AS660|8eKOW}sH4JoHx(Tg+ zl+l~Rw`Z+KD)r}f|2qd{oMWz-eE4M2inI91;9rhhGs=_u?Rrwuqjd4?&tXj|ecg`) z@SrPcB57|~2C?>Os=pI8xzF6_H%3r@x2%0@kpv0qc)DMFpN(PW75C&4ai#?d`UqZ% z#jCj5wKc4)?3T~=R`XLd&vO>iH7kH9r0VWm;P??GSGx+6Ja-~!4Sa`rk4dXN@UiIz z5JQYsf-6L@BIp}kOIIC`rTmrr+;A~#s}yKgMT%zEY{PZ(?cT)cm)%gg#ymu|`1W03 zJ2H5oQSbvJh_u#q_$FLr+m%vH4f80_JbmKbP3{uz;)hY6m7D>n|6$XfJ9`P=Run|% z*qHhowwe8v)>9_Y@xy}=d^or&v`yj9L`B?A60IVc|7_3AdlJ#TaP#**lYSow@Q530 z|16f1>mriYlagq0MyrlAjP-h`@ct^}i}dWJ)W7IDi2v1eksSrWt@86eNn%dlcwX(4 zJV8~>UA6Qpr)TZ)G@5n2V?ry6nWMJ$>~+Iv#8bz987j!HY-1iVYk-!YZwTtud=!yAJiN+8-EiTBX9FfO4kWX*rLWoPAuVuT8Uuoi%dl1%CJuL#V(ih}^7vhVL%kp4ERmc4vO2GpiJI2k}w< zWdc^IG&2U-n2FN(s?jO<7Tx|B@ul0kmJ00_JhhNKT zgrk;sG_T(!|HJX8lLROr`4Wg^`@|Xt{Jz(B^9#83&4fSV3;OD}z+qR4a+^i|&QoZb zFOHb!nd2JC+H+9er@6JNa-q7r@LF@Ud&jNYPM3FT-6SMM*3cmKC_cQW%?LB?LS4oi z_V*1gwDTd6`TF^0hjAr{sAW1nG8OuPsOWU)zLS5wV-`75TT?sLQ1vlT@66MRCxyIi ztW7vB*AR<1S@w}uoc7%KUO{GjGFE(_pr0AuW1vLtYwm9+NVFbfmT6k1yJx0#aUIdH zvSy-%^-xvrw)qxIeX=KJGGCGmH%D-XRiT{GivXyFP0K-xsKG7$mG|aCy!6&11oLun zXT|#R_OOTkgG_wc6clt}h#`vC2ZQV}ahP;)_$=*Z^LYYN!Y6JpH&tfTvMhDlEEPnzq=Xe(G@|{zx7Y#W5;8Sr>p6@;4gU?s?@yU217#nFU@6rOC5+Q;NMDOr_6Zv3E>_GBjx(zfaCpbF*YwOY*$?aF{9jpHhDLrHX6)K0YQa4= z=Xs9)c4_CVe6Ai;`lq|`C|bhkmwa%{`%=VLtUCVtds82k?Z@4l-A%ZTiO~;Ju6LGy zkfM0eoAhZSM?hjbEMe)5_NQEAzmk233+*Qt$j=z+ z_R&fH7PqLDe>hX)zQPflR|H)+KJ`Yenq?IhMYY>qPu6bpW;(5qX8W6iVDK`x^d-OX zXQr-F(r+>KF8VGx+k735ofIgeD+EP8 zlB9Delz=wCW>30pTU?k>YR(I)L&AhpxcBRRL4te1b?4|bHNc@TCfq{R*vNRvusA&X z$)g5`TBbNlO}_^gTtVZvX-#>EFx{s1q}P9cY?;eHeLyq|Is$7f&h-y=HlTse*atfx zPqGbuI8CHh{Y^Ulhtq&{UL@TsVA}uV64kdmsbWomJ1cd!`eGlSi8?x%IqLXCl$!5D zv!06)i8or-czIbVG2lC{k27eh^cO|G8QxF%c(co6rrY3A*|seYjxaF4f1Id8c2 zvKt941y~eiR)F%_*bZM$f~5kVs~_U&SXqrs66J~oD?{&pReo)7i8g1*>V=z_tar#D z9Dr8^@KW3^jz7hsv%ii6K-%*rW|K{SY8JnmThX$x>HgSNSp|88#w0+G@^p&tYdxtp zr!V6fMWtQ&sf-kl48FUgK&uGvFpr4)yf;muqpxx}VQnuS(KI^|`W}zFOE*@5?QU`Bh3P0>)hKMo|l9a4xlfRsih8qB-4&GO(FB6Uy8H5|%@|x)8w~vD8XP7d>I}jZ}hA&&+@vj6Y(I$=4 zr&1z^q$ti$&0Sxpv{&ORgnV#mJ*x7Sk2r=sd7d3<;F3kGr7N5;xMkb@Ed%Sj5NT&O z#~N3csvBik9_+Vpno-O-_GxQnwa4yyZ4@KL^5VPbXDw0q4?_E9s7_&xmW&?@>OCwf3<%{jjy@T|l_YV# zD!yZ1HZ?}G{xJPCo$11oBurfHwF!i_l`UCi@Lc3c#<&M?2%7{up9UhKkjlLnUOB)0 z{r}MkrG%Q9{_td@k&8?dABdS15mQet#%=)VySaQxeq1d{2v$S1t)`uP$_N-GD6r8o$qI2uo$YR)(Tg zx_A-zgX7NQ1$nY=l(?wCkVnGk+|3Zrc#!L*g0KO%C8m!mxP}24oE)T?X ztaj+T`K_q;hRrW0;E>|aK~ORL&<@GKBDpO!Y1Nwc#NZ-`O=!F82HrwufHtBVDA?{1 zsr_?#%sI=ZC1jYtnm6LseWsP@-Rq_VxwIXx*nL~KCF%HpQ^R>T?eaD3t-MxzGP7G+ zD?x8Oywc^sdspYjc3rBjZ8&tT8u9FcIPefT)h|Z7Ye>I#n8BM5bYqj#iOapp(9!ng zDv-r8!B2XeaFaI5ev>9Yi)Q+;8aPDXDA?Fy{kH?_PuS(xGE&x=V58waJK_gUB$6a= zSvT-1J>%-Vo507@r)WC)ZKlZl*$z8ravBkN{!=#dRWnh-Jn(mU^z$``@bP$npoU$M+c$xSd~-g<0q;{x_+ z>hooq5sbZzbe^eTd;L)C^FpPM)wWctRk2)=qnJQ*(*-+(*DYvYo{0_tD(9;pdV@+~ zc@m(&2o|sjns<f6x%!(WBb=*ICb@i~VT z`JG2t!n;zoV#SHrDIPgL#oTAiwB9k`q5J~f9wS&|xEgqf&HA|0wljZ>LgEYjoU2ci z%h;cc0|Jx6Y1rerqJubmm1a2ZFB0vZT;!_U*s^#m=R1B{DHGF>Vl zw%h`X6!Y|?m|C*W6x%5#HgmgA+fMGX7jNWdXWdItkI47}jApF6BiOj=#&$=pO;07< zb%R*Y{D^&INvo&j7F$<8*O*{Ug6@sZ9N~OkXj4TM+F<6ZCjlPxWH9b?A|F}qhVlV6 zBA!F3xfOc(yF-|9b@?pxS>owMv+Z%r`2gFUe!+@G=S}ucfWIKy_0&!7*~$RLUkRNj z>7PVwCSNDa`}dK+iV$kW(8Ls_vSnKsZ4Hf=n}$>x*qOD(E{k)9pTcduVI@SIeR*J) zHCa#2Mx>V&H_1Z$-EmiBO|}1IpLCpY;BYGH!lZ&o|LC9@R7k37m{3S=fy_u|!*Cvq zy9j8%nI-N2)Pu;=GHPPLm2i67Y5B`>{asyc%pO!c#2u>&o0q}B_iBRP`n=uWT8RHO z1%u|9DxHQ8P;xJQO^I(@3DZrJa}c^G1hn1>7Z{r}i2VLLT5G%vhlHbL!Aq+uP7gVe zRZTF_7T#<-hBSAn*G?)Q=f~qORg>DCVzv~{vTt!01TO)U3OB%9L$T}nXy5myloPAy z#mh1$!Pp#J-B{C^Xq5{2KP>l0!gyqak1rm(Li1bWOyvh(S=>chYlD+X)F>o}RylBuSfS@VI30vcr@S17# zkH0rPHdY6^;<-8OSu{)r^3WSXRwtD&f$^#%`99v-Vc3Ai&mmzDx@j8LUP!uBCt$Bu zk6iS^jp@){MqOf5^+vi6=0s^sy_+*@(#C6_{i)w_vgOn)2O3?bvNa8hjc0dv5%_ah z=J9A`MD%vS3GDc7)yQ;Rsq%o&q`y=ZZuBw8R#KT>9CS%SX#eat8V^1m(dkW`S16He zW=i#wV3zs4>D4x{UicWuvfu0Aq%3>amN z2mT2BrJY-nI03`D`^#iFHSnH}{=-q4*?-gu>=xBA{$jr-vnu?4I4)PsTmF~-!MD-4 zj7~a(Bn4CPuio@zwp~&1!SL;%2{E}#M``cimhuE6Z$g7f>VX=;Foooc&);*eu6TMi zD12msNF0_QgTae3UNfXfgWz@NQ^*4Ow(a4>vkWs03yy1wQWfSzQ6=emR_5QFO4|Y@ zd(5WQId7b=YML@CUf_JO!L27wm7ruTi`Tg8>vDwDyFWP>x$zic>L!~!rFwd*#(Zb3 z4_A8dW;Y!Bg~ZC7NAu-(>12(>R%uY1&eoaTc#rRKs0Tee`gTJ!t`2vi0HJj&#b2w| zFQ?AP=Y2}G8>i5co)wPNX%#EI&3+YeiR#kITS0=T=H7)o+(r&H{(-i@wfVu83#TtB zd@qxRI2<)ybbsssa|HT=>n(8zPig0}3gtLYLyjDaXiQ`q2td!YQ_?qkLFQ zL&^6re=|fQH|QhM1C4>{l&=(i{WgpmR`o0yEbnEm?Io(3T~%JO0*+dyUs91@O80_^ z(eI@3AkiIWE~U21yC9XZ^!^C*54TW@xNiI42m{dDVyWn@m-Mw?+fV7w*0fBkaeC>0 zb@;Uw+v|SQT4|S5_Vs)+sC=#y2gPdaKFxISvPN+?yg&jdvzWD#Iw`3}_GdZ@&TKr4 z7}FI$?BXdrayPGloiE!Bfi^;{XPpA*T#8KAUhhXT!AL5I=jSY z+GNjtzT#QE>#?inb4!;%Py6_J%YesHC80)MsoqBT;!|7o#~>i?t|^0`>+Xdc?~r{v zT@uF#^Q=o}Ywp=c-ZuRa<^(0xxn3&FvUGQ6(VKNhnqa--c|(|22;u)l+FJ&-^~QgjP}%~;-KA(D zNO6ba4#nMRu|jYH1Sn8kQlwD46!#**-K7+l;shuT2^uWF&3|WhXZD%d*=J^7oHv>C zB9q)_=05lL^SQ1F{S94m7s0#$7(Gt0p+?Go;>9}8W5=E#fEbLPTBZBEx~if6Tf43!iR2ccOFsh* z94(rzUpkcvXtlL!wx}v^%fjm_9%V|wv!~OCit%h}x2OPr0E;2I-26tDVx1)5!=QG%WWhw~=?C?&GKxhe0fzwR z4@R#7-*|>;?1j=JCp6(qv0+fC6c&ghRtdxMgysk^hwju>Y0X8Yu{Y-h0DU`ti%w)> zl~OxI+OTKaaT^Y{u`l1}b`V!g>wV%cHC`A;n$UwR=`i8WFQ4({t%YWWLXRQV3RJY~TujhLBm-Wx1SG5_K z7Jg+-2{($Ut*KN2KN*L9SXS{QDzD>(1EV?}U{!5Y3hpX9{5d&g-ejD$>c>cvV$`%G z{mT9j6YinC9jUcaywAc*iN|5LHDMXrjowv|gYsu(hYvU#^|drlW3`{Go#Dc^6@WiM z>rcZ?Z{5iBb&787!3fU2g4p(u4sC+%94roTHfB_5y|hdP2+}9Zk)UVB_oJ%?xS=Q^ zo)R2+U02Q5WbyrjIx94P6ZqJKU9fL0hk%$Oz3QB2trT|(2%4)tX{c3*{r*k(7IXxl z?~tvNtjyrzq$-+SMMaM689HdL*sT{gFL`TQ6VMGxsz4CW2DDJaooRYWe9U@L>6v@2 zb!D~^;W&SA>Qbepc8FdUe8~v%%@>*e(HZ^3u#;g=&4);R3E21)%Kyk0Jx*OPl1;c#n@8$&qY#7}9B{OfbprVyjcF!Y(au*5`dhmI{ z0S;w_?UYN#AbBpD@c;@Sii)#;>Yhnh_YsG@0Nxf#iFT_MUZ5EmOjtD_!G8Trk)@%w zYjRNJ+rpEOJk4Obi_?z*t#6wSL(vXL#Nc}K&<46^&YL6qfU&j1llSU=6y_fBb# z?rFVU2kyj>%lzv_d2Ve|ZL+E%mS`1&zUPj#sg>eEUa6_(CBT#<@D7c2V!2`74wp|C z)zI1n@EMqekq&V^5>Hq?M`N|Dgn6(5Ju1uBan<0i(2HW9cu|<|kY(?~9bd~~lB&+z ztmGuSWLA}NYNX@&)+vvqV@UEd=nAnRw>z5603P5Lzod7z7V6Xg$Cwfump(_d*` zVFi^(;Nz0eKP_n+RmcJ~OXXA4OA=drIws>fe>9uPq4415-Z&2@e&zYAs^sqd4d|Ql z!Y?HXkFkf7tub#WQ8m@oc z2|x3|478_`@i&6wNQmHg#dtnt8IO%7r_;KP)4#+pd}n_~`e}FH5K)Gnov6^y^PD#XXCz#4v2>D#3cs0Ha{2=7QqRt|QjF!G$Q>{HNGa>(5O{@6ppqx~vL z!{WN9=2kjk+osQozdtB9Xrs#4PupBpZ#nc#bX01dF(51{Kvou>pS7b)q*>$|k1}}c z=ld`^P)ISWr$g=fKBh5#TEJ{Wjw-=)9BNU)kiXdC5qr0!^_2U8wvw+3#$KQnm!SIG zwQpEg2ejW6j7qa}FLi0Y56QLTJ>4N0E@}u5H$Es)#MOv;%7#t~eL}C)oQo%qGQs5W zF@7t_yC`x!E9^vaJ!OpluM4z!$~U-jfVg6GE12z+J=F1>{{Rk|pZYJ6qv(1E+#AV)~6X#K#R^=PL25S?5?9AcH`{{z1-xYtx*136bS` zgMu!d9Jj97w$up+U5#)0Ax1eZYn~844_%>(tAANtY|o2c;>|}s9(OR2O7nj*vxPqs z2Hr*z>x4o*RyE);gA*2!+v039or*4$Xqofw_hA1r9?Oba*QPaxjl+zFgDDLogG@J( zFqOcZ+{a>ksQs14^s47q=27(WX1}GDtZAy z1Zd+xccSFvAeuGzGK^BqLKfu*8#|41Xu<-C#=?4 zW4-QQ%noXW#s-^%&#EGxFR5s6AK`$?p^hqsbgGMt4--4p+jJ>0=yH!(x-a zjfF0RlEP!YTt5jiy)v^f>r4qN?!zxZ-cD(3p|~H_5U5{=1ixopwDC34M5;@a^6#+Y z_dYoWrg(66<)gPy{5*3sgrTLKuPUocCXG5!*d4lmOI(BT$n}5m(>XCk@zi$$={*Lc zWn{QW)~VlqvV}_-c(4ar{04TNns!ZU3Yx$0p80JejZr3NIq$DlnWk~^=9T}q^|9M$ zke1&Vn0hL2L#?5De=VdwV@qHQe{LxsuRY!)*}I|ctJb!Bd>~0Si%5eQn9r`o@$P(4 zDx%LgHw*e|z#4g|XpVWE883?k;#5bvyHvOs2Ng7NLqq0sT}#SpKCsxue7q;G5`D7&*pAix0T_f zpPQ=WztpiTDGe2fWcL?4>Z!BS4^+JU0|biH4Xa^AzA5|n=p{maK&#X~-0~v1z>R1F zm;Zj?K;~FVX=Z!T{fs>r;l{>HZP)vIp9bUARTw0nW03>y*Z8~M(t>@I-{al>rbs_h zY{(nrV_Lr;ye>KGHpXC=iZN{S5Kt)D#P@I!<-{DyYh0F_W z+sbhrd8MiMfx9NGQDf^mB*hq`y`9mK~5tmp)U z@p3P23wHp#{9cVUp7f?qQS362LI1;ukt3+{JEb!hH4$sCNx<`sU(*`n+IorFb9$=a z679LV6I+~~gw zH>M*7LkGgQfXO5OlOS}xjX$aVB<4YGcq?aYY_aPo;u4(w67@^V6|&Gjo@>>j_<- z*A%~&+;OV}p#y?%>;fH2LiDEeYZg+@78&2d(VNBdYj-@&=^XvGIY-lTKhbaBJaWsW zF^A8VYi%qt`x!Y}I~Vw*#r(D(%6ZvRjPL#`%@WGL2R&A0BR^CeE`<^B>Lf>Z85{ccgiKXP{2$kKZYxJYws}o_CRNHn!6E zo1#ui$&D9wUBTx^z44N=FGF9}*lsq9^Ttr{`?PeFE>BtHRq>^7?pB|ejLMFU$&^ej zBmOURx_%*Pt8X=OfK|%i@B^ z{5VBXeqQ3>tp4si)wM%5naNf?@XEnDL<^r|Eobxh)$62mhYwUh#aB{pi(K>>%|}A0 zug6>y5Id7c)qt9#=9z;_W+~QUd*# zAERTn=Dq)4RZZ9-z+bW{4!f!Isvs5)Gfw94##tOvJ6Z?M{ z!&OzHzlkNcV0m<;tLe7M-B)dUYdmJDN5~&cEA5d^$nN?7Fm|-~gCRLaJ+hmwVTkfp z`tTN+3df_ieR3bo){{8uV zzyNuf{PFe~7jGX%G}|?{h*@#I)Pz#KU`VaYa}aiIFj0-AKQ{H0Mv>&%{3jN5EneRK zAL)z^QwSn29YHUbO?~Ui-v^U5gFc;tgRI}gQ%t>yx->FO=xBPpvC))-+jhqlMreo& z?_=htZBwCc^(k*x)BY2>yxw7=NgH)sh%|wdj*R5L)Fs_?YgxRA zi+vz>@O@5L9N{%5Q{{x#(4w#oCH;nf<+HS)ZMlPW?)Zhv-?k#KySz4uYEU9aVFb0l zn^?L)rYLJ4iax#TOV7?ewqoyca!UJ*)#VMf zJ_K5|)W%+y`vkN5pi`5G{jJ?iLXMdl!;L9Fm)$-fV}3!K_^>)wqRB)lF^1jcGx2?B zh%#(5+y?uqAWF<6;*Gn9LnG->5b$DloSYu>%x4JPO7r;raz?Mb!kS;p=M zi^Auaj}=AfyATgob)t7|eaBkLc=LXT#$RxLL?5S23g`6_e#yV)$80^0cL=$7cNc{r zVMI^T|Lu5^$Id9a-=arD`NNyHs#$AuOI}}zpY11etB`_^G#%d_zK>?D#W+3H*J5z! z&+7x-4vDfEQ``C+uVhbSzl<$kZzY)z*9j!HIEj>)VoP2iF(GJSzFbM?A|=)(AM_2w zzAhjH1;e7Vs*uggYX>uqY8_&ypTIRO-2@?Yh?o3d&|@UMr1#S&--o2tU5BJ)rU1@T^fde|j3ms-3Qr+*d}n*Qqh&s^ zLsVugWQV~pW#~h?L?=3VX_FYBl%~f4dJxsZ(xSatzn*R~tP-4^ERjOI;x*h4_ zN+pmSxDo7?-Q@t&#aVt-Zdz20bl;nOW`DFcs%|{Ot{MdC-Jobjh$R1H@YwBa!8)mW zMvCW@w|pRARgyW76Jq?ti=MteoYJX&2BzsN4CP{u0^;F_1l&{eyz}{+UsJ?~Wq78# z5dr!xBSY42=D-pT9GU+zp*>w`4yyC9h9sN!Cbhh&$IZqq=yV7=C~&HxoR4Swu))sy zI$9+VO(znIlcp$h&Sypj*XjmyM(?*?o&bxmLk(D8DEltT3L{<6j9_G;-;;^{!cgXN z4XLTQ@Ovs(xUM+tX9=!)n+pGgZimh9*G9@_(0_(cB_eKJbR(hUolzLs>&9AX^A2o8 z10q*8{paM)_cw{{C5h$6$G6GB!~2y?TK3(+==?y*qXoRW`xU~irX}vRk7!O%LR#cB znNcS{ya#PXitY$F=dZ?Wn- zb3;Bwl@16rMXz+Z+#(=X|T zT@-{80|Rp!E@lU9tJ)^#ygTC6dt}QdnBW5_G-tE$!4M7HrTz~CS-Bl589I^8IRJ?X z*mx5;bbC8zvExW;&JAEH=jgtuBYJB74`Vm-s7KFQ{U9f-A-b&+nXsiA1J!mtShs2d z(tNFzHT13&zrrx7TuS_3s2=72yE4fC*ZYbmc|o_QW(YAGbl_i;H+bMCBS2^h+gG+We$$9FHsEWURktn{(Pz z&uR&)8`*6%gN|Dq4s60RG6KwXpn<_I1PcS}xs%*yY(5(ug=H&$;uqT~a^rQ@Pa@;* zID5lry7`>jwby9HB2GMN_P%#kFKR72tVY_{Jd$@VqCF;?noFH}Wwn_VmNA#^uN7iH z3%pXuS9ynxs4JM1sDkb5^RDXh zf|NUBQ(VK6#E5@EcUSc@@rFm+C45GOdp1qp13-kRcBR;u2g9ISTE1lX{8HXvQ0Gi0D^23#>)h&2(3_cAj z@j#q^kW;DK+1mx~;V*`-L!=4-)_Gh;Y3Vg}4im*|b-#*uvicMxrb_&*Y0*co*Aq^y zbFT%)3qS(H*gKY}BJW$t&ihi)G2vm`p7k+KrkWs~I)ug%6ZYx~(tKrB#)=$`ns&A< zg7hc)X&@qQG_8wz=ZYkHoS(2C#gJkz%c|Fy=vSvCVu`pnXhf?&=Q`fhlHC-;3%BM`ei`JFLa%;Q;Y_}PUwmh?v;zAK%-DlkZ*t|VOO1QJ_-Db2J!g{fM3Fd0U1C93Yl zI>Gf-XGos)T4aY9={6jrNeg*oNvo-y*2=e~XZ#lDf>0e1FdO^e1+#cq=bcuKv+(bI ziGeaYSiv5NnirNsDqT-<9P)4~N1bhB2)iYEU^9N3Q8B9E_d#%IFQ&MlZIeG4d^+anIL zGfF~29O&BwGtfSb_E3=uIO@h-%p!W*7bIdKev_qi*e?D@+~KPF?bU*$fgWFts=ixR zo^B%8Y&)H7d7i8{&B_LeGMiA zG-C3(X1J;NI8gEMb>ycZh;HH#9MIAlNR;m$d>4;#jO_!dTG%?^RvC<5L8jU=yZ28w zKbKm3^3K^}&}+24080_(28p{j>WT54u+q@VU0K5)67PF1ejlb0kR;6t8$E|E|9~ew z`X39dq|{9?28!QI`Wf|a?|{q~FIgy##%H@@c=2K43c~W2(L~wt7V6h-t5%}(m21{I zDJr_})Q7cwNL^6uUq)*_lyhd@#$;^1xrH^!GPp1T5W0y?Pk;gWS`j_wj2BKATsrD( z_a>1XJJaV~Q!aBTOwhf%uM2H+gV|e)z`As=-I?vu9oBpwkC|>#C8Jt~%6D43 zza9#$mW-Phe;#RJWpikwsqGYTO)F0?Dg0)ttlR|UIkbL@WO67OK(nWD)aL)pWPQZQ zd+MFixlVx=i&D#42icZ*=-`t`R#sxi^T*Kh3xhvck(NIugfE?T6Y6dHy=&MmioED6DaM@+F1$ zgq6ViXE6HEG{g3)@;?mMhUYEIZ*_H)WoOs-eEd9js~Cy=MLgxvTJ4J=iQ^$4wHUmH zPy))7)chFFax_u59Eag8M(C=>-kfbm?~ftn`yxu$2Op<^x830ftln<^>Q02IUX|{d zxZqCW{d?HrDb)*HKr!k9(blX^!#ILZNc3BBPJ8di^QX@b;QpE+ARcMyi=CB5K7X0N z#E{G%7y%Up!ba;c+6Lt(b+?ezf9nhN_JP!_GJx;Ddc|JJQ-=a7bNR9eFMhg>fk+_R zjMwAl&l;=<<@r-(jz@miIj>#8rQ0t~EHIpM4S(R}jnIbYM_Y@6+Gbstz);ASd{;{K`OIkAjkt%kfo&=-woK-+jyGiA{0B z)L54!jkjGF8C1>4(bW*Y$G4kqJ}MW?+zWtI)cOn;G<8?Ni11y_9rNk6C8c8HS9O`6 zU+>6$J+$UvS2zCl4JyOUE6z$b7}jVq_yP%P@7#Dxn_$t)$E59vOcKb)6(6P8U2Rdu zVRcc)Q3;N}hLD0bZxR+lDI3wb8uOt@Zlj zh9h;|R@4ef9a3Y8;-cP{Se@4YOsKl+5*z9-H)PCAaJl;mhnaH9U=n+e`oQH!26;b> zq44|Hx2p68KfEI&Gh|*!g_6ICr4JZl-o7vlew86G^ub8_jltbCsp|X60qh?`%t`S= zq^i7VYDjxvBg~nx!Ii zH4tI=$F#%YuqpzlfvD&jys)Ad`T=CCjE^Smiik{@?oCY&SOLxsg~qy%xYrwSjfCn# z-IX<00B(D0`-4pt9o;svLj?qnI>^Wm<+#$CL^qQOiS3HG>M=8rZ8IjCQ06tzsA8GL zA%Dpsf_R&gCX;o3>4$RxjWm0uTm9+=$n&5)j|lViH{H<_t6MaX9e)xBj9q zDzHpsDYlkuAVVxD>Z_3_qJP=gE|rMh$Ev3J*jLID_9HV_-nKBQaXWdKh-}-p(b@$2d=F z%!2PbT|pjDRSmtU>h>c~$@fOATprd4I*{8|X$tRRW@(1fTLJ$_`s@}oeGCi2_>Uc$^9f+wtu`4X(jGu8uyyiZ zK0c`Cp+7+%@`jbunuHt-pkch&4z+rC~UB0_d3 zVE{b!JJYU+GH2zgo8@GHG8AVI5QI)J|$M|=~r6N))}x7ihL5`Z3yE}i&Jxtmoq zB$B8yL^)V>wYq2jY!iigg|JywQ1g&|egwna`dUgI&a!_o2~w@Le2PcEn65pdp>^&( zS8gVaCjZyl=g1TKvzZ#}$#*Zv_5S}|;PZ!20hVGJK(HoH~<^K^U?x4sc_EBLw zBfHL6g-;2y5^_$u1ersdBiorkHq^955DBE2zas4qe$iaa3t-Q-=QL%SB0X)9CN~yz#ym?mZO?W* zB!lkf6}h5me^$=dLHFGFWe6A@xZ%D#A6uG$0ecnyHmT3;mQXAkR);N^r$shw5@#xa zufbfH>?QPmj8I?d1v46RAvy{_yGyR~>@tx#qK-uWvE8M`xuRF^-&?TmRhm?o7iD^j zHreWYl)j=MTOPFu$XAv*=U8w3S#YQwTrmZ}`E*6IJC|O;UcN&+J438nQrvKNAt;?HMjNIw&zB4-763MsDp8M^NKl-n^jaEQPM1UWI-}W1#c_McV zRt1UDYGNxbF;_0%_X&?@^TBqooM0y*=X*e9GIbs6;gGlLZ+&#p%&u>2|4=6>mp+Ro zro+orTATBRFiOMiloS~`*uI(g$$oDCflc7u>K89QF~(eknJ9{+>-$S1tJd9r&}UfV zFBH~ss7Ihi3;a&dX45YhFBFKd(+um$YXaXHl<1wZ9uWOa+rEuthwlw;uvkc~E2uv0 zHJzerWlt@|60Y0{r_c`P?gSoSnF=ztUodi>sEndqmikd;PMQ@6!|RX=NOo3=Ik{E+ zE%234jd9R~SX#MEML{~_fc%uXM{!eR^~()GdwhUZ2fg^W*uA~IyV~NFsD^$LMbcDH zdDOQaza1GT!M*D9{6xn{QW)hM58jVzqg!>GDk zqBAHaZdJr%Vd-Ik4mR7UxEf^Sh^V9T$JAtBU?M7ET&T=3_ZW3 zyE-1L{ufXXa+UoHN?2qHk~Y+q*c-e7n=0$EkfDc#2=e zFgcbg?6sU-tt_G8ex=#)q^j_#00bx2=AzE?>NK;b-o!M@uN2Pxed( zP=*&@q2FZ32EBM&r>&5adH{-CH7`oPFk$?bKJ)QzD<+i)zzlvY>3L^^ildvHJIgR*B zerlQ6)>fgm{}01VIQE%BcUkrx^Wt6Z%|7=1{nYcJO&_j+$Uv15gS%mPnS`)P}8O@Iq`2 z@89kjCpWgyov_g?8_WHb`r27)KIXt~H_#bLDbqZ+hsnY6!IG&5MW~M?rS#ue?AJo^SLOCrzQqer@hZC=d5x6= zleulTj$1(qr{}pr4<`KHP;Hp46ysi_S{C4`))6j~m~5k^SiHkM@#>yI-(` zd&!?G^_R2bf#{=CDM42*vGu%G*@^mc&R-9F1i#(HrRlGko?Hp$pYhN&aR*1LZ}Z2X zfnqAT{8!q~f~!>QtM~|U8NzGb%<4O4p)^MS*A7Wh3$NcS z>1{ns^PdtsoC-j6+>*{C`pcS?Qx-^Q%}lqAR5Y1fT{Q;Rj$b_e%nhlPCP|wls#tb^ zQR^U=1T=djMW*@v40Gd%BzO)Si9ELSm)NIpouz7Pi(g#FpBwGdGxT%N?!Y;)Flu0iY1D<4 zn`?a?!4q)bS_<=ekOgbSXrLSKCzOP7*tvR~6Q{!<>SJr0lEd48mDA=lqD+RhmS+^C z^ccH4Y1bt*>&vt*jB(ye0_)0BJ3b1z5UqeJf?Z1@@z!{BoUSUU>!(Zh+P&7kk21Xr z>pq|ppPor;LCE=N#1*K8IJGfS4lajRsrz(&ddS~{lWkK)fIq-59tOKv6lK<^v?{!7 z1_kQGM|5relpuyiPEN&Q&UdF@Hx?K)Xd`f_^M1F|e{8G!!bJFJ2kXH(l8jEM(=0oz z@U$z?-E7hdZfREbl_T!?cq*jKU>A{lZ-*9Xi?RcW3l2c_A_B^aXW0o^@b$J=|H z>VgbzH`VaEN5Gx16`kVzhxy{B2LURQ@_2z37iqt`{67CU$4^4)nX*hJbudz}tos?5e1dTys^C(kgY zs3XltZhKXlF)}e9v=~ACgo`aq@j{Y5pkzhIYa?5*jQ-d8J5ttqj2C}4(j^4HQlE~v zvTXcF2|v^jWS{uFag9@`z%h%jmO2+ zE=o*>k{>Dk@D${BVmGXK0db8#$@os6Ol~;f`4KYEL&hJ`&Fm7&ojM6D{AKUhG8}-_ z#~c)YufMZnGC&lUwtDz-|9$giF}lm=7DcY)wH$tGBLbFfo(6`#KDfz$^HsG-UF_bX ze&vT(Vu8ke!3YzfES(!=GaRY2scbP~%bWjaSHSB${JJ(C+<7>mD?3bamnZS27RZM( z&*YUBf-f0&J#eH1zbttn=` z(RitgqH5$jLHD%(s;}w3L**I=h|=iYzyC9qTIdStSc*yR z)qq+%&Z_o=50&fhHJ7y`Y58dmH>40BGkvqIu9G@HYCCTTP+okNwIq2|GWiLTTwH$? zT|w93v;ptBasbY;I#zOBQ}zP!h`KKu5;MY+a#qvQzL_RL*3CUV9bYKFsZnDr>Bw?{ zp6v`v`WE_8`vQr~geC2a+?PlxdI{SOaB9uJ2UT2LJTBQ>F2O~koWUj!V__~5eD3bj zuS2Bcm)@^=EO$|tKZkXHMvp?H|cYFK+T($yDVD-S#DSEinpdkKpSG}QBZCOa?gMk`N26{ zcTqg3Kj=)dG|^VV6!CFBUsFe8%ia$vQquo0-mTF-k^Rr?wedfUS4@V(5-go*GrXby zw=>~CjQ>-burK$Qa|DGwBl`>)rnB&9R%E)N#Bs@-f2ubpC_wZ4-r=&&I4mIyKeH~m ziK!ojxG!AAAQlM&=Vy++`tN9xaA39E$}xuAb&2HgKsDBS5U=nD;wwUIYuB0hF`F z)1w_J(|e}Dw3*8$yNsEz9@4|i_iM|?E9rvo`ifS)k<>Tnh6PyW!4PaY=ZC}DwfJ*^ zx9DNa+*0%8#7J-lVu}IYr6AM)~CS|3{fI`2W0Ni2)J0!!&eG2YPqNC^%~eo&7z& zx1k|BwST6kR+wWK@qBRKdQK-M?fw&-}JJ0f2)wU3)u>fWWtrys=K zvqIPo?ebf`hG2u-^bi>x?49}zrJ5V-J?vDR$-zr?huv7{GYgMjeT7{JeTskI?!Mk9 z#^1^H+0caw9MBp~HpdlOXg+T^%leai!7x(K()|ZXQhvN4h%_q#B@9lp=ht|$UG8Z5 z5MxN-eUTA=)_Jn|wl2PELPO`R1#kD|?D#K3&-t_}y2-QKheW*1XzLeUSy97TGELui z*@nCdw1P}B&7CEeKBL4ACEb&bd23ex(O|14?(EsE?TB1W#R|{S<9ajbX7-8i?r(G^ zzQ!Y!dxCNxOhEQ4jH8($25KVs2$_*z84gH|+2{=4-VBpq3xU)g8pQNW=mf{+g zZ;Ir6g1>#|>o4)%XAT;?@fC%M_J8w0vy$q`$}g=gC8mC0mw;sMu#I|fC`8vrMG51@ z7+>&q;1;r=L^Fnn)>u8U56vCW>=@Gs_hnPsjec+Aw!_dj$kS~b9GmWI#7>8u&o(;L|8#fzrM`-85iS4iGWi-kj?kzK^`V%a?01l|pb=oF)6Pql3XVt8V zGo?>t9tqQI3*5CoJB%fQLECQrscMOd zIYuP%2f<*+h1jiXU%z~4<}9EKe?p#BLpA&27E>0O5z5Is}Vy2{`MW=D2n37 z`s`qfoCMHd0?mNWY${u)!m5=;Klb*meq-Lh9&*zroavnSC*^A&6hAhPQjwtH?Pa`@`Fv~mR89&c9N1pB7$Crj zm^wj$eNru6VcdniI+PZG*?iGQ%9M4@T{XT=JWGNZytbFQn*^a6;ff=Y)=@;U&`H*( zSD*|d0Sz&g@1qWo@>=6L)#=wMj%1B$WpYBdRYfsI-)2ZF#@bG-#b>+8R149wUa9vT z+UDCDV~%$p5*^Z}w2bOvaFsw+3UE^n8QR!Pma4lH8Rw?QZT7nG? z*M$K2W2NZ`eQ(xyInsrgs%S^x-EBTU$GbUZPYNIG3LKq(V`o_IVqVn(hxnbUKxxLE zzq(TYEvn0#l{_a_qo=?3QTRkuDqI@YsO(3l&8C;}3S0l(v7RE5j6rRq8Vs>oLO0gs zW$8OJj#V47*W5|}G(`XHC}-(xR8_0J2Karih&b8{WF6Kyfwd@^>oBa|VwYuD1*4j(m5@X9#F^@smw|SGS zt3M?VGLIt3^Oj~w<{v<}kvExBI<0kY5n;WfHKBBFi~=o-W$0qUn5H^$UavzHQ%$hy zATY6;3TaTf;(SyCa|bI>jX^#2#J3u~1*SCan1*dgqyu0z_K548yXvNgJL%!MEveTx z&wa0|jkFY#)(QaE!n-AtKTQN}UGkoXn+3cXJ53B)^lvvcYlz|*`3&%5NnyE|H4zl4W8x@v~vxw#S{NHIp> zNbE2>GIFg%{dIb~k_Lf&@~hx2O3+TUT;p?;^G45-#x9+cahfxQ+fP)%i7SWkg5WVW z!`QGU9c+<<0J&$O{EE(*2^498y@Fr5j68`H^M7`pO*h@wG|dvTxqV?>-j9D+u{f1d zhL>ctz$}nFCx!Ki6T;QlpSB3gprE^C?iw!skEcHKeRi;Im#Sstg9cInfn_!)vec0Q z5S=x=8^4GVNeZ{NjstCt+zd(GL|Sy`0Bi)S;`JGrkhVLSm1-@)zV*OnCR@tCo;rvm z8(Wf+kp0;>pvpSIrc5ii`?D%SFBmI+cG@WE_valtbREhKPeZtdJP?%CHf$Yj5GTYO z*W7#(iCp@DCb^NxawFBH6*h2wbtccgCUwOXtZHB$7QK~zwbe_vi&c7QV;MU6?@gGK z9UI#2x7yfo@`+ezN@Og{1@8{!q(j1yS(pdsG8ibpYpQxaujNCNRTk^%;H}COUPq3c z+jiF-DxmT^uERgbxX*FPAhEO#MFMOEmAST;+XZJF9`yfoPs(o9!hXBs}MZ8_A5Y@1)SuU&m$Ai_y7u5YU+(cD^f ziBFWSdaJ!DZ)FnGWTii%Gy`@j2g&}~RC1SRY3>xmknow?L-GBG@y$D9CMw=}1h4Ct zz?s_$_(R!PIqFXjk%zv^LeufQQ6qDDR)ZQ)exu8LCP`95omWSVldCCs;ZNB|kJGVv z`p|zeYg@#I^d@80VsO!-Kv)m)al331W5v(ET8w)$@R>8V3&4i&F%iXta|#4s-RIwM z>(}2!iG=yzMjzkIT_=PDz>JGRFXUZ$@CD5Qs59f`ccTYtb&~1n?7qI^(lgSM+M0@@ z$Gb>cK`M!~(=f1!+14p~1*jv4zJOILL9zt=s-2y9PTrR#2GRgh7fqN<&_1NuooovotfU4m(=m=EWQvo444#>`%Y_|{@2$?_V z(U{Z?F_2x>P=jmB`Im@ew97{SyOm%&F*63GlQZ4?ZY@@ zI*BS=7>Q@W59%LX*cPm1V1IKWTF>JrmqHmI4d<@L>OOSOpA~mnS_#iJ4jzrLeUT=F zu7EMo<^qsnpZQrqRh)+iZtj?S>G0dMd-^ME@#-)VusgCQq-bN=HRwaJai*TII{kZ? zns=x{NB2uW|6qShO979reUht2dSD5VWp}e7CT0gtzA^!dKNO)pB^V3%92>rx+KE`~ zeD*rlpK>Z=2p4rDK3b>0D9!Mo>S~PMd=3-$^zpZcBeE z{5gM%s6RY5s@c&;gQ5G@Zk0S_VRZNXJNo1+Q-|NN@0$e*TvItndLgNXEm&Q~4rz(R zFVxAyzZoTy(?iU&crof(8;PwvJw3T;F!(2lSTlAL$&|*6TuesK)m3`U-~}<8L)}7i zU?KbotRo_{+0hYm6EfU2XYrI@+s&ww-4fktQod%jlJb3p5+k_$e6c&ENzA2cC6B92 zTWOSXc_44QgIKj2u+F+9=L~#>CLeAf+c%^pMW5lWVfr(jGTGGlzSqA=@!V_)W6dGo zJ}E9esp$aohzk;`G3j zZ9BKp?itRiy$-f3KWJF}JBpp*}4A+g?f5j$md3Ad2Jl>THIg`d5vlmTp(m9G=CCq*d}~ zx^#!T*2=_&kB@LZUKob^WpuEjC1{zk2=4`XkLZ< z(hi~Wau0APQ|D>XU|F-!NPgh0;O`6bcl#wm`80#XU%iYoTb6;u73li(B#H z#fu~<5Zv9N#T`PB;t3kGlm9id_S$>)%Qt`1(V*1%&tvsI~gyz1xRj z8!wbx+tv|YeD=M2`s3slvV;+N&;SOVwhoR!`81f4tu30`>(!}FE78vmpbcV%M=S~^ zLZpPx^H_CeOKf3a?#uh%RvAmU-$IXH{wJP)m|&!kFertTmj8X`=md1Wap=Lr1P*}N z_w>m1uWdZ=1`I_XUT)|3sy9cULUP>*f2AKQz!lE8Q2Fvd5nTrdU-@%)J7=Qx${7Be z&GyD_#=6d);HM_TzU4ml;?2fh2+d&F&l}DyJ+OJa_YZtS^{lczp|EM?>7#dC-9xcU zFBX7nry} zGBl~vT;p0qD!Sm}F!H{PPa|3Q+IpA8;e9(UplX(!C1!jIpB{`y_7|DStBgZfJf z7AJc#A@8#PSFvd4f5oEzu$G+us1qkTt{O;?65G=G235ZSU44v^_BqwZ8O|= z;?O;ctFIevO5*lbG_{bb>16;BZ~}Op0#7NA~0py15+f0k;46+=YuMSYn=?I~nO`mUPrEkGt3O zO*lxWJHBUXuwHj6{ssog>*QbT(X9wqPjyZ6GhT!q)Et=bq8s6yFI~CIGE+VZbAg+8 zJ}l6oOt?1gfk4#NAOXGAVeUJ+BePRr|1yT7nuSeu5M4V{&DB4)I(Ut>dj^T>7bb=m zME)K{?mXR^hA63wq9bi^==WXFG$J;~WxHHFES3-t-Ts-X>gr;8M@p|re)J$~0ZQR> zM{WA1CE!yA#cgk5SyM9!B5n9d-!D~#n}y})=isgn>~03Vj9EDqfO^^EWsp<+wqIj? zAR(JS8{4I>1hu)2LBn|~edRvyKChkb`r_Q2^&e#w0nTvO)V%S1(CYaNk|L_mu4YA{ zyi$eXGT-dmczo{JjNYVH2r)Hv<;@mCYZ^D*Ujpi!8!8aC0@#i4!0(=cF~&XP@9oQwt8o&pL=4_vPvDj1dkd^Q1LaM<~asgsn=s(j+Qg zRrBBnu+K}FRp#&z8P<<+xC&0{Z(dqt7Yyb&;nZh%w5`)0tLr{~(Z~|B zX}7djq-EcEM_Ae1Etw!h;BhOwRJI~xE>tS!U*6IX40zObIwCSIu9~Qq5S>+o*Yv<4 zE$9A1I-cst=`-07c~)hynSs8U;ulF5Ki$$LGZb^g>b<|NYo<-y-%M;F&N|t^tKlUfVx8Q-XAYBR_6){*=XEKjaGADO%fy%0Kh$+{ zU_xIJ@D|mOWkb}y`5garX-bEv^VN_R-?QB^Ud?5hGN!?;p@`IUjy^}hQbL~kS#c7M zm2CbQz$-Lm_Zk&)i+=%KXgOc9QoHx3L5mMhU@~G&AVZ2U&X^ybkqR;Hc~GqzCgw?0 z5`|!!Ywk#^w9@y-kp>&iHllQkpC9VcJn0j2KynW#DiE%(i_)uk&-M&YeOkT#u3ee7 z{MRaPQhY+2n&5C`sEB3IO0aO6|p{vE*O3rdd& z+%#6c;C2)QHaV5F1@jIw3LR$|;it->xK5%r^OuHXc8oTz69HCT19;>wk*S|cDQDck z3?ANoNdwSm6DmqTaMbyEUzK-Y@F-F43U1y<*_SV`;w z4mIb2{MU0u6gQA^`q}8^9Gg!`nJa{I_SfnIimwx?R<^ZxyDq^}m-UIiZcdcfORZkTg) zi`91N*Os(H)nMzdR$Gr53i3QVDcZQ;`Vx|XQ2PR+dLUK`>DdvZKvaRL-{1b36er@! z--86?p4?;CeLji5Q>4=|!tmA&dQdOxfEO1;iE8?hRQ6kHwFSg0-H$EmschEzhVKVC z@HEBo!{|AcYTFV)8FpOny*U%z(R!hFjhLK5Bj5zBxA}A;+0mkC+}v@?+E%V%MLw_T zzyx@!wPzSqT)BX*3=E{z{d`Ni$naEV;w})>b0-K^g9qveVuZ1JEtZLtY*}xliCiba zj_B$BDWBUuCCHkL^OF^do+U*D*95T^vEN~jSt))^>fT?o=%1x(rPt(46dB=Tq|de( zJ%|RX%r|}8_TF1vScG)+~;+U{q3D}g|5c0}^zs7EEH z#6#AKyFKz$uvikpaZZ-WJAZ;0SW)2n#B{K|_Y%xCA!APUS`~Xi_wiG7Cgjsy_ej#-5Z4vn8v{&<|J`orcl&juu-{R4jVTT>k^$)8p zK2hg(=NF|>jr^;L5!Y~&J(LuD#c-|}a*$ynj{FV0O+hiK%Dh5^hnjf%Bbf}t2&yts z&XI;9slHP7Qou*M9~*Nhm-6ZDK)gt z2ABCcx?Ck?S_cUaW9#U*$wLjtlez_hcA!x=M5*qGDgq6%iMbm-jfX70e^@RIt`|@} zBs6XsJ{WhQ0>%C4Bq8c6Gzhb1^{@}p`*aXbgYe*Fb<*{aFJUSDQ-xZFUtmH(N>&wU z@t!MP0Hez1+rR;ZG^0fET`#|RVhVx3siBX0oh6Jh^2J!@H<@?tjJ(D*10cEyo<-BKzdeHE z=JUN8FMXT_d%V27gZLVzor=5+9GUSvnEg;H8?b5THkr+K73CR=*_53L#fOCuI7ZSF zexy`=$AXk^-W1Q12Sr4JHoUJL-YXr8LNI+JCy{rw8_VOYDjl#`Hm*|f)q$gaA`OHI zsj**v9LQqxH3LgFe~8ZVH3q<>gk|d8XT8&!W9PQ6b!CgdRT?Y}m}&OT>VBT-!1yV3 zJTUl{!98K=<e$^%86|y*$+~8^vQD;--*-SWN@93(Ec3Xj#62*hFKvnu9 zrWKyXw=HVwqtd_Iuq*d2y)*2b845UltVlKaVIP=iuzpTlu3{uw92j+oJ=Bl4N(i*E zv!S2tKH@Y98!}O`vyS`L?1^>Oh#U_npdK&y&PVAO*o+JX7ixLJunc{`PGCr-V8K*Necu| z8Gdp95tU0 zU+d?qd1T%g&A*Uv<>2-sT_NtNzI%>bi`X=cnajpYfIjI+qEXz|M~u6OXaNHa_WI}7GC z-n18=T$~s`6e4NiDR-p8n(NTZ8#|Ei{SU@1>+=WC9rw|UOK~qRfTN@Cpy;ji;9Rz# zisax`PrLJ_I@(~vl*(>tpc$b8m2|YeeMe!xa>~C$(}lw82_{~8_ygJiaaqxR6#nGw zZPsq#qrHLzF?sFbU&=&nc9COSBNuc zAbJnU*ae_RTXEOH+vP214hdCwy=dRA@YyFFULeK0I@r(wf*5y!z4oxLH&Z{I<_o!& z@Q{I`(=E5{g{rF4eEy9|5_=lqxFf+M_E+9DW~?{TBXsVe$F8PIYe9efblW_Zok@Mf zZq@5%6mL}zM?OVeh0q~lum540Amdx`;-Ghc=@>_c9SefQT7`o2PMSZl6HCEdEY``I z0Y5MsXMcSMuufQR*7l}5qmA%mNT6CdNa~s3sw&Xd?#n6nOF1_9gt(s6t&DApP^OiY zP^y)kBXh6EpB|YlhG*T-f}=Nyv`ODuHUdi3pWaoe*)(}ESk2TT>YAN*jnPK69=kO8 ze_$>4zCJ6C9I#S#ffQ$OMnNc{WzN8GSHI$2;p44Y*Vnfoi>3-g)p!#0e9d!apI;aI{ow=c}t3irZfnV0R%&DX51Y#wcDI;-MQ=Yp>J(5td`f(uEo^W*T z=g~4=yllAs>)LUP318`uvx;Ud1_Vayb?dJ2k|>lYajk)?WqXI4%s)6zh)xQ^H!WCo zmDwM}_O`DWE=l^e6GjVQ6y^67$X4Z9cp^wN9~Ir08?Z?C&DEq6$%yesH^P@`{~j~( z=U6qS%WPZXv4BQBiAjAl5cFl`aL&9>9^ylg?|Y5hSisQyr-)8!sOS_Vz#ZAzuSfBI zVd4ZcUy!w^@uK3ho8N%)c=2&ou~ISn8_r@PnLShb z059bF;84&jpRnB?u`(zKZpm@k%B^Fu^x2Ya(jxl+fj)zjW|urrVzQ}(4yPTmf!GH| z3UO^Z2r0^y(%crc3viY2F}P@gD&H4E2hfNGf8t2~l%%_~JlYHn=t;nL959-!)j%Ek zMundfFFm^3PyI`iQO!#t49UcDGIApZdv?$w%a07+#yQ>CL<=r(;XmvPwqaqLlou`< z-0>nWRwo*RoCFh;AH|rFS-xV5zvo;6;EATfw^M6Gtu5kr=|v#9z0axSX2P9>m4xR% zWa61xkv+60JtP_4;%Q+zFdQfEU4yqkh?9lX2X*32)_Z@(dj=TxrP}{M zOa3E5{$UNjFunPQm2^#W^R~kclLHA+dXE+aIX|z?BzCQkFL=f3JTfT4s4*8J7Q6s` zP@C)x{ttDL|F1Qa9%*`+JPV+^6P*rt1z<2)zyB(AqmaGV>7KFo3jy6T&b$-S#f%g` zHeCI~dPMsVEBXh~?q#$CdX3zVgp_ft!^ zK?epzo1ywYMVUJI(es(vJKtmLjozQy6M*c30lPKn+i1VfX;oF@CxPk!#Ku(^57&xe zb;Fs|vscvkt93@gy)gl58%eP$8~#0Y`o=ZuWRR_7@%NKB67!w*G*lNs-ipK#E^=F6w8k=z~px#+}QLgx%Vu*}vU$q2MFOqu7~#~(Z4 z0rDz2JHO7&=?OPb061e2T45_I{kEC`zi)OrdY^yS`pWdIBl_A%-B{N>Z4b;n$vvYb zRXzY&@b`4erq8GNMp7)=MAv={rCniF`syb$X^BnK#x#qg zxOS|F;PNm%*LAc&Zj${dU$1hDu2;=$#{6fel6o8H${i5xj-0zWdbbHm&&B1{zxy+^ z>T71ggUZ=tN9Tc;?NNJCYLRPPF(ht%Np60+T%92oofP|L`e^0ulf@jjZ#fnkRp*r* z%)bRs2uv|EN_1q`;##GJ^AleJZ@v5t)*m!>q*os+JzTe43bEG^0|xpU{90pMc2k{fwCsC zq>KL_5VrT{_$ zmf6gWOd8(at1D25qV3;-GdH?iek%aox&l6H@@8N>d&WNfeJ^&C+8qWScw zgs=vex_j^gaQ&sgkq{5@K3}E&qJ;3LXn4e&QYm)Q8qW8F_}`A}dNYnk#j9jSiX;Rb zvX+Qb$k?Ma4&!zrRjYCW1^0F|nP7e<3NUh}-5j z@Py2crbVsLj_p$UedL12I5YR4LN;G0ow_E1ya!I-itD9iV|n4SiFhVqagO*~FdK z1ZV5Bh$@;`NB!+S-SCLinZE!AAN*%vXXkn#H4j&x&0&)0X_hG+=@VD6wJ?Er+647Y zmD59$+092RMo68TT>O&&UX*Zuaj%J7`$aSF7}wF`j8}cV^ji{o!YGZtOg~83rC4$d zv^tif78qSy&9~xBePU=<<5_ATuOUB%qVkbXO))IabIeGts>IFEXyWYxpF|p3L26J0 ziqoEgWHK&CyRW7E>8tWPuY)F26c~5O0eOJ>@_mHC{0$O3P1b<}aXmjlH)+BkcennX6h(Yo2S2YPqn+pU8QRsCV5V#zX#x$N>LM=kb3iMGmeMG0w?*%hyXD>>1ky9>#e&C`E5eQy$6H zCRKi)|FCq*oWa?LGZxd5F1f!QF&`lzX;lRD={1-!*+0-wiDNSlg;>Nqd-w|n{Ym65 z)yhDTZ_)auM<1%$*?Un%;Oz1zGV#)f$?4D7h}0|4w4hH1IXbof zy>OIZh4mZ@KvOI7X|CsWl+0Qa?kD;&B$iM==j-mFjpS~~7{wcrsxq)e9JRWSW%U&; z*X+y-Jj(fSo6(2nPC)&4)vZ*nql05nhn42Z16|KYhPH*Q_=5#|I-WV-Jz8~}GWfP! z@W5V8#rXVrQ2z!TTM@i%I;uJu*N}B zS9C>pNYvx($!~!33iSzH*ehxF$5`T=Br3>gbJm65Je)Cg=C30RTGATHOn+i7?s8@c zV1DwuIz5@;36XvqOo`8s{5yR2ufASy6O=?t-9`-AwCaRT6|lUD*qDsc)fK?{-+u=8 z6ze`abCceIDe3Q~ZL?NAvrc5T#st;Yev-MmC}{?U?5V{t+`vniL&{45o360srBqDt zm&|*z-iF=OBobNfC~Wbhbn&rSqU4S4WcVGI|0W|X+FP|oo4hZ9=>#XAS08Ueqiu@g zN<8VnII8bJ}_6xc6;Y1JnJ_AUdB^+1W!# zy`-+ni8x#I?sh!(w_uumMz}`YWEYjEQvI;j_#uU3;aU3R%7O9V5jLDlK@QCi9-CilWeJR}1S#W)1Jq%!nGrslY zasK_mbcZ1NgJx6@19yQzK0>pxHc@!m>O0By7t)pd=AS{N|Lx-eWN57uwOJ=tSbK(i zN29FrSEh1?+$rsVoQU?V$w&A360bJ{Ee1{;ON^+tUO1aGh6yv&YalRse6`X56_EJt zKt~&Mz{pA;AHYORuP)#fa%v^O6P1vdUNLM#kxC$;;^a2LAJW8dk&K#DXp7T8I@MQP z&t*51x?iePSUsj3&E=(UdIXDK7n{i>ADN8~5{{-cc6u`49L!S+XGe>pSk6 z@Z5s-3D8$GaWT3;3;l7aGs07p=2%Vbb^fqs+G%*mt|XtlZGzrmcE=BdUvlzx@C)-9 z%oP4DWMqD>hO17wz)Q{~9y5g0e7`~rbTn7&nS zX2WJ&o@eO#&`O3OyR$00+CPetF>Ro6d-%x*WH zNqGf*IS5nud0ABwSoAiuh2+Yft276#7QRKXOn{|B4bKph1pxAmu(2F`$W3Rtv9nA>;w~FFafNbAwLLqUD?xX)99?yd%W9CxlRj`s7qFN{7q6b4-Rb;Y z!)>!dd&9e;ivx?8mGOc=eS?T?**YvZ)njxg1&p zB1JmAymwcb0Rq8f6;^c1x|tik3Nh#7oP#uu^D!Q{d4ji!gUb%(8wk21ys7rg%U}!z z@!VkoKba|vSknj7D0?Sjtr17_H(`Kb_LO&6+y`ofexAA!Bm5kEd0oqY%(*aT{ZL&P zC;%Ecuo&!~Hd$XXoSKyqm%P`I{(qMb!c7?eGbjw>%?1^91Y8oB)|lSq6hvZ1u8j`~ z_Lugkg8$RK`v0eV{{Ko&uQ$`VMeF_#%gFSa27PwQx$czFzPvoF+EIpn|_5my2 z(37Fds&xh&B^0h&T*0{qZqqvPLFO9WoOwsRxj7!0tj0)hCu3e;o zA^P{24g1=}!O7HiL1Ym7l!TPql2_f2J-5BOj-wL?0@+p3OK1s<@r5npVlsh}!_krK zHifW`revfK6n9QSa$}NgVhNH7RVW)3cg|l@-C#iDpsLXwjCQtA0`%qFTS;>2kijMh zp%+mkN6@TNkFg$S@chu_dy&{CAAeC6k#l?H-6o&)K@-MlfrjSJ&JaWBYm#1Ai3bi| zERqKo9djYA?vU6Xlwo&-RWD&@S>J z!|;J$-Qnl1D#3i_S2|3|gBAwxUoU?)>@|uG8(!M6oQdrttOS~;;&mI^m#v*+By3xV zV**U!qhLWnN8wL-ai{#Ws0oeo|7yRUpdwD9g6p-!KhHQr3vDw_xA1&4F*|YATs^^e zwJPFD0<|jqHFhlSDT8Zywz8{R$r(oMS5U7+ifkjWGw3>>%RxuMmvyc8xZD3PoEeAd zZZZ*DBGm*bL4rI{o^o{JwrKP>YE~Z#2i1nTl@skDQ95^1 zsi5DOLq#Dv3PDw$CpO?OPGv?iP$yy&91yz=kr1vnTCKj)qBeesb!HiYCu86@ms%wO zZh2I-AC4cCj!=15^<1m@@WcCJ*5<7HdJY>7s>`7x%{-?QJX+t&Jv|tholz%@>+^Ro z!KT9T6Q})rQY5$?)fnENaR}k3{Q{RvFq7c2<%BuYAX95?I0Re4?V`u7vIm)<>%&7C{+#`Qrj&_2aF|=2ec`wYHn>Mm&eV!<8(S17Pl-$I3 zUE5vEmq4!~uLc;NVVW)L4L0(DpQA>ylvu(-LvQ9q{$UYzFc4!8R@&|O-^;QUn>o{O zhBJ|jAm-ZQ;N{)x263|8k@;P|lrm1s11jwluca<=Bx(adaW& zKpJ?Wc6c>>eX>#{`%*6+==6Ooq^CW{ISt~2Z57V;_=Xt#^_DY+@oseIyVvOhB#`A{ zISMnf!_~B@0zU@ad@i6Y&32dz_ znjOfW^W(~Lv&e$z!Bk`4lxs27q;7N}z^+;D@2C610MCtoSTFa))F6?`Wrfd|I!BtW zB@f8pJK@j+084!<@-XB5`r-iao-4AC-up|wVmZ3_BT}dkK70{O3~Ok~PxsvZ+9XPu ze6faAWlDUm@ARW>p0y>6`0y9u{!#cFk`&79kz6`E+&wuD` z^cGI3S~pqdW6pWG%an`cH!MQ(uSDyNqaP zbb<@<*c4r9^QRMz7mLKmK0nS|n`O>4xMIOOzqFf9~|V^|NzF zEv|8+SR>l7;jKy%cGVxu1AgUe-5sloZqUsSNs$A1j6q@@HSmHbCdnHIS>a^NmJ)65 z@uyF8>ZTX@opUp(DFNMc)?Q%etSdRgc5sMP&WR2wwCv7c-`pD0 z6b#74qmn~0(h!clLnU65efb{!_j3UcSI)8TtV?aYv;V>w=HGUIpttLft)8DQluU3a zZRI{&A&mC`Mr0oq1F@M2umhAhoIGhuE|QZRbIAGCwDEq=WE+H#qO}d8g4MOQPUEyZ zPF#6KZR#TLZbaP272KE4I{Qa(HniH&?CpdPCH}*Y0!>gHwy!zm*fJxF1~EHbT_LDd z6pQeeVlByXc=m0aVpHr{x0l!o#h;%*!7+ca4ZYs3TH`L4_wW0I+c+02(YFvF(7?d% zMzT#P!}YO#?C#hr?@Oo#Z}%*8bO;K{55gl?k4;Id#^frB(a!y1-NBSx4SD8sW2ioT zS(S}beIy9MWkO&Zpzzbc4%#unnW4|jdcv*d5&S~X`33q+YX-BMv3E=Rmc>+~^-B7v-@deAX{_ovf^tt^F;*j=gquM@tR7N@%{j)hnuT< zZs}1uEz|Q{oZsFR0OmX4nY$;xpcgZn^RKc#zuRt@kI@ z)stA#_TJ`L3e2Z!Yl3^qOy?`irKypMCV%-dn6R*wq4}Ot zZL*RSpPTPV!e3duGYOYP0n#Y+U$1ku^>Pry(Ry^KnPQ4*^;IIYS*5U}&ZL0Pu8+jP z)Jf2UUu#cyFdw_4{;QoO2b_>X4Y;W-dTnkF(d{?)-4TpPa5Pa2W5xgM8hb4^b>jgu zZX)dDe!3fbM&ZkO#~8C#`+Xdk_x&MA>64ul<6(CG{8-iy#nfy174rr?t+qAZSNN+n zsw#0g3F;%FJJ#~ea$i6c2GSQT4D#Pp;FSgcSnscFb`%Jl3V1Q+ltc#?do>V~b ztt?sBCA1m3oAL|+)9(esIP!J>MAAM9$lH{P>R_9>Qw!t?KQ9Ciuvll%x?$IgN(gEA ztrKKdPJF6NQ}@equC@QXY$NyvervJ!iR5cgo|tvX?71_UkGGK;Pv4EsK)TmHJ=3=^ z`apShI_$QPws4bvvDgx4`cH_Nvb~Whb~_G|jtiU)-S#>YE;1~T`;F`a6%tRUb`-7SAC46@#-f(V+u_mG z#{n{58V?>~c6pXi7=hRAeBB+O2JP>S(g0!(UCtjP9fjtWq&PSuRw9P3zhj>m>5qN1 zH5G~8*eG+nwlW&M`MxpX!pwJpFZNc)Ap(X0@GaR-tZ9Q_cT5{H(YFtbxKir$|wX+SH7K3tjp#$ z>KHwhwA)S>6`lRi2U9Zz{&9Mn^KljmYt7QQ`5?Q^@L{D9EOx6iSN~k=xq|i_4-e1L zcL7R%rDiyw(qFI4XS!Px-H0$LEiqJYQT?Fq4@SnbyST=lNs5gh*Xw&MKD&mfl8zJ? zg~>QiwW~@R>dXu1?B_UFH!J;#t}=#+=!{w^|kD{<3lrgk}a5*0f2 z<1ZSoRLI)G0%1g=5Jy!$(G%|=B4lE+GfJJFgFUha-UNU5_Pb?U({@nEY*Ku-NrDx^ z7JLZ11?kf~xt~##UR{}g%f#3F$4|TETydQ^v`Sk^eeCo$P(kl^y;8j+lXhEUOOsT4 zYa=sem1pE;m)!scg9;f9=A7$gNXBG0W!HdyA$~L$Ct(zZ9vyG0dWcO~JGVr9AOJmS`6r}J+ zuytdsCuPI48u(e#Se{UUeKDNprB76^tCC$INZ8M+t+@jG(lZtvCUfwwTjoBD>@CjQo!-{5t*E}SE6*kuQlYp?5)dNWUK zs)mBy#eNxwcPJg1Y{T=UHan85lsq>(Y4lD1>h6yRlF!8My}807ayQZCSuNm8hcxU@ zst^?+Mi3qaD|+bSO`sI@9qw#^T)EskT@{fS!YHm+co5F%peOakXyINpzv3LhQ(=$Q zR1?QC5P$+*3SWPLChHX%EgXHj=kO*iB$eUE&#TQ+}V)}v7>}2kF$5o_H#O0PcCgr`qA7tLj!4vXl^dde*Uca0_P21ZTe&3wa1>&Oia*a zDIA{WeMK=@vd>bOy!j>Z(YAhk5`?q3;r_=R7agw11;IRhwj4`mx-0)da9!@yu&Zzg zY|rXjW^%`v+n6u&gD8~GM?!VBJ-!3sshcMpY};`bjf4(rVA%z~;JH|Y9erHZAo-}1 zx-(3F(1Lcn{d6aZybPC2yYvgITT|hSKNd0P9hbvsnEqiA1>8>3A9TE!;<|hP8Jt&L zL$bqYmVFXL7{HA&mK5MmR;~m9elJKK7I7ghqq}Jp3@=<=p@&eRY@@2(pm*|3Hoc;}55da1-xaxu8G!Pf#a4;~#pLjN3Qbb3>_uu&xBpZSL4Q z!`IK%&x!AFUlNA~<6%x-%qP;A76mhtPb+2*1FmX#hbZ_^d8EFP@1ntr3XGGzkB;V2 zEOw1;BlJ}Sg-EexbnJU_>8?km|NEHWe~b(M7hmyjGVj8jf)6lxH6~NWpuU1rmtYd9 zgN1)se=nfFJbA8hSNXH?`C z&cs4z{2Yq=-?!QZzibyfu}yRwjwV-284K=kW_q`3!rS$NnMQ4zLkCU{|2EvKX{8IC zE{X*h-DdlJ;4HlE2_JfV@zaVB9I1_|feX{WIa^aGrDLHAVEf!KU8Iqt9&;L~rq@(c zn@nw1mnh_vkgD4cE1@)}jNiz&^{`B^a$pN?u?N)aH5V0=mX;NOo}O-nNZlG#h3zWV zr}amE&GK1Al}k>#qJ2?@yFG@? zV(JAp7M@P!0W5Kk%Aq3X5c7w9wGY}&9Zksr2U&!PT~`w>oa+IYG-H&z4=MSdLyyM1 zcO<`;SGHn=64mj*zLMo#|F9@0iyMj=I=|3<@j=*0uMS8<+5lFvfU|^>2{AN&y}(Y3 z0&(?w;TLS47AxMDmD#1G6W?Q(@^kzh$&&blzooYMCHm<$G{ZG0&|V@o^B$aWuAC9E z#wCMHm)&<&Qvw7Sk)4l?A~2W|l%fPtE!+(sC5_I!EtVA5ZK}2^D%Sue5k%I*xuX&m zRWAQN?=Q_8u8%+RjfKCsotb1y4F@A!|fIwNcz)QJw+(SL>-3@7*H%6t z$1~>1r_vV?P)hflL|ZrR+xR8hJd`OKE%`7|98 zM)Q0`iFeG#N!UO3Px`ijs@{v*TKW>zzS@Eh+2;jx0n*6hn$qF2Nt=qEt7o+4|eGHuq)dM$YtRiWU_2M>^`PX9_ z$X>ZfSKUh1R`zj4)Na7aT+6BG9J~C;e2w81+&a#&e9ah|Bw!GaRr@jJZt9juY?k;d zjdv7RfV-nVLK3i#kP8#`iWMC8<^A4$Il-?to{_oZOc53S;Hur%5WU{oU@rMgaPmG+ zd7ST|Q}WOw9~+ev9Y6-Lr_9zFp=Y>6l?C#+vejfv(x1i8t@mqCE&D+G8Vn<&uYMc! z(ljnQiRgT1(8u4@0)AOp28icQr`W38H5~E}n$A^5nkuJV7dPiQ1S)^qw(W$htf8X} z0zvvsDWE+pTpb7O&=4#-Kb= z42w|Ne1l}1Xf2pQHZOta4%4&4INRur1Dtr8FQ3}Ti}$)fzisR z#+;pz-d8UCy5|SCdE5_N>Jt`E`izPb2kLWa%UNd2ES{ALtbb71ln<{0Vz>y`Wgovi zu7I7>k4k9+c*-cw(L9qm@5YD8EFoTa+Ai3?q>~)*N;Q!P76}N=UR0q$)Efi)m-@#l zT&sY!Lqr;jzsYX&5@LGhs?>SY)7v%NpPQtMDl6aQTQ8Lr`W)DiH}k99!gT0TeEI{q zHj)wyb-)ebh3HDElwFPJu38{zK#??6DpM@-SpaW^oNvpc@|_h%ucv_esqV7(2_HUC zI|THHj56#B_TJ|RH!oi7+g>FtN%eaRtx?t@$0$%#^_~XB?dmRK2*IAcd?92<)W*ec zOJw&vCiUOZ$_Kq`ka+PFb9?{uY2RFltM)>g5+_qNd0waAFZ1uy`m!|Wq(plef=%| z_930`$wz$zt)>@bOo&|5k4`_=v@x+eDY&OChRRCM?WOehQ z-(9{*YBj}^G=t#+Y0fQ>ZE-ahB(QP6vZa~Ss$TK8eV!)dGWH{vomKiRux>|y4|@a8J6yxYmv`*(il(6`Ax<{cQ$6Si7a1}!og z4O`PDd>}`pkVRto%}-lZF4zVeYvc~LZd$hjPf2I-muf7Q3S%Wcmb3Wm>26Zh>`ElE zXHO1MEdJ{3do}er+wcqpf$HXT?J6Kb82DNHuwmY>Z z$y<*}DsF$wzrxzc#}zvtL@ZV9(|Bb5wDhN4L_AO{zN7uC=8Hb$fz|EQE<$#lh$#=x zx0|!T0g5P=<0{YKtv501`rhQA9w`b5;17^S*ez;T-HJ-bFJzUNlJ*E>Y9z z@?7koTdY4FmSThs+85EZTDHN`%OWg)S{mdToV=$Z*w?h2yl@mm=2J#YdXQZneF3`l z=kfx2so3WI5@P5CyNZ2;+HE#jQ?1Q^#gpXIKMkxB6RKT!gaHSTPeoqc+mCEiSZx(- zPVRHg6^15I^6-y96VgF;jhlYX{kMM~7?o^(+Ro1j8>TmrsXgY_xS5c_*vC+vw3v>1 z(^$dp7o4q6H?!Hgo?v&=bKG3>RS6+n?~lgY9<0B=fh9}hhs?jM)mJif+BF>C$=iru zf9i8K(4t$r)RF$;3_QJSz1R4AzUl5UN;jtxofru0&rbW$=l!ClA>4Zy-+lOM+?UYx zW2`D0xrPyA2fOg{JF}}w_ulaE>qNUjmak;-#<35Jxuw4H+vCO`4sOEb!dtdSlGk?x zLpPyEY)p(_M67T7gOK2jad&3kWqCt8eP%OU@6;&>dcMc6JW>!CC~TxJx7`PN^G?gg z)-1Vos$Hm`1;B$5tg zK;v$Tmw5!4pcQu$V_1NEEpp&cB$#F>YLp;AUKykE`qmdT<+i#XYInSsY5Z;G@)W4J zeZ`qy?rdF~Lnc(T$?BtTU$e90;BSY|+-C{*u1oC-eFb;{z*5^Qnr}Jk zv#%Oc>IaFdY9zWhnzS5?*uhvv?Hl+dBq0Z1<_gwqxDHwtv&xbjq6dw*g}l%wHnAJ|6FL?W{@c11996EnvVX~)@x}u> zGN~6Fw}itX*xB1Ipwi0IP9#OdzPou67>}M;|Ob$O>!;SK>oV~@yZk0IU2lLal@Ev9g7~xFa0Ta@7Bj*xS!frbtP>P z%YssfUUKHGkGbpqeJt|enebgXZqyB+v z`2H~epdY~UonHxT6wqsTorIp3bXi`wj@NHoH}|zLe)&K-lMb+;37^g$p7BVK9dmAK zaDI30Dau%?Mzi2`gxev1mWau1QT)Ra&)vTGDbMrbS~8F$m1m59LTv5~_b~+91Tj~4 zf;m3C343t?=J-%4_IIu$g&nBEQop759uc5QtEsj)jemy-FO>1Y|m(62+P6LmQUerKgV_{Nl-8E09fdgw7p%$vrgPeDeJ6M<)@dUtQpYK1c1zQS=_ zU*>p7E(dp;^ksMBBTq~eZdL6741XTp5J)`-F8y!Jy=7FJP1NsAOM&901zMaITHM`B zDPEvJ2^32yMN^=7kPwQyySo$#?(Po7f@^V0&|tYwdOz}>FYo#Atn=Y~$XdW+*39hL zGr6wWd;fo(*ap6wE+YhZcO)F0CF1HXc{NhMRC0hV?iq$}qQ5?_w8iiEZl3d0#p3hh z2XODlCCaQ3IGiqrYpiId4~ojKbvu|l zZw)es%9mhCB$uI?vG5K|Z`#7zKWd1#c=2B}2C~4DraPnrG0$3yUrQWI=D! zReG@H+j)6adjIY*1E8+T@W^e3?(FKPpp^HpYWQcKJoNCiZP*vAp;-E)KVPWN!zDIk z!pA}c9dcOpaQHLZYuw#+C!l0#axgu-Q*%6f54pJ9`7K6~`57C(at%W&o!cn*aFw71 zYPVi2bQ@4biDZlpz*S-rEwdaZfwyO;-Ty+V=>LNi;c2wN#ohm5w$@%MAq~GSjAw*| zFUD~ch#=l7UEqW-_y?rBl>P96LmkL#R41GdFaew9$qNq-ur1GdN$95xuHOR#E)7hT zeH@c_m}*p9!By-%Br5b)NsZ?Y^4{;z^_=OnJk5fqDkPw2$j9?&*m3aAfVjq3pruZs z@;yK9r%)>`zB!Wk-(V^(TS*gB${f78SJm+a_d5xnNH>U&^fRBoMgi?}^kmo4rNOnh zabhXv*U8d_W#%Y_{;no}R4r1icbcyk-;8oZ)@13a1VFGhTZ%CL{?}_%dhw{})KT8l z(Rxk9rnCRPQLsZJn$vY}wyHB_d*AIixea+eZ{NOW)NGmg_{1htV`@=nvE%Jjg3=(G zE2m1D`G6W4EHo-TrBW9$)~#5r3W!(g?Pl!sk^*`D0+fNA#Lg&gO9~wGjW4}Y+DkNp)>N~{_o1F5Xh^wbIVM8)K6oU%~fnr+v7$yH`0ZgNvN~O z)4Rfbj+x=JmN)!{!KcI32fLS&X)ZcIqO^q;kKE`}?na4(vHOCe zngpM1D#m2#a|bpp8Eh5)(D|j&K4t4t-upw>6Qzem!%s?@^K-wdHhwy~!-IBJ^?WT}Umw?;r(Q=)^{7nfim}-qWjhls#ros5S_)?t zugP4hU3T$5{uv<;p<1`|X?ryB$YHsxuhPX&B$)|)C{mSjE+=SBK{-Yof`x5|aHs^ZlDjO4ll}r%|6Gt#4@n6D?Au9NhUi zpFhy}bn((ch{0DqGCrfAM>q98J64mt#s*XdoLGP2SweO@kz53mf6C|;ZjQtF#3)qk zTSZ2%(=HgaQc-nC{^P$wP1&_yYq`poi4o|Mnd51bA+Y!jJs9=0X@>RM%rk3EHHdMIIk z>!ljM6t<@dHjzykqm^=Xd;=LR7)<=slId2&ICd}BabbrF1bv0f< zMKAbMd~D@edG2}{U`$rHFxMKODMmYp&CXM&)ax$e)1m_d>)$&|@n~C_@%hiojK456 zeW3BM)d;sS8zs`iffVThh|FF^kyi%NERGySfMEnbh5MvGieDZrH1Qs%f11upZ#(JP z>1m2fiTgG)*54;BJnL!YN-^7nzzg~+6pqD^?{J6<+_wt)C3Vk{gTM^(0!Wc*5G_LzA^7_K5uO9Y<%?5~J7>H2AvZSaNF zBtW-%ytI{<`Rg#HD^@d{O$DNZh}_Ax!uCkjswt<3l?HE_>*$RlV@TGz6GlCo3;Fw< z2|siXt~_dilDZ$DIX!h}oy+W$?C`86`b~1*71PFgj|!MRVz9+=bDO2EwV+Vv%7{=4 z%2!Pu&GQ%!j0tDX!XT z9M1QoGD2nksan2j^-cF0I+KEywWLpWy_jO(*H3XK+B6w>Q&})!HKLtI@02PhQa9); z1s4cwbAo2y)Iq%4j&&{fE{Z*sk<$I@6Hck5L{!8E6t@# zAQ8vq`B6t7ME4sq`+*LMPR=*n+O6pkyBoX{5xXl$<5bf^YvHRx#fB-#+gbxNE5h=_ zuw0UEilZo$Yqx%8?~9FT!6fPx8u{?D=!XGcvyS(GJgpbo*-pXE(Bh@TxDP~Alr(`- zG7pS9*LcEdBsJa?ZWz&)$dg9XV7^SSu`(wMz~2qca$GOig({}>YfU3Fwn>RR6+r{* z3>H&7cfaw)uCbp*Zedgk!vyUffe-X!dnUm{n3C%086B?UG8&FUzl(!~2GV*fS4>Lr z3`{mwHQ`)YS`qP78Mjqp;QoRMrR-gwxo|&{E?1lOyS6q zQT;tBy-$m^LrKZewLmgzxO5(aEdYy;+A*VhLhYNHw914PL~&d8mMJ2(2_%Rtgbvzk zzAXxB5XgC5I-;VP7M&1Jyo_2N%EB0wyazo6GTQI07avaLls2QyMF(mD<5dqhsSXyg zHd-Cm1+2vDyTTQ_ri`s;9W@-v;ljKU4rX~U2DrwxWuP3`o=qUYndb{==$<~Uk&;d93wr@!vFTN{C#R7 z_Nx}k%YB}@m2m>k$R8uYVK#V+wGg?@&~fVCoWWf1yJ7Wa#|O{$MYIbZ_m9>*OM?%; znd`Ub|Ijl;8(aYmZFMj^jaw>YaXEq)X3s=whJ&eZyFuJd!AyMrAL(VvXGM6&zt@JVPjBgfi7 z-XV7;LppeViTnp_hQ2@}$eE9wr&`M5j?Ibz?$RzKlyO%15b$?F%VpyyKqm) z?NjJr=N;xA5{5aPa%bB*|Bt!ASddtG@{bSx^MmECxhK1)49{njwn7bQ+_BUrq1Uz> zsK^@^8qHZEFp?-@uL>h~2p*5HuZBCKiKg_=baeTy!x|oA?L#<@5w$b4MAlL<(%4iA zI@S2v5yt>dut#?v!|N2v#!C&j zzrQ&t^DIN%xMgIG7-6wJ<`f{c!Ro_`IRa5IYp45lhN>gtXMWIwlJ)+tBnvyWCxPfU zzqyurD)$rep6)%(jB{Uuw`m(hhxC56cAnmie<2;%=fyNpr+8UnIj<`tZi=Jk_&r}0 z7luOfP!KHM_h(Tnj4wVH%EU> zgM@#u2=7b;>A$PdrP<;>>c^?x(@pLtb=t3nvBo>&9nSpT^b$j6hSwU*=eN$3mwk+i z?f-sjDvkQZ+qZ{%`uVPR?9@S{6(WnMU#kziz-Nx_6V@nRd4H=`{Y5SeAv*>dXt!h_ z+0CFp1q-LHqW~+vbCjMVSj&U3XQcR~4rNb+`4^nM#p@^SL> zYDayXIzB2}uUiUck)o;PAKR6soJ#MnIQZlpvTZaO^Dzq>M?>@T^Q>Uir>@xX-_f;& zF7u5xop6~|iVp^%t+r!b3hea)r5cBY4SAOjxbEaP4peh(Ov|i!Z2Gp&_#dCcG!gJV znWz1<0P6C9`Z_&)nI!2`645&W<9sB|S|p~@Y`rE`PBn=;w^o^ajZA<74=?3(3URRU z$Q^hYYW1;(MwX!6t$KoBA#x_K^{O}y^Qx!m*q`~dMR8*hL?;Zk;c^1u*XtYPtjCL+ zwE5I|l5J!L8ox-`=W1W@xl+su? z8cRoX896*^LCiL=R1pT}H)63SHkC{0dc6{)U@i8PR^$@V%~0d|0L5r=lflp9>!+Ly zLX}I81qzi=t6R?9rmI4#T_Ot#k@muc#oe4&IFgxf1g>)JS`<8HBSY@+AnQh=D;@&ybJbM=u_)OiErVD6WQkQ7IQ$~qeQrTZUc2Zc_nnl2lW#6E zxRNAjexzu`xyYqW{fX@=Eic_OB61PK>zxuJe%#knLpr9Xwx(UGv;mEMC*$4g)JBOcJI=+V{nucmtJL$ES;^9~ zWkkM?Xi%)6r>MUggXvd4$pdTjhn{W-}3DZ!(gdmq(&(mxU z6U)rzu;{zbLgRNNjUXrv3f_}q9#4IcI$xF-&d;bNy#XN4;6fP#H0nJi%myUBy&Jif zB4ydrz9VU$jRKKbdcB!E_jnUGz-6~;73IQcTCXzcM9Vs~S6FcGS<_f1KIEt-WXD8% zr-mxVskEzKO&pZ$a=(Er>`99g&(`fFdy|eAOYQgKd7{xKCB78QjVVL4kYv3%t5PE)31TlY2^ph2yq! zxRuvm;3;zZ@m=hydY^*Hpm9zs+037B0n4hA;WZETfE;O?EWtfPQcOA0fjr#`{uImm z3Pu@FZssN3;v@E?;og8lP*+{a&Kx$)`VmTYQNV+T>TTm;xTx_!;b2+Rz8 zeX0D6i6p!DR!cr%1z@?EAskdi|B1I#CID18b8bdtYoc{9(Z4Gt@5nh#`nOAg)JRd=&+YEwG85O5J4D4g zI|lrCAN3x@9;lJs-ScThJ-B`=U304nDp?#jEd7$OeQbEG$v9|gJQMw=%!zT~m-@zo zi&1wBKka%QMzX560)oHeXw?^Ual>h!VY#YIsV4Ql!(S&QG%)s*Pmd^ea;0&W5j3s9 zUP#Xd$F9Kxg<{>Zg|mq}K1fzZ#>nnE8r!&|7f1xBE>z_vvK8mmRC0~|WkQ>l5?pTr z1KZbeYEs}9$F;&i31RkU52ZK;$$yY+vRoyl+`NH?8e=!rrD|k=szKu9E_`eQQdJ6| zI3z-`YWtaxv{T$qA z0tQfXM{mf`%4l zvYJ)3cV?~-Wu3TqMC)rrVb6X{e!S`gGtEe#R+)-VEM5TLJB<_VK3TGoelT_M`BBEF zsO$GpS&+?9&#Us4_dUw2e2%~-gfN8rWYsNf4-X-e34LWlmBWs z=gETdFBvhJ{ZJn{U|uxFSgUfq45MGDtN(TNUOH`R*q$aRlyY+5;g?57!6 zml}nztY_k(w7R=y_b6lSezhd5co+?c;C;8S?1WLvkltxY8m~N$RWOeoU4XxYI+>y` zy^>&`#S49;sg!Nj=RM`zBs(20JA5kZJ>d$b28#-O`5g6S(WBm3dqY~qGzO~GX^5`f zHgV*K*+ev<8eI)IMK8-=7*esBYf+|{wMS2g3WO~h?gFf`R;{MKPuB!TJVHkBV_lUe z>L5?N?O;dFV$O@99wm}NE&d;u!f26tyoPr#>t-W^j)Y2fh4^n*K4DRs_N&K_KGy}h zC@-olXWl(4S4jl7H`}4`aFE6{bSxX(#bzd!bqPToijQeoJI2`m!NTycccs~oLjEYdw5rcdsFg?irWZA)nvB||HmjemyqYW>c6nDJEl@4gYJ%kGtn6eC?0KrZjUAt^D-%d}kU3o| zE%&JobRu0c*KO?9^RI$y z)EKR}@(okL`B*qDns;)uE#>4^=4Xi<^h+chi$Zp!mMel7VMWw4y$taA_ln6s9VEH! zw6U`d?SX9sGm<)Gp`S|&tEaNQ8-Ey%z|hgz-=)1~8@8xkhIVI|b3aSl9Hg5) zu)tIi*-yMG-JjF0t$!p%Gj|V~{OXBn3|&_M>Xr23fwTRRHV|Pl_Ank*N9USuI_uiIgO=Ig9Sw#=Yb(Xp%FJ_Td)AEJ70;p5NwXbcuhcz87~ ztx|X-WH6Yq-DSm%%cKty5(r7`Wq5jQtRJ8U~lT4{qbEQ(`%v~rwKnf2}ioU5zU2?6q3Vdv}Q4F*;QxlxCOdjG@Pq7M~)b@icFDq#;Hk730FL}HzIwf6L4 zi1e197wN*ULpEemET`?+uVgeAYO}+NRXmX{=0b>?lFly6Ys=5$R_?P?id(}}*FPC{ z$}kD}g2h05BV^dJ%o$7o6`r4c>TEe>4)!D+mQlILoL}H-!?q&fztX~JdbB5h1u$X# z;x2>ijBYjP28@`goqssbIIoGTJuRI5pYqlzF8=@1SAk#tPjBho(u4ndls2z3KgU}d za-U@r<|Q1mNdo{m8?9huyvOT=uiRUghcRWm^aBLY)->~a8OtM~Ld1PSAvKZy2hYC# zue>t)n{D`@iQP6<5U2p(&dY~a55XWdehMq}b*^gDJ8oA*D-P*|WT&#JTHL_Sqyt2m zd{rKgv9&mn=k7}#Y?GGIDg7W(;}QyV#{#YObnM`$dDcahey?j{c+6%kz zi$yyUu=Uxe29w){@dUrqqd5Z98KA+VWY8k+ZnDwAtDw!7F>hJ<(_ZD8MXfHg)rEWV zB|LM!{_<*r_sEX*YuWF>e3uLkRJW(r3Xs%_k;=jXi&Pt6 z<4L%w8Y<>BUhrbWjJEkp+Ib&ndSvfotk$nXvv{4d7eXo`iiDfc&^Gazk&0ed=}7XE z+i5>qi}~u5ovRPK#`_zex1p_^VS1T8@ChKXG>&E4tDl9)(t0j?nro05HU)?8RWO~S zu|3kXOI*aS#U7F~Z=B?`o3jFYxikcA9t8^-kzZS7T*z3?Y`g86YuE7gPewDxFl{sY ziAg`v>6z4)`Y@@9U@MHT9^01kQoQ%I$DW{t=UQgcx4d=otE&HfW!y)h z<)-JIbP^HJOd9kL)}uR#b*{&TmaZbiQl(0#ilWQ|N{F$n3HEiqFy~Y493p$nB;<}i|=FRrtl%4QH!9`+i)yjI0cb|8Hh|dIw9DD7+qzq^FwNLcC7DEGv1D*AzSQiHSz{ zUtdR{+(Ud{@Y@zd|_k0p_}N-c4IrKVSfP%t~$Ndz$^E(BEHLRQ?khT z&-9l))%}=lkE%)`ri-GY^1v+cV(;n`!6O{=CM0qGQE9!Z9XJ8;Qg5P;hS^DU)C~=z zOLI>{S`Fc3I0R06%+^PqB&Lz)hl_1LjPdlUb zC~utXli_HlmM2AH$j-WX%z&JmLHsr5nc06mXfxI@eD1!-CU>?4@6r~D)0*E4_s76- z&{Ma=kR9wFbTZVJa~TGz`7!(ez0|@FHz9Y60@e2t<|L`9<)gS8B7sYbmwNGrxy6HV(UM?WGyRnP#`}!+0M>s_Y3tzRq@W zCO%aG>rG?OfDM;c$K@%?(pLGB|6s`)HYE3!YnKq?vy5C~e!u*gAps58dX4wJUNZow zvpo6(%|7Erq9EAYP!+T7T>bVREVDtZ&Gb1myT$@bkLG^U5zh zjVJI5ic8Z+**8g3`C~Ec-5%dlTKc?M2H!hE&}Jsx!PU;E`pNT94xeUh?@1m**7LHt zO+9Uyj$IJX+Esv)O9i||dn2IfiRI5+;iwU950XC- zwW}fng&eh96d5oG*S_PFwL1G?+4*m}J2ZVeVuZBdPN?~})2;>ZJhZu_WvG9eLpRJ* z5iwS_t{Tl<|4Vb^XHTXlo5G5hoo3;?9*P~qyC>)u zR)>$5$-`+PKVaaxRyws=->_^x6nJD>U-w^HAwK}b!}|kx%<(BsMr}vjmD8f{N_HQb z*QYbfRavGw_yQS{F;R1>*ROM3jU(?O^SX3&5PQAnmAi}+?q8@!CY?hK{%E!+ih$=f zGwt-7xNX8a>kNXz*1q-7+G6j`rdXAcSUi7juDVFk1F9%%gR#G)(ZlPYubtjc$uIMB zb0vQH;uCG!Eu4l))!t=NJRt_Kmyyxch~x(-?RWJq4`&B%Mn2tZdy1%CDJzl8c@BsW z3NlL`=#$aE#u>Y^dfcBff;xW`!-0|Ww`zYP4=tNRsgG$g0~AM_n4-6x*g=E&wo0^{ zKY_a4NxCY&zpfJh)Jf7_Jt@@G0$N-!GDUUJ(i6L%9L^8>&c1lQj&UJh2=kSfbFD6?&w;5yFY^lW^R_7qR$=Bj7G)PQ5f zpolLPQ^8Xq1?p%MkOkrO0*O}Xip~bwKqPla1Kd%?AXTFuQvJrN5OlY+>I-*CL2R6DF%R?;yIyZ#tvf#nWB-PwE>rjMs4 zjUNCNfqd0Eh(=u73;7@ntrPT(;#4IjayW;2iQSe&5K9^nT4*WZIYYIutI1}Z1xvg2IqCeFT7X?3wOV>5_7V5VkKsOh zUti-Dj%S=C^m)ZRZo~0zZW&(mA-&Un)-uithr<;pDZ~wpHdSRqJEO^tNj(cZWYZIh zaNrVAP1QrRj5-qm1!v219bom2KrQ9ajSA?fA zH|eX?Y9`=OXM5UhLRB+Sc`8O)r*inZe{Fd>@&Hit6F-b8=7``9ULj*XJpp-bz7IVdrL}OlSnz-kZt^vxdES?%$IQD(-Eq^9`bNIeZ(ViV zI0=>^w(}(0T4HXunauNCTxRTkr^qC_x6sP79vND@80oLyS6pPx;S9+Spqy07W#{V` z+HI4WEGuu}Dz$PAMn{-%KS1MRMTa0yd`a-S>?nIBAIwmoZJV2rAy>S5`$>m_@eniI z+T+Z9w}v!M-uR8Zb{FNn?e=$2e>C2NCv@FS^7AH7jWu=a^p??l#0>5I?+F)};)Ex| zx*Cl}q)G+izO{#suJccjfY&!&ky{bP*W=wmr8zcL$}XD9N3*T7i`{#6Sb7Bus6X)- z*4Ie7d(y9p9na!jSdNq=Q!c@iRQ=kg6-rY>)jqd#WN%t_eKJz9dQ*CGogs@1RIT{k#$F6AxL z`WcRORXv7u^n*!*){;wD5>~I+z)%JmowH$Lm~4A6wG%^Sn!%01Y!p^v&Zf)&^s8E= zh##jj&1Y=haMQSF13!2jQQIxjuW~uM3e_T(0&48UA+F-i9eb)u;*P37eh8zs-nTDd zAAs~nFx})ILK9P>crrziNk6p zR>C(cZc-d`EiX;)lh;!TUuElylJj2m3+>O^W;}f2F}V82O|VRxFAYAg>^bVrn$way z`#*^z|84VsFP8i_ri`l?CRpU$PHMat8>(d${}YGZHl<1&%`_tM*2bw$Pq zOe6rd2y;J$hGdWi+@MwS=|5F_ZrCoi61!h3h?#7!%lKz-+b6bsB40=H^yDMp8-Bb7 z@_FD0g(1&q<7esJznix)u|@RQ@#}Jl{Y~ zELXfH692)nZt+#BrzHE}AG7h6s+(+J0LEW|a5(WSxPt0W*OqoOG@rGgm=I4&@byh zQ!yh(VM#4yTM@O{>&qlp-6>(Nmr;3r!bArBGUYGaqK-ZeyY>366Py(kCC%uUPJ0Q3QRb2ECupisx3DJX{IdHIKrx{_ zZE59DZoo%yuRLcvvA#OKM30Umb z-J`yQa#Wo5 zlqob={9JJBh937%CuQ_qeb@r;7ryyG|5E8r;s+d`nf;1n(=YCR3+w!0=@K}!S3vE1 zm30-3D)>^K#GUBNi~v~*AnI4KX^di-F*a9;LZReQy_{sXK(1CMCxP(nuiOZ|Q{@u- zx8#n!hCUCbBFm)KI3EvemU&pSUjIr8gb)N(%W*o&@Xu!W2jHggB|vpg3!TQx;T}KXx6(_jUJTxPXVf8)eY$Cfjz(aAwW2p0^Ube;gOu zq+z5RtfL>pVjWsD78!Jiu1NJss?}H*?p>wl$Z&`SODl=Y^5eZR(3JLPUTmNDX3wnX zDWYv*e`sDeWB&=Q>~D25uZDqRjWl?)X1QN$TyHaMl@5D+^nHZYdJ38vM(GRwDGW{& ziCNrPIzujLQpxv|lx<^F{Q(gxiWY9KEs_T<;>T2D;X+GRDTUq5HvFvRcVZqw8(B|f z(u8C8Ig%rul!Re$OCk0_rtCwY{a>2l@)k}lHPTw5^Y7G3gl|jIb*>@>??sd#Je|}p zCSNxUG_*toM3Jm3?X6U{(Sv^tcSruRa$hb@ypb*{Ji?Y~S@PJfB6<=Gizt_s zOBvq()M#kazIv7Z>5RSHT6gjIHlk+5lLkHFfzM!k`{sVt>}+i0a&w^q&4jA|faI`p z_X;(89S~aZQb{wFvnN9NRfX+QFvCllK&FXV59WD^H8ZIWA-^AnF9%lgTzOy{#8q4_L)% zPp!dR%QG=%*!H){d*`M0jb@TgV(c8!k@eRp>yFAMuffgbMYsH2k}HcN*>AK~Ir=&S zH8g>uD4CBlz{{2CL-j(>+1(g2vbaruW4^u58RSUa5JCK}k*c$=^>o_wjH+sPZb(CG zciSxwPM&lMsun9nl=j#UV8Mp~>vsy&%4~1)bM|1#=j3N2(l3oi9ZIT?*?yyEBx5{t zN4^g-nPN*9v`lT-^{SGR>Z=xjtu0S3tRBd*ZgKUA--8BQD# zgebTmAT`V%EW{am%&@OO>H`}GVwGK2{~f3K}LU^?46F43ZcSi1u96Z zDDURE7Xvupwgb(VaLPJ2NYu;CXyP-R(I6dv5uVrw#O_=N3zZq@2MjHbCs50c-8t}z z!KkKf?(mW7xHI8HC}0oS=8@V9@CHw?^m8bI{IBj}S?**vdQ?8((NHTd zp600Me9?g}26dTkS`_-3*`NFQ;7Q~kG%-Rm*vhmM9;pubg@>|Pzl_SS54WMp6{Shq0_9Tp`K$0{ z8zbXfVsz21M7(o@9=iJe`Bb*4)ryl>UTl+$H3Ij)u=|wG$W1R`X)KXm9E3}}8{Pd$$k8#^5y`a)K+Hix zm+~1`w!*IxfUT`~Ue0X$Y`-xJgTB+U_(#pQ@J5!bVGoJuTZvFWMdH|*EBkkepo=~Z zi8Y?c*e;RK0_*QyooqDB{Wk^2q_edrZS4ElJ@(61mzCw=qyrOA1YS9fpXSfDP_4C- zEf1FL(KFXg0e0;?6eXGH)!cPhi?!n=KiN<7KlP?Miw9xP$KngEr%Nygg#W%{w(aQDyFP@Gl@GITG>%hHGNvOcxCwBq>8ZvKpyz>;pN%J zhlSFRUV32x)rbeoNIlo9g-Aaywv~PJ`J*l6VL`qAWHRP72)KMz6JFE)XqRUlhObhu zd+G@n@%w{&f%{WB5J}TLd%19NsBhl-)&8c;)6t}fkMrw8xSj}1L@_cA~` zmTfQgT&Ae{!;g--N$6P^ch2%t*K5{lmXQ3u$!+K zG?dtier=kBD%{Y-6e5znO>vO;yx7$Hy>&~BL0Cq7zfEd>RmT5Ld>oSmXW{euvss^u z%p>zsOr0Ad@Mq>N^waFCS##Oc7q7%5nk@uJX*OuAMHc)sL%%5g=IQ*Hgdy5^b^L?H zez`aKX+|i(e_f;9_#Z5R!IEHgZE$kFczSI;=$a1NVHZMKZH3%z8X2ZIXMfJ!fv+IS zm?>*K$`T})=Qn&gppM6YDN8(~SnXOSFb9xi-2JX@AImzMn=VG2Dl_Q-gDMAY z@fe4|6o0-tj7aW_{VpELRHQuGvl}=sGW}IlG*dVN*LhvsjvU{h$elOb6aTQsb+I$d z!AA2{c2T-^%=1|VCY2Y%_zZ|(qZw1wds5s@uP!f4>Mt&qt_N-#Jeoev+?J>i6WwVS zas;BnQodj6EBcxM4{sk*DjPz}>5w;Y7aBbEc+!$}*qh}omV(vUz&A`ZEINQ5eLj8W z^ec=GlKB}cf+)j)Syvd||8k6=UP=}QK$70h;ou@jBu1R>0!aU$% zMte*+ob`t-$?sf z!d!5E)$)oO~SejYGMZqHY8K7aJ#*NF188%vIP#R0DhOfGPdt+?4T1_Tj5`T|Q*aDrs=aJtvQ z_mi@VcX(k{UJ%yCH~gOcKPhIUd8!fb!A1_&GSvhh6N8(bQ-Kxs2Rt zT?(sbZmKQEqJM657QsVN-LNueKrX?=kCfjT?|M|?rq>RCUt0LJm}a3;Mr{R$cZa{& z1}EWa?}hBj4vcRBpXeDbeICXXtuqUdHto*I_&d8mpLm)*didhvwhqg)(Mu6i4FL=^ z&%Z6kXu_U@QwW4h@SscwRIl~mP7y`9#il1{U`hs{p0857^&uNeSMi5^N5LR2RUwmYuzeseP+|MzOoCd@)U4! zM^^zoh4gD^^m^Gkl-S4MRtn1W5%XiSylUZ#24iCPo&*}z7zx7h$L%LS zjX3y=n%Y}-+#t^{b(bPDw-Eh-^Kth{$VJ?2DB&(AAy@HcL_k}>tx)~lZTH`{IJN)v zQ*Fw$5pYFrn6iQh^ijNg1;`j3yWudh%2G(g1jU6^KTW z|ASS#?+OLCSM6d>#M{VJV3#=MQs@UXZdPLF0vVO+6Gu1}eCj`1T4Gu%&U3ZztT5cJ zX}Q%Z&fIU6Hig`B97}(R?OY%{f>t<7hEXdb>;iqhS@lA(fgcG~?XE9$yv9t>v%&M(`YD#dvxckA?3QQicgVuneiq!e+}qc%yIZ-x^8;2b zI^7D&Ty^B%7iu@(_Ft#~huSu`a@QhB;;scxQs=1gd_1Lb0iDV1&A#K4ZTXZ5t7k`~ z_XsxWL7Pm}znx>miT_R#qMmpPYq)l6p~-vnM3JbXXBC3Y%P^L*LOk&ahf-c?^M%j_ z!{7NWVCMJHhD*c1Qs(5Rnt8lLdy591@(INi1Gk9JIVsP>f%_kp7|}=pS!}fA;2kkU z@e(u7f9(m0Swus!84wQ?FY}F0PM%L={tsi<#MDlG+$FA5+>_1%1{{|rCf?`3!ZqCIDNpVq5M3DGucob-F z%Ia^^e{C9Bg}JpFufZ6ppjsc(@_p5f#vx{=>7I01ao0BLUIFQtdz*lt5nK#1azIr` z0vt0&j5G}n!+(2(&OHoc-4P6>_Fwne&RsjgQNV%8$f-#`L7-hANoR+kJx9>Lqs>HN z@dBUsV!;^q7G`((vy%yLemi6?N=i++Ar<%%02A+;Q&*vPEH^)CQXTLkN) zUv0C>ejs(fZSMul9<19KB|MJ153qeldc6(W!dxLR+Yc6kBRwsbV44{herHrec^0nu zH&?!Dst2&=%3HaZr^caD3$z>ohr1}1|IV|3I1>R0tvABNcr{SV|Jm@)D)JOq1K zzG7_H=XL*x#zi18f;SO!xNVuYuQ6Nv-_0OB2nvIw{M+Tszh=+;*X+N|){L;0yC|Ox zJ9fe_;_QKk=JzFb=jLId-*h`}9ssj)X6NX+)-hfQd=2Je!mvaAK!aO~^@rN_HKzCa z0A~T}*e#n@x-0e!g1BcY97e*z${QM9Fe!KU{q4ALZ;eW6&EgS$#MFvaXXwekgGPN3hHR*)w zF0l}kXZ?arC4KWOSs&obU6a#Jb$-xAJ|G{oQ~qm&jDORM_d5Sz1!v#pGIW5%=i~J& ze%Q=kM`RF$G3Vu!M?lvZd<9ice9_O^;+fA1Ys{m3+)rLLVI-{ualSv2#^g+5avNT} zgw8K^h9Ua;4_RWe{=phngnj(GayS1T)01MgO1%mv@-`zoiJGZ4y^#KqleKhw?*~vh zO@@cN1WN*87k}VW?f;uka{ZT2f@Uy239Z`wYoVm^pDm(=1e1>NSf#%{!bH+PjcJ!@ zT61KDcYjL`iI_q|zWjsL{?$KC=NOG}GsFAqlp|>T2_M8!q@lKMM+#xV+N8z4JVfMD zLgV_v7kwWBtXlYw1LRN}Jy)`P|EKg<;NPP%_zph{>v8ni(y?G+N6HKKJ`2o)78pJS z{qNPtJ#=Y5JNVmkf<49shS0n&a8-A(5|SYG`o%x3=&!~XaO>u>vKYjpVPGtG$>_6-~UC}?&iN#d0MuEHiz zgN8<6c9!(^l1;kTA`*3uK>@XYO}renJ-N9iHq(P{DUR5!(GjZyj!iNzBLy=NKP`g@ z%7$5`I$(uf-R26!X@7m*^o|Y3KY{O30(yJ-_lQqvoy*V;M8Eg!XX(DjmPk0&+?Qp# z)(u3%y=bQHq)7eRx;bMAL#>kQpUoqI*`^wm45vG|G6zYpaGA9{vVO{vwXF!jw=Yv4 zD98i>M8n3)+-*~BM;0Q03SrZmU_A%Z!QySf)k3=nx z^RG|5tn88P?Rct{X%}L`4*&6P4aX zkWL^f0s_*jRIyM+q_;q@&`YE%U3w9aE)Y5d0qG@lNCMI!L5KlDymOti&)RFRd(OG% z>}TJ9>lc&pWX@-fF}^v*SKjfyi-*3CYaVtv!E|=WQ%E+fXiwHWw0perDl7;ipu^Udn{v&AII~=(6iJAfu;&Og?T<|lY5-D*+w+*qo zkB@m>^|(XRzlV9p*&^0*0)ctR%Di<~!PGD8F-PpGQ+WhS&R{azHO2AU1&co{5-Spg znylxyJ@q>b^6@j#72+X6sHxwrxRC)2)nBz(ze{1<2g1wRH7g;2cqDVqYH@Y?jo z1Un8pMFHwfq2EuY=E@D$fJ7PJ$o-A|wfP?2j+}c72&c>CTK3FL(4MBq&1;fq;Q^$@Uj$C>RvrxhQtP zP)&by+8n-`S6bYGXZ;0=V80FEY@W4HBFtw0&O)pA2S(a|`ue{1Ddhn9>8U}_tB>EI zMsDg2fO@(>d<6hA)5d?!%rxXlKRt+fomxUWY8-KI;j-{;8rkkr*wK+J*$R&cqKNu* zbf#1^QU=Gb2|CpP)HEB^Zc49%pmz()c}bdtjke6o5Ci^Dq{5YtM1YN=4>Ej8D=SFV z9UW^`DL-^#_+Qa06-FxMPU&6CRkr9{ZV4?15qs#gz-@}>!OhbAK zUpB0B5(#x%fQQCUi{GK4SgKJFj-cfb#L<&QhCYITlJLbL#iKE2^%#1SBqG^E_QKw{zySO%Di*(6_i;khK=GP%T-TXt=~oLpfi-(7()ZLa<`h?Ed<+4E zn1YnJ$iAeu#qv`QR#!&ItS-D6>GX-0`|Sk1Sozby?&g38HD=9D0_>ZuJM+*jne4PR z_;{eSqV^Mp(IBr@WJkJ107xDXu+wGrNAga1d3r3j=x|{D6doMbNYL9@;B$A zHS0I@F{Y3LP*V>fp8Ns@0h~0^VEh=I9pHOb17^8Z4vuP`Jrezo;O`Gl2~q<5){q?1 z0`Q?KA}CaS6iIl89vNVB{m2Cb(IDXbAKQ`pW-Snw{Pv1}e+Gzzps*ou@Z&Q?D2Yal zGz^G~s1aHyZ~eh!>VNOyf4pDL@3&K9W_G5laEj4I4M@D#2bU9Rl5u7lAgJY7t#yqx z%6~?(u^Rv4gR2XlmpbRCJZ<@1wx$K*(ETmSNk__qoB3oxh0}2PRN~Fo^Ey-LjwpO* z_vNPvz`|iRMg@^UT{=-;G5m%=E76a-1em@lf{EyR`^A7`wp2_@!xB9ocb!j@S@ncZ-uRzI% z3ve4idBD81PQ+uox8$(GicsC5&1&0WOe|&SkZ!?rC`N^MX<2t=zSrDs2Ad0yYVSIJYbV#Pf(T&fj;Se~u&J&uJ#=ules-m>!+s zKFQ{~raqGbB3B&eA*G$c0YD&hk9GU9eLL3-|F!4zS2%tFN&NA9&qalr`hfD^I5-OPi6nV)O`Qr((qqh3*)S3TmZp$ z%)+rB;+SikXasXUa$cdZ{YT3f74gD{-_|mhLu}?(qlnUc_*Z!}M<^!^V#e)&9Xr zB3|=%!E4s1$cjT{NG)6d_)gWMs(H)n*SKX@>);Pfn7jWT#hw5-xy^;td$%6Ea`xD8dZt^#s1Zcf z+Ir&CtN$TY{)zw1@7}0fgAlXm0mccZ%;*J%KxUu$4jufgpB>S1{QWz{{)*VB#xR?- zm`U=+vUOM{EAk1hg?V*eZ~~Q1Jm!?1@s&O@V6TI9Kz5zhcSr*8&;>n`bDqyN6 zwm5JC%JPCR_g8BvWb|r?%#_0yy(_hNa8 zII!7`>`cl3=tTblosygZ$lWb0W*to~Yw>@0sqW7DyufO*%WwQCNvT~+tldoM!%Z&d zyr_#xP-Gz^CA%j0pAvff&%_`9yEduuhZ;9~V_z$lbU^J8AT7*b1oRT@j%$8R@!b00 zsrb*`A6(wGBA%lgQeG_F+5eeE^G|!V|BVl+&sAN`l|a=NIAq1uL@)uo(N%dz;d#r4 z3};+)+gkDh4K>+SZnZDIP!$Tyi8w|yL=M&_ap1n)t>63F6{rQX!T0&dV7*!}1@9j` zcVVTDSq$pfa|9hCfUpL$AyY{Z3%9F=K98{9D*eu#EfLomc-3Tbe+ddCCS9}0r-z(( zM4J1&g^(k!zu3-p7D4eGCguP0mFNC#Zkmt4`8=pN)T!w-PMNfil^|L_t7%HJFbn!( zd>25vTy%gwMVyt143t|<>U(*O%^z-G0qwm0OaXpL#ovU?2=DM7EF`&ig@qH(EIJ9& z!*5o&9@^~|wk)PuF@0_rgDK-^S)1n`=@0OBv-9W!UfLZ-Dq?NGnp!#Idt9l&zc>K- zeX3~kK#cmA*Q{@nQgNY(=VYg1dq3yA#NL^?9>z1ZU73z?0IWOD{jsYDeoby)5g8v! z@Euz@C)G6W?d?oouv(rJk4x_CGr7D#3OH5F@ih>&(LJ_T?nKfeFzb+BF`<#2!(vuoHWw0u;{_*|~`5!MXeXDGMnwBzR#=G*9i{|vS_@g2uCOJ$TesC8S z`{nMMJ9vAG<6ydtWdV2NgulY=;NclOg!z(UvkeD(?wVImqdy|-cq`rv=Gj2*UDKDG z-<{mU*Q;_fy)BI@c%fnZ9c}4htXLdDpuY^$CMbrYHpFPA^WKj>tG}NLd+23=rh%B$ z*`{;c6RH>3^E%fp*!c{fCqGeh|A(+r#^YhFp0%!%X^Y0)@8u(G9?Orsb{`4iRFO<$ zyFDd&s(bi8ePNjz);gxT<-}@-?${;u<-}TZ^Q^WHq=P#s8XBp~MJy`4I`>?H+b6mv zqR)zdPpDSs3}8~e*BqdEzoy0CyVfbJGs7UQa>?#=*%A;T>3f?5w>T$p@ww`v49qU-&6n&rm+72mS=QLJaY z&cb)nOp0N5@#A$-Fs2e8t6kNI1^v34_g8&EheqYJ_7fB?{BlURJt(C2RPaslcR8$C z=gt1b-s11xBfW+odme}vX6Jy_)Hy>Ll8E8wyM3dz4I|f2IHaRSd z;O@iTR{O24KWyHE_1)LWtNi&2-zz+i%A?@tk_J2dYU}tK3mT~08Dq?3H7}m{4DDJ~ zvEwUvwg{hoyt`uQA~82vkcPVsy?KIT<#W0EaUMkTV?q1D)|JB%|Hx5xbCni8mARiG zit=M}8o7?+3DXHy5l7}O$jx9OAGS%3^XEkDG^!sj^Rw5xyOeDt!^M<8<5wb{!=B)= z0WUg(D$RN;`G4}9acc?o$=n2z*4K``%gKKHlu*mT&7U^D1?02!=94@@gTxOx7sTt& zzU9-E=ni1yU~MSk|xQa+@nS;4s8jzx?pR{qCEe+ycC7-@cOFf$V^0 z9uU&^Z5r)Uah5FaaNsCx@tQ!|YjtD&@<;=aV~HszA-JR9bGtxPyw`F|tV_Sg1ruQG z!(*Qp(QBt>(EIuB9dI;k3SWl;Ga_AVTrtkvMm7R`=Fw)D@VGg@;FIn>`q0bP_kB8l zfx51J`URR)f*)TQU$m}x^$Vm$0Q~~xy8^HkgQ)LGLTQ&B6y{M#na!f7rn81cDEItD z+_!SuJxbEtxAL>(2c*Q0KB0Pe%hmvYGv9Alu$VfQB~IV%FFi#N1FUrfm=0$0M7pKC z=aboN!TX_YzU#Ehw-wJ6ADV*kXaj%85gm0VowRM^={7oXr<~Ep?lQQ9+CoYMfXyEhpe%70Hhz_+k z$z%!SmqLe020Yv26xR!GP+fkKP{i$sOP|k0I~?70_?Z&g+UQYP=bJ(gz*X$xd8ti9b(~4Yb<$J)sdH*geoVRRSR>Zn;hH1M%xg&_1<6Z^w>T69 z2Fk0KekMyq1we?6;>~nqJ;F7DBZ(Q6G@`ir&2<2GNw`dX-hU+| zeDp@B=rE-}nteIEV(oZSf1|FpR6EQ3N zv_w=75DTC=)#cxth4<7j=j?3E9$Ik9%PL)KH!RS&ndoEnvaWq|4sE+NI#`b;)7KJ0 zVlkiHZGBOR-v^}yZvD}py;i$>@rB`HkZfP!(#8G)2j*~B$!YI|=*v$-gh!B(L~X)__#A5|E6%a9D|8zl#z;{9{P4U<-AG+5?TMq02@`fvm_T|?hKAPy^E{xNVHG~t+wV;jQ>7nX7YWO(TY zZ8jU|KJgks0mBku4Z(+!8F9;N@Ub6r{9Rx+m_xzZ=qhwtb!70$sKtz|wIYhvj%ODr zBpx|q=f%YqCS~l<9Ow+n0A7WrJ)JlEcK-dJJ+Hx-TW(>yHeKXqueUig{BlWj@$IX>o^$Wf1yrFwLjc=0`V zqBkyiZ^v|^{H(ZJYNf*NY~AG#kGYl4GYdjH`iW|#dR7WYH+@n&xdia2Qg7^eee;9I zNLu#$r;WU*V?aA5%}OvWIF-W$G3g2g5R1y~w1CBCE!J_iaWkc$42WEFt1*XZ3Q-SB zdW)uwF4v|y`)>?$j|-G1h(WXnRUKwp$&sE;8%5PUtQK8DW&Nc;l^;E&j*Zy=h@Erl z&OB9CvqRgs=2v-69JlPz_D)bSY(QA(;aed~x9X9mOhfM{B(=+L3|F>ngxr$36D)D8 z)(#Hv)_pVKPPi=?yly2_HRe(3Me*O#m_rgog6QWs&b?FsuUPVL(PEDV&-gHGORlA` zZxlhoo?6)6irNN02&~CPTES%`gVtM!U$*YA@zlYrT($z8IX9Ep1WVZV>UbgtX9WOtP?f6z;ZBwlu zeRd9Y)YH*>VNZA8l;I@|xo($UkZ=^bsl^i$Teik&B|1Xa+2lb zz^wsAhuIZQ0jfQd59H_7q)7KGX)u}q-ew>t>u|=z-D3t#C_}dw6{%rL(D?5&^!RS>QE`;r4(R=o@j4AVwSo(!B7%;nh6 z+FKW(8Z$VpkYZiR3|yR%UHox-0GMwBSw?SQ;4RRdV$2TBboix|iG0o+<1?`ZCQpXW zRxS2FCxv!+HMG?_*|;@MNUzg8p9q|Qkdx8wMT;e$B)ViNTaDI({_F_`7gS{j926d9 zmRb(zYX}x7R;Z7rJW`7I0guU$9f#3jNK)q|Cg#18w4zro2Psxqy1c3}k9KKivnuyy zQ&XI)>|GCCJ{d(YMIm|hM$Aif?&d!XD|j6ut?s5(T{E!}aK1qxyB31~a}Ddi`af$A zNFUx7w{rRjyFTJk9#)RKUqct#;G3J;BOtx}BLmL1*B~sPV53*S>;K#fbL*V;1u5>k zuwuuNAC?j5+IREQnhx%4edh}G#zXGVOe1lv3p9JbKr}vS8!1XPUa7m4=I>G6cijPa zgGr&DhKJyQhQ3*8Xz;fRQw<}5;q)9uo(3oq+sqALz8xR0z z!@(4elt}J6<2FrW`?Krp6Dgvm%X*)Gzf2gT z(|#<5*{iE^_&GYK=@k((B4EY1ih*L;7=O)|(QTc6jb;p*GBQ=_H zOnhL7G|nx4p=f8#s$a#(LQ$wk5cSeK3}B-;D3a)eI#wX%uaDpm2G1=I4UV(6lCwBdPl=?qb7Oix?ZPcO7eZ)l*_ zJ*GS&Mk3F6UCnNKu0iZe8(uAB3n_?cw7fK8mm=)h>b+QpF(1=2LkS7;yqqYN-{&>X zLFR5Rya(I_)jR)JMVV3eq(O*JI&+aeO^pvUhH}M0i3P6~iPVAY6s}j@dlsW^7`T|k zO1FV7^`G(Vf7!wnqeM@N=Ye;ZK?(b151t8VrzRxz%xo)CIJ&VnC)W)fw1?9c^InvE za9BG?W8Qr3zBuQkxC0~)Z!>LVT*cQ0m(Q8at{-}sxJ{?ETiChy?LsHVR@zdA2FWeu zlptXPVge~#CRkE(STYqMW-!LMjE?6BU|-etDSIGls^5xopAs88JhyWyvfI`2xe`N- zoCbQjFVS+&qhf$E5(ue8R)FbYP`3HG{_7&B8~04P&wN?TxT)s2hj>k)ccFvH)D62> zF2^lNqR;e2huoIP3=wV(yhs{t<)R|Sc6zSG91Glkco9-GnD1(4U7ff&FG|YH^^tk-rAO;?gWW4(j@R%L z!fM2pp(H^`1XKG6Yh9!&cPZA3F;hjqIrI5-6)> za;kc1pPlS@DCSjbpZC{{+DEVt%~R3^RSw3qRK+ZJyh&hn`zsgM{G{?T&pEM~w-?o@ zu~MhB#5hnDTo~UA=lO)_T#?h(*7vJgTDa1Wt%uqR0zfso_2i4znu4Zv_cg8xDRUOY zoOV*inskU=BvEUGcBP0#NO9gZe@H$1!L&R{(Jw9P7f8O3U>9cHzEEv3jeXeTBbuv# zeXuQb=VX*0b!K}bJy2_9L5i1nre_5MkPUB9WS5kI@rHDc2T(in((6;Kp69Ll zCsl4v)eM3-_7($c+9?Cg(j%}_d{vkoCP+g-$E@%T(%`8(C&Aj2Whs^Ji7aTZNVCI( zj2kDSA)@C{Wd=+_zz&h^eE0B6+04cgk9=qZ=0~K+;z$%rI!_S4ThU($7Aey>#M7uoquT< zbmwY)+bWHV8L>Pv<4S-5hVy&4{Uvqh((!EDR@8vb>iGwP4b|(T`8!Pb!_>#(u5C{$ z$yPUnn7*eJ*CMULdprUHt<+K}BTB;YCU}=%?66&Z%!)qLk)gGd8DZ0{jT~z^k904D zcR)6(kn>vKqYy6VM&v}cRWWh?KP;Hr=$fp%07Qit=hql>%hNNxD&2Eo!c>`7W}gGE zX%+dvtqAlTTT04OZ&R`|A3dm2e}x#rF?}QGH+JrMBNkf>rV8HK%wCJFt}m)FrdVum z0HPAL$Aiy~)0-DQlBLlQr;;pC*WewA|i;wej(}MNkJ2df3wFSiv z;7g~r@|Gk{hCYpokY0HyOBOfB3ihVtsBgU}>!lPV$3I@hJ$sK^vo!jy0jbcB3z=3~ zs~k_?=>Ri0HiJmNfsB5PfVn6_6r8)6))0ha-HCO$Kzbjop zn$45Mge!AxSJ@(4FT%tp0(ocFlsNE#MeZE>J6h`Hv&GJ==lY_kx>+S#YD)OY{C+I6 zGQL7Oiggq2Zifjq4LX`0yJH*eqq(G1dVVdGTmEc)g2}DgxN3_}3x->(9#DEEcAxc? zZa=#yq~0f1?nia{*#mCYB*XFtPndQ{tb=~9J17uQJbXD0$PF3PQRn%8fkEt5ht~rQ z(pH#$X!LrLyXs>TJH)~$^;i{5huzTx9#NOa}Bm!^StCl!5 z5JBtK?W$yAvET3Ovh}{>2ztjN=s}!ohTqwJ@VP|r$;}wmg-!7R_*&x2QJ0Oxv+af5UF%e(KoWm8sl5BpdHWTAgo}uz>C+!e0y9g#7fwrPyOPE;Po?{}LcyhE zQLa*VZ#%`28M(ypA5S1FtgUioB}D0`@?M`CUp>NcH$C>LRB@SZ)LfKO4tmiF?Nu21-OJq*NP#1GnGsQXt>xok zDSWeK-$l$9q1bffW`0o9G{{e4KR3@!`r(S@yfMU=&eS>DgBoU&eUwAJVOhS#fE&C* zGC@r{Cxw;-Bu)4*r9cJEzt6pPgAX!oS%HTnqfetZr?uW*iT$}dbYj6^zWL>GY0J{b zRV2I*a8Fh}9t#Z8zVS*bUCwk^HeN){OrxpFwZ-I|y}B_KhC+_!3>G@z#n5REQQJ1cbsu_(egcRQq_ z;7U^tqNB13wt%G&dSOiBZ~yTXWh&&OF83RpKxQC8#Hc^WaIN=LAUbW()NN&FX%D;JnP>Zdr@e45dw z{M2+=dPEsEd%fO5bA8Ns{`;7P^E>62sXPyeHj`)?{3OhPAQmL*@e4#NRTiH=DTwHg zB{q%5r|rsuHMW|S)-z||C!K3tD*K#>H4kAQOfG!bRPlgT*+FUd26U9k{SHEbGpx3A z^?vqldMLOpenCEuSzy9J(7#6k8oxzK)7ji0fICxKB3&TdSh?mY9{U}RZcz7fngn6& zlG?KM9h07gsz5j<&{6IeD8oDRkfr>SQ;txP;Ly+X&1p!CV%t#r_afcb5ee6)&4e2l zlw(Qd*m1n|n-}|8vHkL(&z=3z-?X9HHCQeHj}(l7@%+NN-m@E6Ns>~G#b$pai%=bokFq}yg z=~*_vmgFZ%95xrUah;HELrKVAoFUK&}3C_jRau5{6bNpsifyxCmyH1?}kgIJ2%h zYi-rf5zBLdhh6U#&pRJtsm|+ZPD(JI3rn|0%ll1+`F_?e!>Dj(ps>az55lE9RvC6{ z|EV+T?kYtH_V{OtgeO{*;t--DCXDueL3)tM^sy)A}D=h38SL7X; zo077ol>>NZMKR;Cx_7?NTuNKSHF<)oYC;jtdtdC(HS7)^>Y{B`;Vier&@l>z@R~^| zzSIUn@XMTN*m*r2lIgn0DKtHQIPH*AXGzG-s&t*TyWV(B18N=LI0XP@OX*WOamCG- z@&L&x_gH{F!1To<2A~$wutzII1RHY1*Me0 zX1j>hWNsLO_AdG-f)KOqqE>E%%r(N%fA zpulm()HAtBR84N*3gkFL-Az$$(Pz*GFPygm_NTjx%+ISfJ6Q`91xMW^L{=v}$Jx(m zrk2iU1ZZ~<8z0S|u6lO0DE@A z$sx(CIaMjW@NU(NcH`6NhMOBEg}Eb+-wJzm;}R@W#F65dQsxfhxarke@o5#|otK%N zlPJgJFvxjKfWPihU}>JRr)zX$W`=Nn_Q#Po2+?YJ?wC$g$){o^@5aWKc~@(E2?Ri2 z-Q6lU{$WWUDk&<~G3`wZjCHK7o%xo^oR1ru$YWHEmQ_FrGFgjvVYz#ZKjk(`Pv5H9 z0&Alsr#!awr*4Smf+cPiLZmSL>>XZlX7;t>Qyttpo_C`Aqn=K5Fn%t&f8`xLLSZ=Q@I|tKH3AiZ)P|*rkp8P zNLM&5Yj}o4VIwoOj9jKleIt#R&nej_bf$Kz&J3>TeE(AT2%}A&o?93?d@va9%F<%D zX#%8}|wR#nEcNtAfZt+cbw=+_W&PwYwb@`&g_ zb{s8a5m|NN?IBuSMW>>`$*qJP5-2$4$*JxxWxKtNcDW-Ru?*A0|7=&{&D>(EMVw4N z`9rAC#HDD*(vnI4t!*i11=^fiXekzUk7IE@*I32#rz0 zJwzpN^GnwFryIFWMvPqxEt1C2?UqFxO^RF4bb^C3xCmu6r%Ow;{OT^Ma^GQmZ$X`r zQL`{)U!=igA~HVoh%gy--r6}dHLAAZhd5F_%K^XwhQ5##Rbk!YkL-0WICon9%_N!` zzp+SswOD>hy57d!lc!xenrY#xu;<{KRqFIRyEOxO#uZ-a8r4bI40}k&;CYQ4-HeSK z*_N=(^GI>r%Q#13S)Dk(s(r?K609ry0bkGxr&&$;B%k*E`=Kd^q=WFXg#6PdDf{K9 z1j9aBRreKF6PXUeX}i#lW3xnG0k4+j$rT73bN&{}@9Id6N&40ENEUO4!6wZ`_&HM_ zwcC-ZqgHlx2w90*truw?ti+mY#ab@-2{`Q_rxozt^~C;n`48v8kD(m&D}4 zOkP)Yu@TPoor>@IpPM_2Q{|8uhn+3#lVn8yAZ*dqYAC>gwy-ob&m0#$5Y-~ryW|Z0RJm){>$Yo0xYXvBDp*BmMe}BE7Yrb*DbD-$-6Jzm(|-hm`_DR9wdO7g{`t zN20My^TH&C#eNsPWZhRcJdVOmZ;6P7wGk~`EonLsAzZBZTRpCMZ9H{xL2Ovt*Q=jZ3nbeg`^r znSL|)?PTX{dt*P9k6y1wt}#9vFsB}y2&EZG@F+Es6_m>>k>!o<)S>5)%%8o!oqTUW zH#nkOXK0%75T0xCitGQbKZQhu)JJ{m^?GE787`Y6aSXR-xv1ZXjUZ zF=VsZ?5?hQ>Zz*tf10}Zpa0W;`A`4&$3OnFEPd>M{NvwU;O~F@hkp-_{P+L;-~QJ> z{^S4sKN}xz{Z-ao@sEF^+~42+i9o+`-TsMw{)r&TH2sy=Nwp;X`qxlw;1D?9k9l3z zMgDgi1VW&Hg|L5xAs2@Ji82Tc-XQ!h8bjj0+b2~q{9A|kUl8cvUxIqb$8!Z=br-zB z5IBso;2StWV1IwT2<*RtBg`~)MNp*Q8r)sLQSvX80EhqOE4iBbPlN;CySgpFhgf9o z_+G;Omazv%1Pb)~7fMs)Uoe4!6HZblOa1?K^FB?nCDq?gvej(HTx>z#-IhpI7xPN~ z_Y)k&vex79cQY9Ii~b8d>YusT?y30ua5auq2kwge6Xn5d{@b*H8`S?cQS@kxN#Aq! z?56Vcuit4&r@uQH5-{996K;aJ`d9exPDtqpm;L&#+Y>%tjrk|S)=^2MC|a`8c$6ho zOaeKOUC2NpW426+6VI+L^So$}Tz{YXKse$6k6U#^J;9Hu?%~B*VF`NT`jBRMS^SVR z_;p|U_oWZUxs0LEab@{uz1_ z{DAD}xX}i5i6eu6nCRdU1@@TWfXOzyzW?cqec%Kfd6sfX>-N1Hcp+FwEi;e_;ecD- z+=i0xvu*coa@D}W=Q>2Wq{&JCyLlPE@^CG`Aaj#qyQxrNL-56I0qPe#{Dx-gjJ*iDo$V=jpBs zNUM-b$@{1Xl5X$wyEGZTk9F0yaVXskR!?xhq3GmPg27;pK7Y=}`i-n1Z4xT>fh8*b z{RlEEyXQ+b7zIZAcD0{n3>Q91y0MXhV|%IKpM{nRu>u2R(L)FCPa(f+%EsV_P(o^^ zEAObPy-7yYU0BfpjU;VA2P7edVh>0%i;9w#1s)MY^e`&r!OJOX5mM~qTVl(f7CXH+ zlFa*9Ro!%!&NDaU@EDL!w%45=nd$;L#K|Lir>1{~9k3>MA~M$B;1a7m7mBhWpFXt2 z6!D?VBe7akR9|VB!XyvwNH4(8*_keRty7amf_%y<_Iyf8;$Pw5fZ*9}(FT}JB+0$$ z*E?zQT^Y<6nAW>aRYrl`D4@;Y%InJH0g`Mjnkqf)>h-|tL62^_x-NyQ`nj)+wPUwO z1^S*yYzpdb`QBIB^{BelVG3KdkZJD-f_P#-*)&$_0ZIT zrP+HFefsU7=$0Xb6QbimJpKp=xRna~3#-vB{m38@KGH@|lp zc{hMF99XRdPNWYlyTVI#t2ttUc6yqwDTFgMk{o7^n`GuKzV&I3jr*F66lUOJaoJ^j zGS03h0&ofbVC9;Wl@#q2)8rOZ+4VYx$Zz{v1^LaWuF2Nj?tPR2gJlhU*&HQ3aqzu+ z2QIY)Rku8QUN@<+ueK16<=t%)Mm5N7F@BOQByw?T@PKQwbQ;;8aN7d^V_dSJJ)beY zA)!RoRdfS%?oUBr^DB#aE%U{RMRzYcj*O|=4==SxRckk-hhs2Zrqd!_YY*p2RjMRP z3M$54IyPaR7^92_cASk!$aM}C#|PSM&?k3LsdLz;gqp{Q4RuLJ%jM|I^{yueH<)QA zto>Q-PGYYzm)VWntiTdZ?bynj_y?)O##=^rxRfF8hhk;mvsbxmIO2k=#yIy5{K0cM~9iBw>ux9%|YDr8kB%a*C(xDIbp?^-? z1)fdyRNNFyjRQR;{KON>O8c8;6Bf~LpFH$|TfqtMex!aU8eb{y+A~$6{O3yH0 z-+oX@*HHVD(dE>I_Bj=t;2VXoXX4tqwTlQ)g-{S{Xa#CcxhG**;)62fXfFfH20=Ii z1*-`6v(?N+akb(Ol&{pulIy?Zo8Tz_3$K%>{A8cnvkkcF6)00QdZk+AQ<%K092W7W zeEY0Wde~-gTG)#pxyy@Q=NNxSh4@KKuCUq?tXym;EX+)=;PKig*FpgM*nCh`{al$+ z-E+Dk;olYiV0rc8^6DwM@mr?`OAYik>u5fBuf`2BI9_7;Va&`%+^6(vr-fD-ubz@T zW#2~kkLkfjri>GsswD*gSc!Tx`Nvv5_G_QSG4mixCracM_OBf7(8HEot)7&D?AQ-Q zxC~QEX6~2961PD6;^6t%P5Zj%Z!Be{1hc^sN3LC+wUTE(c$&A(is(o9;I4mgMrs;5|C%J5+pbSNM&C%HTyZbdS0#MG2?PiNTOm+n z(2yxL7Cf3NED~Y|EIe=>t~KlgzA8T^uFqTXn>G4AT(W+l9&}gMF0w>t+lj;p<_ZvU z^Sg!c+dV&QL0XM)OIHabdvngZ6)Mj(WXm8g2qt*di&L39iASSBSE_NaOq8C z;%ZKLe9<*~hkDpyCHO{vZ7YeRRp&)u=vfT6^6a@(tOQ`}m4V+;>3P~W5h0)?7H!2|g5J$=yUXEbv@YTOu%JZ0?j(1*3v$BM zes{68V!&0A^%za{?*?na?-kG$nkq5_M!66Tu!DDro+HYR;Bygz(oM$XVwbi>^J|;zxDD=Tq z(JHcB><&1Ltwx6NrVE8bmxrAlF?EQ5Arqd^$Ujk#&iviBO=b{ho=9wGExLgpPuq0_ z|84;2NoQZ@*cK@jz1aEi_Xy#zl6{3KmrtuSma`ct*RJP$?_@@!hL0o#unIabOpV|e zOa6GWE+`XbD%NdW;#n4{3bpwM53rk6H>4_N_JHIJfdk~Q zxn?!I<|2F1W~ufH62q*M?caD9@M*0YGY`L7VKT6%a6$|m8d-MRccM(KoYQ8ax{KKe zAR)rQfSttJITHz8>5~vQ5p?pltbO4*X%qV>$}b3VUah~e6FYR8fBM&)mue^Z3YCG) z_4OaP5Oiz8r)Y4Lhk&b)q=xf*#gued2l7o7aI23Cb>|maI|P3U@H-35?e>2&*_Plm z>+G6Pa-2znc}pKIql)Moyb`k~(gvF2D8?r~K@`U4Rz9trQmI$l`3MXc%LMnSE<&oK z(-C}}DUCa{L9S9*>zqL_h0)_hR<>rO1HOnexB$^JV?T;dpB&2VsSNWt(}!Freg zYp{Rb@(Z@ESFCn=;^9%CyfQF16Sz&oNjS5R$oMC#R-JaFR!O>#bZ7aG)P9yVK3sJM z0SDoq4j?fPey+@m(L_wG%Ljdrq$IS*(@lWuYg&xCpG8dwS(H?!0n3jNI&dglP&P zb*RkRL6_f1mONj=qC99Nxr=>W}x`IG$iW8M{M3*;_mNIU?CG zIP3$lE3S4dRQq5)V0gjw>)HJ(5eO=TK1n)$OjHr12mQG}eAm!o)gN@QfEf^OM?lwY z%C_g1>F5?romC|T|HEZ6!=)XPDS^X(&qa`_NKi2@=njB~z2R8f{xHr+{n#CwChxIA z$VeyHRM}S)>%^G^6zEU(iY6Rlr2zO6G>7z5 zBr`U{=8tCAB&A=N;JiLsOs>gQGLM%KQEyEZHP^)lX%QFzfayo$)3<^B&P2g<3hkOE ztQsgaKFC(8X`0{>=w~LTcnrpUQC{gJK2~E!t{|ZivnBjo5c^#v+o_&`n4VjSu;uT8MO?0ggP8p zOMy$muXqCW16Ytv?rn)=;@T}Od>ilM8={IfPK&S@uYeI^MkW%tXaSGR@)TQcRA)Vu zs~eIX&nY;?V$JZX{?64Si_5iM19ZZx+QBR^g{xV z1SQ?Rb?h|J#*rHBV7NZXUBAz(K(vN{g^-I4D^qnu_MZKM8ZNy|LwauVs*GFq3g$+8 zw|niy7^JD%cCpAnEnLzGBgsquVTI-;0|aRi6v^KsJ3nqsLVhNtMvoYAc)ga5-m~xk z=tDgupeQg-QL%xS$L&?Y6skx zDp)j2(D~^Z8r=5Sm5ZyHZ=>5)vn#{*H(p}p%%-CFW*+dZ8^tQQ54z=5>YnfoaSS*7 z(=(qBSE#S0piZMFvR7WKHFC4RBwU+P1{OL4R!5zvX)y=+nR89~gxfE}RUwgdnvcU- zOZ^Fwx!SW>rXiTl=K7ECl>9x`D7d#H`Tf1&h!djQ0Yg*x?)&dB(rcEp+kE;t1ykbq54G> z%2Q|f-A`X9lsqlW4;A$d?2u?7Qbr6pWTvy2dyBcUo={nA8dn?` zc+hS>_lB<20sV$hOD11@9mIIO%U?&+p~DI|_Iqvp-W-w_k!c z_3QhJO#*qM&6#Q(?go`pYJyOR2)rxiZa<02s2+ zUaPNnu4yTR5^fyFS_rbvKiTD8r zILJm(ORgqx)9Im-9krI$Sg` zXKZ4QPA}C-i{_5r27U3<>k6#P@N5GXZ*zThG_MwHvNmkOf*6Be^sLoXI|$8z%bUa9 z-GtRlrS7}0%4YONClOXKyU-tC!#nGUot3GXZ7|zAsh!gmBy3xhxI3=}!PlnK%$b`a z#3z$RXZ^}Bxs@h$n8degUihY~Q3Jq5lP{7*?z!mqZKLQV-wrW`WjdfR(QgxXjl>TL zAr=M%MkN+c;N|k?>*~$!6$sJe1OJObZ_q$0@)S~?YXGV}dhrPYq8^`K;`1_<&=a(w zv8rkH^ZL#NL<-qCrm~NMl{jjlGh@-lhiR;Ey(P!ZjVO&4q;_ zuS^ipTS4rnKWzPwc-wV9E3$bDm$`s*>zOC4!DxlNH>0h|eTazS{?6nyDWgYNk;N+8w`cexXz3 zg!=+pm2piyMY(%rY|IVb(|CLMpT2vcTYw)u*!So)+>7BQ8FsAFAZmJ6AXXaV> zh3IUi?JlyKM>!Z`(a0G6CdIaq-1@!c@udbS|AEqE)T)(u)p5; zu?QHL1n_k{Q1T=Yp$h1Sws*f$@a|UI)sB}twa*Jq+9wax*PLVEuglN%YhLPi*7kh} zF$QL$taDNkxOJMHTJvRXh!5gyns@3zG9d{P?C;^L@w$7j9D8W}ZO92q;Pu58%}QJd zc@<;FPoX@YGWokM;D@;Guuj$W^N`E_Iua%%fbWxf+5s*Y3yo^)JTlab`;!BDCHUh( zb4zPV{tYBi(__vaCoQL{ZlkN(I zm^F0?7+&;!#`FVs@Iz*C3wa-jE=u5tWKT_3-*2cOQb3PGnj)bGkV4Zp1KQol&SFaP z=@2Pj<_>9XH^GE_C@qs=xDRf3Q@-L_NPf4CLN0$*gbF$R`!aH7(16oq7C{Zu9diAG zkNh>KwWS3?U@A$>=Uc3KSmpR8z3{VSx$2|iXoc7q?aiQ z4*lplua;qK_B*WM^0TnAo!Qw3>SFMLTGtT8i1f3&oJ?ly*Mal(a5G$ zDEPFzqi$#rA-zwmL#g~GU?PlHQz^z4LXr~(B1-z{3lftbaO3zDj~;!Nzv>=iV9A6= z#H(YfWc^iK0Z%8GyNGLg_)%WIx8IvGS5#t~IX)Fd%XEZ^O1XO3h=&D!X2-T_4{5-KwA~vE>PMb*@!03$2Yy9GOGQ7^y-FzwSbI^( z4IA_4O!k*^BWxCzKve429L)RJ&CN8ztNOD!r5Uq^jU**8kn^I3>vK3p!MN9th!o4% zEgwd=*8!_o?|?dY%?}&N@|@ozvmt$h2>U22w|b&!;1O_9lXqb}QuxMFU#ETd__kst zOp3eW3mXBCsRQmjfbHN4og|Gk*N_Ai zE{*y4#w!~(aLa(|56Y>cpi%9J#sJb?Fd>~Y=8wuMH18Rns01+u3=QVn{ai0vUn0nY7M7JP&+ly{qC-#sCV$&ffMQ>h>3v&g`ISWEyKW_|Ykq03U(;>`lr z3do{IDvAB(G;K`5(+^ZyZB4Pnu76T6Nx5h^bX2_nEEyMKS4Q~tLcQ`AzB)nZzT3s6 zq};YTNEMh@x+Q!jt-pO&Nbe-$lRJlrvClKsfGrBNIq+^S;QpIgQw7dzHVO2bVbc|dt0ODTnN0L-$d8JiaThoZ2<#5~!LCicQdz}e!W67$camY~=9My8}tv{}*?nGA8Ll^`UxxiWg z2?26Sj7FwYe|(V6hI^TqUQS#0uR{|-Bm&M7%3jL2QiPUuCkbH4>;$a2D!4E%>DyEf*?QRb+nBVl7@1>)9t2aXqebV@{IDR5d|| zVXEMsJohT**gM*v{{2-sOjo&B0}VtMlC=yRBYD61b@&#|33iB-`g>f|KZ!)}w8d3` zkO_L-dL7>dU|B)Kpu!T4Y=(NlQe^Q<5RHo5;c&gRf#Q*|oBc!m$lm;_E?Egqj(5{V zf?SJQ;CXrgDPo=EUVGhvz66c6CgLkf+Xn-%oLGP?b^-AX)Z+~4P~oQ1?lh5~dou+Y zfDpNeN(+e>nYBubjIOngl%T;6Jyq2a&p z-i~aLU-6p0RjnWSa9~BYov&+5A72qjU>Lzl*~!AT5+Qwk@ld-u2gqh>M)CZ?&zAV8 zkB*PsTCd~k140eUzmNOk;DJSCn#~@>UM{fGvWm zBz1q4!UdtVxf)J;!`f}$EE;@v*ekCn0DLZ2yRvJuiv^;$=?G{Ffu+dqO^RZPwi0fV zFYB+DEXD7(W$Pp(<3Pcyk3s;0q#F%7KY0k2FnH>pELT~u%FKe=#%mS3 z+ghQ>f{5`hh!Vl&gH4I~{mnIHN09@a{Nl|CtAs|j2xvCpTwVtCHCo`cx^neA+>DTh zVW0~#^c^ZZ+pkb-ZBq@yWlVDu!^sY&t2KdD0aR4v4OkUF1jb_1f3BXHIzfO(*G(!gQNhP&Az|Mg*8$|@H{r+j@ zc&&jY5rAbaeZr9h>)TQtLcgY^xBziQfo;uB2#(kM1h7S0gH@xZskN+tRg@YT_K-*) zO8H=9@#K{qV&`YdA*teb^`STr2;w@UFSX7{wCyUC4RE4HI~xhe`-A8^64S3LM8bFd zt}F`I%BJ5NU_Z~FHB(6R`wz7vRVfD+XGBa zn{Oe*fTUVNZc^yP^)@wGYj>E6Ha4Z)nG{)oc1P&duUDaWLAKp!GC1p(T$h7vLp(n~ zBqd4FS^R`rehjLgXfCIO%CWCl4T9>~Puw}h{fIa*9~SS1f!+WHKIED_ot&b95V3a*$>iNLyzxTaTYlg*OBxi*u78SmLghQS3i~>maS|XrORuQz*wF>sE)BF+U+gL1c@{dza6-)w*WJ zHRVv3PTK**M80>d|8&K-6t$qa+bMT}&PSyo&tJokZa`)+=(Xm>K5nn7O$R82bl<)E^iiD#1fNJH zJigAPZjLEn@^bXOo@HN_@lntPMz$ z(O+RW;+t}nwkjch0z?cMA6_WiU$4GEPh;M9SO30`53;`D&-%80 zG0`wrP4(36zF(^n3Ymzjj>Kxlim8#FC0XtWFIEow{R4x;lAM5n3nzmgkbhSd2=<+T zBlQ!IQXK4=<@}PWMYt*FhulN~p<0I5#x-ZNqE^~9GD$=84vHf@;%9DlSGiE%piN5x zGOiw&k-9UO7_mrORb_5O%b#KgmMlzDGUx!q053*xZYbI(Xw3p3E38d)NY>NArmh^; zAWJG>sqPYP*!k7k>4mTc*NC_+28B8>Z9@DNjC6=+>cLuZCTm^qH(T`G1y^i6m!{&x z=^Yd@ga|cC(RcW9^6Qq>t5P2VEgyWDVH#C!;a0HB)EvM?e6iyUsrzISQ5ev7f9WHm z)9dk>T`vG}I*`q8w|T6cVPDU@GJ*CBG$0X(d&^Ofy++WbrD+QFnH>(r1_99xgtC`5 zKcW(x9Jl)fA6YACICm?uhcH|NVk#pQ1nigE%udij!GYx6=9jPf9hX2x>}E{RmW{S=3yw-pg9Y684Iw(z1Hc+;<~C~bf6)6B6Qz%lcFb93}(XpNrF z0EJ<0-Kc&gCpbXV0iRwi4L6(xKEAa;;_BA?b_J#aRH^CkPJZUJgHYIPP=svlS3zX0 znNv+i8=tT+Bj)zVLFpT&>^?UsJoKfK0?*>i>)2bDX?`lH>k*7|ttA_D6Da(2s5pUq zMlSXd(FHhA(1RkDai|Fwn1W;R;0M#PyKteg*=kSUN{qsqWO*q2cLHVNzDVp-skl#G zWYo_U8;yPWm5o*FEvIMD&L@o5<9^|xwMkaw2;%GC66(*YA-`4nhxwEd_gr8ug#c0% zeGj2Oa+rzB%YkfRzVp9LWaL>)K`%rM;@!Bip?DXQuZk5^u7|4P344{4nfDrYqm9>I zn_%nCb=;h2+=yAh2R{e7V3jaocblcq=_7I1lP{CMFt>@#(fZp zgG;ax0CCoW%`OCdeKcPf@ZG}1(OX1}q%m&H&jC+_91dt<%)6`6AfSz>AX;#%;1D%0 zL(d_^zT~-b_n`RZb!N;Mhmb5%XNy!>xoG^k7EtUnEZqI&WB<#Q(@W|eu~<7Zx4WTKYS@_^GUeVZiSUTsaVr>Pdm)EchA$| zQJK%#^Bc6n0!ED7!Orp{3rZJ(%Z_K(^e6Z+XO*Zmi^A_4-c#ekVxCeVDM0 zF;upB!ICz|Uf*a85;`CV$di5qDnK@#ZlRYSn{9y2t#A3Rl%k2#wx z8Nnx`4U87=Mo^eA(aOo1YJmD#klPN2WqeIOp(}l4D2&jkH3;~NX7&Yn0V7g36fEHK z)J;%huV*}79s(%*=k(b|GtaFt`4d1G8>D?{3HFZ02RfuE+Nn#F_GjpuH6G@$^YMgU zQ{(NUN)c3`cLZpfP16o9fFAc8DaYcBa8XAo?yR&`U)Y6@*P$j0A2ev%Dz5Kax55{T zuPx8r9JH zyDO|-D#K}$v!Iqhx~tX8?^f0}K1C39KiagDIUG4-U=+v)!)hn;o97jLPi~m+M%v{# zyPs}tC_<4Uy8QGP(kJO>KauWZT!pcqN(W`2E{M~nrw+fV|0-9~A;d$3Xc-6lP@w7W z`=Ky(G;flUIl9*WTJY4Y0s=JdwgVpo>ZT0tvTW&|E}<;-k8W6*S7x3>fZVIY&F_kt zbGBo(EigJpcr*`{9AV1*Hz|YS1c7FddJS#_K+l56b$tVCDm=fLJ{;13W{=of3%YK~!XV*7KTyZa9g_G1CKr|XF>n08nmQ+OTTM`GD}%kwJbAE4L)vS*cqz6S&< z3Ga6hcMUvt0#g3yf+2U+Z!RjjXE&_V<(~t?aWk1JcRT>!j#uO-2T9k70b(6?jdYr$ zoby`dp-{%+b#Sh{R8{N8AHbP~O*Idq zrmj{-)qCedq##M>PjMU&X*?*64UgkPd0w5?fTB>4mWu#ZK@|I^@Tr}(n9Or)3%kU3 z=D@3ULOV3XgN#-D6-=z%E1-G>Evg74WO}gwg*iHX5E4DGhd)7Ksi)H<3!;qLr=}AH ze!+$h#%)7h8Z=@|{$Hus@9=Z*Lx*k>C6kL=Q?^Ex@VMrCHM44%z(!2pH6NTA&!= zmNUR3v~RkyOvd`k`O|O#z}dk%1!_iyeqk1yjKfz;fQ!^uW7Y*LJo`*{UM8sHWR&$h zO5BWF)2B(5RT-)|3_$ysc5xx)VglG_`D=rWeQ+^v11I8G+0TrpO*yRXE)aM85rP5L z4~s$7ui#q}0t!>!#7O8_(O%N5$!;7=p(FP4Oy>Kd*Xuzty~R|0jk+- zg#hVl?K#uF0ao|BBxK2K;XE0dk9HSk8g=v$ziQ=vYv7MYxe8}8EaL?tlNRbg*sr~# z*Wmm5TgeS>ajv64o_-?w`~*7X0zn8|mwW-PmJgUm%7WGWtVcU{*HBskXIn>-y(^jS zmGV-Vp;%=JXmXa-N64dP>Non)z)m0(Dlcw+7nhqdCx|FHP~U>AaJmzNyr@m#_Dls> z*ecpTFK)T?6jDp*0)?X2=gi(3#W`xxv-I+h{%ga{*v(9S?NH%)$*MfnocMVEEfj(S zY*!vn7b3%yM^>>qawvNu06-cuiIB>T8oyWt4&B8t@;Yyz{Kh7Hmbi4pN}p_xE&t2m zz?@>B_vctp2&BW=v=u=V9B$&1kE)mW1H}9aKtlZ*fXEuP?a@$m#5nfTkjDD96#)%e zY$QjflVAod+*c>qcLEAhabK-Y4+Bu|oB*IH%F>cQE1dE0Q@>0agh*P_Ve;9}W+YJ6h6cC1HZl zWA?poxd;U9FCYj4y1Lj{8(UD!IFB={+~5fEqo}AEcm-t38XK$H33e?R$We@=3lt7u zW2Jyxko4Pg?D%HWxT7skchce*FK;(l&G&>p)L^ruiBj?otfi$TtmE`K;i2T`-qgAN zn!g#?YC(P9Ktl4*)ZQe5O}!@&G#MUsQ~l>p_env;yhIRRC|cBAhrZsXlmqL6z?f|?)I3W7Ua-YX8~v;J zkP*Eh3qST*0F?rf{Bb}MJjJX^%#DC@^zmX>A=yG@WG4q0;v%Vi)G7! zW56DN#);0j=UXY@Y3A?Fh+=%^!ZFyYJ)Jw?neDWZjJ1Po{^)jKH9Vl(YZ#! zNCex4pKUrvwMRXiETb;nxf~va}H}zy@1aHgqUWM zxs=WCB+9AQeZWRkh1n*V%^Ax2h3E}LO-K8B)hDuTFooRPI?_d~e??1RmN5b+Fwu%a z^Jl#!Xo7iJJybqjfjc(r;BL%l_1lwN=z zo#!B<`k{#(Tz1eDVe=7NfkHtX>B(tw+}sDb@__P(L3SkyiUEz6W;d4Arlwm_%!`Xa zqGdoAP-e;~dQSa*>;{O$NK&*8VB$|Wk7l_%u&^g@57QL(KMi>+7^GmOJ7`9-}bM; zwsaUu73LLxH0&O~szC*yV@cJYpn)V*12t%d#-wCubFxkl^ zmY$PTb4H3Flh5)zptd4zN1HBB-#v2J*INP)c&4`|*qY z&czT==j*DeE8tfy;w^9#qKMbN&99)uml$ZgRa{F@oW?F7U6)!w3I@nc0J8~aHs&z9 z#~4c|dgW3M$Nq| z*6l~O{Iobhb>^e*txrdX{<4+lRNp8~^BIAF>s0 z2vNqg5mlcK{xt>TwL%uiGY1(`%1?tP98_0<{5HoF8ZM9ZVjU)`@L*GSu|*RtIOdvK z5H7&6OelPY1W0uTH!2)v&cMGKiBlz=AgpfDtY~5$6q}yXk<;@7C=m1Z~{H26oj*46pC8KV^~U z5C4F4F!c9>wu0vr&=Mes-@BcIP@@423ZR}4%h*UMJA*qwI@tyuFn16wm4%GS4V&g- z?5;DJcfO2eWDx~xuvkS#YWJ}-K^%7*2*s@tiS#WT=r%U(0W)Iv6Qj})9!O~c5@LyO zv>J^5=~@0D-P%wgvqiqW(aL7we@+#|8b3|}?!gLK&s)?5(pn5q90V+|TCKDAB>jUi ztGh^TSFqDG*FK+ve|DnG6gmL+41Q=1mY~ujY*3g~^1~BDh3A6u!oXk1s%NUT6_IduS|LR-AV-_$YiTZ#rhO4!5TmNfRE|^3p}_83+L3CQ z2PXfidAw{Nm%upC#h$LaH!gj@ycl-pP+LO!9%vOuobt#>9d(JYMipzq;=+~USGW58 z9X}bh6OpTIXR;W4q7&S;eDYHXR}bG@h+Cso{T%6maE9c=ev|#9zl~ROdWlG0Z{g=s zgpFSdF0N?s-0M#W`@j>r4#39n!K9{F%Dmu<4UQAzi*;;=m*;vUV;v2=&pG4c^ax;0 z1^R;bgb6Pz%R=+rW-3>+E&?taKg{pzv*JGLzdGxQ2dKX@V$Q-_%Aic!iTh%AtdFxh zsFFGVU9H^h%$J@*U#Py+)sgTmO;k9Q?ZzKELHe}=k`-g~T~t<)9wGyi4Sx7ypYU;E zdp^(D>c@#}KDODCj7p-$az5|IO7jaDyH;SK?%EVYVLp7&Kob;+u|PM+ic7G~{~@1f z`MvkM!!Tj;B;9wL`zy1%&PV}vtk=rtt{WlwmmrXJnp8X>xqvn{llGcn?4OQ{E)!(I zc)5lw4E|*E(r}-uFl|kC*RgBm8hRPW>X{aWkR`M?zpWZF9e{-{Q}uj8aNwC=2b0lx zDfJKlwY(YIFbD#{timnfuj`-Y3F+Kv2+calsaMWlA2wVz;XB3+HMXTO*E4B{>?Z(0 zpz#`?K2B|_P3Lz5%D<~@F4=yRi{RQJdDr$(NK6(m2+=8Z79fLoE+s#b zDG5hBYr_X0oi)5FMk(jl-CdOL61e&K@CT7vneSZ$I!5n8Q-+^}nJ!Fq#SQ~l9*IVX zuLaG^AvI;}Ri+ReSwXAt#3%hC4K-K(pgd^5C5zrD&W$B!AbQX?Z)%Ux*S9uM$satT?zPev$ah;7a@s!0mzL(*5t} zz;(Px`uUIu-OwO9*i%)0zg%F7MWY9Pv#tD=MZc+m>SD25{lnQQjPHp)ddi;Np@F^E zI&)VTmkQ)3`lkplYyKlI&|2!CAARqa_*-ALpa@@sO>UybW11t#*Sf81BUo(j^Bd4v z)V*Y+vU-`t3`i@jS1oP(tO5aaE}*_OrJ{*fSuRx}#i1y@wE1A17Z!CLh6u*-(o~R| z`bemqY3%_qcHmQnWouz$cz-%)le&ZDBU~eQC{g zuRmA34$V8IqsOQH)~{x~zbq;3VRH9aq{BZfxv^5pGRJ;&HsmfM=InVdbvyeWi+K#c zUs07z^r`ZF51hiUcE1J#fd9b;t`OXDFMG=5%$E@%OraM6$gfVt#)KS(kL}`p*nt%s zQ^g%nk&r>3NRWQ;)@(dx-RCl6`90A*np7-BqBdmiG9I>BulSt=SuUAKg!e_1DZKoFDg9KBZb_|@Salw#u@(uXVPmymj=*4}IFYS;IXs!46L7u07z z-34@~J!iQY@y2jlF@WCk#fj%M;cx(-R@0|yMLbRKiFNE(+)3<&-RbLNHfKi88S!aL z*f&}{%@)Ia@`E)0C1cqFX-AB^D z>~E3Rk-rD3kdcYA&d|Rl9Knj&nquk{|58Zs?C$jEk#f*v=tbao#q=9N9L*e1Ll3Y~ zprS!8rnjk>bf{mz}cYH{s&X~Bp|fN zkLZv0#*qoMo$89i(xK`@)bS|XN&+)8#&E_AN9JDCkqJiS0l){?6m6$)+96#7oe1(& z9T*hJlKuz#e%;r?EEFW=KpJ?b`3?Um9+C2kx_C6Yqa;F}N#AH7`YrKZnnM9{c1Ks;gu zIwaqIrWP=bJR$a5w@^<ZT=PZGH4UYGBR4g?=~^< zaJ2|xagNts5;a~8YaPgg;MVc7pws2t*8$_b9B2p#wylS(W{f`ZQ|c$E+H4HY+cdlZ zsC}Q@yoBq%DcQ~ZZAXFkzg>SwnwyrxcOL@Y0za5HX+_=lH6w4oBTmjS zd($B_j!Wnxi|?N?Ie9MlkL_=E`58vDPSMg?ol-*`P4I9aYY*2y}D3y zN3b1<*TSC-ANHwcM^P?iepxwMQ|&;vj(Y6k5|)(K>xe(wDqAnvcjZMoTn)#oWDkYqh!kod|ei zYR<^e_6q&@F)L{Fr~$fxPEuuu+k;DC1?52r^UkS$pX{zSdB-$xNui;!{QSj=Ba9?m zM>l<0D(luE2_sN3@;OrWM#8JRA2|Y4u*)-~k%v@6^ap_XyAzNLrp-r#6&|UzUH^v+1mO!1`>_tIZW~ssV!pa_pblEZ-MZ{CWzHHPNLB zol{v%={0dN>@ClLaJS*Ofi&y^`Zw?k!2H_4|904OBeL!*buOLes=~+OF#4r>{|F$UU6=ww(-M-g-4e#6xNK;e$Jv|{0Ie7&k_X0TH0fucM#{% zNrEQy88Ed_KH#xUab3#G&4)ok$Zcq-KzWOcdr|EWPUvb~xqDrPBEHbrk_ClP%OQUQ z2{SbDJ(maj{hhra2w{An9YVO?iS|+s%6wpsy5(s+ko?ySu7M3JceH60{;okzDM>^w zmcgbYQEo36FIPj59)RWRN-446MPv74<|DwkZJ2qig8W&)0o}@!_fiFq?-e#>GMxA< z>%nv^=x@K`g0zx%{CPZrg181{=t7o`ALMG_{))XS_jZ)=}6un zu?S_N-0-CA@E)jlXG%fz1vyp+6!+l4uRVdoW?5er?UT8DoHf#9#>eUaweR5{5Cr~e zYEe?`(V$uRdtlrb7c!J^?;96pyt3uzjwtKSq$Hlgb%IpHkj@wj`O2eAxj(PReoRz@ zz>)pP$KZtst4VY<2n&rYPNFw>j9i<%JWRDO=hBD?0;U<{U9Pe<(oU4WfmDdZa`1$; zRmrLz-tY|IEQ8KoFx6j-4Qlba0{_52_e6iW%rn^Rv;Zm2r^vwe;Rg`;hrP*?q<@X2 zd(tIV0iiEQECSLgQ^RG|gSCpM9c+FAF4)#+A^Xd%BSW(#0%PJ-WFQRwjwXoBlT(38 zAi~NzInwKHRNt!u;em3SDQ8dYHQ}>Z@}lvq81LbL)RyZ7kZr4d1*$niM*rC7j0BER zKv#)(0l$=bPo;;6WPFQlNarq3O7mGhcaxZ}t#|*6WncpDn)2*$Uo7F-lt?WQQc&El z3Nr&iJXytlE8_>=-mhnu$@{$_4BzxOXhbOO9Z`hM$YLLzYi6L<)yV`?K!CP{B@Dga zz+E8zNHoPerP{4`$Et(HFDkzqlH9i^R)#*LDLk1@0E-9sH^{xu8%+bsa6Xd5yZa6; zZ>ve!Z#qVx~x_$ZG5Q%lrE9PT{n7Rj70j3|Wz4^>(qllVA7&l7VpG$K?-I za(Yz|kO0ZNlSaZ+%T#5Do?3mp%7NY>pZ3+D&M&#`D z&1wMQBi1B!L!7gRim6{UZAIplIRhBoFL&lc^W`^13#eKjKh`iyQpyP_Q$U2{+XbI9 zZ5H6B^5KGgKI#T{G&cZ>^J4#$XyIdE3r6Y9`2%JE#UPk5b|vD;)kqNcx5Phah5L`> z%8U((br7bYte94@sv(lD(H~gqd~ZCZy)6MC{@INSJStrqGParf)WMGroi*8gb|E0X z@5KW^mZc1dgl7$t?Wo@*Gw-Wx(oPBhN%MrpFq(kZf#5US?4gizwPZ;UxC)y9ao0CC zf)-lAEL*gj96(oPQQi}|gtSA=79-I=byHgxEn4qSUH3u2PGsjdxCHtrh*e@53sjX? zky<%=ATMo$#YW1~{`}>@$o&2sSlv$f2kQo(Egx;#wYLZ5JG3oLS%w>2&4=+`9qPG< z|L+}@j-+JE=Y4mM7vj?H!6& zJOQOUtF?=?Lrako+4d{H#3YH-JjNaoPGMia*wx4)JQsUH>xXy%EaXjS#Fs^K9}s{qo|M_zka3VnYXm3Icvr zpoa?i^%<70{SMBMPCuIO$C%kz#fLf~r+H+MO_KLFq;!sl8v}r5c8h)I`yze;C|5ID zApqv?SPEO03$lMrSDIl8UK;{qc4RSe8*V6ssE|)v&H*rSK4(d(A!pQWiz&RnIhNaVL{;wjx$%$;4f(1G?AdX!V(*j3E>g6hMD61euBC+;F{s3 z_dZG3-9oDCXnejM;cWTgf#P%zW#>r=XFB*HE_Ve}{A~7;faX z-ircRZ^*fL%BrHN6t5fL<}(kxsOV)pXG%26$P6AEH=*;z~tp!`QdXA_;aMEN}ivdi=d;>Ql5Kh zR9NUMdD>cZQyqC#Np!S`gcL)`MCJEJQR!W4?wIztaY}qt7f|k(j%5IUS74=Q2ls`< zh^H^8&Y6KGi18IkVbpvGxTQ_Ra(p+9c+$@q1=AhJPTmRB$p)CL!p|B}BkATPc6jyxFIAENX zeCmVhvq{+Le9}dPu|WK#H;_xAn-^Z{e(3xG1}|l(b{!ONkL+(o$!!UjYs=AxpwI*N zE-wn9L;dz=Ik)l2v?dKKw26FKSkT|8XL${^3kewrhTM6(#MKGKewFEt5~C-+2H3<5 zDoXtAf5G3yEbunZy!^Tez!$@xMI+c<5BwkqnElD{p-jD422x6Ca}c7^bQ|7dmL7*? zT$8%Qff_KMy93M@00nsr^jghMnZbX^4&~OPVM2?0Qf!5CkW}D2)1g8GSiboR8v?09 z2ibK2;#PEaL_ zbPv@z73QUt*NE@@8DN-rUx^1(X)FhcT1lB zF%(EzWaz~r3L>b9UTE5#{U*MZhhE%J=H@1<2&`G@vMri-(7^P zhyS#(@ctWyIwcN*mx^zFcPJh89=R_hVWN=7S6n|1`tzor4THWGzgH-LCcTiE19y`o z!fWwhw!S2&dj$glCU-?&1CEcB=-!n~g(d8APxuU|ORtq$K}&Ih7k1U46rKU(7z8@$ zh<-^P;Te1FDT#^(ie}Pt(k42E#7BDF*$?VxSpCL|2o|pT(#U##;PXWw`14aQ3@`;xMq%k!UL^F5+Q- zwE{raY4oKLKc!;|g$qiG^NrG*BS$GF;5I=FK;d)**Qd5^g^&l82aOeoY-tyj>-zEAEAVSM9)>%lXtJ znCIRZ3oQVmlHS`z#5-+-b=%p+?Eif*4@8xI;_bL8LDu?z*Z{=A`%OT+Bt>w^P8&#E3h{AL&T`0Jo zBwS<;HmPCPNOSz@1`PkWqC6Ku7T6}c1Hd3tPQ>SBfVFa8r2zQF{&vSF97Qnk;#U+v_tl$3AD+4}C7;8l z6}i&VDNyr|`<^K@1c^xQ8~#e_B%;m-q&aATp`{zOGVh4(s%LMi>jhx<$7UYICJ&SZ z!vTf7>gOWht_9Otd-rGJg$xudjlANk-I+b5Y5q`rlBAn3TPb+CNQu04y9a7<@S-q_ z&a(#8b)~HY2HCOej$|qz4u76+ZAYEI5+9A#Qip!Yl={Aj7ZvK`hX{rwjsPFw;Sx7%4fSf?& z>M?t1dY3cnL&!R62Ib@0AKxTJt<~?X!7_BOQDT6+Sdq~|sVPzQ)5_Z5M49-Y9Okrw zC6w1HHykxmjm`|T?m(NUd$$fZ`pLa2|LqoTQUk6I42QE`+<88z#lrKvs>>h>iJC-) zitZZ@5z!!jbUqdQ5y&qd)9o_p-}@f$hX(X~l_CSwNH6Txg58To&j^bm2fKED&>!U7 z&b=({{$-mR_8l8w%nrH`!^ro;LIT(| zC}8rwQcs03bma(hJ>en>^@h&a$3;En01$$LDY;i@IVr%B2C@f=9el7Q5;w0lLBDLq z`!*U2LJE4~(%RFT!t2v!!(sP8!(>u2m;DR}TYRwaW76obHD_iwvqJ^8Lz( zd({_Ti5Ki$%wDAe^IiB3!uEC^Z8i~g;z7w&id+@e23K^`=(jHc+25#q%f0_Ae#q&(g-|d&Z4T?lkN^dKE)^o;s9M+EpQMFfSVfwUJ)ibP}4Exbxq{eBDaR>04!D?nBjSBRgE z0^BS1<>YtgXN+FsVhDUA_`P<>+5tEKbTH7&FQCc+vFt+bax9^~ZDI)RTl~l%?rAoi zfwg$pJS7w6f%Q{3pGb?-d5M6Pj&w(J7%~2kO^G^NYy@}o+(~Ro(T-6WRiG!sXq@>; z+*Lx%;godMDZmcN2Pn$s0cTHL9s=FgcQ8_?&j^S`+|koALt!!ii<$I7XA3SIoXnZO|1?^6y}7QnzAV927&o%=RS zl3d52tIR`IU>FIa$e;=fe>mro5NVN5d}m9qI-nUE*)p~!<{UxYA9e26=sX(rXZ>#a zxg^6sn9T(rIehX*OV_J>?b~rG+$Qmcpdq1G$+~c1#xl3o#+-lJ#LO1LA>ykJ^#1nB zDC9^dxHbe&4v59)cHE_yFGS;)4MENNRO7o4q^mT?=|BgdehA)B9;r~!xdG|A4QZa} z^9kL{^}b^PTnSp+CcCKqxOc2zJ&|{GP03Xb2WUTDSRaSF4t)rmAwd=I-@3`ng$tni z;TPe>w^YE+2C6iKS=Lohg=QpbP<#h)Z{-CyNkQ_GF+?BDTnu=50n)~+{tXYdm2-ws1G_T=GP#RcOYV9#E`!r1-8Lx zwh=(o=~{?Kdd^s>D9$@x7I)9!`-u&pSC`gs5iopE@H?x2QL#F&X#oWU;D}7!5&J{^ ziUM6#nJL}}r8|pzzc(~E0N%cZrlq3*`9Lr*avDi4lkp{geZNJGKjR6egiq4~)NL%R zUCA^&^wwFK|JtA}L||;K6)zN8fGAmOn|5pa0>*oU4_PX|rmv@W=O|EghrfAt$N*or z*VEi!-ntj{5XX;*Je8jS^&ZnWO92`!A+$s!*Vz3jXPv0Cp!9~hF-WZd&J_4*fE2sG zSH=O4emEv9r`^&06xo?8D?9i3PNuIc)5~c=cThPE4ZDm@$(%G^S=D_5+eEu@3W-h= zD>atuTcy#-TnSw(2t-}K{@j~aByj7H!Dt2KE(<*#q2tbjzA{-u3pefv`p!Sb7w2lf z{t+|9bIj4NSaLAmgzwt({_oAcFYq{=V3wn-A76%fg8v;IvF7{w7}XyLfk&{7+Msf} z9%sS~r4n1v^a6$Q1!|VewY0@>$ouvLmbgBg`qTsU;sn}iEIFIwH1~Q}f1xtqVL`{< z;hi`XJxR@m@39k`-^I}}*!yN9boebS9A^d#^nX^;Pi&}hUfkKHHFu>!>4|>jJn&q! zJukKP986A`($XRlyd?{Xcs&6TXkZi2`NcTyC<$OCZ?TMOQ_ z64QN7;ioZ}HsWg75@6DTbo?m>be^Sgu+q8}sNFA)`;G%qYSAE%a!+szDiS5d3pp4g z|ET5rex2r50JfPX1s1-nc0{Z_pp3d9yhQQF!lFi>$$vrPENE-mrJm)mP-{ms_PYF z9W}z3GXP`ROaAKR;|bnal=A4c*ve>sH~>xpCq8EVaHvKoQ2;UvEz&&-qazPKZqT(n zW-^wYF-;FJLQu;%4c@^K^#C#JT;UxMkO*xe86(KwmDOMp7Qw%(o{ zV5>L;oQv)bj5O%{v3uv^Q!jSPUo89X#q({?;TpVYIg{YFkgo26rU|54tU|(uwYiC} z^_g^$p9R*?v!L94U&Jp^;7vDpfts}|EfEnPqCWUUg4VjJ@9x6!M>zJWYD6D}Sm8tp zpjNhE0(~?Tux#gO#C>MQeQb$CBChcwv^U_hq;Jh4tImXAq;S2)BugcW z1)}ng>AK6voi-lK0y0E!W9%jZ{IK0e)#5M5**;nSN5*v0@y7VTu{$pnu7%Ol0ixUa z@$d!fFlf1^@%n;h-VuK)8~^}FOx`(}jO5xja;()H1+RR&JoZoDpN%ifjY?mxar6Wy ziS~mos7Og!S(3k6>-E>jSpEY&AEtR7k8Du5nz-H3_y%N{!FRDVtz-*G;&e3*lqAvu8$=B+iJ>xtQ9bmNjET6~m1P_E`dL?YrI1OYSa`*m+0WagUVZekS} z=;rehtU5`wEm&%Pn3!)tT@9C)y#YTSGnE8z5H^0`;{3F3^ z)i6-#MSD1ZP#72#S?x7M6rQ>5gDp0`Bvyjp0mhql7_*X6cLxDm?mnsv%vXQ4hTVr2 z$GV%}l*nEAF4p5a?M6)e1M1GJ{7UYUx#Uj-LIl5kL*ZRN#Zo`1Ou--lw&|OU zLu5J#*|WPnS)+;~WL82afyeDQ{esORQPyJbaeLBDXb57x{!aFpqa|>=E<@j}jjDsE zav5NnA_*09MhM5!*$K6gIr?N9VTOg-7vp;mBibDVlK;)?umjR=Y7M& zO(sqE-HYosT^ItW_;DP^j7WueTjQ8#xPkf=+PLb&I-ka;HK;1kwU#xFH+hE*_#y6k zMUo(XO6Zb2U{Kw8Fvf(fGwr+z0Gib}80#965}MKDmMP}35J#GG8#Y7) zl!NQlrwUfF2f2#J-?a5UlH`%!DX%m+mRy-9K5EP7X0mw9U2nnuEJmt}n@9ep{5is*`e6gwWMe=@oG`|nlzSkvRSps7x zNT#GCuopcq&^+y!ZXI%;|9ur3l55Fif?sBiV_82?+I@RtnPqi?C(soj=H~IJHMBkN zW0HelWQYtZ>pgb7f%%LJGY#+!dNotH#%X+b-ye%NHP;cKLt$G2N+rO`1&J=|u%Gmu z8Zs@;X5w#wL5UCh2ehx0Kzwt+Bd11-hiny@MyWy!%> z_k;Qad@?RJMhM(TKaRBIRe|VwK_Khf-9m|7LH31aYi@ogv(tv}obrm(P+rgLZn_Y2 zWCL%P*6y^mA{`=lfL#c9v%So|2(uC9)%PK@Q}o-ttUL6%ud8wZPBDsf%>x)!b>v+n zdlIS5z~k65`E;zRADa$QUebe77uacQ4E&v2#G8Nv^e{6TTM@C4u^EM?eCPVYJ+|owx69R z$VlVfE0p&jB&HWbrl6;X6hfaeKs#n4jhz+mGZTxUa@qS2%J{|vW}ZM(vq%_3$v`-- z#UAg?l*b)D7AcWndI^Bx{$;=MW!J?9x2jaIO9k};5D=cG7)%BeF)qaRvol4`yjTkc z2cZ@rDFI3Xur70AT~Fr^)7*1QYRoL?_XmWiTdS}$YRy1*c75BZK&ML3LI;Cb*i1Ic z=@_WjyO2l|1lQiv9RhzW{{-Rv?4xP@qez-4DBP{&TKWS9Dd?4eXUvN_c@W^NdgNo+ zKs7py7k884Lz zSkbh{C%kSx=JS(dfwg4v@pFu~VEUYD`;50L7kC3~wGh}yTgHz7i9!<)_r|xpXtQ%j zQF#qwcC2Hgff`%XB^r<_)gPR4&|Jq?{E18bw6oRq@wlIIFS&-Ou z%Fsb!p7kB>JoLI;cGB)m!FI`UgCIb>{;FI zS92$01-T>;sDYw36dy!ZPCJgvA;mGdD%KxA`!+bl0w|RNrvY^X<*FfRml*7C&0v-( z3&kdqIi3(5d0S`+{Qx)TySOAo9i8WZzL5&xy&|erFm*N6O<0&pU$Navp5>b5JX6d- zSNT~0l)`O%KnO+vXckVD{}>dEQ}XW)&Xju@BClNnWmJ#t34n(DUhFWsH)Vr=b6|7a zbz|CX4r}f&fRlizjx5%|rXKGk5pasa=D&{&{22|0<>$m?%b@V}!3NVfOuC~YwP zItr+6(vWxfd47aSXzt1{*W9GwkoZ(NN&li-+qC4S>xX zK#w3`N9h+08#8KN#$X@Cf>c?BB0o+#YopPfv` z>StGyQeKjVl$;C*Um&9^N30#F?dSbdhYDayMYKV!q^n>~Q`Eu%6HE`C8Npr_dOrGT z7<&)ba8_zRYAxJn^!U*BBT-@2bngt<=FFbs4$D*XP-jniTo~<6u|Ap6)cwpc{OG%yW~T}Z>XQ0hIL~0Mr6MIq z`+ie0wHzb+a|4lu=!0)915~XSlFCgkMrJLAdFX7!bV5FyxETyu@^VwvE*Muh+){o4 zvouzazjl+f6q!Lk??gZniM5Rs3_c8W3PIuM%^?YhCPzQO5cn!?NN~0DT4N2rg@1iC z>_^dHJ-M`nB}?!0O>XdIZtAzB5pO^FBdTl?j)n<_IT)G5dO2wb95Kda2D?>{)q!VdSX= zN`ol(?TM;9m;h1Cg9nZmu3CFgy?<}rxRZNnW+K**Pzz-mI!-#{4V zdkUV5ybz|O)fASW`kS0@W+K0P-gDk{4GJ*lc2oqZeH=-Tp*Ix0JJfHyn7$>Kc4K<{gc4e!}Lxxdx6~ZEV5oE z?mQ1~iXPh${AIX2(R0$Tu^>-^X~`V{M23@Fa`&Bp)OE64l335`wRwxmrFe=~fE1WJ zOzeO^DV4~p{Nx!6AdLqOO%yBTltZ9JcX^p7qUAPxHlT>OSn$WE!Ew(ACgxeT!N*we zr%@cRw7fdi_F%ah;4`o}4w1hyq|bhDoT>FGaAi<>El?Bbdb#x%APQfQCPAKS z5uHtAU$o^Zv1jkux(;CjL;LOeh&=)XK9ZLn4{LF1AFx92l*56w1}yRR%d-$Cn53)0 zqDV^~12m2UwfFIyQJI3fPx}Hm+~Gs?w&54hs0Q$zCpfRZ0|=O45C!|Epj0rO4Xs!R z<9r0f-zPfE^^6!+X#dx2c8=?Ec6*_)n0tNL$@jOTIfk zpXL@p;CZx^2;`K83sD`C5I$PN=#!le@b{8?WoTeW;Atb!J9+7CzI-L&BaS!^8?uV( zUk`pPFH?;Lngo1BxEIJ_hzM97{oJk6U#kG}WK|F91^WPu1pt1%4p7+jPzksLUmVP| zRWMLZzedZy-0#6u{QxW;k<*RulNjsMcLhN*(-mtz8`=q~IaPE2a;@T}yFVhaa_9Wa z|MpxttN52$$*yiYh%Z2$cJZ#prA*8o>g#1xsE78(_e&A3!ddcYa|%t_abJxyxQdep z&*E7FPAqCaoZpYi_y+No-vl2Bz@~ObpWOr%Jpd-em#5(d@!dMNs+uLr?px~6d4#sI zc;|6Oy8F!Z8fqE59}OherEsUsJ|el=w-piq;@RR}Mr#O4`O{j4L?GAT?}OhTGLE(` zX8)d$TCM-S7stbdYBk2N^3r-1h*ZS>I!FYrRYi%svm&dh@ZlbpI)xf8>D@P^CU z%a#^mcqq{K!U9x*+#b(WOTX6$66r1!E?$z#M!QfYc>S!I0j5-4D*zzh!=^jrZsgT% zu^o=Dp?i$?<)Gb*xW<|XFM}1D#p%wIeK0XyE*S-)pY8S|)TMg2il2Q7kk~6M5OKQG zFo{X&F1^1f9;C5fp2_bhR6%3dri{LK-pi_U6ziHsy$1^73qMrt%QAcA817mLcq-ou zy>u7vr!yK_uZzArARWWyxi_UiC9MLgzn_u}Kt%Wj62om0D`%?*km2z^3mAgVmQ91@ zVv7LYe_V(&3IP!SWKXE)Gq@M13gGjPpjKhRlQ5x}&g_RxResh=h^zqBBfh^6_hDXY zDxSiL7)}7dLTeS?0sMKfD0KJkVn%#9MY%xZ|8W#hsq$h4Xxs`qClch*AW$<&Gf)j} z-iM7e0GEW9Y(Iw118{q=Ko(u7q(Tzxas>#u^ZMQi4;91JOTSSHfd^RjB@;NLQZxpt zEYOR60ABUZvh^;S82kuaJ>pJ&+O_iksa2eZm?xVPUlXjwtp8$fE*I zE3eZR#NY2$!jpPHVu`B$%r)TwUe-hfz}aCQd1Yc3rIaA}!i($>RhQos0(1BN{CC}e z<%tTs9tgZTMSff^onQxUqzwytKA&w>U^xE1&(-q57x+wGkgO~RAZ@m$ zOd0depH|sk+3m9#d^imW`g{Yt&roy0eR)os-EC-ToDvZr`Rx<5WrXldYj&!GoMIJp zI_bop=ITg^$Gx`e-xAz@Wl#|SI$xq+2I^VDQ#+laXnc2R%8Oep7$YHwNWs+uz?7F} zB0|&*KYPQ^Xpz7MsV>CH0vW^w%@u&%!!dwN8}IQqz&8$eMAHEC{2zf96&SZF=W4)U zrdT;71_an!-Pn@X(+N99@K)&m+_JwD_e4?2S*`b)`ZAysMKC~4iuo8w|u--%5m^@p?$T|CMgo8%`C{+Rk(PY2dO&wJs z8K5id@hJ|VY_R$Gc+VS{G<{VZX7_y9KKbQA_>IxgnF-t-L+D_v8Z$k3@RDNyq&xWf zgJIdu5xO`Dmox7P<#B#VPlO8;{5VOG2qYx?@zhJ}vj_MBeTra}&=i+<9jL+KNh63G zaNiL$Jw;_G_dCDY3&09_OxWU$Dm+m{C;+hn^Q=@SyLK&wO0HVgmSt}9;DWvn#c02G zAc{pW-X7r@kG>H$mIg+66FxFQ24-4+0tg>Ovq|IBHHiQwl#M+e0FE^80+^95$c1<{ z_ZtWoJVaRVhz5^i4y07SOt96gM}wx;cM6-&Xixi9yxQYlN3MD)rq5>Q4#Ii2E7z61 z*WygqGQ7(gZkU|$L+r4c1NS`R&B<^x7Lc?Ie~}h)&wqejMN5ovLLB4YfMt%tq;Xg9 z=;?^&;5;b?eiq=$B*5LM3EV}XWCJ?e)42oC!+gI=Isl6Z(8t>cY;7HSsY>?_q%fl4 zWo&3k=)VHl0U3cWs0osazzFt`NqK^yjYD4a^ReS<9y($GxkkBiV^LhYZ{O_bgt%GA$SL~ zCjGb_g?Kj9O)#6Fm<5pBme*f?o|T`G?LlXfgdT248k&2Z@KPz|s(02o()hWCq>`Nh zl2y{Wn>iZ_$}!HDDZfTu{#5Hdd>!Hk_pL(Kg+2qN_+A`MdzXwpw30sf{#CpkJw&gJ zGuo%2WD$>&1*#*oT={{2U#yY_`Z|z^O1*M^J7oWuS^6-Yz`1wE5q|@I@Baz3Bp=!h z6gVB1Fit5rlzzSfm2;C3nE)^Qv>CU%^$S=%=>FY{8+{P>O$mKKhLZPr`sG- zDqYzGExLD0|0tATs)n>|Foj$t+*nH(g5_7yVK#Cm$#3|RHZ>$16dBD#RCYMdhKRqB zoL&hAwiQGCmFS-Ax5j%ZB6&*!ra}Z#`t|d{J(k`&LGdX(!4B2vv;*LO@cLDUqGG!* zV*2pj5Cs_`0EM{dsPscBm_tFtTGmeP6n4D60!?tJ)?P<0wv+8;SEJp#{G{CX-_q;G z5Hs$JV*B>9Zl_7^v-d_CH%6Vtrjf6;!^>=Oy3=($hJLM?`G0Uekxr`1@)H%bWUkqD zNa${Tvj0druWd!OAd3DH8GIC#C=vza4MYS)$?@xZae9ot=XM`6?ohj`)?8rDf7-1$ z1$2?&5vPLY>3!c33=Ze&3I?cp`AUd=wX*5E9Lv?}h$73ETa(J=(@LD=e{ zKI03a`+aMKSidq!;`mlX&dqHI>hb)j;p%KUE9 zkfOWAL$}JT=f3~EyC)jVH^C3T_%dN%qZNPP(S9pcE9A^n*xQD z6-jgeDF>}MW*~%IiASe#Uwx%?iM?8J%R_94j}+8tO(ePIt_>qJE#ByGzy|&+cOOy7 z|LXRM6tm_25_4#DFYnn2+Q(grZ0S%tIkaQPhu!>ewoj0AVT)=pGepjl*1T4YOn$Mh zPS@yN+fU)T$F`w+ByGXgqTU@`Se{;|4~*(>lxN36-%kCm;TKQe)2>WKf7`H+SIyXu zpXYlJTLm$|1#gCFZcFzx9j?RWg`M(HuHXryDK`G3N30q9F${hn%zWj|)|SS7cKI;4 zjG2@oxI^~x4*rS!SVk@r`p@w1APuQZ067e-I6&kK`3nk$Z;dHtZ0{3suf>Qo(K#o0 z3WS(XKHgO;7@%072ci9e&@NFdRjOWy){TlQ|tf0H^DU{{MpraI{RHO_G zHeAB%V_Dha1=e&P7CiJcUW;r&FT&b0`i$1E zvmFCV_qN48Cg}bX9@tpLW2DWcQ20mfLa?!Ggh$2lX6CLZg9H~u9R`Wgsqq)$%R72_ zOdezA$Lx(LOd7o;zK{#`D-=Q_aXiHuM{n-kxl_hAPk7 zaFO!~oZpQujt!iVrIEU$Ken@xr#3-toXK9d=Lg6#w)#1~e?~|S3pbwf-w|<3SA974 z0_d<}mHWB!iFBQBTNTa=ul}8t-1hlGc8l%>0J)CYDO!d{7q?9y99Ovt#!E%U`TB{<$#Q!*oA?DD*!E6e%O$s8P0i{~>eJIM)n4xQl?=Jkde%I)Gy~1;E6TRl`_q1$Y zwcINH&UFW764~H6>uDtLjZyM=oVfh3)&4%sbU#6NH1AsqDu@=^X1ZEC%I(Z?KF$wB zi%Bkh_HP&g^KL`}9qp-_a&}_Q`$~)(STlKc$^Ch6&fmLvE%dk})6SU7=j&$tfS>+l z_pl{FD?23Dn$UxR2U`jcoYw>F2gM%;M`u}+>*RJ1fYUr_kQiFMsefF7e9FAQBAnGO z%S(qfIV^Q#xK1P>1C7D?y_&&gm0C23kGAGK;YV20Gpxj+AdR-3>4SJbD`q(Gh!S4$ zxY!ITI?}kO7Cx+`?pz+}WM`pYXZwj5f3#Ws+EeewZr;B)_%O8kR4;I|(HkCiVBCeG zH|ZdSLYs-iX()>n>st!rh(of6w?oqcy7);4Pd`k;!{0IrCpD};-A$ZWe$O$Bit)p> zzUAiLv|`l1xfEh}Ev>6OG2b-+^{ z(CS&92UmS|LGZ%p5HT|OLN)yQ_8drcEM9-?#tx%VbnU-7t#R*#<3k=h@e>H>Y|@Uz z!Hj+s2PqQn1zvjo%bTHFCHJG>Sp156iiWq4NrP7eDYgow+aNDea_vPefi;dqjkDnL zVb&tJJi6I_9q^~}%Hn<)?{%8f=Is?j+MJg)^_xTy>2e)tZE)ZzGZ&L}$nv*$2i+_^ z{Q5|l&*g9!&r(i^ut(X}+aod3?m@cJNI zQ~KrzFkALRw!B{^5}dl!oh_9}N9OgSQWs~np}X^9q+ozZ&gmh4O>;kc*f6a7jk~cP z44nvB%l%cNX`w~&CC;ufxWex=0M z^SV#*A@QIBLJXiFNZjpXVwgkpDq-RdM1uw&aoXDKk)9WC4=7x@XYsq$s-@u65Ha>`<5)> z(NFbFQ#C*o{W+uLUskhP((GeAWHyT(7~k%I6OYn;^>{pmStBr@&{WspWpM&)q zr5p~#r~3?{O93*PpbZn#9QecK-3)`Hc%IJAXD5owZDT4e?mXWu_8lE3d})$zYcch_|}ptHmZn^e=rV_Eb#$X7sEGKGQGJD7PrtV_$}SxP>`X ze}}TIM_fOco#^yMwpp+3hA6@!*tI9Pk-p{IBYM*~QsQG*wf0Wu72k{mH%`q|g4E~k zH@AyrvPlnb{lca+8ht{U(O%lVrU&G$xT0E2&9QSyz8P&2X@4uDJ`VI2{0gb?y$rb% z(HFuW%wvn7?%xI{T(-pMz*00ZGz6OPe`> zMg6&U2AbHtVXEwnd_3F1<$aP$%-%uNc~i3E?Z}@;{pVDv{oX$#n_#ik=}#gcV^%x% z@%L)1Uh7jRJJ2tQR%Ogo;>XT!Z$O9h53B`T!1J|5*lZQ~RW|jS{_EQKs7;(F5T43vs&4 z`+n7YQYlX3_&_fzC2;w#;?VGP?jfxoukBsV&d88Ggk-JB;FHYyq3+<5&<5ms8$a{Q zC5Y>Fi0;}e9b@^*Vm656i)r>SaB7(6f$ALGLjeDP#lF3hfF;dMN-MadE`~*viBvX2$+hZ|KnIkgepzy(9pv24APJc`et9f@aYK|feHYIE;e83ORH9RS;a6dPM3X6 zQ5NNqnu~uU?=4M{!18wfCt`@>caH|==lMgLZd6(O60w)K!sGUX`DAi$%qFemlcp)m z+M69wxMsiGCfDzK=r8Q}Bo*()A$7i@+kPK9F1%0i1onR#aD15$3*&x${HpH!-Z;SB zSMLrKCthC_Pkk*b{Y+5>Yo$7TNj^(=R;Vxs3$19MR6if#lG~2(w}*eThXX?bYW-5) z5@ak#HB!q5h16CZs7f!ZY(!=>ioUjuB=6o-6;JKS_C1mv4G4{#LZa)Ch z^D`AX42#-~=TZYC1k6Ei<}*BXs4rPO$dqhe<;?7m9+5IH%Z4i4g;Z(?!p_D}{HWC6 zSjBj-$c2Cx=6s*+7-QWWy_Doai)R!7U0QVhBQ=6I1>w|dn|mVQ7H4X@$LDQ$mO=mm zGMxO_sgw0s_~}hgrSTLq$v`TB9lv?~eLZIT=0ru_>Zv#E&Y}ee+pF~H9qWSYm50kSB7!vYve|s`Z{PB8C?mxi zfOs>zHt+okz2aMwFNj>l@sbS=K7uKL(qm?`J+u-*-YXIy?#F%_7H#Nc@=mUxw7;E_ zw$l=HuMiX~8$KDbLhf`@X$Z%FlDPmriqHzY?0W0Ys-rWmLc?h;)fC-u_VIJWpyQ2lZg9c6>WC z&nRGSkBZY@5>01osF^1^2u?W>lvDFkz6$Z{c#p1ogd9|;{?EF z`8$o9>ilg^ z?9{z=K;xL$r!+P>K_VR&ng9OqK+h9TfU1JUNMLyTVc>vDEgO||9T@1R!+AbuUGVr; z?sB`%gNRZuR8|^vx6yJ+aYd{7S95uruYO)}eP`Ia>1BBK({N=D5;Yt0(3A-n~mvQn>*H;_C1)b!|I=?p74-VGrD4&!X(uGS|O58O* z+s^Xfp}ob^-R~1%>^15wo(F0Iy)_&%afjNF=d&{01XZq~`rF)0I1UBc_uwHkw!C6bu>0ahGqDcj zf)9kVIx2Q)Wgqc()!mZ*=v_4rXD9A!&L`bNi37`nD>6oGo=={WgbD zB~^0zFsTIjG4{sAkEjVp5)mVl!a4Lbte>s!S#UvO!{YRP$;~tFW&A3HAaPf9#CyjT zz;ri}?}1j^$6ncDwtBzB^L`e)@2jzOe%p)AaUb@4X=?EUdN{gYC-`Feo8>|DOfqW_ zo#|VRK65-s-t%DOKEa&aG2T>NR1nG_PFQ4xz#)kIf-ZhN+>y^okgot=J&fML^E2?N zsTkf%>bdR{ZBrF_wdEJmFMCotCS^`US7d?*P8rOSq<_O16z_el#%n6P-||Xoo^L_R zlis{L)RpiF6gCQOx3^O`sxc8l!^2F>fy$@i#uwmgJpcAgd5v&MF5~5`zm@blB1V;p z<PPR@#p=5QH?mPe-PEPhaLg^4;3gvJ%sR(f3z>tnaPBYDJjy%vSMn z6{Yw0sfTy>Zt6-8E67%p`;1-T&*kZqFpfx z;DRB;LRj)t^k*;NUKVfL@;|rU&CcJ_d89;ox}A>vZk@HJMlsoViR=RRCmDH)^Z zQ0x=%L%_bL--jbiQLx8|n>qoYNoX%)-rD1Edk5GgRK9$S#3u;{d@MH|GfRs(&X$?7H*JV z?>)d3=*g9GzGDn$=}*@C<}fJruI!J1JHnP96s**r1rrJe8E^c=Rga%$5n=R6*RzC- z-ndM6^YGo{ql(G3bU(d(1kU?Dl2wbiQ&%SM|cHP(b8!sC1 zQ)A5ScFXzfx`JC|&=QpIDua^BL)hh;d{-f~DS?J`lFR3V=JlMc&Kd&~?f*ipuzz zpPn>6l5YSY-aFDLh6#K?YG`r&w?m=|obk}n|E*>=ETks+_ud!#jPv&kNNo`1^q;F{ z!gBZrBgUGLcs$(&KlY{RQ0Qg~(-`g}C)bPfFyt0cC3HD5_Y|HRq=3rp=lZ;uEyvL* zfp;Pbh}^yrEar{Jz{4SiY=foOouA~gaL&zTeYx%t1x%5$+|M(;ki5a1u1PA-Pxo1f zN?GL?)}nga52t0NJcvUZF|~g+5!ziT3m5N>yjmlp9cQRB#|D+u;llNJOhY@~N_ae7SmX*AnEZ7v90frv*W92wQD#Do11>GH84L{&iq3c*q6B zrpND5na*~{EJ+{J2Nt9GSsxBdpq~>xunHtquiJ^ZvY+<8EQwc7?gd(25neYgoA}pB zySzSUFUuHVMB6Q%b&O~CDBq0Wub_T9OK*~(vSv5u6VJYaa*nUL{2qmi_hU9&F~s-G zL)ivIV6uq#bf+jwR`r~mpnt^#=f==-dc*C@q4(yisK^)?_cVKG^=7}?`?ng2$y0`V z_@q^b5p{e}Nqs0dQ5w{-v7<1P%bT?k9bS??{iHW>v-;ynE#T5yg(-x<=2`t647O-$ zZ+$0vk}g+Pvc$uUE5htF3TWqye)ifu(y=-!H$OZ2t8Vx2?q2j_^frPSeqqcW!YGbJ z3h5-cTD75mdF7MG)&g>0?q5es9An9mn>R>$3D~oU?9pZMmQ8sIQrWSAC z)Pb7B)9Dj;HwDYFQQpI^U&|TzTi1*r^eV>?+uZ$y63OMQ5Z)`h%_Fhhvi_Q_GMhtF zh9?*TVT}#&p-D5^sYZa39sina;)zwFH(PE8C7KTFbjI;sikj5e^d}~Z(9!CicY3V&qqgq{N(5C&y#1t{QinF@ zl$KS_2r*&;(h|N3^>4S2>VgZS$FZ*tVdhkePCrsBd-W0gTX7>4i&c+`8P*i>6TV(e z&iei9A_qO~x4>JjusC=1(H(9OGuKm)Ab4Nc{II z$V(YJ8w{Swuzasq3CXth&R+p+&jl!izQR7DBee*YX0E^}@fhICI>d+k*7H-m8g2@ZbvwPo?O${qzT70~gqO zHRr-^hy`KsY*H0${1kE|ygLtpYXH#u{)O^?r+WYK3k!6!J6g65n-__e2E32= z8{{L3^#CoHEr!*j@`+1ueTHA3FORwz~%>T94i_T)x_+V{V-2I<-G~)&$JFH`p2G7xnEC;lkIa~ zLf|1mNkQfLb6jn;1G5ajNfVyMffLQdD9374?KmIF$3_pZHN~ugzszMFhe2Lk*iWpo zx$^W3tM~}Slg*y1QnNqnQRe$H1>>KUgGqDFKi~Vn!XG9e9xanD>gj=vSh~a)Ym0sF zXR1S(f4ky5kvWNeTDZEHjU#2>$K5t4!lvUBAt#(985uf-rvv=Y*HksxhYF!vR+&%y8eQGdO~zjuVEupmPt zagM4(@X{y)#_?aueH%=+4fOygR{05_$%TFvrkt?P=KV^4;^!4aD|JH5S<$7V*vtnd z=Co+Bv2R5B(;;Y>Tta%b=OBeU$9y*v{5hvwwcaDmTzv_|ZQkRD zRIzh6ee{NEyzY~9sRCBDjA$!MnDpELLlv{u?2R?O`1Z2G;<_BF?d(1>*8zx7eIAI} zoL1Jle@`izLYbF$GQhdO8~DAz%kGKCCQvo(vi9>93OzVScj{{z?1u%rYk7c)6|X!S z@fVthM;dOHdJ0$EcaN8+YJNz0a4#i-`%aGwpwIL2Ev^!k_&K-C5*I!P!6NvBifm*1Az8!cOD$x=f*E|be>@R|&HBk2Dx&H_-ppgUTeoy;K8EJ|Z z4V_M583v{TA4IcvUyIo>;Ss9(XY|e?{3Dhkr*H06!m?@|v_um)EImna2|eF7 zGg^H%gW7V?y`WVtP12ZYMS;TsRw;2b>5vaG&DOqDl&I)Lv5aVW+CbR>|DRu}eT}uJ z+aVQnzPjf$JOG$e`20fvu#NqW%vAEX&KkKVg**%6?dM7tZrip^v_`XT<#c&$3e0UMwZ4T`)M=5F=HWX!tt3rbk@Y8DyDGl^1htG zO~W&4ukQvsQylk`xM*GU7`eeKCKZ_Z8^6)UL~X&RS>YnNel1l!=KRCnJsmse07s(q zoZY>jlV&w#OT;IBGNv7je{WDaBi(=kyZ=Nz?v$TRpj-e;I27T&QSv@-;{psxBXIBb|7?PU%iU1CZ?(g$Vkot8t|RwMj^o;_9DBN>^{oH1tbzW zH}vW$>3BFV2SYY;06W60gH7pP+dHXjSRiW5s7-J385Phbz^WFuhqQBF>bpA$;Jc+Q zv5hu*35)71aVW2k(lpdo@C^VJge}9tBdEexVv$PS*AScmuX7|P21B1Z2PX- z7k?+`9teCT6U?(<(w;oiFS(e?#bmcVI; zsYr-@`?e8mMC;-E%;Q~(a+8jqM-DTu$i{(8VqoFCXIlCz5>n*iY`m?4t~rBAk-sV3 zj1$~Ryk7L_=~Vp73)2Rm$>{AdAA(Piu(zF(>O3#rh9r~jUgyJ1iM zuAc<;FL@Y$O@t>A)-5_I^NS6kVEMqzJQjPjzjtbI$F0C(QLq(wp+ZQ834dYW+Ig}y zV?Vp6n*tPU-Vb2B)w-Hf1+$q&E|-$*y?|w`;x9t-(M4()%~>Fdf)=*Nmg{w5J16z~ z1tI=QQ(^UXBrBidu`#~kifcjpd-UCUFZwO@o7L{0MgblCaGM(GlomF=gl0c=a~UbP zHYvsTEQe04cJW~Rk?l7+F85(ASAAjChl|RA_B~C+Q>pa=ZnkZ-g^wK__3k{e&aUn6 zY3m%^2WG96nQ1Pz=>aQm4<0!eDxLGPC7yqwm79y&pSQeKwABYnRqFF*0}+@vz;Tga z*YYUi_P6nDU3qPvmlgH}5Zp~1*JrGCo^TPK0x{GVT793j;+gs{y8^Wa#~^7@ufue; z_BcWle*5Z+CPDl>Ujpk)YH6T%084jQKPr+5?O{eh{k5E~{N;CqCkTuCp7zV)<3~ek zn6`(FE-!Ta3qJKCvGoZSMbA88i31Lt2+@9YM~CgEy!{h_;o(PL`+A6#s^8xZ1ZqiG ze;d~o*P4a5riatLtN{VVjhl@u#FfQF7gN3EN+)rxJxmW3l70KQ0HW-58AVhuHzBOm zu}sEeZl+DW0zQw?Now$?ooOao4+oooyn=@>JQ#gk4^#A-l)GH1Jh10?ZVw3G^q#9$ z609M-8iH00PyxHWfhrGgX`wH;@j)MFw^j-R(e%Fdg!u^tz2!<4l^0ei;DzH?J1*=S zPQL5P>Tez2`|;5suA#&hj$l8w8OyZf zV>;0EbKx|#3SeG8trG>bw+;Ft?|UGP`*qnpcWcRjr zZKwFb#2)7h9r3zctFUZbP+p|lD}P&H+!fc^bKw$=!qR7sKFYU=ge7dKuQ1&t{_4d) z{$0%3gX+eoZe%~=Xx<{AU?6R5j+G=Q;zj5Ds%XNrS~i=wJ&c9@$~q*A+2bYSIOs@r zkJcAh`4pM#*J0xfOZJY)G@F}B#}Y4*`~#6g&|Z)W*&{rVlC-`7ADZgY8vU93eY6IW zW@>vHiZ-p&u{Ru=m>GZi+#V|Mf4Xzvg-dNx8Nz#;yRxS}=ybBj($v$l^77%p~c`+JudU97OpIr8DBVuv~#|%^mFgH9Wx*E zp8gTtZnKPZ$*WjP+7;9p`VW0pe*l;QH+PhgA;0@WskJz}UPt|6bRJ<-9tADA0;Gk0 zt>zh^A<;n_?Nxb1sEjVLCk5)oX_lrT8w<;}bQ2`pfBD_`e< z7wd1BjtrM=q|KVS9N?hGd02QQ7<1g*b|7R>oY2WNoV=?dfR=mn!}#OVR|~L-=E2vS5|&`~DTi$oiT9 z^HwO2R%0&-Ybr-Lr>J_5=*~E`=DvAs(iXv{alQyf5H<4rn2G(8$D8qZ!jDT)GoLj9 zT)Z5lI>_^I8yWMUptbLXblp;^4H{JRo=cf$`q;E%W8;BaU=DaFM8 zEbnU#6wKvkSU0^>GdMY(?7QpJ+cRt*fDw$L3CtJQTuel#kXmC20 zfPtlT&xvz4+#!LP4CC^?Z21EytP+ob5#mdV>t|Waxn_SNY;@A`)y>{Ii)Ro4J0Rh# z1+~}9XACXw@p1~tIN>9O`<>m2&mnn+9r<=(?!#V1yZl0uel{7MqbHc%_aBQa-rt0X z;eS)nre>*ca|5sq_Jv{^bU(+EU{5!g_3hAH_p}vN!aD%X{&pd|dW(J=97xgQ@d*OP z4$xN!-n_5x*LI|S_ThYLE!f}q3bB!w!X?=J(v_4J^y@_59*aqHf0xlqmT{(*gfsO+ zl>G`Hx3aqp3&aS|tvAxmx!vjcz4i46oBLm{_=VQ@c|r4x4LG|l^eYnor{L{hPj76I z{n~%#UJqyf{&@_*K8(N5pBWh*b9s!@{#g4^6Ur>jYW!^r zq%=Q$rWot?c>Zj9pI1lI_}NZ=YUNM&K;u-(^HCh_x5QBjjbU77j%bY;8q;NT=R&5A z6{B`aDN$9H(9Lp;-QG^$!55E_vP>~t*`pN3dy^1!wun*10}$Ns4!;Dqkx$36UB82{ zB(;*)&wT(Osq`(FbED>7&VS}B&=VW=8fA1)NCk0bC6>D&71MCCi4p})KHxPC=p@6^ zm=9082%{xPiZZy??Ap<@+X}#xIw-X7b}pPR zTwP4zF^lCY-H!%Ev$}z*eJhmDjP!GV!Cco$3ZlG8BOCr1o3TaU!4z7D*Y;(?IfE9O z`*|#T`C{U_@0a2FX%sR+p)mYo<3ErqzUbNIGh_x4YTCe?j3|u7;kVmdh@AO+euaCd z5DbYPU{+V=2`-3f-;=fp>-Y&dB*0y6AaeC*a^64SA*YHvXbpw_bGhp*|Hg*kyJaS~ z4I08`UcM0gE=Q&jXC{pUtE>vJJRz4FqSL;pyiZ|dB%ym|v)_0*C~3c^_ar%(EdFHv zyo=>KqjKo*yXd#?%~zrN8434tIsD^JmZ51h94mkaco|+TI*AI)t~CX({eB!Sz{3o% zYOCDLX7vOB{ByZZT#aRjph-3VsU#!r6V>@*lRdaz$J%NB5x5-AXgFwi(Z{DkcsyWjMJ)+Ico%;qWNf!Ig zk=m@%K+q-X+Vz?!_(0NEj>u59FSiVR-7BDYPWa}nV~uvtfp{L?j#?Eb&f#+y-m}`V zwHMF0lUfFwt0KDz=t{8o->(tBp&B6Y!gJ$E7n>UJHxe_b;tl$GWfx_6>f@$ zw1#!jt&Yq~wOix{wu3ip#La$KmC6T`a8mJ@JH%6)I$yrwmH)$xefB3ePT-~9CH~LD zTng{h6$BS}FIv9VA0@$5-_eW~Q%$z+U>ogM#EX3uHa_A>mqi1Zv0&8WG?) z9~AsB@xt`}_P#3d-gjK{XfcyBv2VOT^rqoApst3WwXy@TC*R=#FbMs0&*;1P{K6Qh zr+6g}JJ8!-ry#HbnoF~xl9mOR4jI^dGS5%gd9zQ=M*lllfl_xwFSCcr@Yi4?ytG6E z`&iNA?Y_*N5Amv^4;A1 z=%$AF0n@HLdekp2bcG4tyqbKlz8_oVKa`A5EzVQw>hR?J4F>lBy))ff#x1HnPJ`*g zpYFu#zJZ_Dfp)Lm;d@3phPWS#nhHf^f&H*u`G!3H5m<&J66YwgZY`J_j-rU%kiaPhj)+VVKs|{YKibD}zD?;|_$fKlrN&4|rW~yEtw{DS7V5)Tv>BvO z_Q^Pupys`z;~I41x?SMa8p3A>w>>WGBW=(NNbW%@{^)IYBB-%xaSiBjw=156eK2#isgu=TnC_Bu~y4dH*+L$wGcQx|-Cn2WJD% z<@Qn1OgY{Fj(Y5SuH14^a*4v=q=R*pF0Cd&G!iTz+Jjb5a_Z-naF59ooh17nCp4&h z;q%FSm1y4^P;f?qG%7BEUoh|9c!x0`RD*Sz-X+T>&+jYgfxW@!5?`tkkN`JwFIX#G zugzq9ySU-EN=Sx)Sf7uviK@^@^>tLwaPRW9l7y=J{CzzuI~(asJ3A>%y=5-h!$FPa z-h=v~#&ppzOFXd5Dok_f^w${-7z>xNQmawL6LuGe^W_+tC$P}*MrMnM1W)MiO{llC z@T2oEJZ#2z1Cvwm3)G2ALcZTHGx62qqzTk8@#%abPZGkfqF6A&n-6knI#6gi{p!EC zR@Zw^2(&>Vat!dG&x2Ad;hBn$Bb<(+g1YJkMjfU&!ya29H7&+ekWSv9Ug>zGZQa;JN zO$e#bQS+$a9qJ@qoX7Ravs)MbSw9@bzV^eR)9+IQgF>eRpZc7zVP_EYDbV*6u)+W- zxQ`y+trdfsZLYC89bF^b&muaP!%;i^0O1ULHYB>Tuf)COfbHC@o?DcJ?MRz>b(@#2vOy*m5RzFq^W zUs-beIa3UAaD+)42v2IPp}i?E+UBb12$mg1o~-`qOA&VlcwQaFVWZLRy-(YhS~K`A zq-@N*bKS8n;6IjC3mDnYwj`alV4Df^N>M(!b~zP%BFof^It=mNlsN59-nQn zTbcrakT&fZ8h4a{oeVi?v65@G{(`ByiMDy#j~ETPto_>q2%uv`WnsKyY8#?Z*-EoV z>YjO?yBP+S&pl(t?XiUU*t{e7F5M2gmspDU(fWq6c*as@VBaq%>6}#-{7eS{M~hFJ zmyt28qRNH!!M&+M!V%9c8-%znUpC%?M0baCrOn}KSQNI__6;h&wx;&{I!g8-d4hoq z-f?3V69x5f5`A?Q&U+{@d-shFbm#5B-0OTY&K0d?u;yvN+f23rt{D4O_$Jn3`E8iu z*edGZ2#$0PNUz&P5uC;)DpMewANKmQx_R1+#v3k ziAFdAx!*QsDcpdWo3GMTHa%(Q4vXBKS6KCZtpzAt2+2`R4v*;3rWYh6I7b8zR zE6U$D9ea-W1drk&UKO<7Ru9t8@h`>Lz|^vQdYdJpg+2x+6JN{91_U}`H|VBP>8Au4 z$R}lY21rwE;&no?k*-O#ZV$DsuZsSPODXh*%+X01s=p@#{NkCDz0|ia=M#_SL%eWw z*~ceXo9ear0awye_K%TrI6lJH_e?Z_i!0#?+_PG5$7O@7cX*5B$xZg8yQoFm1J0vs zl_Tz>lhr?ee6FLvPc+#b!(|yEzwxs}e+6$ZRv(*;9SOqgOSNC@Jb3(_?a$ZuBfGpu zBIHWqu#b1@Wg(G?gv@@0{9~a|voF0}?Nwch!H_v3T^GQ?##eehPn-Wl78#ys?FVM> ziAfx|K${i&_aunVI$@cRnD~dM5`U9dUf}2k2qeXZj72ts5BKD0NGzJ0YSPz!@)lU0!|Wl{9WyXkOSl8}`B)wPpvXuE?_wpeH`6CkkiOOVWaGf^ z1(?bA{#nGi+$Vt6#5`Qy@=o~*Vm$1N-~ArsR{CmV&|>BS!ICK2MLbH^{O32vU8F4X z%DYC<;9R^WD6iW~D(_*%6>j#HDd2X5iJb1<@w>T>BIk75kPfId#}?mqp87C>hL#`Y zeUq01aFQ_KU`a;!L6hYrj))$=J8xw0>q%lUE%nA{=i_) ziyDS!53mQKt|w=pK9ItX2blH+%Oy1cRgRxIt6YB(r(W&Ndowm4IW02HF(ddXkz5A< z1vs+}Z68&Oh|xvD?bM1TsQvqfm|}^+^7@Fb*+fg?_NpGHUw6ryjaW5<52Io7I2Xw3 zV>0Y3QgMeR8kv~`F;IHE$Nay>psirMH`Dk4;s!z;=Zst%t83F=`cc_m=t+9Ig|qe9 zG%v0vSI3)dd_5R!3D1dLXYC1D6P_zk_x1C6=*hL1MtvATJ%(mhprZX7WvRQCOl%Fs z@pZS8mJTq4r3Ta5s1z<5sB-S%*c8&r*&aLeEIzN~2~Je0s&D)9g&WWAlkvlRlHU8= zCPIT}Ja7NTV*3npf;B!+w*WS#3CWlGa5>*-LzXy)R<(tOJ$)hVpEzzG4@AUPir!o4 z;Y1MhCqMbGAAj$WmXTG)tK}*Tbged^kcvXi06)r9r!-g7}s*`pNX@lnGuO442Og)jqqXPPH{Q*SI7CCB>VnG?7 z6Q+vac0wOdIf(wm5yyYrQ+^s%QdcIRCf>eFTm0mt<;sj)D8v^XqG2H*1=3oS2F8-u z+E`D{s}8V{Z|C8uF+D_4=u~3{OTqJtVIgl4t)R_R`^JQ_o)d5!$?+%?Mg8DzSQS5D zziX*IGb4bL^9ea)t?=lT`R2rOw2oW5HtF4Q@Vx5wA@h($iaYF(;}@Rdv$3UaYBJdJ zpv3m$IPx*Zw7d1_#=TOqpva8yO59Ah_@B!ueQ20EuKlAU87){64z~UQ80zAZ zTUod`HJQhnuE7>qVe*IcSv?6>WE_X?@{J2_w_gVFlKvoH0A_!I8u zu=_@j6n8Y%+r?J%LEq9uWzXejZM^T-mbhe|x`zvxkqKakMGE^#U;3r{`uCYoxi2^T zt%I>+Az3$!B9P}j`i><^L-{rfd338$huCz~t(c_BvATm{z?# zA@Y$g(Kj%{T-;;AydOBr+dRl^%-RPvztgJR(^OJ;r;Ql^ z9-n~_XJlrlOCuB3^IG-PW{$YM6;(Yv zz(m=t{Eo>E7lG$%dCLysJ#wC!0PBrJFUPIkCgJpetczj?z=$MQ>9_7%!@co1y>B$v<5bkvQjZDGb8ldAHFF6vd2>F6hvNQiJt3ESUrt_o z$3Q}J&gU|FpRx@%c!4m=>%ddVlB@vHjz1G+Cu21LEem^M5 zlZv&kDrI^Nr!YU~)K~WP;U7uYm8>Wf1-ArB{1gO5K(ZizND>r~99BQgo2p6AQ6!#w zLWi4IUJ#q0e6s7>%4w)n?(<8k1$ljM&j{nPX#aNMFYdFz3|^U8WmT37JKMcN51O3d zqh+CIk;UOdCr`$&1{L<^{;pT^7Gg%2<-h;}f3o~miCgv1b6Y zd&j@BN@FwfT{j>zINU=8>0jPR?MK8kb0xNwmqC*$|Y>S8(m4GFF4Pd;o0lgz5MPlJ)<2CNZ-7Cie2gc zwwuY}0?Ut^b|sW>Tfe;Ynr>E^LpS` z_9c4gF--_G>aEpe7iuItd=Gc%BHQ{95ce>M>IU>^A(dX9Wpl)M(m@7z-5nT*7$(_2s>AK;xFBD#Sz|B^Z)1`3 znC4Ub7ecFPCTOETsRY&v)q8G(V}&QmC}*~d6N}r|wf!n$h6i~Uk8q0UcW6svZ0JXO z7t$xuLYG5V_80{}K@#YhZfzc%mzc96FSE|Ycb2YFER6ySe-RYxV$+pbaQ$I|9hCWfyII?h%<=76zt;`UB0euZfXIce*zn#?>=F(2LcMoe9FL*?rf8kPjQ`jSC;!> zCCbKsM59DoHxT25DLl+`{P5<7Q54p5c6!QVp@F$1Y3M}NPig}5kZ{-QO~0^-;Awq`%cpJYkVwHdPNC5qA=rQ6SeIu!0(CkbsnE4d61YhNGG2xPETJWwI@X^qz3Hy0q zeq%u5T_&_#j}+7?e0@v}S306q4;X=QEtx^w>r3thk8kRxI!fq(tgfxvbJqNngK*r( zges|hRg8jgDXE%9VN&2@pRd2cg=c*c536LbiJh4V*wV(km~IcD*f$FA+-F6;)%0bc zp?WcIN>3uZ_xl-Uw=90RV(sOg_|PjsJA@{*+^*Rhj$4*$j9L$Et}*Nx6cj&}z<>Vi!2ezOQa^w}vcS-KUz6v2&oa$pTyOK78wE^7<$rcGz#wHx?^lQHmP)&@W2ErBuIGx75fQu8nRD`x^HlF@rdt z=1t2*kIrA~{cv1Uk^V|uqSZ-p#csoprE`z3Sg2d72O4kn&I?x-cS<@Kz*;=**VW?J zEOdVjzR~A9c zr22Q3j?GIsUZHOelP8CHq*ox>1Xc=k<^QVf-rPnG+rqAyI@%Y_l1nQpINgkfwr?hG zp26()P?9$#`?>_*J1^A>oW~RISgDk_DjdDVKrT}9 z4sGS7e3RcDJ0!2~c&{uU*Ka4J=ka5em*KR+_<7zAxv%T%|9;W@DVG(Qg?rrJK_PUHdY zabe#fWR)`ep`71iy~P8{w}R(_s}n#%gMShX9hbM41f_@Qj|%WD&L<c}? z=C`13V-h^Ee5X98ea=2FFp!}%eyxlf>uKeBWo-6r|V{mbVcanVJ*8N%OxY@(mO4)uf z?h=ZSsW5M(-x0uwylFhTn1Bc?d6AIv-08f zz0UI#7@^q??V5na3d4(qkfi(7njFQPukw!Srj<2tC?weIUIVuSvHysV8@e(Yay4=AnkthU>CK_iJ_8=nVe&q)z#9qtMujHrHX1Fg5(qA4C797LB?udGr7$iioVIh%s zn2(@jdIKuTi}H z^dny61%#V@a|-cjy=M$5Yh{r5>X6l0CUN_<3GNVo^6TWeRFR;r8IccsczFePUlEIQ zwR%r5aTijNJ_gzlpJ-ps!LNxT?(laZx~*P9|D?{QM+e`{#WL9pN&JMZDYia&HN4Z7 z>3dT9xa5))_9@fJ{kpk$RcDy}JQ}J`mcEA*C@>JbFVfdZY9|OVeZVj)AXAuK5a@)P z7P|yTfRBLhZ`qeoUL^}qxmp~u35wc|$XCCakaM*A`iDZtdxgv?ZZDTAlb6uFH2DQK z7jCso4rh3qU%!yyIeY4{+UM-uukH0IkZ`^$M|YH3ULHJo*()dE^0v99IHM7U??z8b z`^X2#Qsal~XN5QIkFEc(_jn;7`K{ZZi+#0R4q@$Gt{LXwB=qKagq&Pgh4-341N_~; z-KhfVn?N=g6+$Th8dM)Dj5TMiH1e1JFc*Rn*c39*DkQlr^O{<#0fX>aV9=i#+QS~? zqx}y&?2yJjz2vxmexYlsNYbMm-eC4x_s=Wm4Nu{Z(ba4>?)kfVP!j?8b!}G4H!ztx z>^Gntj%VvC+&^G!iR8_^r5K-4g&;`~vzh)VKMqVXUpO3Qct7^!8nmrFFASyPyJ1Ze z#82e?a(K>tT3FH-Is1k)3V77hNnKmGppx_A%$mSDDI7TzxI{w}hVokBkK1~GPaE2u zGH9mPVSK!~t1i9H5+GKXAQrC z5*3$*613w0e~;T1Py%)HGY6nlFry@2=htb!<-9a zWPSNo6tlO1H_j>HYF71|3x4P87X8sfmg-c~_o$fZ4A93K#n~Zwoj5ZqE)YqD4=SuE z&dog{pthKL+X~!RRpJ=DY8EPVL96`>ox0W5&z>iG9h{7k-yvQd9wH2@gSR?UoVX_o zBC9`Jft2S7a=hs^xBO~mpIHdj@U&fTx2Zhh-UF$}&hEEi7#{C| z{v{x=^um3Hr}?D5zt#F>ujl#C(@x}zJ+W!hdw5c%?ixd|!sJ|vWZ|j|MQY?vz%n+^ zG?ZorusXAO!49#~*<$d%@Ur4R?2Rdx~gk-P! zCd}`%rA5p_-QkjFe)cu@Rd9a;rj#6T zOX`dO!|GmxL;*U*e~=<$-43S&Dzq(>u+-@ghI+y84HP!K1@D{%y1)|n@VpOlfQnO& zDKznbHBom#3i;UU*)5#Bj5SNH8m>fswD-{eIIGiR%G3u*?P0SlfQ2t>9{h7ddb(g& zQlTGY$$dHZlRETP03rBn`9PPgy!kOT$tBu2=4VVkshk|+jH@pk)P%|!I&={|e^o#1 z`Q^2Tp6;uw@G0Wx6vHs`qf23Lx>&fN7Z2OUVa!hp$^KsZGIPF65ZkO=xNeERPyy@h zb2(o-ZP6B3a2ka6J`hioDThzycK)IN#`*Q*>S=tZkO9OuGk@hlIKQwc2%QiS`hGhK zY21AU@A;V52KFh_nQ@mE-09pQYvVAKx-BHe;k~%;dTy2hHWTAwOCI`IG6{D>XR>A} z!T2X4Niow_SJ9V5x9RHf{NntyWC#P<%X=nm`$=CV^LVJ{@tbXeoJ+rcewbSg%O2qq zhRd^k4oyW57q;+}=5BxlN_@FlOdncPdl*7d>w0C~Q@Vc3(|ZvCp~wCg<+@`qWu?$G zb5Guo`U=kdVbp>j0`hX6Mn193XmCT53jWf)`=f%!Z+qL*?F4FA`-)XZ!A2f23?Yu< zI)*GZv>zfyuea(1OH8~4zlQYiV&?Y{0J*inR+lPe?+w=FKICgN-gkSvq z^bCO0*EDsY*3V7(d|(^mlDdRca!-ewdkqpOtgd_)VqnDmo(G8vUC1amkB4qD1levGWF)-gRgwu+zU{~>l>CzJR_8;Y>VBKVmqX`> zA#)-euDJ3tpKB4{3#IXUo+1>bGc-gp$jG+yGblTrIdN}|v)g)Kr@Df1g=$LaK$&BbKaFm+5 zUkaoG9zs0gUBwlf4(K-0rUAPFo@h*WsmRW#l3@?k-{DYybYovLKlVPQ`6iEJ@G6tf zCVZWzKiKV!E;OLjGLSy~0p8_aI648{iTTHH-1?CS_P5hT^UBkK`?I=fwWd?sf1YB= z=jO3)-e{&^!^-FD+*+<12x;;Tt_}xG6)2a^8PV~xjdB$&^DVHfY@a}ZUf$)2u3A`y z?zFAG89cM-A@P~Ao!ph9`T=P&5NW!Z#nG#k>h87lJ?}yM)-y|DD_ICIW*fR zFuUk#LqGZp&&=-+%`n-Vc`o^?U?(i}@rVjdJ9@Uc3YfI$W#&Krp32X|1rmI}yKpRZ zKi9}6Bbbf$7f^d8Og5Uo$hQozlN~9s%y7Q;q$b(>X{#dJ-zD4hx2KyN53^`^pcmqY^$T)|EF@y9*%R_ILITVGal|6>9xv`jW&!jbX3%fA4rz5DEj6EJ-+!=?neAW9QVY`^T(4pHcY!>DhmL(7S=jIda;AjQHn-2>5sLN>?XtFN`&V2^7 z={AyCn_jevMef++Q`uWn7oev&2wv*@z7~6oG3hh7UMjdTFb`PW_H)@c>e%lhJiHYJ^yN<|6lmY7~&NY#_QeA>LZoiU@_j@^17 zPlY5a?so?kq4B|1qI8$Jnq{~(7n#ylE2=oOCqazCTTzq|pTs>{kRF+G&8iJRRRCl(y)QZRIYW&tmV&2N9k zR{yH;7arP_UO64H!X9?wtRSv1*irac!i*{7_;gP$PxW-N@Sq(W($iYjxA+5*Nzi;$ zsZ&=(E8LO(@V}AUz%WHE#L5yaJWf5|Lpzn_{fH96=!$tucJg)BtgTE(2q4yPX zCPncv=u0~{+RR7yL>rQ{EYJ5$E=v+JVImQpdgg|SbOF`n73!$%mK{Gw)RcN7ZXG0E zK*UR&Q4OIZH9-&U+c8-R9ER%VHxcwbLp{pkbLxLfcfaKPx6@Vwt{gNE15>sAl4L8L zpO56{gwSco)3fAEhnVh;_xX_%R?W!Hh6^2O49QGECa>1$$$#*j13#~lQxexH`@FM* z0mry32y{-4_#5-Xx|LpNQR~#?1hI>bhpc&Wj}`Y2U9y~T=CQ-^H~n3Dhu=tV_S3z5 zesnZFUJOv_SMT=8EBy#B79D`nRdqIaAR@X8uGs@gwm)&$fRzpk=L4vULIFI292D&j z2uv;vs(8PkuKwK|93*VO({WR!B<(ii68y}Pd6uEg?s3J4t?9@<_Rr&YPkb?C`dXB= z1QrG+*QBL(6hKNde_6=o!%;4mGd10Uv#yae-cV3;A6F9~g%LQ7STcKjszHIg=JB9?;jY}PuNhcUuXeEk4M@OT zJe{KSpgf#`??>cnnf0Rhpgw_yQ6j^g+&@O9<-f|kuW+aI?fHT3c`Lk9#%t;NphxVd zal5gy(3^*BNF>KM46%ohvh_A?l1g# zn4JAKbn4-azqChkP|dzklpzb$@xsnW)>*(uGW9Qj(tlHL%(he&rV(3nFTXZ3LHO#l zc}w%~?)!-+$<*0pG=%ZjKL(1j#_J6$#gCvbOe7deyvHil!CC|wj3ul5!M1fPBUz`H zTwc|W$>F*BYv0;8;-4V-AC6+EtHseqF(OMpuDleV(y4=)h)y=SY2G=JF_-H8{{(C$$oouY6k zKTY|mujOgq*{S=bVcp#da5MT8OHZoeXtv|STIqmPXh_OW8$~|{Em*_+Rm@0ucq@ne z6ciJYX>qNcF8GR<0>$_`4-Vg+HpGy8FO^GS8s+lVUz63sJz>W)q53E>Ugg#xov4yZj|Fy2AKh7+F$ldX+fscv%T~ zPq?a0T@<-tI9Y{i+{L~6X1t;cbzw1qIO`NcpAVmIezPhQ`y;_yCC!MnXo1ZYptR4J-on^4bV}4ZEOQ z80u>E#=m9Zc7qVpKVb1Z6k*EJ^B^Ye7XS3 zS^YcPIQw$^1-0|DmWM@&Zl_d(>w36 zIX!UfXDTs+#p8hYXj{paE>gzp4ck7ZTn<~<{ac9Nem}DTZSSoE{7S~#ukpthIDsv3 zu`RKAhVqfmW7Q#_{?-5oMD^hIRt=VOxw|5TkVW69ivEo5r!gQUw&5^LYW=a2(eI6J z7Jr{p@j9qg3+=F*9#CsV+i>5)w>gViNaq{%*Das;p&U*>=3%#&KgEV(#m1Yf0ABl7 zgc^+lL>_$DtxXlP4)X;%QYG_nxyo@EvQB#;c#%aKcVR%s@+>iC`Un5EZgUH<0cD0e`h*J)WI5rOLJ%s1K2wWk2_bQONDd#8jct66ffqr)|gZ26hinWL#{m4s-v?{O`hdvSGjMDXa?> zFwPB6a&w|%w7W}$kR^sGI>^cxiMGL9yIB>U?M2-)lVg~&I9YOFzuqexFp(z9H-9U6 z8+#J@B!JZR?>jZzUC@5z^tzo2_o=B9dRKl$lGjLu&ipXzjQL3t9|`p+R33axsW-=K zpShqv3k^tp+<=D?hiB$=OdSI{VONXIRHT*T^-^wC-3G>9p6HmoJ4|QfgehGycU3@(v zuM`oeU+>GlDw*R;C;&fwLS$!`cas^Ct#jnL;HR$5Nlhnp9zVd^gsPs-)0y9d4PDOA zql;skiCZ&+kIxC9u@a*uK7P z5mg^RL>2gueNWDJrgaj-X$kfg4YFYzxS7q|nfzf#;Wb1+7vf7EY*tjg7yDr|VGFLV zK`r|4=(Fe5=sQ>_48P@E|KOR`7Mgxe1(>8bj9z72iAbZpIy2oq)2yI#=???{Q6U=m zJP%<(ZLk0e&!~!phs#uE&3i%Uiu?FLnYrtB z)_JcppT;N)g<~8P*2a-<3`G% zc_{2HEj-|+A)6n^9<}$|#Yt^dpY_X2y=9@EO6M4a(^}(qoP`W@xDXp$bfx#FP2#!t z>*qAw*PUn=ZGbDOanA$6!}lO}m*P>qzrqZU5j}S{5XxBF`<|&218pL(ADYg4qKgYQ z$rDCs`_Z|5{u@gHBFfcQDLz=OtHZvi@Rhf#joYa}KhC@ zbde2Vjt{qQNxR(vY6cc-7x(RS)^4|>OF+=-O%6B_yo;L$T{nh>tZSe7F^%3XaG92P z2yahl*!AJQtUaS|de7dOcV>kL+9$kA%fT0NAfK3LvuOInFN)+rB#KWz>IQHEc9ht& z5vI-(*uW{5r@E1$@I0VVM!a}E09Y6Ash@D@sU7fC)E@cbakeEm(@$af5gngkl=W+C zADZykS>=2oa0R)oEu%T-8&wNO$64~<1)u^JsXrAhJLdyo`kb`tlhe)ys)aJ(fabOW zzwA$2Kv~cRxieeBRT}$F8|j3bsHyf`m8LzX!Ju@ysd_PcP5pX9nCwR zv@^^k%JJblcIsci5XUV8$65>Wup*>5oeBC&-w^?ump5`+P1<*~BR6=kDuS0L1yz># zn+A#Y6!c_*-#scl40Au%o_s|et?N#GR?SC7O7|vJWzMf*vKD;KZ=)>+Ok#w~LH}ux z)i0laz5&=v?Kl%7MNXQL{l&D6zf0Nrgf`%bC(vD2HbF|}@Ac_QhXRdF6#$)y9C&Lp zkH@0a>@;*Og`D!CVOfI|7vPjX{Luob@0(QL`h660*jO*pvt}J{hQ00HYoN6C)}TKP z8B%WVUGUhq@|LJVxUaKMkR0#t_e8dEsg?5gi>l6#lM$4%6RVH~dYmqtM9tGd12}b);t7ng}e$STU!WLs#9V4!bk1 z%-N^zF6pCtOA5eE7es!Pw$MgAPJ4|FPL6faTSfEGR+a(%96+6w%ckpDLIx6@J8{9p z7(@}LLqQzvidxYDV|eSznr)GW51tibP(v8!)xxp}u-!eB&(J6wQ}GPbBEpgu@SZcyajc zNrua%pc0dzJ1A8TKAb3CC+f9`5h0#r;hB}z5jGTKp!?-lC3M@7hAYhR;w`wTmmwlJ z)IoA{G@ta4JTlft2!BZw;kU#pt*bM1+3CYkPkNPDBTwNYJYIo*8Xq={Yxht7NvKp? zb-FNTVuS1Jm|UNf3Fl-zE37Dxghkjnjb<4E}v z6w*R-5MRAOD9GkL!Z;uof$X=dz{+{XOuB*#sTR;v1UtWwUwYUPyLpq>hnZMOgypj z;b_da^t3C{2sJZOT|8q3h3``_o|et`m`K}uI1G;kx5 zK)Q>!a1J@_E6J_*P5=hF%F30b50p9tN!p;-4okze0uL&-mMKcV%|je6Nj#15T^J zon}@Vh>zYp9aR5=pWVTNh7QHI8VaYa9VsmLd&(`2C539HhE#6axG8_O0!d8}pag<` z&*Qt*P9~{BGK|0tgy--3q#ufzm2V3IbaXk0V@8Z-_>0?_(XS6!ejIvN4(A_MbK(M# z{Fex&_w@^A5z<>U^w^vHP3H%?cH*7+*$w&%hNeXiynY;Gp~uz;#R%tkC}k_oXIR|WQXNqenC35YJjeA*u?Ly83WHYL@y4cbT- z0btJPT&!BNr7r{_xaa8YF|=$8Tg*iVOX{KAPQ?W`JW1-=c1PjHHXN(S8y+Mk2L?Ydvy4(2)zu<9C(ThEG$KN5$(s51&=;1#P>Pmg4 zgDBX{*|MBRsg2h5^6sw3?RP~y0Ve)ZJUndzD6xC?LM=tIJzQf5zWgts&WMHb`O!bM z(LV-X{h5M}-K%mL>q&2-gT*%`_Ckf{Gk4!cQ0UWKZTM&PTQk>Ktendrw&Vd>k=3~ z)#E{h0VMD`7gb2Nrz<{>t|(wBk;JQ>P2bDjGKni|7$TI-uF12BQ zFZ1t{uJ*o6c#v9Mm<6h#wHqKcf$&Q+bov4RH4!S&9o{e(-pwTT_jVL9}ZvJ>6*{Z#z@&AyL59858A;Eoa@BB z_SJOOk9|(DTCGY$)rwMbU9YF>1N3Q=%M?~W!S~iC1Jmcz{}K-<;g2(u-o8uujB=+3 zk!X;^NIDX^JKYoV!-3VEW!V?abL(XU=DkkT?-RU?fZGNiUullV+vVMj5=Lu$@wI;7 z)F6u$oSSspyUq-|G&w3!(9pNybwqiMPO>1_{=n~dESMK_MrtMi$irRgEnE#bmfrcG zI>vVgSaJHYEAruAq49kqyh8k3^9Wm(4D$}7-Mh#S4`2xdK3^DF9E9^+{A_}%-8dP| zA~3pW8RY4C2~7IyjEV-PLs^9<^7FdVR0=l*Wh(t0sc?YCE+hf0+4~966e!(09OB@9 zc_!J9hK(y5=zTf=x<$(-T{Xi%JY}C3`WLA0daCnmCSZ-pWUg6LoaH?US7ctQvh%m; zxQV}`wW4`6wf*|_yvL_Gg+#|27yfn(rc9FSd|m;xKxaGJZ=C2S7AMeD!a;_liM~;L z?BAH4I-d&A$m%*!dS?uX2tsHRK?gdm(eHB)j2$UGq@0{s8vEijnob9;@{0-s%Q+d|&f7L&JH9aC z0BeCa7gekNmisX~21eF1AQmN9NbrQQOCB-}mBP36_=86^-#andHA4*3M-qi z_ciD4a{aM4R0B2UGr#z8tUsD7y$j+?4=0u~bO?E51b2s>2*7<|y`B%}@=4yH!|k-M z4m#iWXC1kOLcRrfZ^1YM6$#LrA=6>MG4i}?Sz?P>Kq>0wB);}gID16vgug*hIX8=E zD2<4x7B=ZpM|&;9v0oOo}4gS7Tw6{&vwy+MRBj$yptJluFK>V{V@kxUz@nyMCA!UT7S zq=0*_slPYJp!{(!0g5j}m~{Gn3krVSizz8y zT~_%SOcK0<=QV1DzcN4l9MM0kYkpwRdb&el>7cn(7Cz0aW*g=?BwETWsO2h(GTq^pu3} z3tK-}K{Gbi9J`?*7W@Rt(cU%5ZtrH(9^!_$CzOFK*ySCbR~iosOT41_TgsYb_3BU{ z$mi=Jm%wm45Wz`GOO0hA{+xHL(p9*99>>oqyEin|dnRDxMQklH&(Poc8&_zo9Qn5v z+=D+17CZvNBg)~*EwE0xzRo`wn;GMxzwkRq@Vd38Po>$aWiR{xH@Hb|R^L~4VPp$hbFii)y)%;}5`%OR7`auE_ULOcdJ&Q5+MSFV=Wk#W9 zm0wTVUD5FEI`2e9O_CfUgaj_%E?6%G8BBUj@5o5EyyK{{WduEV$ZD++7Y%KBJ-)j= z&j6p>d5$g*X>H`Wh#F@B#16glb^4PAhWe0!7it?WA=o1e*1aJn zIPqljCwaE*OKc0_Tc=2>Q~1&dk<^YU4+6WEJb)7~c@R&sBw$?3uQE1W?liyO9W=Z<0uTK21*cGUG<}mCDxg)@V2GEP+$YU&8=P=g(p1>e|+ty8}P8}1+ zR`*mb>#^Oey@bM|e>JvUS@$aL$Ecsh9R%Uo!5(Ag7R^yh;(OyGyq{H=GY|E73qO#q zdD*|U-jnEZ^@zv?P{An>?qBQ{43JME4GxXnW{$V|k znSKJ#j6}m-$G8M6$w%ORT$W9a5M%$5bPrF@&kGk0yCZ8VtwyUGKUpaXp9-}(XZMZa z=!E7ww3=t{%N~C8;{vSFawdkFOh=xei?FY5r<8~E z8_w$%!NkDoA@QjqvrXl(wGVgOkoC8!sr=%g^P{}V^xC>g5dCJ85#Jx~yxB_mUVHii z6_ZE)3x_{+PeC70VBVG|?|ISu`96L)yv}iN4VpT#_;{D-*olnAlv2jHM4J<{=JMu) zJ6@u=f$t1=SkxZ$Rw4yB8V7~mmvyLNdsOUqN^{?wH@fihqY=*GqGJrGge>W$mmy4d zKj`M-oX#Mn_o!_~GNxg!BXu3Yl0XIGAimq3uMFmPd`y0Ya3PnDq^x)A-QOd#dO8zx zek;uIl8Fc~K|!} zWJ8|^K(bo~a*cm2YP+{#~8Rw_` zH^gU<<)D1Vy^3H&bXokP>JW}b8uZ^WC#)_ z3RhA{e}!dYj8bfdL3XPDGTTFSdkz&)rrVT)^&f-ME6@lKa@8o4WAyzL6BTi{S6Sj1M@-lMb@JqeVO|L&~$XGr-_abEIXJ%4H`TV1d zF5+j1K+SIWAk?NMQrq$a-WP;@%1eSy|E_~`s`VSGKJxW35bs0+lzm@+H5y)^pk0>- zhZsWX`zNz=mJQ}-(ffV>I-Bil#vA*?^A3dbpj5$rK$QhW!(&8UjboPlg8XewUY>;6 zqpyaDJDbS)@geo>OMo6hl<0f6Z`17Mzk~k#hR(g7&yk?-S3we{ozf=X9zS2dBECQZ zmgEjql_ZQ>!2G)BgC{Li*+#+_kAS8y6@a!aLLL&cNe8Av+WP2?tg-gkhF{6Xwj^JG zjdj_W`C6wg5454>D6bcUc!-ya1CalysWI?Q-?mklBQ!)tZy@qHisN{R|I(gQ5{ zylMRxofPXROQej&DNddwhLPY>O3b+ur|fb(yZo^=QS-v4x5mIz0(mYt}}>Jb-+ z{XdCg<>!DtS*+hd6ukXM&qmsNeOBkg^hk_pK=ys|RxY4Gd)3wul_cG3pC8=-DWH1ce_ z_in>+4(#g@IyX89Huu}lH$a&I4HPM<{E1`{oGD71AjkE<3!x!9X?&G06Ee?u8(jJ# zpAURMuAcMSKAvLkGmr)kkANadFE?_WAY z#hh6!W;6W@l=I<0a&_b8Cz`_X6xroixJ5g=_3L%-SM7@c>wEPdonDCqZGBzK-yvEP zIoDEZU`Ub|u@BRFmah*pr@jzT(6z6t>W960nGe90J`Xp@e5d!%r(G^E4C9zwP{=6I z7KVakq554P(YN@v6nfG%v-zX>hH=9uVl4=f_p?Bzm+s*PWkw$OdV_&5`=_$`Z(&*pOIq4u;aP_I?4Li|4>T z;us_I3+jvw2tftpauErGc6qUnL|@J;;nf;)mkHDG3#SJL5rU)9-S2)+?={u+b1TfsEW&o# z(m$ug_+WVgypPB)I6?3kdiWffoQUvn>YisP+X@MBqkk7_$WM?~v(86&$nSmfN^k9J zXRx{rnGoTEwnucll0*0>t&4LgJUyPHUZS_hTL>1mRnf^oPCYYG%2V(GCx`~frwiTe z*@PhokH`?0K<6ppNKnm^%qeD>sk_h)M$?+wvtPv3od_#jZPrWobrrV<`yP01_?a&d zRG7YAMsVCJg=Wb!T*#$OD_&#>a>ylW?l!pqzpH#81Z_yc&~sXQe$rnCt+?Mr_mCL_ zuKa%J6&)bU{`58DuX8i%6GL>i0=y%6vL?0NPgg3C~zqZz)D2W;BYrc1oUkJAD(vZktTzf3z^ z?V!_IXs>@K9()t4s+G~HMKgj}8a{LKK%2Is>TQ#m=cD1ZSCEotw&tnw-}+6#bSgL< ztz-3y9);vu2km~0aE2Z)t~r9ja0Vqm)ztJ>QU2pJPGciTZTP5zkeh&Q!dEQj{+!9C z!lgA7K_lvuPB^^2s*G0leQtNnrnDm^ekkxO` z+a4{&OL%)#w;9bi{4~A%BH`IT1IauFar@5;uLd0n_xtTnC-A7h9B|+H$mp2ULF3`-C1Sfxyjzc1K#Mr z+QYK};(_nGkY}}-IO_}p3labZB^9=V6+cnWwP7}>>B8?^yLea4?^9qw~j)ierDfXt4d z=y0htaTV)dJ7OMa*iYSgJDd^AGS7jX*eOq2GN*Hj6CI?i``F2`a&;YmX#lg-DHQT3 z&ME6VC$BKxdg;~@tN-c*(i7jtryO~OdSGF2VxLgizEAL+T#dxrw^SmV+9M|_&HMKx zm%ngM7pT$PmhRTp9fb2QdGRaSOy_RR@7@|seqOXA95vyubZ1D>uZ-zO?F&y4^me9^ z$$(+0aEn`#yu9S)YnAqCdG7rn;`at#27@=~%9;W94TcvUMu8!=tdlALDQ+{W3z~h& zSLlouQ}~Xeq`JjpC97cGXinzlWzXeRaDz*{Mle@_)k!TbPCuMP4bpo)KQ#`#Zt6?x zzK!igIY;y}(3cttG?)cByAJ?1;XC)I0ps#M5kp^9JCX5dYfAPelEC~vr#1&GchCmd z|7o8)+t~h^n{3$DChQ3Ob#Y{B$;UZ%Zc0tY7F zpT6faq%p~orr6*gNoTgDs1iicUjk%&6cAAanWs0I1Vm*P`1(FnuT}SU4WfuiW@N;P zeTqo66PHu&iI++NLWH#L(ye7994VM=UcE*h2X4oznYsfQD$|9sFC94q7L3Q#teU^i zTa>o_krwbc7JO2vHb11%yla6@uNtg=zAx7FVy(Rq4*GTYgeuA6_k1IX1a>XJ0H9B( zmGryfKA7LKya}JwfR;ET-K=_~I&;`tH6CBOn3b$Y*gJzK3hs{yd@9&G(g|)zI9u=j zb`)Nrle2lr>=R(UExFy@vLJTT z=r~8eeb-?kPkd5BEH~f0;r9tqgb; zYV+cycBz(T-%h@1rk+xfP6@7UXP`f`H_OSNF@n8_zr2lFgvL#HcZt&iYx>QP?3cS} z=mv-<^zyJ$DiXaO>lY&^h9ZH>Qd$T^Lr$l3WnvrYe1dzS$x`coa`?>ZvI~1jb_iq>!Y}Q zmw$;UrtI$nx`zJsPG1Xjkh|-};9?M5J_ya2|J%00xV{Aq7 zqI3H=JSG;KXW>|ywUd(Sh?Z+SWHZg9)mjeE9rT9_b3sKT+xV5&1O@N~mG!70@AsU@ z?e{8x6$?2Q=ZQ2gyOR%wqxc?x2`mWF_+klp(dGE3fvME%r-=;D*A#Uyt1JDmsrPr; z-0M$AS8{*0n}_sLfQ{&PC>XlcJd`L|M|*#<#EVlC3RA}P$pUIF`*Oc3={?u#)cEQy zAw^&YW;3(w<%Hp6np~nbtk%RL@nY2TSQ6eJwQeR=LC$V!LvN1;#e+}zWWnIZL7SN_ zzR*efwYRR&+}1Qc-np0o-uyfwYD`JSt99pw>$(e_kC}^p0$#uGdxD;~Me%Ci&#T~P zBZ{2%$$Uau;eAK42F~_kkCxoUMIY0s9~I*LHkS906{w^D!%1SzHU+U>A>%Cna&W4< z=HV~qSK&7(K3pYMOEi`XonSepOI=o5hUy+i;gP}n#>WN+t}Zw!)|S^z`i<2a9WOYk zPKd=Au{6kJc}bl1U1(0Hs+=urcih8>$38P7EE_oH2*l9?=BK(k-X^-b1V7&>1L!yL zF#9N%?djlTr;L-g;}J4qBXL#|ybk>>Ay?`(s1#@RzK~MFK3Q-N-`V32r!xXp>7K8LuLeda?bC?`*cG_cQm3`C(yMx{Xt2Q7%paZuoa zn@NHgqv*)MCulx$ z2Q4t0^B=mcf9B(NUZhgkxt{yd?$CRfq>OMP6nl^YIxi0#a?(#NIQqz(Oed>O$j&TM z_hId~SWdnJvaHURYQ9+h*KWwFef{RidpV%5!6BJF0%bAq1nFgovrO~zZGEWljAG;S z$y72rIx zWd}TIIlR^|@JBG?%5%O?kLksv-jpTVG5HyRlId?WI-#zYIR+hpGres_lkMA7pCyDR z60uMpQ)6XYxuf`m`-Kw$m%X6L=N9oad;>KF4Z8JYt*ZJZJl^>dAO?igddPpx17=#n zL;hKRkb|*#9IxlMGb(T|?n}--{q+m$-?Crf;+{OO)hoK_+cUr$scvYXaWBKmGRoHn zn4LLs3H)9=0c94o55{Z3am8K>D3NEt?0>le*OD~*FpG5kPC zRYX`sxqKA*{Zd7C_v{{blrG4q|H;Do@`>Pm@;*reNzaerelZu7lnbB74M|vMjO*#} z{c0ty;rb~VKlayrUb9zQFDkKefd^?k(1RkFsr`2?#(9lrfS8uNY-HHC@=(a(Wrd^k zh+4RQka2vfe>gp*mFVK+s7;a!AbtMGTTjz433bV#aOVy)5$t*0^*~`nYf$=Py?g!0 zJ8Il*Q2!eJ3P}$x)e#%=Ua7!`Y}fX#+vm0om+e;;WbMO}Jx{E+KX~CC-3=?{NW7ls z3oE49y(wF8SXOy?Tu#q7gUp7=rSdcOnJIF=pKZOfnpG`w{E%n@@-7;cFJ6bpf?E9h zczz@bY#(qCzK({2ZMH&-Wz2|H^AJcn8ATqA((z`psr#vXUw-hgZNP)=Tb14|SjPW3 z*WC2^%}4#y%Zg^&%I-(zdwjmgpf!{Z(b#7BQ(&9rZR|EjPkMNLQ3zbB(OJ;arJY^Z z3x^|I7@>O6v{(Gn9_o?G*%Wr!_lFLhIS=R5?=c3&OH3Gtd4xmI-UK!i)vTEp^V(mT zP44)#3g`F%E`NZ%I2JQsID~L*Ly-^Xd`i%1RP%ArBi%r#kVN4eK@O!WQ!~}PBS;Er zb7qXTt1&C{g}zi<@WW#c`Wh~$VPX!gQ+Lm+Xv6Y+n@**?U%Ibd(J#&av|kJP0rBfM zcZq0`f&eFzlUp2b0q4&9Bw-e?Xt!fQu4f~+@1J2&jzcAq$@(Du-{L-dV^Xr*JWjvj#yA;Bik27}wV zx!CVQ1o?cDu#<7-hD?A5PN_{*8aEurmKr~w^Z05bp0!%L_vY+uj$8nso!tAUe1BhM^J-wR zWvmAm>682jxLResUE*!+Nev>dGcwe;+?kI(*`+e*gZSL zdU2X6@TblkwY%EbMh;%mhZGvTs$%q38zyWkAz^ikrQ@wfhX~sk-&*eA4SR<&3PCSk zHGtDYY>(DfQTLcA7xB8jfm(&L$^oM$`g0i{PU@gRQ(z2wLyBz+QO)Zb& z=u|edOcC^|wfc)mtXidJ>x#fgJj2s-aHZN!g(wG8(=F>XI^+tc%ahUP{!}>VH#ri$ z@npARUH)3H3r74-;U+>x=N(98N5(SF7aEBC-TE=IYUb(TeJ7&Z^fJE^YADidX25iH zgRa~2vL{*}q}+AEkQh&bQ(%8VqiDaqRbjptNMv9v{?5y8B*np9ugT+LS;}lEusubjp&`{+Vjb za%sHNlk;+aGVwYp$G|u-Wg>sk0yN824a+w`G>`86nYt$5 zFb|xoNHSGBL{_V%Z$qkHOU6DE=_;RoiafwSs(nz{AYHEeeEKx6uM^mNZfU9COP|zh z!=5$RWsrAaZ|*}jCU4%;R;RnKt>V6=l6Ui6L}=Ob$y44=SKrNPg=I-(f3lITi=l z65>%t2eRfc7&&q@0Hq(FQp3Wd^h5{5-mM@Kq1Aq7B(LVDsb!5U$e*=!?g3SE7kI~b z`yFJMbB~h53mOa@fixoi&xLt{WCVsCeqdQI>)iz9H}k{1s6>mAV^EUd&!Qv#c1Pla zpU=wcy<*!A#eaQVVFMXZ{HnjqjCr8HRVeH+E`fP$&}IsM#u&?qlGy6^A!JA#K8?r2 z^YiW|w}-l_djGD*B3IvBygd5h`yM;11KyA#q6;KQ_OVbkk2_^1)`GMT+qEcj_T&*> z!}WUlz2XSH>%&cv`8NP-)7baJGl}O=Eo+>2+o#<=s-hE=0 z^LV|0sJkC!-uUg-PgW!ikIxwmNEAKGMKGcF|^*bb(%t`zPrH>&@SX z9P{RW;EL?~3Wd)~z_Q!HSUU5(O?ZFW<#m+Q{Vu@QyVCX#)2oZ$akXxi5+u}_Fey87 zMq~J4*Dm%wvr(%i!iIFY(eK61>?{IY76msA<)N(<1Av#2E*FL1FHwW%i&{dYKHKA0 zH%$|e6X5gjc`je$K+RPtW|&w+3Vz-cbG*b^mYSLTy0&MT{*m(~Y2UZhFfb&Pxt^iU zn6l%&Hhzr#!;Vjcs?rHNk(PQs4l(nb_gn1VJy(&^Hz8rHg?ABS2zvL1KlA%)2IJD! zJ;IMoI=1kDrS|DfEM})2*E?7Ep(#}Crb3$9wfdN>omW~fGi5gC{@%l0x5y4ZtKUm9 zPlk`@eOXM$ef-{7Vh?6dt9b^HR4V;N3TWjvu%a!v}Y(}u%RQhd$;wLG4s~xkl=QJr7^w7 zJsrMR&deF=&Jzowj_S1z?ETcTX$YyXNUU~2eSMbc>)%-G?e?NPs`UzO|d!}_Mr&OT+P9OMeQ@`VnK8)kN0SvQX z&I4n(>77*JRDnZ7<9Qv{*lDr4^=WrDvE>}W-D@@(knVLM9iY-82R2wVK3ru^Reqm!@s-wa zQ{Ka05&egheK-rU$N-pGlg1CLzNzCfY%?P@?cpR?t~61tNpJsy0I5X97dtxpKCeV@6! zonVQ>7=(hY94V&SVvEQ?+jtwkWoRuUUIrtXvd7_pwA>YqeK=?P9a$YOt(6_!LF_^|snM-WK`4eBp2Mahgy@q2 z)g^7ncNq4bW);JA{nb5$s*H!+!tg{M@l7)OT=Dezq=2;Z=&8}FPUjk>osyDY_CD~77U1Toyisu-3Bbq#IogGPj z7lG7)f=*8}{C!*>;v~VX$@|SY$EP$^{o3aU_agt&co}g?~7)LqS5_^tl@zV?%zFt0>hvBwcPzP-vHV! z%WPZsw36ER?)*&f0EyUho@ic>-FgN!EyjYT1XSn{MG(Tt&$$e4%sNl~jbueKvvoA9 zE&>hDJU`)o{Kqphu4D@zTRSMvLM_2`*}-OvaU_=lW-CPWCkhwRROzCvGx=cmhc?Al zjQiDv7`sf8zm}z*?@pVER|Fjj^5*Mretw3-XKt4dQ=Xs`aOSa@b8b&sJdfB}h^If= zD?erL79Np$8&~-YZt^V+1hbqSFpQM`$5)bHTNWl2C*ceH>ZYOtZ)t-e8mFJCKNb%A z29cUD-ym6F*x8+b?PH9$6}Bch3g03?CEo&x$VU$jh^g@S!fAA4xGLV*FzzOt1aZDK zc5C6$i+3}SKtfCBC-gtpp5;q`(R`ZYVYUZuJ>=#xK15MGd^`EV6IaV^gse339_7dd z;0Qd&JNSN2%r<{R4j`Yrxn_}hNh6eGFH!2n$GmVrU`P=k&bOyc%uPkXd2z6_X7MhM zD20P5Mau2@vIi_y#08gy|Kn8pof@2Te&SDnWLOrrH88nNkh;4wFI9$67)EbN&-mt7 z-=o;#H=l=QH#AT}WxTD0M{(kQg0#LT zi9Yj_?sd-780c0=mSns3=QF4c`NqnxB)bp5X~P`}Heo^%mog5EnaU=BYtP=voy;5TOKHKO0+Qng7D=mpe^eP~ z?J0;2T3PUux9ZB(@+I4M%iif^>R@FR@(SA3>)eSwE}3+wq)=cg_c}^`V~%)bRNzNP zCAa?iUC|#svCwtk*XmO7w-!Dzn8WY-w+Wp~*!Uwn==ZZl(+-MNhs?&VAKd}mnQf!} z;;A1|VkyJ6DA?{r_xz7+&Y_Px=!DkrmR>~nkI zhZ}rq<}~gXMI}Dp_~`O>aOKgZ&6FX2i7(cFX*_YnC4u4h1szW7OL?fvR9&zvUDVg~ z=n`UK=ss6#m|a=pzMp!K?>BnS_|I293N`=qUFY|zbwgxBik`0O=~JJB^+&(2ckJsG zKpu-c!f`Tu4AlAobzHLCrvq9B+NC(yjlFGQ*^LNbE?8t5nSy~pB0vwd2*3Una_{h> z5v!yO>46)%`F!Bqfe^LSbFBb{f?cX8j{N6o`)ACo%GHQ7;pQ)jX)?3vhcM$q_~aLi zS6(>HpO*#}ED#WyEYk1yk*d@ct$@Y|OjB&ZCL?IA60>N@(GM7jBy?)MVaxP$D>01^ zcDvnPt5DE_1&1R3=odTp9x44q8=QDjFD%pHLx)>|5G}uwR)Dt!O_;%B!q@WfZsR%-Bie`kB_*OGgPh9Cjodw2QW z?@ME(S9P=A>GiCDfDb86xIhjQh-9RaKNRz>eRcO&A~<5*5Krjt@?Z&DYnKxfOcQ=} zl+}IT&heo9t>{KDe+TzR!%%hp-8O_#ux5SQ3NEAB7SWq6@7Cw32J69Q0fMuG7fO(e za3k;(sNjx+UR5G3e&fnIr8n2ucl$7=>B;5VVoJvA4eQ-xsGB#^l!+g&(LOJf@FGjr zMI!byk{+sSl=rN(#v?o&hfQQ#*ibTwLKeB` zDmgT;G!29x0(^q-n&l9_tv1lgA@P7&anQ|k0h_WFdl;R7q3ZtkU0J)A*E3gNxk*Go zq66#|-#?22AVXlAkllSLcr%r1o-u;b9a=$t>H}Kn;VC5X?LK4Zxzcs$iW$MJyxpX; zo552Pep`%7F%tY4uhwfBDtrGR2L!H9h@i1)D>(hyMv?#gTz=c91>-Fp#fd}IDrU8n zv^+~VjDNZcDMIA?k=ChaGr#JWCB6M?X;XB0UK3@S_thSjza<72MC*v){X06Z?(t}T z(MxyUvl53;_E@6Lva%)A27du#nM?b73ActKS02?a!xEK)kIzLJ9sT_Y6-?h^NP7$9 zGC2puxM6?`bb0Ubi>NXL)hFV7hi38DYyC^WMlUs@mFk&u_A??jV3bIaOs}?% zz6TNc$=NLrMdefcQ8d2d^Hs5F0Kdc%$N;>wP&uecRb~A<2n0?W{m~{fNaGl@7l4Ux z+@8HP_n4+WIxouW?LO!s))>fbLMXE5m8Cpfg417y*0H>!hXqNDE^iNJKClAYUp)Q*NbioZiV%J;+j2 zGf{!kr;Mmoe4wK&c>6`L^6~vTGPQKPxRb3ulX^?Lqi4g7+W+iZ`~7~qJ!wcD)VG*$ z4fh&OlnqV9#{SRB#O~=+U(Ob^0>x+jAq-QiV$V0Z%ynUi2j$a9yLz)I4XVq zi{v}hw06(kUY9$sML+$wP{#6s^J^+K8;_?gtNVwc9VvN>uV3erqg#E1<8ozwVBgY2 z_BpU{;VC$!!-LaXp94jM?=08zixx2%u{W7UQXDyw@*(OCxZE2UX~eW1?*~sIh~sU) z6z#lm=gV8Y?AQG~=9$uWhe(IrhZT^uz2D@xL4R7n&xl9P&~vfUU}Qnb)*fhE4KNpw zaI_6MHc}PBzbWL!v%n$CmLrEJbvvOko+|6+6CEd)oRl4!_q$g2C@DG7e-r)fh%LBF+d&c-MZqxZSFKXkZy!I(jxR_fdf!2em!oZj}^f2Lh{XJxU(BaL! z?HBRYpcS

q{6lU-|5=gJ9Lm4VkxCHXacMY;t4ib&osmwEF|dWV+87Qp#M=w#ZZ0 z|@^+fsAK`Rpb%dwLI2zwe>B!{@pT>j{X+{|IB8S}*o_k9~#a%32h4KHTJeh+VbXyufDa8t>YB(HS4A zo+2BB?>%!M5!sjL|fAH=4D*2Nuju~nYgdY=D)FDI(z-kx~BKH=>-n z&e^{Bpfe~SM}HpTzoOQ~lYI)Zkuw}g9Pww?*4>{7@&4*gv&{nX{l#Ow8Qso{UGc+d zY7&agFtTyu(<$g9R$@(t`?*s7DY)g4Xq&_S*Xv3gPppG#$Lw_a(dgQS6B^QM?fr9J zO4Ob3?{sRc@+TJsUtoVNx+nauw`wRYstvcTGTqzjSBROz!XAD-{>VO_c>u1>3E=eF zoeuY=_{eqNeN4hlv`G5R^lHqe{LFoI9?Czd!1=R}d>X5i!UVt$Sw7=HwK`F@sB@D> z@I%BSr=lsB?VUM!^SH_av)^~1lZiZxUuzLieXi}T`zakh*ZDm$gT*w4(!{j6M+0Kw zcE1#DuW73uwmycog%ri)t)gU795kFG-Tnf5;756KR^J52O=NJpit^X}dOE*<&^VbfFh zlLN9_&YaX<&EKY0tO**y=xNM8P~`cdd>@`0z@%sj#@UA?af|nn{ydfslEmzov{?4R z(Qch)xzxy}0beJX6WkkB%3Uy=#juo+#eYqIY0f~uEZ{(usm}?-?52HQyz_0bQ78$T zt$r8G`2B7f#V$_4g~8GsO7vRn!5B~lCaxTrV@_8<5r<=d-gOVc$&+(*lTjL+e;d{u!`|}A~+u>d-&!(zhI*C?bJS7f#4;gJba%|Q6Xu5EJ z%N)Mb>%9_;rJ-%Q`UZZk0ob@xe!WtjngfJ>+QXCq2gQI_mRknW`JbP{K6N9Fc(jB5 z;t9oJZ%GlMrz6qYAu{HB|1kC`7G(|vvm6<&eV+0fL9+`JrHfX)8C+nPD1F{jx6cXD zi(`>;xJ*NSXg;|*z!?~=O$-fySPt73s9jM0(&t25zOdE3XO;V7vF46~0c*1N{q-Vw zGy@s$3*xTbmP}L#?nvj~&y9V)kr@RN9lyk662osabKyO%5LXc1bf#f+u7T8oO~t-^ z8Ew~0KjoG$X4kyXNF^WYB2NZLx;rIhkyFF-OZ|=a)UH^ce8?RD$l;snol_=l5+9`4?qL6(2W%s`ewkZ z27d$$%^$k}7AE9LygA|?RXPWL?j^>Uh1!cwQM3mNl8@e>6OsYSm%o{J@L%j}&A~ke zk1v>ReSfcf&YTZ-YR%uxET;En7;<#^TsxSwL+!Y?-;~D+(7h*?=nQktD+wXCKuLfFd>cW*b`l!y! zopHann~P#dn{#~%f>!vkWQl?^bCy%pq=hG&(y<#@Vjwl}^v%`tfp}=l?56L{syQ(| zyG%NLl22_=w)ymO<9wngn>@5qAg>{KVAohIYZVucK4S$Dv3*d!k1?DixH>XCXWuJ! zhCsK_v6N$LbiA=K;Ux|i<0AuuZ=Y7$p7(m)N6Gg0Thd2rUJo$rA~$f?k^a9nS(1%t z^B>R5>fbqgpZoaqvzEe{x^QnO{_qR)>#baBrIedJDmBGlfTQwMX zPK(a|zFO{CPn6WN=~tXzhue?hZbaC=ubZ$QNAD>`ct}*a9*7RZ>EvG3_O4|qu;!i6 ze=O$N%Dk4q+nyVPk>R%n1tcUO8lFgJuts+A%oqR&IKGYYT^-d@<#}3VQlJ-OCJ-n7H^y0RXp&p)Oq4D zPYO)bf&ezU%}IV<=Z~0+!2y4l@vas6T;@p2aWA5H+>7Y!u?o-^@^Lo#{+89>D8jQ| zoc9S7XkD<7AUML{^pn3xQOltMYz^CZd)2^zf3->CcS<)DabR#6(iW|KtYb zYf2)Ue2_?HHo_nUK0wg^U}@WDu|R?eZlyPoCbCR05J z;<>p|G%selvS#WS#9{h_2L%{f>-l=p&V{-LxNu@*j4k@(mZuD3`i()N-QnL}3F-1! zlwiiIezJN?k@vPUTf2c42){Hau0!{_qN?Yz5wp+ZjbxKqtt{&MuL!e`Urtx%zt}iK zd5(wqugCk%6R31hL8(cFvzj+SU0~{~20!=CoH$tsq+}~Io*LWfgu>Hlzg1QkByZuN zMzJ9n^*x;`qH1TKELgni;a?8KFVu@to`x5KRD-o71{eezHkBh8w9gW6{JxPtZ3^IU zi^Gc%z$yXX=tJD=KLsE})%|`^bVWFG`owhp zAvBYk)eKpNF(&a?|89%NUI4mY9Xq*A`?SqlBro5wHY?@59y5BGlx!~K8{m>v=dzT$ z8#*aNLmB&xmRZY*=Ve+1oIUaNCS4&=*#49rqO=@Zs%;mV=~4U)58Lt7n%vPQ-f7ZV zNM2uG>7qhdjbN2^2<&vc9G1zD&1%oI1|9?2=-{5>qcPLJjpfURg7 zB-@5G5#62DvvBLo>SiYCDH7{o@d~qLpYfF>S1WaY`xPxWuhWwe)(i)LXc1)DBj?so zboZOU9EG#{O`|Vfq-ajNt&3okqCQ>~TrbH=7UYIOIjAoBO3A+c{g3 zrc1oJFZf~~x4+is0iJX|c=(Ijqr7a;;OfQ5eq;bWibmNsMg7$SR4Cjy1~VyKYVhP@ zR~oQ13ZDFQs7JL9SLPW17`3ORlzPWa+q}3~^64TIUG&@iStHK3l7FVrpVElJ3!)^^ zkJLBnHzmD&Nn@~PycXZgZ=cSM$FS)2Bt1&S7QVH9q#nUdk$y{ZUCwc^$&Jb^@WR?B!=ckU@xhV9_{VK9 zr)Msxv*Sab(<|M%FQSvOsq48sRh0fIGrGA_!n^4&jCy!OzTsOB1*Wt`LM~uxeF#Ph zQnY%LM{dyDIeQ)p;$6#^^-y#Vu<2gR*b7%a?Chc)QSjvtc{m)}8&$Q+c5kilni>#8 zo%>^)7vOGVtcldVG25y@C8bIyo_ETw?<-%WkMGCr;T8f!+W{Rpcr$R;m|F)uXdl_* zk8qO0feTm-fL4B@6Y71DIDlk>p~=Pa`Oae7j$G8YG^uzbfg?L)PYO(mJV^a6UX13& zPJTTtpONN}5BSDHo)KYJzDkl`;j@ICub^`0@|N~0u+ks2wxGLx>rXy~=tkKd@=-&3 z4=AU$hfws9us&NG`$^e2|9!;MDCKz?u(pypd`i}$uVW%0Eztcn@n(vCt^Bi#`3UPP zH|kmpA&B}oXCKBdUun94rNJK6N4~CB^P6<5=A(}>Uab4)xL=Oed-@dSMTCky9eC?q zLC4nR0vniLJb6B}!d*H&#C=j_9>iPw9y$4Ch0hO5G_dpt#G8!`lsF$VB0iD)TWJz{ z`(XV1N^uWtuB1rHedtvE{y9}&H0Tic^-6Id1iy^f?3XZnIc9o;86&N^ql%7QMk7so zZJ8RMn7HN+EL5F+&fdqLxFv~nU}0Cv7{^(1Kibd~T!R@>yhv?7ctssW;3AKS_9w(E z$D0R61k6{^yXRUycR)7mf--C4gl%!q1*q#-0Ud$xG>2CSd%TkxgZ>ppFmHtNlx6Oz z!iFQ%fW=`$$Zwt$^<>kPF-{AK_j}LW zkGZTK%2jwU@I`_&9z8T?gzmsKTgux=Q&Wc= z70`Nn5<*o`tGps$0ruB+`zj(zf_W;((c620s*}Z<;Ek@-)bB>P|M}IhzOioz9U7q6 zE;+F4Ll`g3M}6@(B)I@TyL`(8Fevw_j>q*g+i(Ao-1t-KzIo3!xKxKRXh?tj!to?K z3RFlUqV_^U5!?PS0$5A~AHYT&O9;$M_#0k$HLz5hyB{@o#!;S?|4hb7eo^oG5$6z! z+hzBWQ^0J{uL?NMDrh24UF)C<>Sf z)&eCIv&wfNc*xscy^^o{@;ipTcHpe#c*LoPS0Gmq?Z^z@<#O`4|rhC>~m(zdl9Z9{pDwMd-rup{_ED8;Vf2<*c- z8sevXU_Q~*Yq8xR3CnZx{+u1Pt_z7ge|x>g1)$K$_BpqPg}p;uX}>XbW_6!c5W1g~ zCc9l6j(P>BWZzPLE5YEBi1J%q zhv)wJjz{ptCjmXwR_wnntRCE2(<1X%Pxr#;0xt8DfFkd%4Y;o7TPwF)gtxyLr$i$o zgDN4kzlkTLt;9jJ=c8A2)MtbZ>7AX?frmHly$*HBdP9S&JaG1n4n_E4l+AmAL8$*%t(y*t5Go$UWQY8f!%I`i0RRfSClo6I5E*I&37q}(0ac}?9;;wzR{RW9# z{po`k%Z|sdt-N6k_ruoTuOsxdo`>LOWR8(~ee)zQ$0E6GJ^XHzJ=J9#{zRKFWvIp9 zE^1Oj>Kq6jyn}hJ9rj-^+VzHVVrbvr{HY^9uX}S^-*4Q<@CrIK)YAo4r%LP#4 zgJu+7(9H6*TX->@CTGa@m?u0se0rS^#NX6#IEtiVZ1~iElY`3f5}B-TGkdceW+a%<%Ee=W!LG?t z`$Ws?`O>gu9I;2HqlR0#5924n4x_hWkSJe}>fqh;xzW1QGIuaC1_amVhwJxbAw#ks66ADgc%Epb`Ji+kjq!kGo7&Q|yn{lK~sjrWT&XIoB~t}nO^9*pC)pZiqa zugzf&09JC+c2j>ZM-ru5`n|%mOQKI_3ny}NENtX%=oKH#6M1xVx<99dp3F`ZvA z@|EHI6S&_Q3G1eNw4dTejJvU)sQF*#=b=TR3_u(>NC@}xCk1dxlypVG%1JIC{eT5N z_P`a(7hO(P|LX9Bv!_kRBk_Q$`|IzQT z9K15t&^{^WQ`~SVk?Sh<@X&r1j+K5@FrLZRN}@5$BG)Oa`sCb`<=tJRR%e`e?2r3C z^T8^=_9q)9T4~ms>(bxz@0J{op=UKVO7BAMepKeBolkbC+}B6E-hBq$!U*qk3J8RI zz=U;9aR-P8k?DX6dApyXYC14mN6G&_rId zvVX$n@O=#h>|)R>YjuVddy&HyFhG^F^I&~X#P>T>hWdJ-D;fOUz+OWyX6~$1o!Srq zzed4ueK4TX!21YHo-i%fFwEsg3Cuve$_HBZT6d&xFR;-rZ4k->KJAb&Kf+9X`qN*J z(EtYv;>jY>^4{+fDDgK-(Hxpw^&IiKIOqrHApE{t+HNv?xZA>ToKKfld%mXyg(u)- ztg+NrG(NqMY(_g#NTQ(*hzWYnB++mD?>l49l}B-_6v9u+&C$+JYWeB|?MP0LeRS$C z>2j;^zR42qLH3DzKR`lf^EG`IDjDtG+f=T54^TXs(Tm+bbv+(<{}jioH--|8`pfg1 zWVI2v+Yz!S{83euQI~Fcu5*7jFT^A}@C(hFbKP}hBJFFs@ArkluTF$*QM;S!0{Xk< z?e{?*%d;I}u#1ov61GgQ9a)xp+(i?UZ+f0OU$o=nLZ1!k!bCI&Q!R=MZwCN})ul=I z!HVH8N?B8Hl}~Qf=dMV!Gexb@12a*y;zZi{2AZr!*pqv`)2#ZaH=Gs_?f*a9E+O^7t`xo)>3LJ4bJXE0y`RI(r-j`yiVA| z-8tYQ)p?`mU*-5B>=-WklSWE57o|x(rsUe+$vGzLbQ;DDCN{)d7bOP9u&;+j;C(2M zWHBb>wVC(wa+?0&dk5Ct(IKkT&+m?!7`b0m#t2tbN#Mcv^ea_f|CH>|j4rXT=fk2E zy9y+-26*k^BZsuz&N-PI9psae3eN}p4OVCc^A}z=Y6vd1ez=A*@SKx zE6T;>N1wQZqY=U3Jz-#Iex7eQa9@s}zt?R8U*x14@0fsF;k0Kj-r&~zyz?9Fjg{Ge zTn~{GraCZRndxFkMVbz$2BRJi{*lU&>@2 zm)^)?fu8g(4$;~2AhO{2LT(7>E2we09exHjpnA5{{!c-!Xgh(~PMSR2dsjS>BYm$B zR4BTUv+{*nyO5bO8Mf(qi3DtPJk3w!z~0-3(Rc8$c({HvrBn?#ij@A@xSFcjsJ-T2 z_H}Nb*kfyozB!84&l~b-{w<2AWB1qZM$}|}>`U**_h(SSX1l^%Cms)!czH&^BOYJ{n8O8*;~b+opG{BlN&O0###WoUdf>DT zi$ZpX;r0OIoI?hF(%bi*0N#_q!=qY^HK!qji!r z;emGXXr9#OedON3rSGlHDE(<4YRI(Um)uyi)sF(Z;OS~_s)qLV4TsuuJ9g}8EztaE z4MpjY^*W9(r_1NGgi8PUlW}(rxi)0iMrOFUgApTA^c!K*-!R_(Btd9-S9FxeAItPH z?Zdua8`G-{q6nyFyHsjuWo4S$qbCw^hTD)9b8=BYI4oCgxcqXgzpLy zd&v0@8Vm+^)ftzQeXr@t@@|6tJZ2ho@b-y1qeT4@PDe4b+}0=H0yXFn#|G5lL^rso zAO;it@jj`iACO?w7>e}#lB~nUWID;U$aqC*rpGv!nS!;%gS+{Ge^7<-S$0&J0kG)- zN{T<@M9YKcFC8gqm3jTxG+x{bJr|7zMRjwh;0(*zT0FpW8QpD^cmMXP8?R1ajL7Ie7xzg{?&;?CbY?j(rWbrUgf_2gBq}kj z%adS?7Wx!$v+2(o<0@jPC#7?x@fhbOblP#abiX_D*X1SHKA+pTPcp;V>n`I!93}Vl zGz~j?5APaos+PaL%sP{f1@MQPSHPrpV<|_MTJ8A7^FCX0{xX@eM-$awzA|W#de6sp zpX$~Xm+2ngk7k-9gzl-PyTvpgs<{o+14-|dqRd|a6U?Mi!+d>(VhZ0EgIUm6o%7OIJ1F|B>Lb}mU(*hOo-Lbpne28R-JQcBX5ryyeQJxE zKjyPrVw~6eX91`dC^^-6xKKj3rMiE4?%k=@!;|oC?UXKz4-Tt@&&~hzz>T%Jb@q;ds7r5`zxpp4 zMN=4gg5F}bSB@yJv4&`v1w-Xe+;#;G_H{)Qk7gVy&8hcOE|{(-A{+{H%gl;onEe+C zI_$vR?4uqpKax&(7m&h$Io)PI`>Ny7mT$z9oqrnvcqRh=94F5L?WcbxGCbh713YrF zNB@e#Hf6)7wL7K=&kqFVI&I4{+1>q|pJh^;__@k*)7asL_ghc?Oi~@yS?gpsEGmiH zr|t{;$*K!n?<4*Qp}L%X37%etm{FsX1vW1Q9z72K0sGTQMD!&G1A4j4FZgT8S-Z5) zq!$5UkkOoYxfb&5Ro2omn+>(~Sub346$DmB^X;@>QEQX-@zW*h@*2_UUzQ0=6+&hC zdfHwcA}!rF+p6-8KNFG7JDq7~j|%bm*fBLrIEmhk3;gh$Sh8hT6NBI;y3{Gv2J5$; zw&KPBm>+{_b2A<~WyZAqJfDx$zztk^C|+b6MKj#Fri%W%aHGKpf8M9=fgNfTUo@P| zMJyLMJZz(H{S4p5_d$veDG}#uH!)y0Ld@z9`~lkl9F#^~^0S{qPp+_e%9Bt#s27&z z4+ZR!?5s~5?&3ZI0Z_ODaq%2?AtlyGn&|oGB#Aj|pAH_q!M2l#%T7WL!~+WGAzej# zfbuwGHI3(|D}#mH(tvDyRr~C)&(5{>ya4e-#TwdF-}UF3>~m5zY1+wt!hc)>6Yrt* zM?!e5EZ@VMW_1q8?Lt}84U?X0Cee(p(o*N;z>OmeG_Til)OcRnA0~tt>N6f@aBha;YK&USGIgUcUNnz56T%F|Ies#H&aD2=HNQk`N0KA8r8?5 zxE??1X|4}vJ_0}?a$%lIUhqQj6;UHU@zUm2J-Egs`1JEzpz2t-+gW(lvBq5SFpvWz z_-b(WYmXK(QMh&EA{lQkglPRZc(`-n>hqvo_4%)R1ezD(qKEM*$a=mw)P>j7jy@T~3hb)yIQ`VMLSa4y6;apUMEEyrY}sT#z~? zofUmDXn=i>&JeYLbo{zTJQ|lau+QD8zu4vH^I)5Mj_VpxwtcgfITb(D1^&~wo; z@jMFXs=+J3&}dTg@_bl2;>X}w3>I{ZTl!2J}-TN9buW(Hwg}nq>#e@5Nz_Uc)Zg~`P{QKYO#1M}4o^t`d z694~Be6tXCpS^S#yauoKaA=_($n{m~i^#_Ejc28DIU1V!I_nq5bCmj?UY_?(rX>RBn~)&;rzPP8k7Q!A$S*)zd}fpbo4iV1bps*2YS0e zX?g31^?60@ZKxZGnd(7szSr)-rroP+z2dy=al&z)or#Kr9e!0O^ao=pZ$vwCAZhYJ!Ah+Ly!I>-B zF6ZV9QS3f36G~h=vrXp*SeN2=OafAa3eRi4ur<6g8+gk%CQ~RDS8CH`lL!6x0p&MS zXPZ}i`|dc0mV93&r^c8C5*U?VDfSWVXZ;vI1d z5?y2Z82R-VMvv<1NA}paux5hbCnQGn@3vQ~(bpiBmkg*iyfC?4H-%6cvLp9c?m?xQ zT6EnnOg_gwr0cXNV%F|}%h`TILf98=2?KfhdkJO&F3mGK6Du^f;Gy1ZW_y=8>H)ib zyvH0b{^fkW<<=`f%T|g);796s9S)>PMINrr_3AHHK9Zj5)B1$CK&JcWQ6mLHADh<% z+=RV78qfWnvkf~G^zCy@(KM&e9kzgxehfn5gCbsJFCO<(C=ircN*vHq(YN{#r#@8A z>_vx#J%=Ul4qw^$0*Uwy&={zA0-6L_;Ph*uDI@%HS-#hpkxy6YUA&CfZ8;gK8qwz` zK3F;lQ#qeVhBzJsWD>q!6^wV$QJ`xYeU%*R*(l8)^_xtFcZH#_PA_@%qb&sm?_A_) zz%Pp$n%~Rbi*QAe2vWF*JF}9=DBK*r#N`=Z-l3K{^@w;kE6Kv(_4t8&_HI)g!SC~~ z?DHawQaly>av#O`H^YCju2^=4Ez7=Qk&J3vH?YU&26$EYNyo+jx?Wp>XdUi1e$0*L zf8=<*6RIb{AHW~Yqh`aP;&cSh)MB13{MdIb!IK7l_4Bl^CB!7RdW(-f2(~Y%H@Jd1 zo{E#1fK$`TNb$rc44tLc013l$bIDOUpRx#*}P03C20byZHbQ-H_^(eKRB*a6rm z8)r@ia8U%K;lE@MjdppQzXUj{mzo}2-h7DDST2drsL~zXSjF~df`V?ane#q3+c-ST z`yi^@XS&|5pWQMinY>A|q>u#+Lv+idf!G`MvB3gY9-=PEe=(KEwj& zX`mJLXe2)7Dz1muy03}`Y3lXE58p$0ub$r(3c}x}eWk_LPyx@Y^VW^1p4>d+I;wN6yYwPxs}%Cf`2s zxuMbX$o3M?hkBoC>%M(e=yPck%Opl|pzo1bkl(c?`~@+XIE(L8(cYd!T~g&L4}49T zAM%s*UXj%Y-VZ?b^4s<)6ylYQo!GFx`-jgeaF4!m1^<_oN+9>! zm#5S^HJkM=R|~=$34D2)X;pc@z~m2-i@oadnJvs~K-s;AJMqe^{sEw~oL-EN(!GRx z0&%TwGRe55^LepFYE&3GVU~^VOEQWC`{QSB!=2k`#kP8m95?Z8{V^7}wyvyg%BL?) z!}9o*E05P%zElhF5Qr$8<%h;A6H27_;`}b_I!~V)4f_-4_qjb%r}uO}#@mB~u#Qr* zK?bEBeCc*O>yR=4cMyCQ75tVXIz$-0o^3tqCa1ZS*AEGTBR)+nK5P_N?l1A-B{B)( z{?8L0U&-17B*6?gHGUsE@1W5fm!N}yP_x9SM1Go&Hte$ksDaIWFU{UGU-Rk7dx+Q7 zHn^|*ge?5Swkwz~Zff`nq6&e-_ILkk_LT(v_AHFCsJB#8udDKwB6tnL?CR_&!j(|d zI-*(jcsvYn@BK+GKBjD>6#O@4ft{K&pNsJ?;2-=)A%*O6wNU_h#HZ@ihR`-mi*SKF z!-ka`V=Ixxe4_8S&y1T`G5b|CEG%7FheD&flLf z%;fwU((XmPhDVtHvZ}4c?E5$bw5ws?~(|0*Zq$)ips0gvC|F4LDp^6e^* zKB{MHT}a$#_3QHZmW2G&yN%S+7|E=c^f<7f>tl)$kXsAC+eClna7&`7y3fQu>W^D8 zWgd=c#cMp_y@LYjzGf9_JPwzl^oECP(npS8QIB3=%u;`P)CsbcvrZ3zw)+x#OT12L zg$UTowIx`4S!Uw(eN|A0BOsSsi>kht3wi5*`@cDc`&3_ZXnA7?mPKC#jM#&~o_)`& z3Yvi)B0j@ZD*#$R)9E3wu6wYgbIVAoI{YkAULY(-dzuiN%;WW>!)ozy=$^NUp`n7h zanE3%+B?|`s7^2+GqXe=@^pI4_b0R{bcL6brRXuy_iMA;!2Y>kDJZR5YlK6yT0dVTI`g)G3MV_1a9YgZt-Oa>N$#8`b_s{c=!3F z(HSw)4FXKjwA_y4>neLcD`I`11aL4XDpC3cy5Y;xV8`ICgqOyLYKi0-c9O)aW|`N% z!viu8$0{EJw6;7~0N_VdbDq~jtB9B8)tz(y*FFyx6Y65(iIyu>kzKI!3n>^eE6swT>I|2R}-KA+zeGgOVdg5 z#)qR^^h*JbbT$js!}_c{Xo+hw=g_PjxbfWbiCYRU!L_Nk|{61A@7KU#~@)`jgssIAD!`Rrbj9Y2YpKT zIRk46!46-+uG1-Rh6Bc+<$f?AokZ9{RPyBU+9wJv4a;=|Rxm`z~wFAQ9pA>pBG%aHW?( zpv)U==l!VI>eBeK#lEk{zjAWiZ{+A9N$dk=f3~nG5W2A=O^oH|v0jz$NLZabP^L^3 z^SuY8uqx2-Vo&DjR8(p=@A<(vv~QR8TEsjj9qGw=empk6DC2Dp!{{d?tNR++3ZG_% zQF*Wj9bc4B&c_QIZ{lwRhoM#LttmZd+r|j?e-RJKFZPVWSi8yQVJ_M$`(!cwNxoGB+q}{{i8`B^3(PLf<^k3-Za$vOD*3Ec? zdv5tt>{q~f%-rOnEycta`p*05oslUksMoVwgyd-wN$kED6~jfgEL@ZDKn}&sxe9J@ z?=r9e)A-j=+2{JIeQHief(Q}1$>#vYXT{Dbg{f%zEzkYFh9nqk%!hw<*se{b{!|{> zH~riBbTH~5S=x{q0fwu@k9!P~@+`BvWJPE{SBVu_01gVa4rHmQ{T;0D9*OPO+N**# zZ`2f(!~hoF+FGrwZ=2IrEAM><#+@LYxcg5a^DPR1ir<$0PEgs8#aBU`BfQ>~;;)Kc ztotrZI5#=7QMU!e(0v1&#&Lx3(eVnSu#&If{Nn9hb}J*xkOI%^0s3d^ znF8Ae+)3Au)RJmuRG&}Edlq+fFfR%`?&KcDrbq#2=9@Ae?Ek*|FT6^FX*tWaDhG+Mv|QxgM-_T6`B)?xg)Phc$?%kT`%>ytL74)-SPZs!==eMq zdj#>O(CXsc5@As&r)_RaQ2d~r`;DoPTR^H?He*V6ha#%h@b+~48Qik8ZqFBLmeejV?$8+fr)A>2+#&A2kK$t6`Q15*W)~W3 z(q*1;1q@0)bjxyp$wcr(%{9z#fq4K#qC66|l$^Vu{N2Yg;%s3fue88#L$cj_EQvoL`E=BsX&NIcD(7xl?l+GR7Y$d!MrK3@bUmewHCOl`EO9 zarUJION~6P@9(WuWQ9mX>4t}%zs9mjz>Jal9=&eVegIF&Mw^g$L`z=^mEeteGFJADA% ze`LbbF9K%rV7NhjgrSSwJQYP?=Q2CxC0;6^(UrcKY&Uj|GAH1wtv8+1r$=jX_iKmM zY-UIeEW85$ETw3_K$N+LoP!z*4SvyO-Vl~y}%3z!qm`LeQ zOmx`gxA_YV^vU>TnFx5mTV7|eqHoXR9$ zoWrz|d!U3Ms#cf_hf?~!c3oEy77>q3eY0q7X-++WT)%6e?8ZF=h5i2iiC^bIJ###7 zxyL6n0ymfy((GaF9ujzLMcXR30Y80w_B-IK8pf43E-HCRXivwvh84l>gFaIBbKAuG z<+_we*++O?8Au%z?wa$okET6kFEOq_4@Q6T8UHZT*;xma^>Lu8ANeI>H0Ge}sfPKo zL{7MdMxqS!)-%{N!i)|M!fnM-hbn?%Dt1@24owbv+cZOty|d|avc114=wEmvjV!)0 z#GeqbZd)k!1}xS*p4*q1%N}+tnJ4<;naysiXs-HxmK`*skw?Q(76IL}3iu+cLNR`+ zamY_patpl&5=-&7kiN}~h}9ELY`34{Uk$&I->|^Gay^j8YAar;02+g}GW$p@r<_mN zY657K%F|fs<+D=JMs^HJ{#r5nU?EZKf7NubYU3Nx`H_ozRC@NAQGD)8)GlBU{F9gM zYa9L@E(l1WhyU4%xB{#|8q*nmNHw1sPwy(rT7nFSpl~@4V76a?WYNH`mP~Jizponj zS3EzXpH!f&e}^AUnVBtJ8;?3;pFX0DDu+OdltVbQWyAkw9NulSBrk$-8^KXb*jwL z3&STCt76_}%fj3u!0IflQ~aGkXE1fb5)A{OZ1?IDI<$`8yLk`bc#_2(C%wWd7(pb% zD;-zU$9SnN!0m>T>%YKn|_}EAjhPqugH! zx(#qED$cw4$Y9Kw`gOW+nb-Iks08hzYu>0}aB1(mHJI-OzjC_h^Z}n;&9OY)nEsi(CLEyb zm*_GOWLeL(@ljCJj)mk_ctd+H)nqCgi>HQu?~4!^|J$QQ?;;RcaXS_(z+CUq%U5&& zCExEav@({~DVJi{J+Ar!GRm1(>fWJ+PkwXcx`gK&>o-g$hLk<7QJ{D83d0Rc9-9@m zqx0v&prM+iFcVgXuf3n${`=Rp-O%TJ&B@DlJ4Dj*B1BYv9O~NaBZhH+3Sv3#{;>{* z>7QXhgFX8G(TJHvfmbhUrKB;GqXqHM9@hxr+{Jmm#LeP0b+CyfAZI2;WaZ1ulyH+!L@(5J1?zkR^2x0#~vy4 zHyOcPA8D)Y6Q<$G241AWqlFKfRhC;8ncqv{GJWxRZ@2wo)4kIN2%3fmi|?)*Ivb(P z{*oVG+7v0%3V**f&9Idr4t6X9b45G0nzr8kob#B)h3`9WjN`}?J<|4oX4Ob~$v}%` z%f$T(D52d>{8+}~bI9cof0ybt;~?QR2Bl{f4;|&K`%53Ygc6bU9=3GO3??0Wv4UhD zhl)K-z+cO*6H0D^&ZYAAxP&)53<~?!AA}=qclD@_$7WI*1EWBo?}YqTcjScHc1uMVo? zNqBA|i^+kq_xbsAHqut(dJ z150|Y8mbn0kSq)bfhqjA`MaNE#OR6qNO_*Q9M#!jbrIcsikSsAr+m&J@;7i4#}n|+ znaSJe6>1A_`^$wVWB#rQTtr4Hl!twN%*F%yP9++ZDTMekaXO}V`)9PTt>1PwqX3RKG(vgU`ktxcYk+!_lJVH14HPXLwSl@mQm zF7XU0_L3W!DB^OEEv0it>;(y`$M-H8y|JHR`7vWq$kuY($HtGnWN_t}$KoUi7wISD z_F!n>gavs~he;V-X3BH;{ou9kBfcpl68r=Fk-leXc;p?Rcr z+ik1mOrE5)-*NKtOJ#W!&!NPatJCp7N7oV^d<;eO#eH{i7Oc%L!jCRJksMw3Z`Tyc z*AqT+97T+$L`APMN8Tc5gy8&yA%nD?vLE+k6bGZr2;=A=dm!Hum@L14&LOZZPMW0S z^|lXBK|wBeyG-~r&-h&G_s#P;Kl)`!`GZ+?+t(3vOsv}cd4jLtq7}ql{w8Q!v3;3* zXPO+nuG{w&*=ggUJ?oyF_HGmz-~a?9Lr#y= ziHDV8D?PF%>U?fD6O{iPm;*vS&|vs;ct`j^HEdNqq0LsalMo2oY#*rcCry`Q{ZY)C z>iuUP_hYBi#UbORWxD1vZ0!rqRvLI$;w7Mv)yL6&7 zMWp{0OX;CGKZI%f*%E!jCg!|9DSdla zD}D}bVsFyM;GS-Uo`9EJT0M$D2&CgQZkV+PbI*^lzh%qgqxk&GV=%SCAJcuxj(`~l zUg@XPuO~Vk-p?PViXGl9f1Wy*>@h&(3HSGGx?NJErxaVuIqnjmHT!^+sZe;r&4x{Z z2zpL?zc^fve6hNT5sRm4GYqO{rf=k8^S<_>+bpFy~xl_Wb<~!PCVvp-|D`ppK8zOas##zOb{w-77jp{U-=jDgIJk zHufPG28ed=FT5CYPuw@8P;HY?i4M8S9Yb!c=JcG$E(Wyxh_6RIXL;kk>@UVsuOJ_e z(1iZZ*ECKOVXp3AZ@106;dq#Z0&izlDF<)8d=%kz^ul-%TG-4~a6PZS&4Jxa?wqha z4EYw4B-Oz=3qRv@89)5U-z(HD68b*=f+nuNJlP}ZN`@iLc<+57`S8!a*+1)4$-W$f zC3lO_4dSd1-blqxi6~Y@0WCfvN+1gDd+JYRe0S)#_E7U9x*LBnNwAJXzI_-9(}(dF z31}Ho60F*n%#7lvQ$V1UC_ki#@$CxBCYanll8t53=aiII!dIuu^fk`u@s_`EPGwep zuIQYT^$(a6`aSLQtap1lD=Fo`P3{p7;XV<2K7}yB{W^JOE%j$#Ltfq0=V%vA5O@QQ z>{V^Q*puIE006jNAGf9?6Eg{EEK9~Qw4{B$pXoaP`4n-X+Kr{VCqI%oTpME#pMF&BNv0{Qzvd=>H|^hAWF(?dc21Q6*k z!oGFO|6Wnuy-c_`s;5FEE>9s{)B~P&jB)+}&vp(EDhnr?`JL`3Pu*x zV(&%_2O%QUIPx|6Oj%6Q-2cFMTC}I<1!=zXCzfpG)|&zQ{8=LDXAwGE1{5&a6-tY& z_{`_Nf3q>2o=eIJu`FjY1YBP8#Qw1z`(I!)Es>oL-r@KViA~$1bM*}<)K7djA6N)% zGU0h}TcsTESN1U;GzqU*Vzh5F>Q&hIXNAghmz>Nx(C5f z`V`!~+W~+{CEdgSt=JBBeSJ0E5ukqVeD1K!ea4J59$hqcJg0#O_~aNA*nuY>Y!aQF zPqC*+w*aMtG^2zg=e1o6A6CY2%grP zW*^wM8&ad?U1d+QJ$ z4WmyUzS((^wPR@D(1wC&C!%`aZrsP&e)^tubnnd7O`dtNv|qG6V%a74Iq`baU+aEd z?O&1cIDqc>?Bv+DPM6uO}o1 zs2#(Y-y;}GNx=_DdtdtV|9-2B0~b;;Hvxf)d24E`iuKsD!szXvfa zyk!5>8CS-xwr~6{ z=Gf;weahgQhCQ+gO=}jqF7E`lZ-1@tE|R|Jf^zONE5gCb_)to($87uRer$WdT799> ze;uQT@{SGM9yC^tk1J8;Lh46pXfNQtJ&3NDD?z(6nod-%C0|H`EH zu~N!>LmjMz|FDOLrCMPHeob)KeRRss=k4kAjb_gG7|c;(V6kJ)9h9M81td)4!BEAe zxW3lT^q!B)KKQak<-i>3r(n^dTAZQv8LP+p26dR&t#?qcors(ZFEA(7x*SVzTl?{I zHpSV^#c`bV69csT>aD4DkaU;VK6Q<+LDqcZ$z?K)BvfOp2=S05dVg!{S)QiPD>O1! z>Ki(w7lpGPSUqIOu3ngEN15w*Bb+`5nhk6dT`JtP`Z{$YS1GZ84Kx_%CkO}fIZah-(qE5DE9+ok zkD&{tUY5zWtz5mhkv8jh;RaZk1HL$z#e^@GxD?-jx>8-MgqIgwLLU^|CnT-pbK3u< zG34W)kJaB^)kE0>$gi=Ky=SX1eb29kr(CnJANrY>6lYx z9lzkm-k#6~7E`j)-7Kdc6k7c|zW^fF)}dmXJXm?a)4}eKXX%&Z!uCC}cpAdNEII>x zd3P-Xyi&A{(8eK&w|*GMWnScu`#BTwcUk=tGgHcar0HV-Kd?GJd#_tH2A_Q?@|;is zAlx6CN2k3m4+5MuT1F%CghZxLJEi>@PGXg{-J^-KhHwo$i4wQ;I)3o&bVX{#All>3 zctYT;#ml5jwncN zTrRW8s50Z$>mQHQvx@ekO2LccU{qdo8dSPzSZ`@dcl&kJ8)C~A@KB-Tr<&qk1R(p;H^;R#T}2T^}0r zfKh)sC?aFU-@m8iv}Pt*IoHDw+%qVy9?wtp^anXUawN%ko`q87H;0(h!J_@!p$R;4_)7*M zz|D^Hq1YbXNs#H(+;;=Q`yy}FJsDa-cPT&YB>Mv&D**j^BJ~Ba(a_(eST`KgZ;jr_ z1qi5Cn|3Jl4o%I)oa&P20{v0ZLu=J&q{ev5;77e8wO~c<=x{=u-t@O|n6bC;A5N;FeyLHp?y2m*Xn-@aMYIZTjPH@+p!>M|zl`iMnkE^niQ{I%=_>@TwC) z1inhQ>B)I#mc&bq#iaqeIvScLL_{kzF>-+T`9d79|2WnMia0#o=vp0^mObL_FkqDEtsQ0#7!e2;1Pl9#PKprXt7C-q5RVJwk=Q#)U-;G5X7K~9vaA1Hy)=;Un(AC zU3YXC34Qh4fU|SpieB%{eL}wves~^aH3X=w3&N<6IpX98k3)~S?lycQc0pJrm(S2r zJ+py{+O_Q>>it0AARLZke|rE{jz?Ut@=D+NCLO~u<~C|XW9EZ7J|113?8on7CBap{ zKk_DWJX{{i9@_|!EopU6h1HiQvaTQ3I!&uUSRrf8nRq?z@kv%0jv#V1-1&le-;`vK z@pBUFv2!0yO20oJfu9oM0yaLadzUVEF^G;u5H$Wxh4Q{38qXJ=>uX90xm>CK$3WGP z!ULMro1e2gCCkR4jKhyiXlS*(8Kzbl<9hV_mVwT>&;>1Tq9WIWQLv$cTtKw*PEO|B ztaGRC(eNpxvV(Ze6B9iV-}U?9020vzlu^(cY}{ykXCQ72#D@TQeeIc|H>WaMbAGob zmCN8dRu+`^<%^3;5B|a-?agg}xO5O6ypSw&45uoMRh)#TPV#S$9XZwuD?7su=<%Gr z`y1Kn{VRQ~`%1_|oO~ONYfR~NpFnmd9J3YPYjHtUcETVBe6IBu9*8RhhP#|_mG_~E z{fVzV$6x9m;9$xr-Tif5Jx>H0Lx*S1%2B8 zv>%NT&<30&K!I?8ViU^YwCBRzoJN;y`|LByI+n}NKzUs{4v(qa4XO#Um!WR z9}THK?q3f>-Rn}{gPGI5#k(+6AUaWSdUxCnYX+zxR%N})VlEunZR{B|$ovv!NC)7w z$Rd|{kK%TDZ%f`hxfpUQJZIm@={HZAE(971Z0DDVV}%P|PSONcbOg`?r#ZB*r&2wl zLBl=J&e1jYGeOMf9L~`1*?Y66Q)qI=#8XDvZS};$IPliEJ)AUjTr9#SOJ0B2gJ+02I_*{~D0$X^w^(*FhndU}A>9+&Q8sHbl%w2Qn%FTmPUi{!Yuz3zMO7G+K5YI(! zc%_MNiiXfzdpsT03Rk#Ls{wq%il0xUYA(4SF@4@0o~mGJ`vK6KIxByDPxJfl9C_>d zMvQB`bZr?-?vz8qfDERutHg?ZUVOo!=Z6UK0Y?oOa-x`6ochzNA zu#T3}fA`_#y&zsMhEq35q={7Zgk0-w6 zcz8el(wyh?M+@_P4Mh4l|1#BU+c8zPr4XwYyY+ptL{lw`uFJ+mkKL*w9gbron*CVs z9B)7=w%_^)f3?O(1sjR*Z~@trc?qS*-w9iJ-cgJi_Gu02EIjz78RSVZ-pN-oQJeY0 z*3NTJUT=3_Gkl8Cz2}Ta|HdE^D)^M|VioY(X5ooZA%FLw@nxa?lfmLilsE3fJy!!s z3qhLQH?gL1#;Aq6 zQb=ccc*t^Rf7SYuk8;Wz%b45OR|d7w4Vd&S>TA;OCRorTpN5B3Zyq&4i|#TS&Ex%y zKq$b{kW0+?mf`ZfALH$zF9%}+0K5~lJ&N4NpfO%pXh0(R>*)H~3dF&vYHu>EIekI> znYfAywuO_@z#V#?b6%=HD4T?6e0N^ctfgac;lnr?UdfzXi^9u-~o9Q*hwB0M-GU1uxzK z4T4)i3Sqnr9u;dJzc1~jx+`cOeIme-UlXi&tNnYsp&9oy7BJBjPu{4}OY>=(51g%2 zSPb}t+HaC=Q*X>$V>K}r9|5I%8q51>Z2n| z^KEI&PZc%o_nLuYfmFbD8(QZ0lUiuKi_N$63+^56i?R<5}M=|MS-j0W44xv*ifX$Pv zyzmt|>tMm-O`|Jq0#!WqaXzEu=@dQ-9}%%wRc$Pux!Yb5j5O(&%x(9hZH~L>xKf9LckW zgVik*1-nk5PqDL+e&5u$xCO8m_`*W`dt4{wL??xn3@=i@1ouris#LLu@d62s_^J7( z5(%h%?|sF^S1@+6MR)yW00>QY#PD#dX8eMZRGBC@jDE zM~$$E{CePXCS$Z}Q}%-4uYNU-y@=Y1NG7leBPf2Mw6Tp5@A`3CO9)oQ%Fi;^IXhcf zFoL~Lebobs{eg%KGlWh&V-#oqQq}Es>%*P9O-}F@qp7gFJn2s@Ljseyd6mG0BXK*zxW67vRO0KziJ%`DVDG zb>DRuUR)zm%f{!{*U+ulaR>J#M@f?gP}kp9*)%yE4{Y;Va}>``Hge)S$|n1hwnY>z z$H>JK>F4-r(8o@3SyfSCKZrhEKVhiwc0T>t%2h)dyCv5=O8M>ir|<7%+bBn>`suLd zN2X%?0OzE^(+__uel8!} z+aiEyR@Y58o3~{CChvlau@~pZ9P-t;;!~L;tIMO!NIQe@)Fubrw2?d||D_Whh$TRIu=`|^6 z4`E)AzeD82tnnG3{#NH5%cXFadgCC%7NXTUx#{#8L{FlAkASKBD3uL)0^WH(MCfHf z!s>WW9x#XcY}JYTDaH0N>R69%;1C<67GB~UpQV0v;8FtOjTxC7Zm^#VCo8?E^yj1q zg6LbDdn5LUi#CVe?8Wa7pqXyJU++d;$rBj9fvTZ>ORQk=&<sp8%RV z__%7tBW2=CsLH_?fJyw?ZD~xIpA&U>n}L0-A7<8Z^w<3y=&v_}?ra^djQ%WKV)!{d z8V8!<*m%;T1*f{zMkwaQvtgzTsiEciPK`7YuOHUQ+vw$p(RbgYsZVArr#H9nC4R|G zsRTPCnGHh2-xDFDNHpv@f$IaF+Hk`4dYDm7gr{hOvd3gcOBEUnM#eg>9E+4(WX+%w`*u9GLO*upnzSZ*B?gP17n8V%QFoF1PKm&O-9 zyZj|DxL5zVJu2HhKXhXwQlZSL;cLl<8a8wL`J);A?S*aUCcTkfr;m+ofr8@gl{oLC z+RaL5Aor4_D8LNnxbHi~d#IfbwQmP9LFXpj;T6(V%oc$#2DqJ4iUdbkatXDoq_`@4 zlJW6H=fJ+EJCEHDo(^;2%Q+l4QX#_u^DxkSq3(9I@?zk=cypNW)5NgJ-S;S>Q8SJD zw@J+&?8>QPBo}X5zM*Y6n#r)?!Et|!f^Zs*rXKHb6L=~f%&A1!Uc6wE8=@cUnd}?5 zIqQs*OG96iv40}o*q8D$SG?o$I5FbacU23xZa(#^x2hI{&oIRSV+6jyr~a0XBt4Co z-s{iWc zsS=Nzycf!OAM^kwp#G;*#3JTzK`yQVg26Nss|sf=I`v7ra{hewy0UTAM@f@nP!yNB zV@QinMxi{wG`hmXapZq^{svYsTFTCaq(rdLK&h=vll018vlkOwHMkap6czy&z^1x`Cs4WR<@68j7QMqYceL>u)uj9N zD{ITl>FOH#$Mx%&A{9q^Jp&nCfm4v!{SB@^kLE`{p*{{0-`O`*;*!DGHDexAaS z`(BTMlz~}T3Rw*CEDE0lR(4y@_XbN1{Y6>!aIZ|n!ewc*#Muoiuy%8k-oppmw26W z$$dWNi+(CveIwWlPtxL-&WfK>+I!FwS+9OPz*BajGcVJHh_L1m>1x<>6D_gF_XmFL z&m6I_YD!M`^g!XpQC@>MQHSKmuT?aJep0Fopjh))IM|oBLuYUEcPsemW=ZX9Ks0D9u!UIGg1N&~} zGg0Nf|Ay<%6$D?*sN$%*!nr(gu;*yJ=c%m@PEQT&K4aO#anlF}K)_MBS4&jDv8ZZ$ z6!5Tu66&8eY(%9P2mbYjr=tfTuM3&k=Q#29DfbRR1+znoGZMp@WKYRyRE&Me(8x30 z26I0}1ZP><;D?zX+cf~iH6VqOdulG}tw{&8y! z;JEiERDW+iy`}kilY~3*TB>n7Fu(2;_>K+F6DHp`XxZ~nW*JYEP9x-I`MXsX!efiw zgnIgb+oK%O6!E+9gouN6V%7I$zHmrSbI3)cXPGlYNPZf2!ADyKWpK{_l$1 zqStxA_Kt~%Bg#8b^uqQV?j|IC=DJ5NUP(IE%>>_1@$7|%x{Fe*OaR9{Z<0A zfn&Z3WDcz1cv4E<`x*=!-6lKSFV4c25ufipH}eI3$ayl7(8l(%D$M&e1v}sp3jA`d zloLzcA(jS1(dqKsMv0KN6SuzbtK(fNGqcekHGkGDq%H)i@#8~HZW#p((BFkef1B#5 z@9?kAQ&nU{rT75RXN^2KuwxAwZSggIys994=cn~hm>o{zOssLXUlev`TUlNj(ef^@kB&Ozt zm?ssJHUtZT$8DXd>+-CabCk$SB7bM@vzkC0P`gq{ip+B!JxWSPO zeo`2EN*lHwl3`z3HCR}(HFxov+syVG%BvtvG!y;wr1uZw0kjJKI;Vv7Ihl_dGO&1G zxUXmDhT`zCJZ5mTz6tF&PZu2a#`LJ(ai3=zz!~Y(V(h-YLDMtV+X>KN1a^?1IWC?Z==W+0>&R~Aw9I(`ikw09jg%uflO zcaj#opBL**Sh7{tpR%kqYqAJA>;@cGYqP5<$NcM8gpIZd3ob(`(ePuY4vne?9zKVk zvZstz1_P}L`coa`Tl%w)>E{K`{da487^)wRVQ0VQm2kXAqdcD9a=3%7a0ca!Q7#k? za!o`opmwdulhO-NTJfjvS#Oefd{I zUpZo*Ke72J)Ti3r_DEL#4k-6&-l+`2`z>o^P*$q>y&Gyk75FyVA2=y9MV>UU>jdnD zae%wR8675J#p^TI?YQHU4mTIw9*7*z%)Pz|9~8=(v|!d0j5gxALhLQe|@KPqz(Jw(U>FEq<=bOzE$^tR=4Dbseb(^vELz`KW2IUm5-u4N$x>- z`EN*^AuTdKv&(=`U?3$`FIjx8X^mUAqZP_&AyDQj=NIj`<{&sRSFvN<>{vmWce(m# zL|rcfU!eSQB}p@(9zh=Y`;Rb|^F)p_%M`1bGj&A!cZEfB*#O)axu>|;!BNCxB>a~(nS zoxa%nD)d>PQ6hT5byNKaggQeH5ANv~4S3Db@~G2tLl7p~v`NGl;v@~!i|AbDpc823 zI>XOFbs?aw%XdB81mfkG8nRnycZr`enxj@;n<$;q6}2xaV)`>dtd^L!6dzhgPo7)v z;fcs*+KhctpUxrPPjfi8-v*MOf&f_8Rm6UxEw#d(m7wSS6Q5s(KTX|T0a*+UqxSpG zd^7Q?-o-?o4P(C0pR9S1ui*%r9{~aPN3vtMS*IE!QdF_b!?vLl8p;}gZTb4f+~H7) zBEY9E?%Zu+lU}W_nlpU{hLmvRyi677+)e{LhVM zoH|Q2aEVJaq<1J6SWN!YmMdYzNq1E)rm4OSM@bSx^=RUy$$#BfOWqs0aA-$=7|Cn; zymd-R?V&@&iS2XXzm7933Ew}I{_?~y1+b2MZLgr{s_zu~J}ld#u^nsjTL>rHkxsV! zg?l#tyr^xNqKRb1BpNXn-UI8O(h1kqM9o`(pDzJv91_%ZY0SU}ByUPiEI^Pjz+I}@k(DPN(0 zVATum1JM*CJwZ?R!NRsmVX-N`M~|$AqSEe^_7kf$KVHK6wGiI8Ppn!OCQ@umih#M% z`cBtGRK3s{eFtqX*IOc~fv;Ar(I)=l@{m78WO-7Q=al}=J_z+Rt1YNAmG+k z;+IC|QRRAp_~rXhc^4C$hdWHctuD(jqn-!~4uosTY-r1KS7sT*4yHnnLrieO0TndE zBioE=|E?vBD*3rOp@Z#^UwfYQy*C1Ww%vOb#PIYf(kUB#KPehy)-v~$M(5EwvBy=U zj|Is^rfa6^uvaZzg(`z^7e2GEY)jrz|g( zUlIAo=DKOWZ^8+g#Jw1<9`kmt4SCSdE{g?RJYJ%&5RJ!08EOFbKBE`=71KM!9^cPLEVb?$ z!DGeVAph7$z`lE?Z-4ou^cEjA^avnI3-j@Of6@4xoo&xY)U4!%!H>$TQr{edXz@j5 zt*fWUAQVpL0B0)RHijRx_h45NdZ>%rx6SY2xga~{NH@R+*$+D2=PVIOp;uR>k_I_g zXN`V7c4w6B+1m*kE&N>{i9tJDObUj3QNvJ|MK2HgDq6QSO|JFb@Ol8=(cx$-qS0n? z5=4h8X*3(IZe$#C0vdH#6@aJkjuA-~%uMpx#|*buwQR*aFg#e&`D1pe*U6!<_4wNg z&bYJLU)@%pi~lsPV+k<&Kuj<&G=tPou76sSeMM?Yc4{{H`ufJC9+V{0fdk%up401% z0PNPhG!Wf?3M68H;acsw$4jetlA~bgqHa%fKb1o_PV-5<gZ~3E1!Z3eWHq1?e-FX__8OP;2=Tv2~w>;3%tk&az{=S5J z(K?q8@TDFUw}(Ora`MQCp(EZo>udhv=qJ1><`i4Q4MCWbAwM%;vgY~6XnY=tWDjxl z)Ja&1?bhR;vk)6fk7w$;-kfrhrbaWIzpUR^dTLH$?u#0xd0qbo&@vsLh@lxs1HA3v z#KT+cCcq)yRU?z!69^pR`lihH?``=g3M}xY{-EKW8*mKb{CUK1to%iu$-}HfKing@ za<=ckB@GV7*L`bBe2pKO{8}A1u9~yPeS{}d1Ro8Z6vpbV@xiUWsPI?BbK~6$OnkS= z2iRdpmYgV-P_Of<$DpJLScrVT>pNfYb$z09c@1Q*h4CYxarA4vZX^orz_oI}zEzQB zh9LGX?0Xb~m`EF#*e9n0m58(^%&s#1MA)o%+k?gVot;yo*+Zip741>;Cef2YN3A8Y(s;>);)3!GL;R!0pX%6d+gFRk;4*uC;)%)$Ff@c zFMsPe$kM9cE-dkQ<(ffWn&7a{hqotOz%@5gCdK!U$5GS>sO3%%mBE!c=^0uGqp{=z z`JOsmf3`~+jXuFy*x<#dGk^u%Jg`^TPyOz)?a8gxr~pFiK^*fj6y1N z*?#wye z68pfl`_spaV1k5?ukW9O(LrQvjs*AAqdd1U;1^SjXQE&8AvkLbP zdkbQ|G$c$Q(%_kt{Bd71Owm4Jgo;1y_`Ne{*71VogQT;vYUxB=d`+?G?q!AVKu^`? zZgvE4>K@7rP3*k(#mXp(WCK5@mS;3b(C7z(%xL=Dbx(LXiRN8lcYQs%lX`Gj-ZAG3 zMLICJ{1xda4*M9DKpw*TK>~1HP`Oo0E}MbwjjIQ&1EJOIr}Eh)zwq*e@%xG<-b$oV zog}e8yDGO{(F*zNPsRinPS>_dTUasvP_B39`vKk!lDYqVm6BNH`mry!-?!Nz~6ro+LB7_VpceZ;;( zTzxzsf#o@;Jha2)etYf{4Q8|me&;lhX}VD`c$WC6{W0za7JtRR7k?;!-K03HI3aJztgG1cf9^a=L|36j~9Zh2i%vEKa2b1G>h|i zUGt}Dk41Gr!}-2MPQlxzt{=;53;P9*27dKxuE#$n<@{#qpL-rB>|?U)%8x*6l>Pjm z$r!5w_7y{?_+Jlg+r38?e{95W1x^qMMMJ9=8Y;N$GrK0znfIWnLQ=Usz0vAw9$V^t zDp?DBlrCxI3T~24V5)ISL@V*peW}H=ry(tavtjUgqqlgT;2?U_V(HIMXs4=RN^A~%%) z&xGc0r-~P_Z~Q zB$E~W)}pCq2(zzU^HsgyIQzv6jO7?V!`42^7#?&(2IzYvpeN|mGraoR>VloUK*@X7 z;=6p0`)aUXI11kJpYeE9ly-|6_S3qztKBx9ayIusLn^#F(AtW<9&Pma9Zz!pJpTv? zjnR}VWVU= zF_W4LG;9Wqa*uw3%2B6W?hVJG`*POc4RuC{hMbr)5$7m*vi#w9s*oAvZkN|FD<9l2 z;l*E%*E2VWU8jqHf@Vit9FTV{8SYjGptN4;O3BsxbO_z?bX9ds;i7&(AIG}>@pYf$ zzM*}jyek+@{M>Ka!;hso#5m@<9lQrRTe;!GL_j8_x}mXi6=wSVplu~KQ<*z@u$`5) zJ)~cOvmP$T?-bx5PGe=H^CR*wrM)!7cE?NFBJV=(*g22o*02mjsXu*NWgp#HBVO{C zz<-_h3=5iyYhH6eC2M-;fux=l-;dQmKfS;q+;sl| zt7Z*>4;nx4Oe1}7!jBvEw3$9*2hMdjD(uZ{?j_C&42%{`&-i%U$O=}5zn?_By3-9xFYQa-sErmqbca9-hkWm4N}i;7C+@%~%}&^ny8gQ}gUgQk+=!TK z#5WXIYx#Kgl(3yOVTm)Q+rRVVdy!wEZ|{z3bI{|T1U?Q7D0}h+rADJVJQB z1yO6*#45nqe#H$8it&&3zbM*}x5NATmLnPJOFkJ$mE6}-IS%clKH%JoaK9y&8S6Kk zGi^)qIv{NF&4zpTMex68UGHrq6;VJ+CRH19CkCmcwQUzZi^^9+asFut&U~&4pvz)$ z7WTJixuavQf@Gv%mN!{wfQQ`y;T zw(kW`Tgr)8(NYTdW!>?^b)$~#Bf0H{yu>RrFTk4bP5F!VI=@7~TPmo`qXBB>zZ*^>!r`y;2%ks>ArK0`h#G?#UrM_14Q#{t{lsAaF(C+ z(SlZ4*3r)SK00WYwJi6#FYF(VOxyw?D((mlCEdU4p%mV(Ou1H~mn*Y*qBnes$9(rw zGI~FMX91OnFR$mkxyJ=P$PCM}Y0SRR3E0mo6w;e-=25(4HrsKiq)*cP!z40se0BWz zjRQK%S)LuXeIOu;Q{a#deu5a6-YbI0$FDSBuFe0#N0gEGEx<|ltX>I@^ ztm`^#D}ps9wTNs>)4O-Py%Saw|5iqY@O@AY-{O(byo2iu^AkLb2RpXe9>U+ZNMuV` zb3)nvlAAyW-_LZrAN*1F0rT}7a_PX}fQK0lr@;U3)|Q-yDM;LRV{APP#^o_QS!H69 z;r8l^jbsUx%J*QvHtidj2gzt6TQl3F;1Glj@q_uc=kJ-m_nq(z!vJJIm!k*$a#@RV zMfH~wLXJ4!6<&AyGu{=YK$$@#C$^5UvO4O{u-22O4om#>iHqL>eerJJ(HB`+Iq8f9 zqS4-Ub<1>H>G!(;XoDHd6#u{;czY!7Q1Xc)VImS#v=SVm!ZI;+iEaG*Lb;0dvdDxe zEiGvq&(0XNi{qP_d>RkznM!Av(Ttohr$fv1@%gmx4@V+DgDokF4VTmLT8QzjTLSRQ z?U5g5b#!DqUUz3$xIMzh^#%Naac6T4;F4PaD;jDG7RC*=fGH3=C`S&7j^_IiHb;P8 z@)P2>5h4z}5l^qlS%053*e)G~k|-FBek{Y|o`LkA{c6GCON~b0jo9>sJnYY{74;mz z7W1?0TRG{F+lnBgsjTW_iM;m}%_&#LuvvguCWHoHK(qQU{SP z?3}?DsUtvg)IpK{w3f)I@cV+8Oe7ozn(vCIh0Q+R?p1#9+5PTPA^gc6@-ZYAa$LvG zrF$ThQoQQjq{eqdy6VTSdyIt0;o4G7Ag`*BO)-A+lDiqBOpb?+NSY~ zMeW`V&8jO0o>k#52X95rbUd%`f9nx(7G6y}<J8`2ftJ@X=8_5#YKy@S^xfeo7?Bi1dX69mRR4+r-_&$y^) zdS;OFYpA*5VJgoy;beQ4x<><+RUFYUhK7eWem*gjkk9U47Z$B-&}c>O>++7Z818C6 zq(isxa(tJc)w)31{&=lNk5@?&{)zDWOiYy~n~&-KP7J~_?mXro@L-v{De*weFX7%q zKY*VvSIf9RPID#Kx^eN(#1uZrs@ zQ{)d9YSVCTcZ*>|%?0MkEPzYWKc-&b_wEQV#2?&%d)B-!HL? zw$`m*bkEuj4Kovp{dB;+JP;MO&Cpoliv6I_PJ2;9_bYxij(z>~`*YANWJiPacfZex z{r>G+&izin5F$9X`%P;{v$Am|+kGr+=lLFX*TFEe0V7%KZ-;(f&pYQ(yo~5N*&~iH zQ@PWzX{ig_*!z^@lB05P5X5`d#jd7hG3e;#22n!E#jCwKLu5qG{Hm`rSj&q*FTkxO z-N*(HuN3RMz(?{7KW;KPxL;dsLEU1PLZ&^2yUNk0mOOn#gHxtXOdWO;Kd#(9H?-GV z9NWtoy2yvVTtxkr3-d9Xa4q0#z*%QrvBlHp8gg;er3O#x$z|E6{4H}k?^YetNgz3a zOXwZmQKIt0;0xc^#)g9k{U!N19y|Q4Gv;zjKJg(7DEfU33JcpGg+{{%x?VPF=f)~9 zX3_V+K}^vJ{XDUvc`qwc-zRRaCyw!to4>|21=Y}Lntc;3ei?mNd?-XZgDm6*H%bG6 z*~fMxE7J?wjS4P+1{ZQ4cU1n^=6JICLnqP*E|=n*z~uWR0M*+oYN<~WyA$`NIJJk( z_?J_^;zs(iB4v60M(6j9qPVveSa{>ys!mr=)6a67LeTy+j3#{KdwYsvUbUkS6Bjx= z$@YVk(jEc?lY&E(-uU|r&0mik*(TP3XbkG=z|CjBL|GLV)u&J{v>amlfN*o4rLZn5 z>YvwHweay7y4dE1sme?5w#HCv^tY2bE+oUw-N`!AXaoDk)>VSTz==g0{H32p>Swc& zHr5lJMgcZH`^>r{?OeP`6|fr{+Z_L_Uh%LOzSx_fOVaWIYY< zVLxLHfeYa6gWuNVxVA2~2p^~QSsmG<2?I}YoaeKODye>d-e~x`p`e)yd;-@gAn+A<)W|$j-}s;dJ`ti zP(r%=`m%pjt36m64hD(lld&CcAYmaTFhlUS2YR#q`bm!yy+4j1qu!2)*%hcT--b0( zM9PafTb>)m(wrgSlHqcHOBw`Ic>4JU)4rn+$Xl{0pXcZFNLx76>Aau(bYiYZ>63;Ok7+=gGU3L=iSVuHlLS3WgVXgz?}8QRE>Pk8%5YfH<^ zKy{TSUQg+ADYMq<)XoAUEvnr$B!1X1D6gA%WzBQvUGnZzAJzrCVP$$CY2|uRRFFdg z-n9Mp@?NGt4s%g7w&K_EdS;UFb@<6T^xS|R4S3c23cI8+W8X(`uBYM|Kn3yI=zaGC z<stW8sk6YKRc;Hf-0y)SZx>^> z{75rdOnBmNSs&?jp9P4rf{X;6l*Wy0_3Pp(JbAbjw-f%h3>Nd)BhqXo1BN6_64umh zYLGO{$=VmM^82LsaR`|?d7|j|*P$+a!#Vf3WiW$^ql8w2?>X=xSJ3ol{-MoRgN>@Q zN^9*LQUDKaFehU7quAZc&?940sy=k$a=T`zn}39jr{nmQ0p%vLmuH{7+K+jU*Aw+d z+68ZZp{_RmLvF{ShK-r49z{lA#v18^YsSY@Q=Soo?g3=)!uWEu%7)1W% z+|JO}jozL=o6UXA8K-1n90?y}bR2+9k6Tt(m|Kv*tGrNNlGLDp=0Q*HY&=ZKq9j*Lw9j3)9T9tha3fT)PaMmdlWUk!Tc2Zeowl9pL~6EtGjwZ2HwE-JxPF;7kxUZ?mSA^Nj zE~yo#FP;t*>-<8a*I)6;y!|vGEdLU;1wk@-wIJlUXy`h5Zj94C3-)WS@9qho*b7?S zHRBO&XdL3u6}*{g!VnCX`$shqmm35IR|~qFTDc=uz^T9o8cjnlTGHLK1G|7IHpWv^d90HMPa^rbs~vwSbS8grNHuxBquqi{sr{EAW?RVXh=hM@Ov zO$ipA1zzSjd|#e(eedRBzWmLhk89BCS`v=nvL~;pz7^x6MUyQ=CzqGD#=cQx=+$^} zGK_`l>33De1Pzq>>GRgakP+F4G4Vr)x((gMH(?7M#?5@7FDO zHtz>nF;~X*B^3kkj~!OMRENU5aG?nZ-5(r^kiN`Jy$uLi3F54(@b-k@CPbbxry4W{=CQ^XvR22z@6%IMLh8(A>~s-I7}?9YJ)07JAj75^ z5J&K)M?rnip+dBV@pk=)k2%IoY>MkAB{-?}Q`E}yZRvtek0yPAL=-0-GV3~opTpOH z=qp4cpb7e>6PZC$KFBm0^tAU(nB~C{RJI}GnSiulGhap?#lPS^f9CN)uax_8=h~f~ zmfDf-7s$6cr0fhvdUy&51?S7SM^VA?Yh5B{)-fN6JbKx*>9sG(&*KJB*7N~CCvUgD zm*nWN?#aVdDO9G&+@dZoiJYsa5ZHQq0=suUdQWN67e3CG*v7JeJ;@p!6Rt-h_(6sly2NzEyFphnLJ}9oS zU@j=#R)$ro!-Yur+xgACkNN30Bgt&J?XTA@OMYaW_w|wq47e{r4jVex;naK;pIx-y zXWI+$uCjx)6+N0I%O9rk{fa$$*@%Zg^yp~6!y#q8s^{5mr^zYh$7S7X5z6U%OBJcb z+A@#BoBgcK-GR45lLYTK)cLF9IL#Nr8`)XInDSKeM6aG7oDPrA^WqUR3eZ`6U$E0s zGRwCv10KwK3@JACy?R)tW4C;l4vl}6w*2(HOHJ-{g7n-7<-np586LG$0(VaST&Woa z%-zhD)|LvS{H8j4`2Dc4gn_ zRTfLMDwIbQAaq`-nJ!~is1UXiq8}lV*i(HL6}}I-<@>>u{+{w$8&l(Xt?XR6(%&Te zP?Qc&U-dNtXPUz=43->c@VNK}CS!YeO!D*1km9+KlXALwWW)hh{76IKl^$m_j2?i( zgHhz?38YrWQ(#ScC{ZASSH}6bPzeiDxnqYPsX=+6nu8V>wDsV!kz^vDpf8;!y=Q@B z8!q~m%_)0u7_Z#Qjk!1%q9vQf*3o)$e!TWI4)C z`_l0G`hDqpnzsw8mBOBEuByE6@pDCCE>gRDB+2tHvyG+qLihsrnROru3{k#ql54#o6mh}atS?X*hKV@g zERSRUb=2cD*z$`I9|H};~M%?dDldEjW6@EX3SQX(^Tgvk(K&FY_CkCvX zkSAdVh#G{SEBjT~99gzKQBr4z46DD%96H2i@dJ~)Hb6o7?G2t*KNoWA7jV(((mwm| z0sW(Y-WA{DZ@sHeuZ16dlPygEj=9CqHE$bIah7lEyCtz@Um3g=6AIh%O{j%m1Xbul zI7Z17Qfl@``xmX+4)voLa{8Hl zU|sh(>vF1@3P?R8+u!RMA%^dfn=XYZ%Gi*Ep@jr^J7tT_xjBvRSEnP0O@ z=D!j;ucd;ucJh6OHv(C*DBi;|yG=sCaCdx*m^E84RI`P>=qD}@cdf0 z<}(}GL{1k2j%1(!+yP%Be+um!4wvj2$ z4EJon5GJqO4H=wqX5m#APd!Y~Z_?5pXEf}4D08txf2flKY*r^)VA6;~)}{CK*zI{O zeTuhzaxPF42`#7N=86hbH;GL*V5y))u?Jn4#uwh6*>7MkmloL)QR3e~QXBVfr`bWJ z3;{p}Il7g-kiQzmBCx%0eG~*b8W1n-QY-<(KybVU5ymETE`w z2h(y#!{`Bfy6>T9bQWSx+Vs0^;-ITv!_Unr--ao|b6R(j*UM#nAtSiFICksWL-%?) zZk0LhK?XV%ZD!?f3-braI1wX$dE5W;ThQB|$kZz_=`{E;Q0XTNi#EWl1D0wY{mu-j zav_nrjNuS+zsog+aYkhl^nGpSW{(+nOqCrdOYeU^|4=@`e0kDYs;Q#xil=!#$5}Sh zt9c;C$28CnyzAs=3G-u8Fi!DVIgt^|ldDP2KCGEvO};)_V@KrZZ*F1++G4$K4B0lLVU?x>b!yhG~{}Iu-hd-9>=b4&=LYh zi>KUj&Sj2nAGMSJ8qcOTOfXY}!))B2FZi~*H&Wr#aIQaap49npFOKi$s!FjOwlVG$ ziS9m#Lyc%#>Z4Yrx=f9=M4qkWVa_no;xRxjd+gxM+VGLaQF3^){H}xdC12_x^s2CR zEi<({1otEYIt3gFUrf?{HDnrvo0GbP*j)!~9e>nrGE7#7Xy1Mh^Xm}8xtAsL!Gv~& zdqE%Z1_~LkOzZOu-3=;3rvy3-yU2Vg<@0inqxNfqe=#|n+6%r{z6~xIv2vXj$20T^ zP5AC|ubiPU&LI&-oga}@Ue@wwQvDl6vg;$)FK)1lazd9OG!+x2u!_Y;SJa(ZtL@Xk-W%LTvIo6?HRyT3g8x|ZFSWv;71l8RxAi62aeqU% zdU!_eJ-#0k8?b>qR0kBg7X?K4Q%*&RDJW8!{PT1 z?woqx7p+F1szV@9j`sVb`GN0Zi7r=$^uchp!lW((b>eZL?AatX5i-+>u{2dl`{8~? z68e$&lyTgO>CztLuCqM{&($PRvqETrV4(t^w8tAZHiGg=z=pCzuD)e7lDgV1NVTs3 z@qwg!h~F>b&FaEHx9+!q)cMdyulddP_gDT~`d@T0)$MAsP(WTz*MPh^72A}7`qbyM z`}1>dzq|CMxy-N`WD7Hp4pLa%vk^&4!9|78ZI8#WxHN}AH3YHdP`i|%U7-Qh-6*8+ z+On9w$vYH@Gna0cS+9SpkJ$lbr>jXchUP`-ie78n#^L*&pkiE?} zc!fPH9*;c5?L-$>L*!H!B1(b*%aUh!K&4lBe`MaHpv&miI+xl53~d8-N!f_yqnQ=# zIk{XIVWmwJZ#NJhUk}Cn8m+@Ihs`%x zseatvCc$*P4J`kFmpx>Os0l#guH?-AHoW+b|49`SjsiRfIfnfdYf~FgHBa?|7aU2s zi<}$GD5tB@2FH%cK*_{w!hJ-l&M1mr{atwTbhq#Pw?8RgMrFj$?U%3+6vB!nxrWx+ zc|A%^HXAALP515xjxJUfo&sI(--dSgb4_@b|PZGWzaS>14Pn?~}{OkJCb1e|DqKREy z7tsh9S5GZ;O7knZhm}VNOM1Ie3%y`XLDI(Y}C zU)#ad_}xTy9}!Z6H0Q0^CsW~1sd)u^EN)f4&>1!(%bKp#=6&okE=}V7JXD~5;6eh8 zHJp0(Z_-Q9nMoiS!X1jc?cn=?uVXAJH&bzi{VhIlQx-EY0i^m56jgq-t0v7TubIpf zAQD(sBrx^-Syv~o+B2a(EY>3mFFW&DRZtDQT9|WM4H?-vF$+nP$;~oeC=2ipvZ)xIoLO=L@h_0ZpK%p<{8ay8Y@8cY{ zCnRC(IaEG3)>vQPZFfCakikjJS4!0`4AA1{V%!3<%sX=V0bn=&0^&OI2LRdj#HUif z3Htl%8>jq($Bzm~v|bhvh$1rck<02>ur;11lChfR+@Qe$ih8-}=L3%lNHms1z^XIp zw3PZKKL|5{Mfc14t4!`5%}8cOJkcOtKo6@QVWxaB;Nwwl3z_%Jevf5WZ_A^?btL;w zm4i>t-PdSeZ>`askib-O$Gx*7_=p~BJoUy4QPr^?PrusR1^9T;;1s~2WDFxBd3et^ zD!(7O_0ff~YNz|G^hu_M zx1As1rbABw=DJ2F;HI$JM(57}kYzQvR!I?h^XEEitFx$9bXMVDdi%a7SY%T?LU(AQH{Gk>Lhkj_k8 zmplVsyBPJ+@G4wfc(1pgu$ppDQ9Tq_CA%WqlfQpOxHrUGz7#37k6)UX9nN~~fj#dS z)jAAK_@e{EWUdDnN^&VbL4$qIU>VGQ3DZ1(KHXGR4Di5w@ff)g6PlQOiYFEn()GL% za&rD%)=OOGb4lOe6I4UV+Iz23`7C7tXX`uL=N{(Fky?eCOb?kr;qERe)9Cer{P>ZM zPPyfM_}%83N7Yw;!muK3DEf9uEFrma?|`H9ej6WbIP=V>v2P_3XW}3KH+D{5oaCO- z@1G9;=9^6NKw%Ca5I;(TU27V}O31FiH{N1@g2n8wbw?Nd0Qog>QvO2#y^e215wQi(f10CLes@KQ;g%K0^0ynm`@t&@(_~-) z<}yUDLC0hLP!!v1Pkrwkkyky!kl>NW-zg{V>0{EvW~+x_QGVqNLy7|@m@Md+i!7`U zq{GD9c@F30cY%v`vLYrEQ;?=bFp%2f8O@736qf?t%H-!=j3R2xgF_v9sX+^#e%uGj zRm)0(Vp)d&ddy+}&Nrkw&|^wd4-9VD7Uc~(ZrLk;z_S4#_L0EiNId2%mz4L_L8QO4 z_~|!YE`HnvzNvFi%lib&Y31R)9bB*ad9tmEqyIw~B<9%Mj_8?F4o#uIJW5745UrVY zkbMh}c<_PoFa%pdH}36&pa9{jxD4ym6#=!Szmo|L`po9wtjcjR+o!;|?27@Xe8fzV zzSu)3*@+Fbd&2D@F;n3(DKl^#*=YweDc~L-Nk-s;vS!e{SFU;?bVS%2=vbxVJoP8u z9cJ;l{m;=mr>EM!Pe4FFM=Zz+QTgE;TIWM2m#guH)ZhY!VIf6^qMRSRdgqYS!25n? zaDN~Co1^I8Jwgn}eZn`x3}T=KqwP^RXR&itPp@C@``{iOSPyD3zskSjH=eBWuF$U% zO}P1hI7Ae75VvAR1vu>|_*S^*S?fbFZ2TlR-Y=JCSe^ABNoTgDs1iicUqWUd1wlY$ z6hYoZKpAD8zP=CDYt^m3Ri&tqWJX5B*@xXlJs9AE&+3AA)u7RXyN+gkITReF?yA+f z@526otnb|+&a^`?^SEFS4K}N2!)0#*W*0$B>&+oP;vT_rnVv`PbCp{lEIu*2M@KKD(J5bYIv%+-{CxIZnzC>B6TDq=7H2sJzXX36rLso@NSyh^ zHFYmc{HO>1FMW*7lnHd`H6MOzbzhe2n~{*AJG{O&(tZ9@xFm)K;ljaQ4+OByVzD2c zndRniM|s6?)@j2{fxPcg2v>SOYcDQ^hpuHQtKPZ=NO#;z=1_#=qU8ntI71SP#( z)t0>SA1;Qasjl)=aBjX~FK6`!caiXIv6EB!nef9qU}jf6%=g*ExDlDTCpL!~-k0?E zUO42d>Tg_=yfl~-#HL}M`wXJF6Lb50y{~h7X%ou6W#@grk1@X1#rJDbCu`6>k?7ZDH_nthCiFf!YR~_&ZZZ4Ee1NU*TMZTC7rcLW)K@pZZ4`>AD5Z*u|>Fu45_;7>iwl2o_l&3lQ)r4_&Id~M32x<>Ej3fJg3rcO;~>X(?B zG+43xK1ZN_ug{`OEzCA&WwFG&XJ`3y@DA;_%UMd_7uT&)_PN(k;`B3GJ+2rkj^{+h~z0(C6MLcZ``4>;fg7JYS?*}H#M9Z zGwBID8xR+6Wp1&y0&DOBQm&R^v;+ioPu_FLZe~2@u8%Nve13#ucAV_$xt(t6^Y8ZU zg3VuHSCa?8i+#Sg^8ETBToKfx@&19<7aYtzP@96#KIiR#4#yXIf$)IzJRYKbTEne` z>WrXic-ULNN&~_D(LjTKKWES2b+z~Vv55#`wVGz0;#VSZ)atiQA9LaiOPkYo{cw=p z+-)3djg|UD3-1wZ@?$`pYivvJFwrjM+J}?Y(Ru%_#YOo0TxbsmRSQQyDdu%q| z2+zkz*dj%rSnaP95(n>0xU{jywYa>5IiyJ6)(%AVs2@NFxFnWm8J@(aHZ>*m!9p(g z{ZZ%_DOV+@Pgl1*I5@5!$nWplPU8FV%C&z0u9avZXx~o+2v10w8~v>08@0#aU8ya% zr(LLuboT!~FxQ}(o}FsPmwXcG^->LS)K{?`oW&k-?}E+}Qu8CnfUy{B^N4rhXM4-%||da5md!D);xG->+fw;yw$s{bGJ+3#vl#Y!)H(d$-W|iR*!#9@Z`N z)Jjw0$hlk@vuaAnt}`}>_sAD;RP_kv*<<09KiC$5YB~S%AEAR$i}e@+(=?POO~&Lc zB)oou=!2R@oO&UTO^8hhlLm_qVy69ELj`xBOBbXNne60u7*PxEvNyIE8KJyB;c`mT zlz;NmdG4P`t1CRg-bmVq%%CXe8>F_+C%3O2zl^TEc@JiYuh3+!exL6hemWaf__LXY z=7UME)i>bEUEi8q1=aR?c@0|U<5q{L4#2s_t{28YkU^U|1 zrm-!90a<{dEx)X6{`QVz>7x}&Etk4qEpdtpI# zVAu^Zc4`()zL?av0a-5mwG9%fSLBi2ulQ2}V*<5|`u&mBV39BYQOHTWX6;O2ZWiDi zQGMPO4B?apCj=&@H_<{nepO1L+(%wzE06JjO_#X5=Ew3< zaE?#2esZ-B54V|CHZBG@1Yf8E&=z6-2F{(u`<FTuwLSyB4WF7YiV z)T?u>)U!gs_`rG>FT}@Kz8n)-|}Du z^A>iN9w5ndpooa&Ldg}>CwoU)?|fFm_>5~VJU&M;Bj@I!2_c-3?vg_eekc;7@HL1D znwa%9?*5XcYy<~~zKf>;SAvo!R@7MuyhOVk@3rY#`Glh#v7>gV$8Vpk<#dn_hV=QX z&CXmdYov`D1-P&HqaN4^aePM>B=YBa7o3R{3&0o-BI|PQ51shdFUK>E`ISeb!-GyC zh`ou1VhX&6wWQ~tUfe>UzadGA7E0?7t;BD=fiJts>VQ^3}u3@F&? zG6qk3&(|4QGr0Q@d>oB!gPl`na}pd!hU)78Nd0-KOc(tzu8V<#AlY(`aUaB{NcU8VM<-x z`1&z^hkhU-RrK}ebhP0E*A0?oxsOx&{R7yc)M}gy0aNr|crCu4kC<93TB7R1ar5Kp zxNod1tUCDTBQ~pd=~-Jd@CM~GGe&?G!dSdF``#O; zeXhBTiN86-z1s)m38WVAVDM4#UHg*p15-%VoIA9``<&_QqxPIa7EM zIFQ+7$PY+Z-8K*VTTgJbgq3)_l@8`(Xo$3%iOP)HqO`L~ldIy5xcnjL4w_b;1WPajTAt(K*xq(V-8NxwoSYIBpE&3@Xirm7=a}pJ|CpD!| z*<;?PAWs(|EGO?~9dc<)JLXgzXs;n*L+ALBg%@y4tF;P5JteYNg#~$v@aSSVgcvBu z1LyJN?jMHmnqn{1{p7PtP^$5l;F)LPX3>vg;CGpe^v?Gc21&v1Epl;&(GRB!JJLxG z7dBF9d%qFB`ruUu#yh>GXNE-_c=cO5W$F(;*4UeQPt_x>u`9ckiv=SYlVu+~)6ww8 za@$iL?`vB&tmoEF_UM|c&8al7LtnJ1Q|itO@ra{1vFj!5#=AN%rBbk|BNI zw&vY70M6O+YrOp2CbzRPVLsO-5rfYYb0{?=4mrWFguC9(yat7!DVD>&LzmIZIz@Ia zA`ld&T;lh8RCf-QzwcL%hU=f2fWguxe{mg!gE3pDVT85?KS(Y8wa^(AiT=|&++c3n zA2;fJ4_3^;am0(+=SQRwoEeD<2^@jg+@JcosBDv~6t#VR-RroO+XGF>`(Hneb*@F;QfI&M3f{m05Z{6e-F+zH0Dx&)pDsmY z{HpK3pNAY6qn|Jy5?pt*y0?<5?%6J}5;yF?KiUQG@ls-0*=x_*q8P>@ecw*JWTwXO zkWdmQ{$f6yz7aXP$5@mb!+R;Ckp%AN$1I2Y;jSKl01~B~em!HsiSRc{JKk)ki)BcKeKvwjXgi8}@G&TMT z@AaFxXu5v+l)5=Z=7-)FMA0{3JX?8CtBb1;%n`=qH@La1@bYF?&VP%@gDqAQ={1A? zO8M#2<*DtevzsN4C3kL)ZXRWNMZf>r90L-cz`x9HN+#XVo9*=ONN;(*uKmQ7uY^o) zO8%?X9#)y~McA({MVZ4Ehd-l;K+j>i#SLGnUhrq%BP9vzHnam$*TbFkd-l%9JUw6Q zk;0kdb@Il~KJlU{c$njH%IQ5$>Ii)ngZv!k27xq(@XoD2c91^nsns9BZX*IOH3~qbcM#a!E||Oq~tdmqH+t6e)ao=4;2`O&}4i)kEu-6dqo$*@VLB}hYiTJ zp@qV(>Mw0`uAU@J6B!_aV&!t*QwX$E9YR*GP;xHDUxoa^?2u(RL$57eV z;!keC)}TxS{(YJc=kRak?y~UkuSk1JHtj-+smyats}FQ(r8*KYHa9JkNQm?*7^mOHKXJ~{ zLVRA(u7$U7KpwfCoLUEgwo=?nKCa6h8@5(Kktq1@ipAH2-EI8Cj>`P&_cF{@nv;Ej z+9a*MCAy}^Lv|*->bFle1u7B`PMw-rp1LpKrGJ8O)VlBXaTTlQi(cHm({k712V(65 z+n(~@jkYAIGQRfswAkxREO?KL=+Mp-`!FAjILB9fZV3}oeDu-HehN#X2IaQx4_rmM zTj3et#qqqB`Mz*d-;_|KO6LE9I|(YHCOiTTKXLm-E%(4!7tmVmnX10kz{@Wro&~YN zYacw%_Sku?^Vz4L^02%MRfvhxIcnXuSx*svxP3iV3-}Vv!@a`etL|CVf-8#?bzhPL6G?RT6Hw+?5% zf3imXJx}@3ESu&I_Hm;Y+o=8S!z>(c`Z*#aG5b1bygGzQkb;OT18ACPZ|51#Ul5J& znQ^n4_gB#!>uS|STOhActH1exw~hUy0J5AqjYJ8I`yT4)4@D<&7pCMXI3Huf<`>pM{7PNCkZ52Lriphv%7DT|Xnk*jPI;XE z%&G|OLoVk$6c0kuhWo`_=tq^T`K0)0dE9Sv*9+eTk#|-P>)*(P^Vof;Xtc>JWuHY&lQ6Eb-B5*y;O?jzY)w*do(pLH&r;isbziHsX!bXwf ziWuT+&U$?Fyaz#X9Nv_A{-`5X@3B7;L~JBEbCzEeMf5QK`J@L6tMU8HA$ta&BY#qf ztRf&mNoaX{xpB@Qh)XFF3!CCtT z9FcE%@`d@&b|d6H|6Ec8lHp=&r=P2QufQR8<9VC~=L38_j}w&qq;bumdRmTnydYWH znY{$grFx{j&+IQDs6MZ~iptUDQpr)z2nqbM)b1=U@=@jPWB*tL-d+c+-1rMRU>vk% zZ3jz0kr@u5`y{g#A1d{_@KTV+t`z3?!oF8A`b}Q-_@u14eZ@R`4&S4Am6I*|^8GL; z8gMvY)DOpmg{f<R)9aVyrBJj*_fa0^gFK6rR!ARb0-? zgM*xG*r!hFpQ}&m zD(a2;3CnvAsGbkq9Un!~_N&r+mf$~~`@W<|$uHB!JL^y3NZCV>A0INdkkPg*GqRr- zcHa!q;~rYcY5UEaW5TR>R0zHvY(V+oJ}#?I>`e zhm8g%NWp$N`^5LrzH}`9*@mq5fMGPF2t}k0j)&QMa4%@+vX>3_mlW?qQ1t#>bME7l ze8=`Uvb|SZ)3~e9_Q?E^>k#8!B*It|UcI@kVu4>WT0y(0L5~NZ2+}3@#XEGDUzM2j zIpZtyfUSfluDaQYED*4H=ir3~^IG0+&U3q&KHuazkJkNA6L)o6<&gXPetv0vk6fuo zbrOpz)@ZoKp>_(kbJdPX!ah@Bv6b?v;) zNN&LHjk3E}nqrU~hToJkAweo;zRsysIwrP7UE$QX^wxOsjZOje-4_eBYrzS(gBvH= zLc|~=u&F@7ef7_9UpjtC*mh5SYEWv@4{tjjV7=a-rOGyMZN%qnwB2Gh#fmE!>?J|c zY!s@chj1ejgdR$5H~pP}3p^%Yhdh(y!8#v}ZceThinfes#7mhjVnQjbyicV|6W9Fz4=Yu+03 zxGX9xis&;0B=G;Df$HS4#Dw$FTmq&h22^-tmX}JkGYi%Ust_>J;i4=B6|LbHx zG1tYqK<+HPrizRi^~HaHLxKLEOLfNhz4$y(Q~2z4+b?kpDtO5rS$wk9fX22x$fFaK zB6Am<^%fVfmHf#$JV-jTblQXQPFK`xu{QfRPfXpqANSRM9HT>AZ(dunCj}CtC)o9Q zRb99cL*@LAMeySe?dRnpJ2Boae@V+d%9=fZyw#P>ymd8g9QBDhDa2^`Bv7^lP_`Q6FBs+;a)m65F zEQT~HhDgYF{|eLNvx<^ny9kbZkuOsZZS}=@J03ZAwjlvX!lDm8I>-(hE$FPQZG_Qy zQ{Kr5K0#o7h^bEO=JhO*PxP)wsg$B89h?^%IruPM=2qwCrIEUGz;Rk5eY#WeyweXG zit5kZZ`NLc9jisM5tLQ^E5bYx=0nr6kJRx1Z+*X}+5>aDBhNk=8VHey^n}-Mg-jEk z>~j)H=7OK?gE#DPtZYd^HiG2vVjF3#-1`*z9NFirixMtHOk^Jk?8H}{!(O=?>=czW z?V4FVdpYBn{d*7l-CP~0JR^&mC*4(g)who!Lx_j{FP65pugD`OM0FSJj^V)wNI{|OMK7(jlp z^5;k+XcV#&6j=Dz5WqhsIAd`D@`s%tRq)wiRv)eBgBp{|8n%Xy?s8$@yzG%m?CgO8F@dps4qr@S zJp86dWuL-t72*(}blM!&HD!8cxg`3CvH*p@2>=^y`TlW2(`3&%tOvI1n$3^sKE57t ztoOi!G;3JCh)828rhOi?0lsE0`EE{~X5TJPN^*)Rxng0JYgcLSD?{#=cIYeB*sqN7 zsaK8iBB%(_YkeMsyI%ti_~0fcwij#z%;DFP8_YG|SA&by3cy(#9DJ#oOcc=O;wFdt zJ1w;N&Fa~x*f2u3-KvPs^t~#_^VG}pZ*7P-oUGF=TO1o5K@hhd7>X@;bEKmNBUEAun@G< z&wb0(I=>PGsKQkxH@ag0X!io{%gO8U2&nQo&bvgnF8U)1&Ck-KE~c;@U&L^Q9F&;I zOBkQfc0uFqP=AJISmFeq&w_>+9{Ge?qwQv1Nx$}_Ba=#ToIj;?31Yq3C++KH0`Gaf zM0Ue}=|fz4?#->G2S-kOypRrQdZqO3n!z@w-3f!R4?v1R z{NUun7m+~T=ZF0UHUszij3J!mFVss+%tEOjA@vX#;roLT^YIkQ&&uYM2*ygLOzo@b zZ{ET20i!* zf{72*w#3wej8#hu#hv@|_Ct>bwG`NnqPLNHv_M?v`K6*+%6&h|OX1O4#h$;@Cy7Q* zjnhMCOILFu*$eX8eb37ZgGlC?ezn#@1K{_1OSWB4D5G5h2r}>fx3j*k>2^3<26Zc` zZZur$j>Sh1-A7n9@oAv*H1^2n$EJ-s*O3E*V++3h*hl2YaGUz#IrBcv7$S;d!{QUt zEp!x2ak6#(=FprAGd5BeLpdmCHdxP3sKnhWeqj&^zu53t;6=42QHv)He+&2-9YP2h z1;lY%{FtS(`trV=ylK!S8msBkU?9=cHdPVmHyG%+O!4u0g4Ujm^*FcJZ29+yWVr?2AOAktW>fwb?eJH z!BX7@5`jU025`J-m?GQ-rfT2i7w`~_MrSJ48pd9^~ z?$Y4=VSG+k_D=UhllV;#vFt|?z)R#I(;OdFZhXDnqaYZr=5za6iL5-&{tye7+s-nV4a z2u6t8vz9%IeR-}Tytx53A|5lgr7leREI zUfk0QE{P5>AZ#h(&1&DPhF(%B%Jzi}>dv!Q!91XKLbx?XM*rJ_!;(tgIeuH(g*V%L zz}D7gGZed_FnO%QucVm1K76|y2NUb6Mw$O4o^GH~IHL`Jzy0#o%?k~LhGJmN4Mor9 zHDc3Z<*8Tmp?(s<$@(JNyBg%X^EPBTF8r@f9TuY0S)@`pNo5-_#Lc9?`@43*Twulb%|DQFgw3Ns>XYR6`F<{d|17UyF2bZe+kS+T*bk}n0!pKx2XFMA zc%Q+xh??7m=kaer((rG2@YwxMa$;foY^Wmj>I>}{7){Pnt)Pp?U2?v5jO^c8Nc{DO z+dJ??C4yrzty?y1C;3&FccF}g^dkj>^=7{?-Igx*q4lYxyE5F8SbX%G>puR#a4mxu zn1mhFzA{sv`|?3Ij_w3T6c1&DsrDCh`#rU<`IFvRt0?+l-v){?Dd z3ivr*oaCnlJ&nxpVfK|+RM-6s!G55j@5=ptt*s`oHieAPZSv(%T;o;OcYepd_#V;Z zHntN^8Bdg7^(sRfbG{6Vi&!^rV~8DGBU zseE`Tmt!622axc2l{kt=Z+UaN(=qEWIT0E>fyi1Rs&XjXhJL-0=LJWEBF=c5(XejB z^sM$!9%X?^0hU?O)o!7#5S`w$Uzi&Um{jtIHs_ae1x)m4Har4;LE@J{qHU{7WcRDf zdz6secqr}}<1rl`BXz$nWjwwAJo}>Gasv7PbQR4NRgE%)N@jG=QCVVshmZx|Ua>Yl zk1BC6TXAe`*M}$d{RA{a4|J-09Xg;uX$jCM*z4R7NOSg{z!xACmVj-ZtaZ-M_q#le z)#{-;Q`}*!!h?yaMZ3H`4p&Bi05Tbsk-m682ov=CtwBBW!$}V1AUN%%10uz%RMha&_PfI7f2l z9m%bn>-Q{Oivm6Kk0MRX?y>s0_#Vv5eja~^=4x*9{asf`urZQe%AsM+(Ch)aC7qxA zCsY0eHVM(39qnqYZz#Se2V!g*R4Ix>Z=*=x00bE z+(WmnXAf^6M%~hRQh~G5Qb0=I(r$x`e=7pt}tf#pC<;-{Z1C^KwTrCQeu2VR;n?r$_>inbodNTtwj?s^V^1V$Lzb+ zrA+?>=x5R(&$NLSXGN|=dl>bn-UjhsbL0Cv-N|w$KBux!>$z+W>V76e$(OD|vi=2= z+((h}KeYX9&`R)BrotEQ@|AdqjJGTLs#P%%x1M zvU!)fckN1CNg-;`8D<3gqAzx&5?hHG{hPDPD^rje$m0AFx($#z~5=lXqA(`9ci+!#Pw~L}) z6BUOAS;)D5v;fMm8}=9s<4t?~&7RLa#I=qif0J=8g_fGE{Nz%B@9RLbKUl|xmy2*V zMN@vjM??=(l!2<|{UTgAYqlFI;N3VPrGH*3I+=u5CK>6aqT@c`sE9XIJ~QtyFf5)|a&AAQ?N*!i*}SI+ zrRj8qN2Uc}uQL4w_mpvg)}>gY=W8hP_R+yDb41sOjU&}Zhv@r_`%YxuZ14PirtK*u z77=%uJW@u2j?QDX%Gzb!qqlO(?}!rQlNgIxgw}%3i`VE(0depM@HEX?jKI|q|IvIb z7(DtF9e1FVs|XKVR9&*;v8eS+$db}0FoJ9CNGx~Jvr-jD1J;FJal6D4e-)gQ8JAoc zsc1AzzpJg1DQE0Xs&Xzc#do@?lpnP`aUd^{=)Z^N+WOWJMxTE)$jj;#qk7BA2F8M% z{53nCdSzMKGnw!e)q}!r;0FO-Lo}tOq57F$eB~>CKu!Eiy%s3KT$SBxSl_&42zo1ecRt#8C`Ds9fvPK_&fjX_;%k{=to=DQGHwL z9yU>5gnNQ!TNmLNu*oPb{t>_UkkPxOTi$43>zH|ldmg+C#<1{YuE~r2#gtoyEOL4egV9qsT}4iN*9)0%xqSOC=G?-w#W1_y>3DUI`}|b1i0s$)3zCrm ztn1?2lce64R|l53*Sv|#sW$J`UhWcPy@M-97r_BmWRX6T0ku=wg$O4FWbo&Hx5-kp z=|^$UTl;PSRDHe1>}e0z0QoRGE>Eb-y#9@vvmJc>z0Tr_9}JqybA3Jh@eWA3!CrUh z1?tG;O%fhxDb08{mv#$98PJj6zDQT){@#nATJILXDf?`=vhWD?BO{{^6#)pNJkw8x zNq6M7JeYVuyjOl}lR~4x_|^}ScRLq}u%zCmhsX%C32r*(NmAnJelbZ1l21&y3{oXn zzXO0!62rpUDNBN^PJo%3a@T8?R1RQAxqQyfhp+s{sPnP!*`-p%jFIDe9^3Z&%0LP9 zgg2BlDriiJhw%gE8{SOAEveH;k6RQ*`yJGmQ^d__Ne;MhBtz=61=p&+++}%$14&7W;)F zS=T)uDh%*=28GAygxdEt?;;QRSYa3H$-5Cacxn)A1T@VDI?x`>~TpVW6Je?~8Qa4HMCWPxdF;&WG|+%ECK_kK{gW%0s)) zaZ&^y3LUoZ^X&P!nnqu=?o9R!HL#C$^N5hE8x^Mar_(4-C+)cqb9ejs@K=|j=tI&9 zI;prwZ{3HHM!5{ltnOLu8s_)y_Ow8!{1BQCGJw=)7pI=3tyN4ngHPkgfC{;?^~t`S zE&6nl&z`z(yM!*!e&~&*_cafUE|V53T^Ck#0bT=geTX&@z|?skyT{0;V6Y6-0c41X z=c)M`$j*LgkGLD;cgN=Tr{OH@a)iXK`0Qi5pF!%tDxa)ky3t&LK{jsn3^BLYh6r$#3)el9)p6rIa&~AHpXf z=ao6hW7zHZ2EpOmBR?UYYI$h2QFJFEV5sEdd~gpR@OytpIF^6R)VA3H*6dS`E~w)- zA@Q#Eyfjog5AxcWORH)WO)zJGRgm28kgZ35J>R{50DtF)E4e?oLtVT;6UC(FKwsoV zgv=mW%onT=?&AX6QKmaJknXh)L9`wdR-1iU3HV*RxBnm32ASY>W=SFTHg6-z)nT8W zElAT7Bm;oX&RX^NJLh6SrdRn~gL^-m2%S(*^R!KYxcsRa{t75K6#3m}RSW~!DTXq= z1@0yiYmvz>x;bm)OD^^zkNl4LgE^ct#EP=zR1z@n3auV4**+>!Ec=<;K3J+(oG zQ`00$J8SLp>(fn$p^L=NYVT>*@J(G68E&8b%I0Xajz<{I1P8Id&cU>Q8Xb~hTe|C1 zGTY-LiPPq2iug`uE9;(0h+7pKS*td7_o#7r&!`TAyH1Q_+ix)jvMf4s&mc`=YJ+ zu+bLYz_0#MgggE+otOUjlBc;ZVl?^M!KmJO7lN#LQ&(f2HA~}f(9qr8E44tKSIOVs zAU0?6{8MLp4shP(sB7QtxDhMQ$Sjz9j*8VINW^`P+HdOX^U;|}qn}GZSPr5&4P9`j zh8qL$=%+lp9j#u2RT^MS)G^&l@qe4`cC5^J%CmJK7`ho-Vs2Jw^;`ekclrmO*jDyF zjiGu8Jt6?rw65+`JHL-QPB0vbIA>kImVpl|STYTltIa3rSBCm+;reX*{W4x9DCY-) zJUk@KgyHvWe~XKJcM%pq-!Pd5)@Cc00(GaL1%_AAAtT4bBT~4B=Cu9@T_K)oauDU? zEs>fuDeLeh36K7M=^)SA@OcB8jt_5BRh#PmpsmHXr}wM&{KHRM$=?L9v)j;WPBz^> z|7_Fej*8a883FRK7P9c4?Qg4u;k!qC!@Y(0N))pd{hs58eq6Yp$&4JMJYV;I{d@)j z>pmLd*`g0WSqff%$mOZa0_E?T;w3NNXCu!;)5yr-0Ym4yGGEu-^Ge{}x;0PeM#uk4 z$O-1W>Y&Y__=6rAelm>4PDYg<{3mio9wObM1_Wid{E?k&*DeyaOD`?8O89@RIEcX} zpS!#7B+$)$zpg~>1tLv3AajO_3d=z}rhI9!#r?hr$P@2Fc0S-^{GUV`MuXu!vi1iB zfK}lrcZYhm7yXB>p_hDSm-zCt=$h=buOT_S&$?W8PkLBQq>L*$>CDX$o+YNfsH4@! z*YiW6O}d!q(c|FUC=5+Oai6NuetsE+9pg<#4!)~6K#G?=^yxPr=S9{Lc?jsKp7=J~=j`PYi0Aj;Bx;Ngorz*YzUN;&*2C9(D9v|u&90AWD<3T2A? zuuDI(K|32ifG8*KZ&g85C=2&VF|-ql+^m1qzj0fcS^Xu^r6?gonV)%R#h7bAQ#by6 z*{^u>?$D+fmSseY>G@^}Q#08nEtnln%)VDh2g1NV@D+Ox38g#FtkCzR_+ouVdq$`r zTz{zD()M$YU4(-h>r_khVa@f^_=>CFmCmoUDk9VPoAozEEa}wyF9CHK_w%+=j;dNV zxUe^HzeM^d@7SZbcgW;|I-<3&BNP|HiG`XV7||~Sd^5?bjnI@o5yc2PPwfnKpS;^P zf;>9iClEEOO|GKezjxfCI|gS|2pqu2_RtW^D_lymGas>jb)y6K-tMnKGw`L?xuY?p zd-Ow$9lf#kXrJr%>-97rlF5^BtFc57q|X!`41>BMz`F?9Fglc66fKYIiyX;9A`Ftd z7?D+q_$5qlrCme6!!H*#d<=cU_g@=EgHP6n;ys=>G?cx~(CKJ>9?ty_aLwmFQeIJi z8ukbVM5`p-kNwxM`mTqz1I^EG}eBKuhn6l#Ba?ip|{L~AqQ19r(sZVPCeYN7R zh?Ysh(|cD(vJ_)=PlDgP+8nYrYOU~!Je!*?w|y||Ignc+9)|-H1J!Y&o>ZcY*Dmim z9O3YDvdYMZLXJ<=gw)9V{k2rgFb0gd?=p;=Bpg8Quwrmx!bEc%wBzT^brN$j&U%;b zdXtF+4^Ha9Zqq{&*n2H>P3Jz@99>03M*A|9tiF6dx zj4$p;!TF7# zg_@igd5%CkQtr9q4*lzt?Q1jknW!QSq~cjLpo?ekmL1=B`6VjNHLPi2b;^@b%J+S? zd)R|@Qr}Zi%(o{d{l|Hxy^^ZqCoG2X&ha&r`>?$310s(@$kv-Zdtx97V||Daywy9} z$?WpOpdAZWTexLkiTkC@trYx=b{yaP8i6n8+e$M!7w=WQ&+xz*@V%e4BX_t!!XaIV zI(VboaOtyd^X_cozC$XYM~;i9xsUjpw8_{$<3NG*ad* z7(4th{d~dwk@%CtlwslmI>fKIu<+6u#o)nI!2QBtPrtaIdLK4_ykC!f(#tNCl<)SV z)=$&(^M)E`A?v5794fxOdP4#dobA8z9$Bz1PL80&FfbQ5Tqn{<(L0JKv(JUB5c(jc zE{OhJwE3`8cth*ycS?^*Vq&+pM>Vgo#K0DaRdL4fgAJmfPK;~J(`VrygjtnGrU7Pz`IDN z@8_zIe8NN$TmME#5uyv9KH#_b3fh;*^v`X=6fOkq-}$wW%Q);7ta9qy2TA785v8M= z@wjvVEH#~c)sHWq*4X=fN%f0(+=Hz?fJA4yWTU6OPfY<1Os~9rKXC`<(bC-d{9SMYwIlnDCV*ZsK$Qdx^W#(6Y zVPm>R&$E1_9OM;@{bLLMxX_@$+L_xK(lZ_`q(o|TkTnkd1l~Q7_xBgD@*{lub!;9a zbZ>8k_H@DlA7^@qDdHEOABFfQXg7oz8FZ6b?0-n-Yq5MfYQzad7_ zase7K@tKg{y`+GsD57deZ)1e8u+5`_+^M?qmJ55-biFdn{k^&T!SWZK>XTeOb%FEBfLt>++jgAt=Oom^599Jz=WsI$ z#!os+d6?5}yM4S2Q;_hyQ0wU(__#r^LDaSfGn-J9q z>-oFUK0z%24jfH;KLoNM5B%%oba?~{o8)1jgCYV@PcIfF>;{>S9R1@WHWv2B(cihb zM*!`+*mrT}WviY$A6%FuFtVwavwcjFmqS&{poID`OPz}sGa3|!5kgL+{a57_S1~|6?fT@u{;#O5sts#*Q(fO;SijA$(i~KrU2o0 zchgJSv(y;MmTK*{NO5gMms=_Bf&Nf-9crP#V6BBQ=6NKhnSGRMF6^Tir5Q_RFP+Ff zoKBOV^!zN3uL)?i;6df~BD|myKPmHi0WL%;zd^hp)pJ5hpCGSHS}i$o!;UG~>^{0k zwEhBL__RDzt0J&FUBVv>EbD0BphYkMdn+od*%$`$eF)@}W`arF>mPMzT!-1U!M^=i-tuc}_H2DJ_!4Sd|{(KORwr{RlrLDXWxxaN}3Y>w!UC};f`6AuP= z*rRYU5|e&|f22o1<*&2)z7;aai(HKcol(fvNVeR)LBzAx?M&~B9zu9;96Csf6>g+!sNV&?CS4$i= zC+W3WE1bdqoQsxFb0TT)gU3xb+Rhf(Al(d(BVbv6L_0*sLypgt9WW8%0pgywY~h94 zBM*CrS?yCV`8^07r&@z$SN#yRgO2zYOfDQwcw+TwXgDH|BfqmT9c*B2$dEi z`OS~Uoq#RvB`q(9>0JHId0JA_@EbF49kOk|d$T01c90c~UEgI41PFp?A%Bl&i9WtV zJv#u(4(ISvbPmzL5uga!ZTHzz#QpPKXslr`)4!e*cj%!F7bcvSL~nVBuoa$axoo8d&E!inmg+4C_3Dn@S5NwxDd3i z^?qO$Ow)U^REB9+DY2jKi5YMatl8OD^q|M#yAO3bPQoAV1I?pe`&h#8%`0E2Up}|T zE266B>9^dD2X@opjqEEqQymIb{o4YD{&SeGI>D?*?N8f&JU+&!j>4cUpPk$ixGu#j z@lk`su_k2v9*NQ|b9w8F9L*NVswFhHfg6-7vnh4P|L#_?Knc_QXu)hJl z#fwKCQvS#zJHbGMTybLH2M-Dp#Scbl$ZEd#=>@cLn0Fw)-Crryx*JUA8i#P$I*rdq z;?sUhB?#lI`e+Wqja30|O)e`u7qs)kxpWo!fV0jcUMRN@z5Jn?|y#X8hghYi@(Cek*02ukjMPUe@6-MjbHufqd2~WwNE=un{N9^wTYlwh!Yf!#5o>wGGHF%` zAu?W$%tBpSQ5b*dI-mF4ZmFK zC0Hamz&q>)%v`ItW%oVqGxzz*f1fV@3jAanZnEWwsPbf^1IA=qtMD+gC~y8m0o=ky zRfRkBUx*OJepDsDS&X*Dv6%Nyw!uGa`($tYTQhe=R+OYpKlfBAQ< z3m>-%zWVF3YZmipmU)(6^JX%UE8Y3q8RMpU6(-9bq%}@ge;gU016cR;xcV#fAsamC z9%V;;SZg!pnAI^Gt4#RYafz_0s*J0JiiSk;f6~!LdwVGVODoeDa|!WiTG^X_OwsDdU$ni+KBpocNGalrAc)y~XBk4m=^V>OR6B+$tz2AyWf57wN|bvvu-{(ZoDL&fN(HoR91#O$A?o zG2Qt3{QT;Ne(RDYgN=9RF4a~3 z!vb_&&KK$EKEL0#xFS`M}AtZ$33XCq4T)tmjv?nj{hEtc57*J0;QM?2+C=)8ncBD=?BoflS$V%hzoU95-aX7oyvk-5 zHy&^aJQGltfl384%}~hBIE!qrY&fh3>pnswbnCn44QErmVXNgZG~D;61!DrE^~let%2q4$fnv-LZox<=+f;KzBI6?pf5lzy6v?uY`q0 zi=n00dl>t7Xw z9j)W7k6zm?d3i%1p7CNBkQ_x4G#KhjHyM;Ecf~4N`ATcnjeeyYSxr>^yQIs~%uAI| z!>r5bDTHh7h9qDKNLT1D?taZjBohlS$Ar`D;~idpwg=0>3Oxa#hGA3)$mcaem(t5+ zz3-1$p854VTz{*tPhk~He<~7PIaR&jBr)+ApL6y+!rDMV_ehIsQ9>u?3!v26I~aoU zmmN^z)bTu2NU&%(otTxV51d1hM(FPu|AtVIBWmHMf|vZUu%4H~secG9KdFBOC>Y9q zu$WsV)KrMN2zP$3bo+xwsach89X|w3Yc@aV)bY&v+#~LRo%8G5%n^~wR7oJ;HPY1Y ze3<}{@1r86hRVEo)6uikUG08Qog3sF&+$zFTC>T?>HRs>sy5p3%q_XK#?Mw_zwRpB z_WKlnY$Vn17A&5S5mR$vgm1-cix$<=SlfX;YJUrm@523!moTKl%aUui z-H&sTUH^=h5=)QMfwu!V#@5Zle4@ju`8~hN!WtMvxVQ7V48c#{Veb1bWIx+nu9Q2x zmIsVrqNDm}v~)L5?HR~!sRtp}iH6KL{MdjkDS#gBA3gsLc^KE8c0K~kID)ShG+}&C z4)=9H!y?K{m5VyI`Q#p8-7zy5F$P8PfYyGegFN84^fUf(Na#=v!;xl*xlpho;F$6C zR+JVT3Kih37!lV)yX>PdXVI2>hmGGUVj>6a5;9hA(!sn$UkJ7gDk%luDj&&OPxa;P zGbda7()au_lVpt6tzX|7@I!9UNuY)4Qhn3JVFdLfe_c`mX?D+;NS=d<4X$s%Tq+Y2 zSn{Y1EVqR2a0<^lYa>X5(AjN-Ry$twhd74mY#tXZR>VB~P3O0uqa7OZ_UH4F^$#5`k@m-mt3-ze5rh3CXRT6oy!32*M~%DNU9G4*@us>p5nZ#d#Q0<@m*>xen<;> z9V~b2G%{pE5DJlJxN*L~5pSDFMHBf%DUGcfO?n_~-5dLeM}8C?{Vi296F!9TZXUvj-tVP&;r!H+{lAD4>5kxUgpVCAd-F=0grZ>JqdW|IMGm zT|U!3WZAX-{*lq|QwAZvn=sks67IXLFah}XJ%3O$ecoinKHU+S^qmVEy_DyQ*bj@Mv0)|f(j#?@h$Uva6Oa?B0WjDGx z6jxkz(+xG0t?c=U+OMs04Ek{$x2I(Q8^TZV6nO$cTslMLpTcjy*v_479<@hwZU64H ztvJsWttvrcas>wficiXCx$wDxU* zZRrz@v~k=C`|3uk`81Z=A9!YCrFnB4k#FlZ2Ok3%3A=dbY6fGPeOP$@_J9vu*&bP* z=7H-=U7|L9g{kqXPRH{Z6SowIY;!w9m?M|SmYj(%omR^B6Wz-t|5Ki1$(|7|*U((J zRABF35VJs$UsWlxsai2ku&W6P@Q98<*41vR{ev3T4xY> zg9e9$7@rSf{U?cd3U3Oy@&@*&UQopvd>i(!B&re?r>E?Y1-2eS-PWnX3t@*tmH6b? zlqv{$h_Lr`_hB(5D_QP&qpST~C=ceVoZb(tSrB(l@a7qqcxc-PE82H@%RHCqc%soN}~QM>=CE!^b2zb;$=aCVendT3cH+Ndeo}9Tp@!w$MWii}uGq)-fJTHb)yv=e zN%1`w>+$2h=~QxjK5^+HRW>=wL(lT45y3UwFFzuY=2!zHa(`Zd%LeDKH~x_^#GY^2 z9xV$aJ!d(&V%pAF0vVcHQOZu)QhnC1l@ESENFp6?U8;XLIHl>5M}Lop^8;TEjrYDg zXE`Gz%?iJ`u2gix#FmNXirYp*%7I5Tbx3$Zrz0?u@#@oLUGGNczT$gv(PpRsJ9jMJccy;sJY{$%|2rzUUr078-`W)<+pC0tWtJJ;$B zOJCtBwJj13p^G*X6$>IYJ+A17`r7H>?k8a;ob5)J&GfEwn8uL2basxl$J}M{(|`P+ zSW6cEFi#%&p1Vw~d`Iv5>bRhX=!QyPHn_??Ecw`>2oTD1I{fgoGTc9ksx&VjxRJj8 zaMty6SyA&Wm(C!q5(qMC%qD}dJ_>mQ)8PO-1fMl6W0D2qI(oA{@*@^@i4xzPrC+Av zkzBQ9B}(%-5BV)ReTDJzfExL6M!VycHMEuNsuTHMV0i}Aza7POp^b$yb%8Jqom=*( zgWMuypf>V8tML<~7SaX-H*i~#ANSGDf~O00fh2C~+M8dp+_o+ku? zszFU#q-ka?4#E2>trsdH&<;Jvzb$F1fd)c2|9*MDK8Jb;4N!``Bv4=asm{jdXL-%lfI-{`vL_&@W<+Q(g5!ZqG8(C0iSBm zP49uA%b$lu6a>zS*!B|v1I3L_NL-5_C?5Uv?gONLUmH4ob$#Cg=qC0RVvuE(ygbU| z0GbbJu$y3q@$`tGsidfjg^}>4(fj`P5Le@CI64*2&2fKg#`7obfy&%pzW>~ti!s|ju&xOAi z?$?WpH?rQfc#F41jp^$TG4gGzDjT=P9tPM z?zLEur7fV7rgf(HiyS=iP-Dnom&t{R0tk(cPmoEqlT=EztsJ%2y93JBIofjp^8%7!P}U5*~c*zC83)%iR$OmSKTY(sT)QH ziRJ=dg{z{1Hjj(|6!~{mQ5R?WA68elx47fdq~PV-9*@XGQU(|+v-}UHS__Vx`r9U@ z+7bN{a~2`kZLl!9Ve9ND{3Gx3x+`N2dWa$G5~aVD2Uh$|>FGUsS7e8AJ2S=Ok?K#) z+o93;#QH5f0oHzuTOP$n>qyoH|6@fnzdV9_3m9tGnH%98@2oR3`5OJ-}HcqPsEW^26!68)+@P4 zudyu=|KL6vLUtdB8!a4l8wUu~p$8dccY{Af; zKvE0fV*48S;UAw{df6M-(A{z&ZHO=e9zb~o&#KUWo_@810?H~H z=7O&C>9~(lJn*@6#@|T4w|w!i=qg$29ZaWTE^pa=%ef8Z73WONk@3 zRrd+gYJNlSsbb7m&8bnl4tSZngN1Q;k9F8+HUywQ5D}d-qhZz9Wnu=9&+ABZgnT*s z+a7olbPXE*>=UaQjg0&Kn4zQ4{nr57V&9BhviH?!-Q35)BPF@VA#es~ z7hg$|^NO7RX*?4fa6tL#VA$JxK6T}l8!j`aMcX2ywD0=92FtQm`7uD`%E*6>5Odi{U@QmDIc;89=%lk@n81~cT3|+>c9r}${ zzW0f8ZRK!e88+O5i6{fSdms<5Dafs*3T7`3b#A(f(3x{%>BC4Zg_K;mWFY+9(;KYG zF2)$t(23&R4qDk1)!=MwqpHA9C-&dLI||1p;WN^|(D3E>^k&3>wzhr26h5?i(R(Z{ zBI@4bG_0H6^C80mBH2UaZ}WZ1E&W)x{M=;x=a*f=Q&C*ns;Qewma#~KmC#EQ1#_GJ=HyE(D zA4U6dI}b3mz~^mAm9J2q-DU@y46oiRnvSuZ>Qw$lb~5ufmSoZ)LRPyjP8^o9?n5`t>DZPRz7SAj7HusHf;gVzpbq%=p$GKk}Z5#f5o-*TSGSx$G;C5k2r{&3w{tZ3ysLyhQA$Pv6|rKSMobJpA#||5BBfHf;cF;ehF|40-mC zxSi}KSmGdj6ED;s9RF2Y;rZTJy;FRi-1TBTsY6mfoc)e}uk`Dk#oPs>1r3iu81drK zb3kuvmBKyCG|BI}xi|fph+3Vw;1zLqZ(8OKVKvZ_?*oZylOiUy z1$0O%ejY~>Hof@VcN127vOq1JcDC_kLC3;<(|J!n5vN_UtV;TR`J%g-Vy+AOM+5v=sJAI1 z5xX}BI7HmEGz+@(!*FU-UkgM(_dEN6R$r=L*7?0Q+`WxEtr!>>BqIDGqw&`C4&64h zv>Zw^o55AB(F)CaY~fQE5k=er1^4z9>RwJ+5d2KNUH_)d7|wlXHDn z*J^9)4{Z9_F5B~LZF2|5*9?O9cs&isLgTSXxZ_s;j^?eADabganl27GNmKSPk^oZ@ zPgtDeb&%(`FvEF^*)1QIJiA}B)!9mWJL4V!4XJhC3!75#h;QGb>1cPnr%^%SUf7v* zuCPuJuT-_AOhT^$KyI(gV-wR~rEit{^6h%2zsW8$_&hfH}?-8KX21^cj3(`R0suJ9hQ zcRX)ASp}e@zkR8=ZGRq37g*(-`KMouN%py_nn`rklD;QD4^HUdBwq5nLfjA!%F?a& zD|RhlvwQRRmhIQOEnDlk0yaT!`5eD+;w zuZBka0{l4nsWzQ&a+{y2QTX`GJ05?JyS@1_@oUv*m7fq{f_Y;-BS4*J;Lf*(Ux=^V zxcYfITrTsmsZFnyX*>EZTfg7f>ZBekZmUON1(js7$enwjdSVD`UDyTlheE2SQa{nb zyy9wE54}FUBt*8bCUgk)qLWGSe9dT>`kajHanCss@sa1;h{SQVhl+vTyn^h~Wc0Kw z$F!VY2mADr|5~VJ3*UtmLDOY$2(QCEL87MI^CDCCZhV7^f3+@swm=qsAQd7{ZsTmS zC#rQ2DwWgqX<|BBuP~llTi^kV^0iZv)ctM)9%>#HWk}8q=iTrCxeCuzZ(aQO*xs+= ztyCLO4@`RgIvu+$U#<_9ncau}_2el*UaZKiHX)gBg5aX;ysdG5w-5uUb6jHr!TJ7B zN>f4G@_t7^$KYGkMdJIsJK4AC7`&?4xSNx{LXyhcdtNslgOP1g*X%b%iP@S2$zg@< zZ)YV39UJBjXc8I~irTNDN`pOG7`ll-2nR@wEl^TM`%3nGGNkt(zkFe8UuO;77o5J3 zf_ZraU(7Wy9Y~Uy9OnLK%llx(1!x9mHT#QCRi^;(fN@m|xM_#{{YE#MIP)2%X@Dwi zV37)cU|i4@?SXz&1UjG5j?aECa^jCp4dB|d>{RN>i{yQ|Z^GMq-rAW|U?pPb?(KLl zl2;PsoX@>MGD9mOMW37x1&F~7l?MNN7|42=Aw=Dhqwf zbj2CgI=cfMsSrnb&lL>rHW`$dQqG>HU0vgnkE^_(2DwU!QTFRLr3` zmV2ZcWi_)G0@}z~*ZcL}K3f)!pvJG{^B!pLr#*+J1skv}tkdKfjz&X-N_ME;M+_j+ z;e28A7#0yncg`DSV)x+!u;NZqMooSkJzf-s#dvx&YNGaWTyEa|bR3?7{zT6%hBf)u zM?&moD15w+WH7TKjNgCs5Nx@1i*?!j$&Y7Jr0n&Oory*?L|FEe@UQg-<=M|cK|CmW z_|SJ`;MV4*zhtKL-^kuk`e=s=je}o%zZZ3Fv0(;&yPRrYQxC%P+0Y)yFR&3{+xs0272~i6*CCLn_IA`vL0w?wxh!GO$i# z(b=JO?V^SnsBPzh1r8(k?~nWIBPJ2;YVYZ!f(_p|dtROS4wha_dpIbv{V>*v!|@MW zf4+Xvyk|&<;8O+T`YPpA%vl;}o!ZDQSmD1J+6?Ze`c7Y>KlMiUpwKE`SEJ>L5q;ao z;HkJjquW;S(MheUixz*r_lewt8vOb0hvK!Ti8PpLYU6ra+nIf%v{5{B__|v!egX9%@$}AX_4xJI#flA+|@el%j+%KuURVq zRB=VBjIP5>JHV&FfQKkF9(B)X8tRn%1;UIm^tJY$kb!8<;W>K#K5teoKveWpaKM#w zncd%^wQ_|$9s0u=!bPF{`q_2uUt(sxnR1@W{4`{+7pLq?etL8V2(UD@&Ou}%gUf3Br zd|yf!RqxA@v<&Mn*hsHTD|GYH*UyTiBdZ2|4X@O_&oHDn%(W6ae%?!$mqRyq@9B4G zKAJ=E$H&*Z-C>3P3V6X)5hZ@C8!V?K5QJ_OLBhcM~g+2iVg$bP6s< z6289!Wp<9x>3bAK^BT!4u$m~4Eb-wB^kTgS&7YF~{X*2B5_e$_RQ40%M;> z`>1als8O5~>q0g6AK@SJ8*$jH>9MF-1N_s3-+5-tz zx_rqIaMD;A%Wu11>-`-aOyN5{q5-Xas%$#apZT3l>;S3C;gZ36%rEU3wjs0DG)|G0 z=q&XGWt-bOibIWgJyPHahKeti{71OAM5!^_ubG|)=?QJwvaCiU#vGHM-Tk)S&&T;x zHf7Nq{TAc|c^?$HGy2C+dY$kJG-yD!J}+#^K9Cq_;gx+eXG|1Q^_mmf)Zl_LT>OZv z5bA{n>;8ET9AYU2|1DNo>=6mcq-L>wLNMk8Z=Lg4~Y4nOq>_|MVc2CL7&Qt8c z0Ru@V4MmQ*5kG8trO}z@mv4-$sz56MR~34fCC$X!oPX?u$*hVWbvp>`awjf;bq7p- z2e$4|5*yxfS&Th+ygmc(+gFc~8yjdvTj!nfO3^pLy40I^PAUi94Q%YANegsdMh_W9i&%ffM2)ftWdw^*2^)5<~$I*XdWUGJ2O+H`R2@ zh`g#ZI^lm$w1nW*0W|5cwehRj+Jvp-uR2`?7>fl&SWreh zy-k3}&ZzKEg1~0>n_hpXBu8gsqVF36=-YSH0_p%74<~R(7`s>i(+lD{^vvnD-(Y4) zbJGqE>f76SZIXPoyIbU$TTiU1uN;gjMy)cAn>}U*?IwI4XTIPXC;P$|fhbrk%+PRM zseIX1bmOB}aO)?_>Z_0Xd`{v+Jm8cAqc*+#!@Vdtjz}qMQkD|!dmH{*y)8aDX@fp9$@al=UG87Jn*M4^h4%c7cWs`IL#-_ zHqfHS1eb|)-v1$k7h*_tQTI^gUclW8zfpPRVg>Rtf(x;ykgnnD&C3cwy+&Uq@j}OU zJQHEJbRQk7$<#O$O|Q!Y*QKR>jo{A{QaUmKEoyo*pNFc{(53gL{t84fA8DU`?i1YKFV^}W~>FCsGB0HyM4C3 z1qrU`0GxYX?|L!&X8Rkm z45LG2Y#+GgT4#|p8m!I=vVPlvgsU5tUHP}YeOKT2AQJy*lXiBqKm@JwvF=}ezTbG1 z1Y0i6Mw5KnomcusBHAQo2s|x46!?FMpuNa0xy!F5;an2*kELB7cw;)A6!DCGR83g- zXoM!Gg5A-|%%_JqE7V-Tpx_;+U6Nzirll=hmK9&PoVM9yiu5BHh6uO_x$I zc|KUQ^YHb&Rzhh##TTl!xNQOH^vQY@Rp`QiM42h`Et{W>rgmsOdl+t=W#?~cmBpz? z&%6p(Q)=_Y6QGI=-R#=|GA53jR`LWGyiPRXpGuxW5k~rBCCi+uoUe3 z5g`SD{-b;Fs)=_$o=qN-(cK;E-u3C{B9Xn-h&fi+I@fbslQncH;a&DmMwIdMSP&% zQ^UNT(Dh0>+j|TQlsCyPDwf|}eOqF0O6hN>CBZzhceJjj5n-s*=l2a<^cZhVO4D}; zSk!}?84#DP6UqU?*3<1lZ6Gu+{#sD+#nMU=>wYG6mmT9Xhel&NKA*FDw_Zi)hqL*9 zh9!y}DUle!r7&-{gCe5?Gp!v(GSKObF8gOyc5BI(->^e*6R{w?GUKD74Ij`Ez((%L z95S2FwS<`CYhx{HpMTEvvqI@h}J773ILDE--5Q0euLJj zXR&&osIolUkBY{`Sg^L@PaX}Favw{s>^~qleJ;heZ7); zo@X8UBG)1c(&V~k5$fNZbPl|kg;sca@h$iq_kcQDdXWYTdpjMR?fCM$BI{Z5-PA#M zX0k`Kw&9KXP_`C9x2VuueOc&7((*_1jsWSzpY!R0 zn_6-)Doc8oN5mdfio9Hck_|rItfD$|4Fq}~rB>fBPuUVFO1tO#g~#px-11&7!IbzA zX)qr@{YA-mqQF!>Ky=M$?#o%h`~6#vLXZ87N53HFPW_e$gsF2q<3uo7WWj|t6*S|0 z+ItUW(A0CykY*8j&iyjR_gufVp)hPI?05DDzGFLyPYOC=0dDy_bv)Ugax8^ku>6jU z6FrOuv}(SiI(-Vj1==(G;JEBmLKTfM*74C5kt#{0caWVt@-<)%5O4tE@@_oOg61r$ zS%feTFh}p#L3j$45B0(4vyef7FP0XS>cPMm)fN~{!`LIL8?bS1L7XfdI^f??P&5mkU@Qf$=oYtXdC66Ph`=Xp4*oWJbov@Q4XR2SYj<{Zl*b`2X5 z+Hy2QsVMlWbD5v$0*`F#E*&L*H_gI4h$E|gG_>QO;GtW&mzHTUb;ekKb)zp=pI$?< z{rzVDA;{2;g6D(1Q~PXN4IlP(^!Hl74tyK}estESC4YQ}ubWv#k$ zb_@eywI0{x43))k6Uc`AAS#E_%8JpTo(<@CTa61MJiU8-is{15-C2FCT>ODaOor_4 zK1chBB74D6T#=&RmpkfZKLI+!;88Wu1t^)1=lh_px8wpfKo=g*6n{vNf*EdD7hqZO z(;MT4O6cW#90JhxIXE1m4PJ{o`NiI@@LJ#^Io{Fj>UdN3n@DVqC>yTfAo${BF!m|# z?7wqVO&^B@z7X2U*(;t##BpTh?ZRI*+E7;dwI~kE=Fiq^#wCp^xD^J{uw->HJoI}_ zuQSv)+=qc^<8BWxkQv^KX{3Y+J9^1BPbjLNVoIi3wGLie6-I-=Mn3>teBh`n?8N2I z1QAFb$b(8+t?GjGe$Jg6ujOnO>weQsvVA1mqOOf^syABo`MSyX(h?E_9)7G_`@DR) zHA!>dl4JAv0AMCjcPoXTEa%H;-PqXlAfxFFxFUy6~zR}>|!w9xnr7g=KLQ?4Hw}{cO zrZABfe)FML3hA`(;cs5_8*AiNy|c1i`G-zM^|@U6Dc6K?kPRz*uKbY$2Js&5&|CF3 zA+rrn;HH?a#b2*t&PV6zCuCe&BNd955R061_8^R<@X?%(!eN>Z#0S3| z(#F*GWp&d%P_JaaeR4ea19KGil|);f!P9WP|bnd&)%uA6mU%8bT6E@3lwpMLFnav@ee$*D@>DS1%<8(Ui5rl ziImR_h!srX^B5CSaX@jL(c<*^U|K~97B1?3jOs+tJ|Ee-RQd1=T_C>ZHD5YYN57Ni z5BHzwYgvH&T?2$)11p%c#soQz*Msz-aO=m@UzX?ZN`a^ZZCqp1Z7d-IeBeMkN9;WJU*Rxp=7iIgp zAu)(#HiA}%Cgl7usKaNN3Cy218A6!@Z;1WM%=8ke}yo`iNtMM)#0|)8#1w6Ar@X;&VgN7NpWO`1*YO-B(66Ish}uM|M|haeE3z@zs3jV^u|Su?HB{v_=DN&rStjoy1KB|+kj!1 zls>;7d20&882}@NpC)DB_6yC0Yea`t1Kyop$p)5X!`uaE%L4n+-3@sm^$1oW`x-2CwH#wH=9w}2sNZjrc*DV134IE$93hSuK-mV z-d%JP)qVGFl)EdkM|VuTR<2=VX|Chc3) z-^ZJV*^!>V*vme&nCgav_H||P)%&op=g8UTlRI6|PZ({buQnDoYaiC~FaFW?D@F`- z119GuDtZ-%YhQLJRL-pjTi3;fqCi~>T1YG&#T)ENQake9U-y+CkJq={%0rEDKz0g( zvioNq@~sx!)@$c|&J4OMeM`vESK6{KF8a`N`-77~qr%Z}8;FNnqRv3t`?3heU$t?% z6Gs!AVrVM)YeM)#pEtt7W{cj>U$$5;pfzjx)VihmIeq+W?FoWA6IeyREcm09%$pxj(S;Ps+Z?x=vt~%*A`4JhOc0EzUH~rN671V!gPaa%y)l3f;!!$whkWG1cHv7blXY3Rm!PhG?F8D>W;Ay~Ly`#SN z_>~PRnwlq{gJUidQNtd<-j=b1!8N~`3Cn;Xi%$`Lb~T*glGJIgKrxT7On551;hFQN zJ5-NDziba?HnP-sLNg?uBM|d{5y&)G-xCS6{b;6U5GFLug`-IjD9F_ek|-9UQcNrD zWJJFXKPPas&`$==91yUw^_#JJdQC>%GwSdnQXVu@&)+^akU+3XaCf~EDUN!4@vDe-$VMw_ox*9vY#S(klqBX!z~kuZF%!zjHThjl_v$6-tYam z(W`m{3=6xsSw#xT)$b_GRWYj{-+XU?SGDKq1jSnQNW!$t!uCO0>)3VVE4l?&NiIlwpe0k$b!vzFNaH-}A3hU>7-qn@#X_9Ib@dw#J(3@Kx^kiUFlv*#_+Wu7C-}#UNs}G z9#L`#?Q^*ES0UMgFI!gj8$d*;%KL0R-{U+aO2G`$@72AU0@d#W#=}=XCH~L<{5ta% z;X1ZK65R40GCDOs#;bvD4){WVn{A9^kA87hai|M#2?sCRKd}8s>%#U#HOBPdn5T$`xKIKdrI}51lLyn0#C?sqUPDnKS6$^-BM!h z#&q@ar({$Z&ZeG%klmVpuGiBu{=z;0)`K5 zR-3VA7!@OYtOkreVIeZpM2NOu1(ES8X12Z8X=c@~tF4DM1I3dn>=y<_qY142w09x4 z-r}pC^VQ`|7S$@*cf?N8hW7_rP+P5Cw3!`bc|}8kb$S&gdA_XtGKiXT(BIrkji~I^ zyQqDV?|B-8{jlRtoIE*1Gms<`M$*8z;a6Jd&Ho!)$r?;k+1oD0<7E3Dy{0i3L7;jw z;p<^6lmTcEGoW;(o>Qh`h_@$sPsF0m@ou?c-yfR5WIva_eb^^ZXNWz_P#ojPHGn^P zVTr?b2RCZV1)kk`Z|X~vui}dVwimC|APM*Vj*Ve-9nE&ytsEd2tKQBUW6Et_vbQI}RG#*(Sf;X(?mr?sI;LG4!cw6T? zUmdj!4gPG$yKs5K6k6DRHr&0dToH%t{kk8Ga_#rxi~7*~+mqGf zIK4eP*p~kQ{j#K{EqMWq%Cr46kBE~)7gXLN5QoM*cGfH44*NF{qDNDgJ(%r77MWg& zZtb+UkEZVAzfSMYk9p>M(;o6b2iG}cR~m#_Ux0Z3{Gwu^6wxYs`Qz5u*9ae||MZw9 z-IOn{dX0uLKVgg97fK;-heAIf`hD+2dgUX~tzxgyg!M%196r=KpHn@~mL#G? zj|05&_~3!imtWQ&m*{)$BQFPchoOnD0`Vg)@dsx?NV7>nv>k?ZMtLKWkNZHYfm_T8 zGw)KHNR&-moEkJn4*nw9dklE_ytVIjpr|%`*O=hJ{cR0Y+}HFFWno6 z*p5_0o)R`Ro&|HW1hD>08}EEiF3u{a_gRd_dAm90gZn-ZeLP;VaVs_|+_PXf88ADL?q zYOfQl7$5T;PG$$=JdxRFT~ky^P!31J=w=gGM1j>_tomHYXc+sX^SNNZ7PPDxP0j~~ zE4)`#(XdqB07>~BuP-Wxi*0E!Km}3XXi8x1-*ZBjE`pbU> z$7elnhW(Ne3Z-pWLvBPJ)$g^m`3JVa{sLAHnGM_{@EbdgH#-NevTwWjARr6JCmnl| zP7(o8Y+^moSCPdKvZzGG>DJ<8mpjd}M5lOZZM?JSO@M2UO0z!RoL{d&@^Ls5rZwHq z8_DfM=1skiYR_$U%F2r9vu9ve{Ufh>PeFTLQuABEW+hp^^PU^*m81vl_q=ek%eA_t zB(OpnU}!xp-ejUxJ2?!e(-+^APFC>NezF0y-h)0Quc2EFDUR;jrC`paPzAsdAF0pt za#`NRbQBcyc`@_Voi7Q?w_E~u{`+tivv?M=5~jL;*T&FB+emVa*WgM_M&|p6s6K^*(2E?Ew zF|L?=;o9!+XXl$gG^}%7RXY1D;C;uxbY*7VdwpheVd1>p@8-U+LO+`KKwsIT zD2+WYb!nM5YD-x4NEg=%7#{dL5pT+~g(O;l;vyC^9R%05`yx-@HZy_5lov&&-VAO= zwN!j9#(+Gjj0wScrex~?h>Xopz!o@7);~%t^{m%Mg!4OWkW2VS(wQwO3ItK~m)Ms_ zQ9%SmKxKJj6+uAuu0b%&x@ip1?->287`T3 zw?A5adSykqa3uARRhf_LCQF5lt@fe4NSh#zA^deB%5pw+XzsNV+M=i@m@%Zc50EI* zja!9=E-l@pC1;Rx2qrwPqd$^I$Fc+KuKmWwLntKMYFSXi@pSV0SF(OUq7IGa>o&P$ za)~qN9O{55z0%EbI@%y^=Ct>mpHJ;H10e$N;Dx&P{d`}H-dV5G9XqX0Coigg)FWB% z!{?ivkCeR`E>wwhdGh8lNuS_YHfZh=(CSn$DjLo|&ok0u;nsAe{cZzPzJ{TF*V$rv z$(&s=w@Ek69k1l^y!_&W@iN0#7Y7SOSk6>Xh_IwJmA;CqylBYDS&uwZ!}VEn$?MqFwI~h=!-WKo>tHdykc@;&RqMxS~{x zhy2HQ(-*;*zQKmYxcoGyZxiUQ2L_HeiE=1eo^-ueW8Iu!Sw2xi+H>ILzVg%sY6lia zr;25Y+17e|ptT$pE?GmPNWW`>kV=|t{PUEfCz>(vTX$6fY3eomL_Bo(cR$ClodC*P6z}~F>(iR!aMuM> z>#*{vdr9Q+RIcWw3YPtHzXDa+JiR{GbP( z{n8~lsWkov?byGv_v3M(5|i#un9Tuhh47UmyrC!OZKy=#7qYwm(vv-H@eN_LH}~Jq zs0{s>?zfc!V?dugZp9_KO8ctX`iRAy;PWRb-JJpW1O;;W=BvFah7nQZA(Y@Fs4MJo zT@)=3H5}y>(Nu-_uLeU_ha;@_*o0UIrykAh`uFgCJi$IDi-?B>_uboxoU}FcSt0b0 zc$m=LIg1e-Ela!YGv*A-5y4+d^V;oaJL^VV29jIz^vQ-zX9`Yj9|LOMiFyz-C{fuO{hT9Nj zNyKACZ>~qT^ow+)KW!FbmpvqhXN>Euupzd^ z{(x~#YRr*;96NGx!ry);wpM|T0I&B5|{h|OYA*><(FG|oNm`wM3QbhfXuR|<=p**wh?I4%ONL$ zp~0U_{Y-PtYwjttI;%lL@>=J&w5#^C;=ugE<<4HBciUm=mSLZXe}lxbzpr7x?eO{K zasF7_w+TsIxQ*vO3mueGBmmIhqa>cUCm-(#a*+EBo^JNz*k=piEpjlLxW-9Bvw5KL zP=~f2_|p5xTPTzh*bcQ<5X;cT!SQe|t(WC!6qB{uJull(nKN_sxFvL=CHZ%s=-gWg z<@4`}2F{^181k{*AL$rLy0l+K254p#cA5;{)x#|ENuX`X5Q6z|h9~trUhV}n0NlwX z-f+1?0MavF_j)f+^f_^)gZ8{G$b`rJ_NPvNLs@Hl?CwR2vgs}En$ht^^yN}Mk`^u( zW7OyN=|;~m-9zBBf^#5SHK+`OcnzRN5ns)InkuxT7xT3A;ZRNRS_!i+Qj^Fmdz|*7 z;n{#cm<{HHh-K7do4;n;2#NG`J61m;k=>r_eW>C zjIl%t4&jgSbT3F4P0+e14ta^k-%$`xBv!dxyL1ca7&~(Gn;RZ?yJX%u}os>7jzX zI)7Ga=RFV0wUO_YY9Nlm5m(1gO)3lBnADl{fY#}pgPy}-$s$z@Y6e($Xay zP_uY2#KS+6F0^@bZv-w(8CERG=~7dPq=1LYVWLuF zzUbH_PY+?5W9CVfLVZ2B&L@Eo_Mek{T-*2W{X$-`D!5Jr)YVfBw>+Ex?8}V? zEdlDFm89Fm9E7{b#9-krU1D5H()K7LIUDunCfz8*$-Qk#$AhW9?rzH1VRH_i36*Hu z`3XJ$dEB8#$dt)@bg&Bsq;75qrKi%}qF6rfXJaDwkWXW>k74YsM)Kw0k=Nr}DY?vw zw+okhySdgriZuIB_ODhWpwnPCqUCDa9aJ z^+X--e$ir{*Uf#E4a>;SF_;A}e##jeG8Vaa{7d4p>@kb;&`#>UgbOoZ(MOGK3O)Uw z-ExQD#fc?v=-LO&7qKx+c^Uktis=h%_d1g08Qw0>}|9apr40+t3=Q``L%|>Ec)`W9a=z&MN;I zqIW~_wDh9+{cF%{?s6o#BYquT8v4t=Wf8){@(G*^T}UCJ?^I?`!M@S+)B3?myYN(2D0LS zADtyh;Wu@v)b{sL&q=p_hK_8KOC-y>%ui<>O$=|nEo5!qP3ko^xWG!*v=nMGsG|!Y zlfQH6QVGuQ3SR`6x-iL+izm=u)1vasvS24!pz1_tiu-Iu z6ohM|f#rSsGYC9AZ={x`SLnLRcC(tkrr>0^bgcA&8KOpm9ybfo(B{hR1aDa(P#{CN z!Bnpm4xT&%|NrFcZ|uUSdkZ@6a|qfcf1~mQx5Omi-yLG zUH3YcB*pFKA6(Nlw!478dBM^Jl8KM(_KB|QdSHsqw(Dd7YoJ!BS})+G1$lU34}vkj}y=e1?U`66K>|6+vkD};+ERcf|zwOXn<3jvu}L{hL3M? zD@ME!c8pF^Y)@t%iKyAx$F7&Jp^SdFF@^W}f(~`pOBdSZQSHaG^9%f4V|wpnI-%{u zPlsj*BP+uKnEE)qGops2yi=Z|0w&VW&#W^Uw$jE7podCG_RBs7i3>!WE4O^Rmpn0P zZr8U|F-#3AtEI4-Y=e8U+n@U2@o1LyE}b~X6_#8^T~r*;oD z3$tnL8>`)RJ+O=bT8g$Sk$(3n*vny_#!O-N61kUxfhRqXT715eQ3kn~%!@wj~||N04;J9-JJH7Och_$3!~gWG6# zfw<3t@JNF})>FG!y^$axsgZJC0Msnu)4Z7a2=DJ&n!-X!J>-Xv&(N!P= zQ0HMZA$DrHOjp@C>yG1Peww_7?%;@d3R2%Z-9?gf^>S}vOoR=kS3YAXmoMx}In<5k z!m0d?F9qJ8@Mz!T5F;CZ@Yk-WE)rjt6HMumDGDs;!yxK_u7!9QKFpB1rkCo*Kiu{u z4ATtzJfB3*l_54_udP7j9z5J!{T$9HuD-?JuWFx2fZl`{-eCb*zY&Kw!W^rSl_R@HDnb9f2=F7k z+qf3!qhy2l-%?r$POrfa4~}p4xJK5;A2j`!8Nw{rL(b-$VVab6ICUg|2^XDkk4cY5 zI1fnP7>Zb*gOM+yYvjE&hO6HcTY25hEe%$<37jXGkr*A6aqSU03D(iR+4uy4XUXv! z^$Ih1XSp)1pTE3oU;j#my2;1Co9b4S&8c;lmg_atGu)kjor8zy?5YRE6~!GNT3SQT znJYheSLusU7~T{eG&218EKyVYRnTPDEXf5u`uvdV-w*AcD9+LP^-PREp{@6Gbu-5o zJ<)?#-C<*_;#OmOdEg(Lt)BP#N0Lc|dhg&4R@`G_9}LhbW3L6CYEHOM<$8FQABSC@ z*&7_$mv$(=pNmWTPA~@oo)@y}i0vf#sMnULWkt1h_bQ}^UKcVY6@`=dvobM7pQQ{p##9wxi69D<3o6aw`XwnwEeT_-c=^w zT*!r)7n=5b0{q)uo*+)g}@6L-#q6k+@<1nncdvT6|&Y)&5i!CeAPq zBgxsL?{j&~e1sX;zT@|mqWn0Ezgrm6WOKL+upmi8cR%Grk4;8xcz@x}04B!6L2Gs= zEnATxpUIIV05I3ZI^JCuz8LScLuP#+XliJ+xXKgx?=~f(<6g-71A7V{946ExNFiRn zsAN+#8Yq^~zpBry-$OoD+n1;?>f#Ou?s~Ujz3cBwfc@uh=}@<9u|C)Wzb2ju%<&Qe5CHt`iM3AS?pihr6z?p{e^ zUz5u>n~M__bOy*C62L+2)5;Uvp8F#Q-$U01H*Ys)dmLa+QS``XWKrcJ<#mGR9}^QZ zP@UxS$Shf6rr+`jPqq~9<9Iop6(8fue%RZ6EHTb9Sj!@oi+RU+m08^)fX2Oqt z0kSTMK*WR8m~+K?8=sw_Gp-xm;5s8|#N~1C*&C)Ph3W6$kv1uELpSszoPd>vRq4-b z2Ni>qbo;%t^liN;pl8evbs&OtADLeJDatas+CSHp;`Rea@UuU229+y>VH1v6HvJLk zGvlLm0q}f+XNLV5_1yCfo}Nv^ZPfI$&N8h<&;9ec!YAb%xGj1P0sk&2xT%SG?}3_S zDB|+mUJLPyjz#?J8l@-rM?=34e~Ga)`OQWF%aY+Gl5D44(+?UWn>0D;gE}s=0w=_x zxh;py`dw#v%kVu(N$Oo`ntgs{fPs1VNJN6&c&jJuSL>ga^0-F=_&KeTvR{wCoF~Ag zeEtR9g{MSz-$dub`}ouH8ZMU4N~xfv-(~=!XE!ac5WR0N!*?1H))B$))gIMCxSbb~ zTvf~h(#PxK96Nsbk6859_A|8OHap9c?)FRZidn@d zmRr+4E0AZt%!|@9#MgSf%sPTpc{IZowlpkpAjew(!5fO|mwQUM8ALyC9p0%b zCfsbN49mCYrI7)EwmJtH#6Zk-SLg{VGEH~>t>)kH_{WQ}Yyq!Q#C;7Hy7}#&!u>*h za7%S7!8bNo!Q_j_8-}v^r*6+CeSfpn?=|x~zXqjJ&xZ9|VAtLXulTol6wAe}_I}>4 z`$#MQj`aIOpNqDT1Z3PWGRZzhp=|#qgijLTKR{T=oNc%IGdlrF+uw*X^Cycta-R(V zX1GhuN~_i3dV5hWw7T;LPe?L%^Rns@UZd1vT%&TgNO?~`skWK#9>;#C1R;scZG^dR z?t6CXceE3Jw+?ZT{<;lEFMM1c{77v30+p=RtDt{Qk*Pn5_!ny%_;)Bm#~7kyKE@X6 z?alLCtjuJr4XcGmkpGF-Su&eVuo+HXRQpW6=GQYq5}w}A@Q|(Tj}JkFh6lw3Q@Hu| zl*2VyZ)h%IO(Q#oqyRhd{o%yb(t2QX_oZe$7C`31yrMWAkDciZGYg#!m+;$!~xYsV$_ z=mnpFl@K5#?0!!zT)n$tO1{CL>w8dLjQdY=`}nKgB=*L9Yj~buGkqDABW+z7y*bwI zb&mjVX2SE^XYdy2=oaVes>&KxtWbz~>@cyX#;1rx79E>9A2bVy8Lh(6k-IW7DJeQj zzn0MCOAr`z=Gx=)-m$I&7DT&<#?6LbUua(Q4Q6$s6vyQll9I_mq66X`xG??0i{S z(jH*OaaG%;hJ%eo)xXOC>!#!Vd5TN_6(}hh-J7niI+IGf$par%fA+LKc~md1^&XJ; zT4Q^AVs6P@i9~}}0NyG@8-kiQ5T3cq`V8A;X-)BA&Fe&j1D6*k z3Ra%gCv<*(I}; zw~%wsG3-)rhtDlnMuM4wcv77Ch>=Ae?_U@pW=OE_H(1%W4bM}-E3ub9=t0zq4ohdk zdz~^cR9&0(_K-@U-`9N&E9IXxPz2>+k?Y0GPG&_b3cN>~>D8Z)Gxq4+vcSoy@98Zv z@V*P$C<&ef0HNIl<2yF^BXgJAMkK+01a;Fp0StEUOisQS&bS-Ebwi1t3RwXM-4};o zF7lq6)ty>78H#d`iHD4a0E_V^^(Fu4bGB0@W?6{y1!8cI=v{aF%i0X^QEPJ9Jv{Ct z3(abGUJ9%XE{{Vp&K2Gb&Fb#LHRVFx$C1qTFy&}4#EK0mU9I8mV1P(5m1A31 zsFj!p@+%-2B8e*8p3g#o(#Z8;uO72_hGt2ksQM)_LKOrZc>d6)a)!D}_m{`g`HqeC zbGV-wN22m~fr2@iy%K%V%^rfaEg&2E+<#Pt6T>3;UM{8S9`j>qpgDyP``ux7KLa!| z2(WWF&Wq+HTlH0}`Ec@@&K0bw!fRa=EKoyuvd1F)jr z|B_=c>CFv&^L`OCbEkov&>djqU+PZ$9)fss!_xPx*Z#&Y&I6!WWR~QBR`uaZJke)D zEynpph+0ad2cY|hed3=D{+kA0Pvcoce8=2N&w;8@s)FSlb0)8UqN#1Wq$#DqE6dAC z73y4pY3b}VqZ2W+);Am7W82{ zO5hG5O$g*^vMhIuvxn2D?#JX7>-9Xuu@AMyU3Oy8yg+6C_>Oj=A(Vrf;IhC=;%FhZ zdcnGO9Rbp~-Y>=}`rP$MmqF~sX=Le}OVxJ4z5XoD2nP?!$B)|9@t%T|1wyCq&+`gu z2xdR&%8utt*)iKEzKicKO2Sma$KLtz_79(6no<9U!yiPBETbAIz?UAG-M%3?mk-gr zx?g@M8iutu@+zu}*r>NOCUgpd&iAZ8e9W=DH5PIk6c;G4FTDp>z?^!W`Rez1Pl|{O zT)K<3M??!Zj-M31V4r>v@8{Y`6-4L;~xPW^E2t zQY`2AvF_i#Y3DmUJ%r0P_4dl_COza&qR~$s%6y)jXX;N4ti4p7it$V^*28+tXEX6i z{p^?I9g*D%0$4!v$q6>7I37&ML^3EBLNu|{IF2ENT$zA0=5#y6U?yf!cO=M0?}?8w z!?LOx%3OoM`z`#q{c`Shdk1-WSh9m^4_8<-gMz(Jc2ycgd$=*DGs@n3-~ux1fFO!4 zzwhFSuTh3e;t-!NTQgeT5-(^(!d8eSpCO(+iSt*x7XyZ8x&LGqZ5sHbQ&&=|M)E?2 zKK%Y1R}*h}HKlKAJ3$brLf~EJ#3SMWe!|Wgj1@Ab+g1@tQul%Yr{qSv_>XN(_d~#HI?^dGOqJW<^W23!GoExi4AQ=H;r#Z8 zSm&^vP|5oDELG0yx;u($s|j`9h0rOv%oN3G(wC@#2X(jCku-YJcTmr|`eD}gv}P(f(=O}m^WZ@f3w{zKw@;#FV3(~un;vaCi7j=-)ZPnz3fh61*4O` z@6Q?U^RXzwxYg%%`;c=RAc$Yt4X;a!Pe}O=UBXnSU>)>z1yq347Kh;7B31R^Zgw|Z zF-o$kV~OnNVq|HJI8LG=-Zb6P$_8ZX7kv;k!82E&5cNZlYL(VZY^V>&FX-@7s%@u~R0~YStbonuI}bd0=%n zemxn{oW>(c#a{)gR;KWF<1MLqY;G{viAXnJ!@MQtOGB~J_rz29Aut@vP4|}t6J%JQ ztS-Rtgj%S$F~$wiOZ%ovWuK&s-+MF zZ!K!Q;zX(JTmAD)y(Z7Q%xju(pRLsWC}(54T-rHfR`w1%AQDK*28JBjJ^c36oZrtk zwAF^gJ6}Y0a1NVJn$}TpUtDcG83U?XA;S^5jx?0PwPAvA)+w~${JAX0oh z^XM0kevg@900564wof(6J|BN_|86e~lKrLZlx20_Xp%ke_cRs1pZ@$w4`&#d2H_Q$ z%BM#?q3!!psUQHIfw=kGyq(u;1v@P(P{$V~Ta#Z!p0@H2J(F0ok{2hJAPO4dQRm!$HG-#Sh?x1(Jn2$bx$h zyj1B^(b6Is3v%;E`q(cVwK9QvQ z{D_QC%g=o6uCjoO2D+{v3MuaKWF0vL*0Q6e6`#3dZhO?QgZ*V8T&YNDmY;S10r&hk z@>ISjLG3PPKUguKZ1U~S{na{R#fCrC@<)giDEAW5ebqx|D0Ni&B1^u__PriC`wtFW(asl&=!C1)2Rh_>7_gPwAVp3LP@k)oG2@ zf=0g)$h>Jx!U7C$lXQW;T$%$T5+66J%dU7;dUHYQ1y4faJf&)^qwp@sxcVjO%T`kCJ$(a?*09ta20Myz+9UUIH*v>cnpw##sxdDT7}5m{-6 zLj^dfvE2q$t~Ul#sRmugIPCdS?fPeJ)s4W3{d7&v$NPQ}raZ*Of~4?Yca4709wbZd zn$vsGaMHErXAFOl+gDecp4bJIa%LaAUwioDmeaSEv+VfAbGsL>JWli_WwJ!{ z+6=Dls|c)95_RX!Y}x#2(Y9tE%Jve<`AG*^R1@HsYgjDJbVy>zB1GaWw=Mf1d7B&s z9liOV<0i>)m8QBrJy~F@{hH}F?-wQj#JB8Oe}xFd>ZYTn!#-5|GfW@1^U)KheWQ1A zKHScPPGn?@yHsj{e62ozV>)zA!~;o&J*wfd&xZr@w-K0qzP(UQa6})bn#P}EAV}M- zfBPEqO_+Oup+TQZdZ=M1^72e0DbZwc>7=6QJE7*MYo$2LH(z`Iq;nOMa&NO2YEQr$h9Y5-% z_^*!~rpU|0Zw2FuRB~-riTLGl@R5G)?V%NpuSBQ^k)V}Fd&kX<5&YO~j|+d=2kh&_%JYvyPtGTQTP&V{VqI+X7lv5$pqR1B8(Jw|g6_4L9CC{( zE$6Xz`5u{T5!`g)=`eK@Miyy!(h2|-^-&nC^7eKw4RP8g66R6;eNY3`Go>qfUr`)nUz`~e4ko32KQ zkzO{15>4*3e}Cz^axdHAv#$5=S76q%Q9kXjYEv{fQ1FR-dUZp=@@P}1g9qlLs)4q+ zo-~orAEk&$9VC@tLh-{$Uj~E&{GlG<*fE2?)tnX`KAo~pf4|Y``5h6Y3oC5C@330w z0!TyfYF&ngU$xTdqa?3>V{k+6KnrKT9jRUIhD1B1jQfeZ%Ayz$ll^)@GLIv?W0U>E z@U!-#4^O|5nurDV9)r2GZBJpp*6!kud;CSw+}E*>H&nTxQN~JCTAN3^-!I-3qW2&U z^&FDwnLi^JesrsqdFf}c_H)G^FK-C7j0l{({eYPepXm;e)k|ZV=hY`kcF?8nxPNDj zDEKP8s3y?gZqD$sfAH9Wx??~3%{<|hwTVd@gt$*qM{i!ab=pTt-ry+QV=`agiby3- zDA{IuTGS8su#L6waFW;9`|q={pB0B*@oLTxGUl;zy$O8McZz1iB2%dJUY32`Tb%%R zcgYBSkr_q161WvUtT1m!g|p86@r~V#-{GZvlg(N&RY>1rIfP2E`wl-JNz>dTzE)qO ztMPzt7#*2@JPK|bINe~y%MG;ST1y`Nj~Kr_6IGn%$8b4&z286Fa+Z|=-+|oa&R^4& zC2l;J=V$4BcmiybwBj*h*SLCNXH}udXzc=9xeB8DqiAaqvAEo?S#=@uRI*c8&L#%G zohBB5Slq30t5kOX3Co8GV+-#I!=o{Ke)at`3BO>0w}E{Ie)HY5FBl2$>w*32W{+@5 zj$i5_x-i8}D!zSivweUb>ixUufWwv7lqC;yGCBKTaT?|PrNK4+7{`v6$~5$%pCL_j z;|bug%m`zEipXWeyP|I%NGO{8YbTLVf|`SS>BFqLL-UMse!qA!zWUUKJehVm1;*bZ z*GyS+Djg&r@McC=rX_g+5<*S$CY*VHczHZ?nK<5d0dg1KG!6619&NghJGWo+_G8L# zt@r$0-L-#g+4*GAwC2Sml8P9T6>I4waO6>D9r2Icz65lv;biA_(XfC<3ts`u4kLOFtidzxn&cJXONN z0PYH7fzx9->NY5b_w!kyzV2b(CziQpo)@&t%Zuy%Ms$-Nl#dUG2s~BN(E0EC`Neu; za#p|S1#RFm1!vMKa;r&l_V-CtJHlOc#bcibhJdUSi=iLZHx_piMG-dph`xr)hX;AB zsZ#+W%-gM{B)6G6`~@dM;TVCGYV`G!=6oHgaNq&j(CB1G}QC0x6Aa0-%qXrJ2;VYBSLzo7^+#1SQA|gO}Id%t&eo{WKn~$6#5467~b$r1_Xtr4mpw|DIlx z?<;j^BFZ2k2&F!HpzTrjERg4de7;5Bjg=&}1xO{$Gv;%>&js`J{TN&XlF>Stj-9{3 zN$-w^DLYAZBtSPkD!1y9H5j!dz5DG~#P`M`Yj9`|D?Fz^_Ra1SDhT#rF+XrE|ENul zD7@De0ndSj?H-tGE9|WMKNkAocAARO9DH;X=qMXy*dvTD)i||+KpL6h1|O3G(h#I7 z(XyeB=jwW%&#;8ZUeE7+l4aleewRb`C|6M-Xaf6(xc`_xMj4TgdJv@x86lr*(c#<5`;528PQ7(b?*3fqX2~((9sKJC0qrx2bOD$>=k33LG z&zs@%ak0%ld8!PiBI)Bi)JumM`;-Hz#H~iSM+`1{hP+WYxjw@*aY5dHK0+1K()PiP zxJj07y@=%c(4!TD)O?!G=c@$M=qH|+)|E!HcjBx0=AN%Qf1HU|^wUa5Rwq7%)q|&J z>B+Z6b>J20R$x&Afo3kc*{w?g{^E$E#+45yByd0%x`21V_z~FS2R9Gi{@xr1sozZF zfCBfPWm`OzcJaRE2_`=D67J(juA*S`W1SkSQ}*IkC*j=iiFl0+M+Vv=xiH~l7VJ1t z0LO{tObD#!@6mM~4Cy43aSqK}UGAh6o!at{d{_18p5!#YXNWuW$K*b`#msY9U8xAJ;oKuJ9Yh?Oe=b|Fgi*HB|g~W_fAE^t$Uey5WOF_ zJt?}{8Lgz4O3(2g6Q&S@QB~d4J}2_955rs2b0=xP*OxcJ zlG))Iwr}eawEKPRR-6wXF_y5;w~;(|-gjORMpbkVkU$-utD&l$?X!_K*DZSC!pPW&TCj zrO}tOce@$e&+qsi2yy}1zu5Wi&_`yVszw2h8#}Fu%kX4}d3s zcwm^5fk&;$=ToTS430ub%U-*+T5W2{S+4>hKFjlS<431AoP_st57IWZ=G_Col77_K z%m+Pd6POY@=2eGM1xT*H@{(4(w$-u+xfk9feVUY;&hq%K_pg0k+PfPu;wOOlmDBV_ z=(XDM`~ke@dNEJ(=?!Lect($2sQ<>j$;QpO(vRoDpooRpZ{{ysQBY9bZYSZETRDR! z25v;mIl7mr+7}+hiIAxFBy#(>)y?aA9?DNfBlS-(0D!Kxei$Zu)>zFrLX(k;_fp=^ zJLvgXj{eYw(|v&sIn;`{$E(ts^G~tu_E8}v_tla}0cmz5JdO13G)weVNA77J7%{n! zV{G}_eH#2Lpy^;z1oDQ_OqDSiUb@u#-{FYAvT^IWW`|YABnr4!x?dHZO zynQ*OBF9@y>$a3Tb{Qp)$soh16?PVN&N@AABaf{$9O; zPKQ2>?_>gYUTuN^>2m1X&Zn@RfibzmRB+9b-}DSe{gKe!7@hyLAHKUGAj5uj4Jmt= z9O9@3Vpqh-AmYp}taV<+gOuN`cX2Pq@mI&c)5#jPeergHH~qx;)!|RRdqJEaEyDAC z?Oa=*DCz(M82rRvAG!fNQ2!1= zNM}4x%}%=g@>W!){VwHA4EJ(Z z-ZOcE=cw#yJ5hU_R{LpP0Sm)&HPTM|3Q;7&u&m)R1-e!u$zdFy zse8GFE)86ODZrbh{GNu`KgMnv#Fl@?a36>Q0PDmfui_el=Me^D^wsCP{ry5fX-Zm46ObAH8UY-0gaI z5VG_!#JBh0D0^$7?0v~{$)I2yoI>F``}}#?a(80*7Rs0(v-np1J{^AR$;q=Nc4}>m zD*;z6WCf2of9s=uG0uU%e+upOVI(S@YZ{#s-dV)nCm4ggK6yi_--QilW4{JY*TMq{ z5S_C(MY(}$7(Th$e)9lV6)y2TGkTA$I133t7A%mft&08_-8>0ZvP4`$RjKyq6at=o z)<9VVcu4X6wANlEM;R{-w4r9D);_TNz?quV;yYA5SvF)dge-e%7Ptv}T)qIRx@_=Q zIlUiTd&o^&{=PcXAfi$bzV?k{T6Q@5@L-0sG~Nh5zhWlnkbRJq(Q-G=W=68K*;jvM zY>&AYm2pz2c;B}ARQ$25qoXa0wK*zF07~4QuXMf+d95c;V6z;YPlncr2=$${D=qPa zV%94e&^1g#ZS{i2_#W4D=*=i7rrpOEmV&mhZ}I?J7-NImREV#rO+d-UCsk-OG^o@b z&6f9pwr^3JCM(8x<{Osnx zaMgsf*ET1`zB9}7M13q4-PYW;jrrL0UY0;_pooK`fEOsA%CiZD(zb}4hADc?3H6@*O<;vX0Dg8bJ3KC zF)HRgz$X;$)!>@`}->@^BjE+jTchQcm|k*+*e6r=gSkI>)SqdEfUWwBOHZ4@sy^AMt!V zm0yZ)u}nL|V)F2LZ;&gN_0=&)r^Iuz_a5UrIJl@2chgZrY#!}vv{NLZA z=hRbO_SUaKkM@!x$hLnfz)3Ft5wBvyer(YFU-UnLOuR8^@+t>^|PqyOj;R& zUV9$veu&1&TlR2Ufl552;Lmdik*335Ydc@?sRW~24YXzZ4U!&wQL>)5pzdDJX2|m6oSVa$DVE-Vd`Xx%gH#6F0zjipP$Nwd$fBaRZqoKf2zmg&y z>+?lR&Dt^Fc4lSdeZIJ_-$5pEQstL>VUddZPXqrwK&hr;qqKHnv6S5AfIptv?IEA0 zxTeGXekaUSkfwJCZuwKT{rxJ>_5Jj9sVhR{v1G$gz>2bhtrhnQ?!n`p<*?G`~>WNnKEdAkG@%T?!|gOf3!He?mMW}`#h})_k~W`=xnP@qQV%> zh`H|T8_HbpQg}ua{1u8zbqPKNY9xmX^9YT^L_0HTZRkHeeJ}NI zS)cajvT%~FT)lN<*G~Qdml@2L(^~?4ZhGf8a(npBA@99k_+or{|0eVg3(^9VF+GpA z)~Ob*5xYHoD7E%QPm+nRE+q6nC2IO+jQY5TXh|HO&NwM@a5ksIh>o`BJ}sdF{<6~s zY0mlnWOHQvunT>^Gkz1jTrQ+AZwc$bDDj(F!4P+}d0?oCFXN5{9`4$!=iyJI`Q>jo zeR3g{=xl1>k9 z9g(>5Sm|fb$Bls(bD}=-V(Q{eX)HrJ=V;i?%1TLy1c^Br-C;9d@lf3*B-4%{mG zL76mscfTT5T;c7c7JE1}8o)(Y;HGQ*K+xm~BD_d3*2%^6v zJ3NXA3J8d-zOjP>%8q<}4mVY)RL$+Ky*(Q|0{QO3b?ubq%6-m;-;e2ktZhEdX6}EB zc}AI0KdV<0z-z09R|KkBw;G(w>eZ4|KCEq`i}bLkGyzpO>-U@!#$)1P&E!eGaelaX zC4ma~vJlKkdnyncneu$E3rO6TFo{wG7y+y`_?ek zDP)H;yy=?>r9K=*eq#3wYk>?fj*D7s`fh?QEAJ(vk{Ss0ihM))zBD8SIgF!;KP{Xo z^c5R2{?k$gQD&h4p)L*|;h4?_<&-mQS3 z?EP`?+(8c>qxBqNcdp(z&l(5ja!zFHkyo!Z=>@stAt-EM%8Lc}V*Xf-?|sEs{r$7; zadAFf%tI(hGw(-FMu9WCT%`f9ADwuHB%4$1o-TiuV6|(_h;rFQ?KkMY&y-_9Qa*X7 zqBv6nDP3B^aQ0hoY{yq|j)wx}AV=AA{+HYRX<>y_b^*A#bBt4;a>O$Nq;yo9ghi>t zW!_`JKlx(O_InOpIJ@%QaLex2?@xZ6;Edu`>2y`n&sSYepqPvI5QZ}?)?#u#)ra@f z4)NB*>3DDs9ZjDXJX>+4TxuTD{i$g(o{;>8n8otF3@ACEyl8!evP+=F#-83l+np7y61WAeZf5pk&@rFpH6mIGP;Zz54Uw)~D-wqNroZ$Ql zEc(j^*o|uzj>ob!P}NO z!&|<5KCV}0-vp8G8+zy7QS|LUrQ3_Co_J$ytO`r9etv$E?{_lpUtU*|IR$?(%(Kmt zN;?ivFnbwwdtBK)5E(b8{z~b-S{ebg(I;u#^C(_z-aJK9*Sf-TCV$4~IlipXV$2IK zN0s@t#vS7i}*(Ghrb)A_~j7jdA5K0~k zhUee?4%)@n!j_rS-yo9PuZwPe4sXo7pD`nSU^|Mw4{vD!xobb2={|x@beC(w*T6RZ ztatsD@&88{!@cf|Qd{~0*H8s?j2{6pEg%>RZ2q{F^3D&idA_gy@tjLt(VHJ1moNY3 zz`z;%@^}YGi2E~+1NbIB3Z-xp?Px}k$p965d49jK+OijW;b#hVL#N~C-U)3HFk|L= z&&+*dqv-|k-w5Ag>qjJpxCry!XkVx2Jpq8qH~}HIv!s+4ul~R*P>&gQi3sVw80p|S z!M>Wdr_&cRAps@$QgxGggmUbi#S1wBi;p@cJvPG4BaGwvhvrJQSV41ZQ@KXf$|8OH%VZTT>VMH`N}ICuLJCgzy}VZuaI zPNxOl?mQfT26rzm*7*YtyO~=L0$;`Udja82kL`2!$p!b&@l5aQs?$6!x6057MsPU~ zQOc{-9P6#zqMX0VfH%L>%f<|z?^QqJXaHyW4MAj*V`hpzucLc!&Dx=_>W6Qjc^32a z$JlU2z2Accw9zkZoPhoue;*fV4;(iDLSiTxZRRCJ>#)LqJ@(l(1Qj|MfPkV9SI>Gq zvn{hiBiK1u&p(_izg_vq`TOC}JiP_`n&Rg6DWmYi{=h}*PG=@$HT`{5mHr>I`*nch zUV0!yZe)y!O1|>ER&QXOu3huKrnHP8E5A?hQf=*Ar|Hx1+vu~Zt_Lf;kYC8a_Q!xz z+j$bC^DngFOL#adH~U)d**+VOh?y&_mq_~nd63)hEB3Sg+HE0x%{82Ikf08n6w*~M z-}`ntNp>lb`3Q{qS%-H_|7<3T`N{VYNHb(bl6J^sK^0%0doD9c3S1hepV1`2_Y;K6 z9vfjn81LUudl*!hx=iJ!kLLut6ksx2@JFJ{F4|W1B>=g$BivvqrKTxGzJFXLPUnuM z%s9w9oMC=Yb4r2|vnh>}ISMAWs0_%T#96xuPh9Vwm|wxhNPTV0F3F@pb4bdsuh1m8 z_lMU3U$~*zY31Tbz*Wj>ePyqYqNtQ%YsU|c6TB3pVbR>3zr3{U;rTC%kmbfC9LrSW zlGLnv5>R^0X70q}p!{1NrA;5l{xzo7Jh{Z|DBArk@B@gekZQ$66`wB=gC)KX^Cx>^ z7m`0?O%=nESSVqfp1ugI4hhlhdC{pz<*v;l3rGl9TSP_;zx3 z-v5@2`09;}*NH~ONpO;?`_6oTDMcq_H^7aqS`B}E!?cKGs26`f)agtOHB9bnyD?RL zUoh_99$Vl_edzE2UH5!X*TECRuBtU|R|Rl6&l5xH&f#*N;)7Mf>TCB~-F<*}0q6^i z`+XVA!hw=Px!ec3IykrNdJ%8@L(!h@RRvAmd280wy#Tdw7Sx>IH$|Aeuuy(^3enZc z@$PhSyw`N2a>u^?!mx@H3sawy@@7w1n9G4=WsXH_p1CzUo#d@X zhsS>J>#Sg0Lr?Y|v$+R!;%eLalTH}b!Ed=Asup=X%Y^$Pn0=5zmED$NHzp^5n6*3J zueK+SN)}Xs7JVO*T*$z=>I<7KhNYp9s)S~!j{N6DhSLm~JxP6fO0~>NBjekcf5QE= zROq-uzTLCHVy|>QKfJGa3(co_zx$shA^xC)8gZmADQhH;s$#ar8kJoK z0AB)e_%{ddTBBj_#Hl~P@Xkgp-&ddeltZ5jauA;T#?Y0Yc7HQWCZs1nvOWW&awObv zFO!_r_e%mYGh;vIOW%Z=WV(9}a6}?1zK?SX5V6@;wijLQhWGs5tjQl+&ynJDpOyv( zv2MR}wTbx%(og@;>^44ccx!U_CKK_b?F&yr>U)T2hKt*q=s?}}+W*O%-Uws=5EaUn zpI9-7fK>QyF2hqb=H9&A4#h}B74w7=J8Wt`8ZWl2DtJfw1kzHjZsQ~5qjrE70?uN= zDDU=$CJS|Bq~WQd5vjq#S-psg+efV7c%7Nv+CLRCs?!IhV3fAFKR*}aBcV@?udJS7 z!~s(|Zm$`j1pHyqmNXfVb`ztLXm=li3>_unWj`SFHs~gXf$`-}KTUHT@aI?SYTcks zSt<$fI&9Sj!};T=3Nw)@5+3KX)zi7yLRPx`fNO?D!(+eIm+b-I4+OmBe)QH$c3JK7 z45m???NtlWkhubf1(uQ3-Ggs8%D!vMb;EY`k$cgQ8Ml2AKj)8AnBudPK-yIV#i_vN zk{ko(L*wmy;=L?3*&}?GlqtXC6ib(10&+{vZ|hFHy>BzO87jEFzI*11S?2fKCCH9+ z?FVPmPd;Pg||bpYJj+F9gD*k-o&`4)PzwIQ=a@q|5f; zB?=g1T*g%rLTGCwC9c%3=Ud(hl3TI7o>;I!72B(lRRyPe#`JZ_Ger$>5!{+C64 z<+l>HYvV&BpNtoE*8?ML5OF-C!gcdi3I0ZVGP&;)k1%72&)vbF4%mcKmHoO>eX}pH z()Dw^&*eUEOLQ{_-i?{3+qqA#{gc_`UTu)x9HrpCA)tgM(MB!r$6ZK(sH@zXGS(kj z`g))f5)*qa&B5CGoZ^Q%go-rw*x+g5bF?3)%Gm}D6R)K*k8e?(xaaUK$}eZ_N-tsZ zASE(p-{qxq3U-LVd70QKZ4+oo19UU{2Ne#Iay|^x$0}a*&)n1TG3CmSU1Btx6@Ar% zJu2sgj63pt2Mi)WIJ##3v*xyL*G~8i0rfZw@yX;!jmgQck0c_mVZFrP`Yjrt*v)sF zjgz=Y{DtR~)3)QGBNuIbHhng%+oG$)A?I_!Q_>#fr5X1LbVqUKhK`Xf1B+MmHsp}A z+tX+~`ZZ{yNzCGL-@U(5lQ!Ko;=9DS9kxL_6(_ZG51e}ZidBFxpOSTg9N2OU^+IN+mHC0a67j z3k(aMC0166D89^ugd`sNutG=@GWRs)*BbQ&OUKy3-(pk-Q$z(qR4*6c5p8wfe|&+w zUE_Uytnl2{{CSt)JtoC|?owh4Rfa7gPK)kojcuQ-ytpEMiy0c{XzFYVp#%H%Y3#@gS-m3u3hH_}{j+k8M&reXf@mZn3AYX$0 z+3r7x6!)1tS$=EzTPj#>B*EHWXq1JIEodI|p}3ctj&^+0HtSV+94{9IDJ7ax)OwSD z7sdE^t6Qtp6ap8_C})rE|Dwo?i9)MeTeo|PO)w#r4p_BCG_Nb@J8923 z*gur7yi-(3!dsWCFmU<3^1BXf4UR|w9ukU~#IZm`76WHLnrdQo&9SJ82e(Y0WywCC zI)oI4leLlOVX5LPSF5S1vCUPi-Xt>D&t*bNgG#i%s>vR062{_WX@4vSc(jK5`1noz zFyR}C5_}YtfaosHjP1CQzpm&nd3@0488W$(k>~vA(FfI0GbRZR6+`IUG?`NCg;I&V zwE&@#k!Pvyk&oPCvp}5dqdOn#~^=LZj1?xzoTE}e(iHKH41 zpPw&3lnS8k`O%M+PlMQ=Q_%St4p8@JzQ*gI-^VXx<8X{av(O^BbeR5>U`wqGy2b5d z$Xam&()$akHna^Od!G`Va}D}6p0DaW%!*i*Qj&_dEIkO)$(y~PFj?YQ2|)p&@b%Fk zc@zO0c(Z)2tZsWB1^b0Yad&IsN(}j}x2et2ofaTb`JqNUPB}WzoihTSG7>&eo(+V5aZ6bc6F(IjfNFmDZRn2fo2DqzcjR2EQn1>^!Cu*flU>N8jyjcm_)PlO-oMd}iWq79PNtn4X^F>cA)W43D!Cj$7m=5K-)=e{S4uO2 z)t>Vy!f=tNlPi3vsQ{)7Sej_}2NYdC--j`xVMR$fyas2Ud{KLfSOziN6@z`LwxBfH z?+e6BKc$)v$y3)xCMVzhJr=#$OKF}YkUL%GAhriRgzRcPeBcbsg6D2qm-$y%`+0t; zsr2i5-;*}}fZ+ot1=dMITXfZeeCmtj&5yc6IEz7rqbqY!s1=}1X5xPnOJ64d^wgf1 z4O|N>iRb8=o96y46m4HIb2<(Z-yzUST(8Jqxk$P&c44M=e2JF@FqaMab5SQH(wK8- zFiN~{S&W-hSd7_qLS2^~%b3Me5{omS@n}^+j5E%ybdAm=|W1*E2r3 zI7QN9-&l~1DQo71g)dBN6-sYfn~J6U!a$nDb&XR#I$^uQJ`vm0*FoaqO}P(=Uw@C< zrX&fMaTiW|aw7Mh_efg~9sf=CStMm)?SqL=EJp>#;77FidkrX$1elqDVdv`cYuWs8 z-ox7KuzN(xYT>IuzwqC)Y&=J|WkRnU;bM;?@FxXEdE6d_?~X!TX8fZk(~*8r{Ty~0 zI9b3p1NuVla%3WZsv8S#$nqb0^vZ)lb#-n%{hHN%iup94wqe`=YX-S581(S{c7x!&{AM3A%*ItA zOg1F8+}aA{%!C7Li>^&NvaeaCRF;GrsU(YG<^$t%LFBIxwq@TIQU=0c9 zR!M_&;M2Ia?bkDc+vo4Tr%C>!G~i;)$v6L*WvsKpFj#tnz+rEjSW@Pf3cE?@_y)r5 zPW#Zai^_b5CA4F8!MCg|#ycgA`OD^ny{Dn{?ME(*g^O^(t9M=UUywIBp(wDJ7Wd<& zZ+V7#=)Q@|=*;%@2#W0~?xCnu@0zfHxqpiiiF+ph<^lKe`VIEU(ftYtdnOw+ zLp~*M5DXy0KAp~3j&G>a{f1Ng9J$Wq3GSfyk7Ruv+Y60EnZTw;MsdM9J&CSm(hlSE z4?_^o6QNR3PsQKM>|s)C62-oK-*YZ2xHBK!!S#u+XKPWgASXX53i5VIo#**=( z=P9C*(Ltqwrc;Sveu40sz>z*T0*TBhUiNK8Z>v)X7Gd~qM3JBvfc=@aJ zkZ!3!%Ycy9De|)WUZ8@uAC4ySXU-B-1nZI-1vCq})fPrj2cscL*iu@VoW*E(A+^yN zmV=Y6&^``hW;PFQ#3WT)`jOT}W7)UQnJ?1v`U)M~W>BNLH(V{mM38M5ArOq~cLmpvxdb$#tIZIqcaTztm^npt$l}29EsGl2dlI(n*Y4IJ32Kqmtbr+-S>Ki;2e)Da; zoo4Om32vZ9$8ULR9{Z+Yh)4kly@^Y=Zya}0BQ**Dwl_QT#m7u?dIR?bhl>gS(bP@K3=qMUZsZ1wn5t#`BqFz^gTgc(%;~h z`07&?2<11i3AM^4228Y8SbKJ``L*ghu;yOpzm71cctA+vV0Bl3aOc?DC$s@n2pt>~ zU3W|nhW)U2Jw990-}O5#hX-L%3YM1t7lS1lSM%E-ns~d|5**=wKthXWhjE=H_pK<< z9Igz6;F!~(R#esPVdwPm&==fv7h;?Q3FN-!-YBfk`@}sThUa;!=+9{Sb`vb=cWnN4 z(pdybxfZQs4;^TzPA^;V;#COC?ykYRdRkQ2&HCES83)Zj>VZvxNM0B>;PCnMe(;)= z8GKx~sDC5tP@S}?X4m~w>&CVcIPdh&_OA*i@yATzUi-dqKpG&k$J-5ig9ioouI2q` zQSVs*4IuOBh_eyoXEexZgtq@BO$^=o0;Z2DNecKLs>j7twkXk=F{tnfPmF1;k0r zkfUAf^)xpqq8?xDrTKzM{jAnt4a(tdQhN-BE<@7(-RXw|kKB{GeGbBS*H7{{eL810 zY3!~!T*uVEO!-gC^xu{6=h>a~a?y-O48Og@>0{3_e``MXsGo^X0pZpncb$D^67K>f ztEpVb{>ca53rR7L8$3(|NHTSPujc>;|Hu>IZc47(>+P4%^2>M*8nM0I4omO;&@V_x zI^2!|k|2s!k7)>FdE8w2&wu7h9^n9fv0fT-)lE z@MHGHg|x?dcfs&pn-xu*Va{~LWZJY<<_kD7E#_NirR%@K$ZU@{q+tUK3tZTp+fi(| zn->1S;;mjrc%y0-)ssUftnVCUkh%)Ato`{DhijnaoNZ@f&7Q`b$o%ea-_2p5{**0u(sNYUaH6t@`ws zl1}xE)loVaq<}aTdQAL^7Kp+etkHfn{Q3Oj+S|v+<|ocg3BF@Fp$-_iVzjvI>rY=p zszoRmx}2N;np8MzAIp1*oaC4}X(CF<-azjAv#u7FHiqwwKg^T3tQ*-0m@ z=Ybjm;J#X}1R^#q5V#_eBboT-;4=6+#c&m2kcM9(u_^K)|4H-$x7ly0=T@3`~Fd~=@fPnkydbl-bS%5MX-)X)2)XR{r&Sj+pp zNsa10o1nS)+B5Zt=d$NUPD()F8g}da(}u7PrQ5`QW|z}%ulwvhHU`3wFW3%VJYu?$ z^sC0p=C#{Srl8jkJG|)SzN==*gX@Wufz*{#QtNWjK|YLOvaOtWND$ynR#ChH9C`m? zLpR&L!%r+nwJhh#o0HT-|1##W{%-kK6m%2xx3keM=95gf?yH?bcV8i8*`nXK+9QTj zZk}eAg7k2%Q)hwWqhGxTW1XayiK!Lv(u>v+jJXj+N3Ac#w0p|ruLJd zjKz3@zwoDW60 zF8G2UBR@DQEWCY_5Ip90oP_3Aku%ws8C9=VOB>%FHVAlIEJqq!+agvwnRpt1m$}wp zG>-!UyXgJS>Y;r%ml(EjZ#Vf1XFbN<_f5@wH4&nXm|8d;KTHaf?IYTTyus z+Grfr97chBUk-=NZREkx0{bq9KmP>$)!tqg=O#i>P>Amj&;(|$5GB6w70L1Z?#K6@ zW*`!vvKeG)_z97+iF^q4{$GnDQ+XFSluzxa43s^&?XkSxE2vGGG1<{*o#4iq(4&se zkRP!3RE0nL4HUo9nSB}*4Lonu50thK#Z_tTI2o9+QuU8?esQV?5f*tIo1j5wOASaU zhYll&L(7~;?e5Fv?>T<2*Fc|~2F$~(hz1wJ+gm63z~`KTLv+B=?AfZC50Tu@^W}c? zer)qM^3j$*gV?*hf#&K7AA;q~bEKK+aSZJ$*}qq`UF|%B=SfO(=nG<LnD(D}k>osyk~|u9HT&U_e}2)?%%2ab#?!DP0spnAD1t1mZQ~)Y>$ddig4uFVBg)!L2aLIv>t#f_d0yW z3H4^ydN})6^5QFbCVhIJiA1p#<8}s67g*lMPsvLe7{SP)V)h1!h7WgvghC$$i9TiK z`%$a5{Zqe&a|{eA3Jy7B=RsxK1oeA@M(omek5z+1f}h5>`Ezmiy@TMLS@SL49^(Vl zinrSeRCr}p%X74wmMZqyr*P_*kf0lmmMlxH;kCDO`MqmJEF z$yVzS-PFUh-#zA~e9XTbCJJDQ5?1n4X))Of2$Ef0l|&c%82oS~&Zwl~>6Kk4{dUm7 z1cC(lg{FCaQmEP^vH9fr+ts>$igcZ)=WjI&zd5D=(7a)0xG`1Kce!E5(R z$kBX@iq=VkT}$7-p*m7s2;caF+`m7Cc6OfoP_Zr|OI=Rp1YWp2dF`CN`%EtH7Kb7| zP!%}Ykquw;mde}ecaJc7);j&WouF4a5KrnF@D_PLf+?QTxM?|r$>yu{A^ z>F$keo!I?l|1=m_iPz6JrJ=E_8tGBtV(7@v4-tDQ%k<9a0%?(+Ao4Om^DWrN*_2<` zTL6FA=KCOfNS_KWP&_=WJ32&vI?~Z%))-;%62~bk- z(|jHJ&9{kw{0|vs^o1eLwx6E&&Fp4?obu=cJVe~-QFxIlNf=9acVhmB~pr#^j-@jec_CtYfQaTkZj3i7mGOH*L z^6$6~sXU3tL2tpqm%g;p5QIN50fNMScf!+&4wY&BbECU*FmCtwD4){i=sMKCoWk1T z^udAbus@!YCFjyj|FEynJ#uY#I0<~z$bbs^?e7ss8_(!pE`#K|QYV(ym(OgZVc@do zcx68xDE0R7IcLII0iroe@k{d%Kj?D4tI`X zD%o=a{kg(lsq6N&z9-pei5{7Je!lk@BF6eac=f(-B!fgXP&xJa99lG_lUIW2eJLq9 zADyKhBuqy6>@hIVe%wIuybs5bGw-CMv-|$wu|KvRTm|A$j{ruYtV+4>`%|*Ax!lL+ z<<;r&pVMJFWqw&eQs|yclM`Qr)5Y~hpELXWw=A#wZFx!g(kQ=u(x~Suvx)u)OI(I@ z_B0@SpGZ&Q+CLAV75_0)@1f3OY41rx#jwW-W{3U(ct|dn6Lb6}gBUU2Ix=vs# z(qooC@R50+KSErqXu~FtA5G&DE7liSEIoSOZmUR~4gg7ms$c_Ya(2#BSA}&qj6+w~9}IxRlsHHPFXkv_03E9N8!AD0BT_kvaoJZckRA zQi7Lceg50y;m~2rm)4eZz9xXSoM~zk~>@M%QvANxT4K<~Q?!`KM9C+C_1G%KhV1 zMMw2{5BEa2@CujT4<-odmK%O|ay?omN0v1kWq@%w4eZ;~xShd!J_>0_|4xqtKbnCy+#h3Ay{;6!|9Bmalu3>}K+)ATdTqv)ZqOxm ztxx;ZSSo?oTm9aC)lFusa@vYH12#*he1lw6^~`?J0;I92rwu=M{M+&>T>4cAkGi@l zFy6IBYJQftkrN7wvjwXhA|TiCMTBY(d?F!JWjR1=je5+%KAVhVn$L7dF);4*OzDq%HQP`?|THDzLw${=ASz%N1)t zTJ$H~vMKCnr^hGBCmvR;2HG_Zdda6M~HVMpcC(0~G1Hzp(g{ubS@T z0$L}oB!&^&nN!?zmLsf7@Q542-ygv>5%L3BY|QD6>XRr&Al!Y7@1s9nTy(z7@zEtU z7?0Uuk3chV+k!L;j)289DP6h8)`7dv4FzNL7%m&aFY`f!h`N)(r%SGS71E&y(q!9XDfd; zSL6oo)+3G`$1G49>y{e$;JRDsJw(TW^96@f~{+^H3G3|W@)QB49MVW1Ihau-^;<_G> zzn^n{)jxM~);yU;f{$k3+GC|n6-9Ya&SeZv?Nxo&eB@uBKHMSB2p)19zGd%T-;(4D zfwKoTtJ{kI21l`IY<_8Bl5H^&D{UvBnx)_GdZ<)Zhc86BX6$Kt!CU>BfnYD_rz*bz z)BGiqOL>dvI}!ikSB6*C;p;Ccj5`QMKV%m3`OumEbS8n={TRiRVUfUnKnAPM`KjRt&Gn9Nf9K;wltB(Z{ z1^{^PqKF!Q{NM|y5Ca9qW_q~K$OF-6a4JbPVOs4&c;1(#w{>$`>jU;+OHJx1Z==y0%X^zcX~iYDlh*YROr3(ZrOK(qK0!y)F^{SNI5F#L1%s=;#Xh#E3c*lh`;b~|JY zw#72Zw_Lc%6&O3){WYVpaZzzU&o0jOqyS_yi4^T?MUY$h07urBWCzst+|gK~j7ZJR zceh*~zPFFog!qB3z9&-c>3T7>4#?H2TG&|-(P$4{{iTsghnM5WKG4R-Y}qv`iGtam zZqp^F84h%saUCl3n5m;nJn-@ zDyY51cQ|V~ua+Uh@u($#YL8~`rOYdahF+#HThwk!2L9zx#kC><@PHCVIxx+AhC=pq zJl0Zr9EY5dz}BQvp+ol`v}AzZvn?zMzP*4XiXDUGqHT;FhHR+&Q`?98;ow6PVeStz z>OAp4acjanRU1ZEo}MR6D_AhBQ8@@M9`^_FCfPMRL(X7%7=#|Jvg8b}N^RTgv2PW| zo8s!8P6n)^aen-vr7m@zznr&KfE4x#D9n3GMxqCtAL>1d;*S;dKb|C6K~?2*M!X{W(# z#E|vvv74l6h0#mYO)~7oXT)mG^Zhp)Dxl>%aj#FQ+4u!Hn!(LR>D+2Y4Ll z5%Qx;*vHp}J%0C3T~h6y@A|dRPW9CZs&&eT4lg&xj%eh^*_UDpNu#B_(RRNs!H-qy zb0wH5etfLl$*;k~lPmX4W{%xnis4f6`=$4!AMT6IOaQoP1m}mo4@ENo;?1qP@RAVG z$K;#aiz3=t81Wj}PkXjtAj`n}hPf}+`#xGf7jza!3d+^^p z5rwr^ZlWI;?F`@J=Y#3!x$yi*^m^t`>O9{*vkMXJz2W*QkdnN~7(coSFflSn6XAZ1 zCl(8_82#OkFdytQr>_(^L*$LiZbvD;Kj5Vv3Kgw>zqIgD4#2u6I{+mGSHXK-$-6kV zGy`op-eabpQ0of}>zI{JoLOgfHxJo}!m|Gr9h77s^&-9B+#tirmbzb!Tm6zcp^v)g za1~zJtay9yW@dUbE2d8?|id3uGtEAz-f#4K(AAP$s{t0+{+XJU-wLhFOgC9pt zb|+tqbookOYjw?Dq3-;`wTGO4d+#FeWNU0ZZ+8`*+c&h?a=*$EZ$B0`XZEajHg&07 zwIsUR%RTt;CF&2Ppde1l`!1;0+Mis?0cWJ-(j21@ORku__b8m#^ZU2U|87KHs9Tbg z&Gk8anI;9J<_SU0@oK%{I;0xgwC=O;s5mBea5{=0V3AMhHF!=CXIs*!&o2!cI$?8( zmMzkueaVYZjO!#)GkzKZvI%lZD9f+-AzY$GE=!KCbN(a~{rVkJPAQN%g`&O?wI8LRM zkt8KvZx%==`DkBGf&K)0I*(u`ap?QNCG)e3mQo4cjl|+^W+T1|pCj^Z-CCdDYoxGgRI-FO( zfHA=hfc^@p=hbVOo}Z<3ilnnq&!5*BeSNZZ!KPy8eM~`(9)IH;!T1FmM&@H1 z&vxNR;`b98dP3hhtEZ17oXhHU@FmV0^F1j3E>rcB?)t+~E=L71_SJKFRYnkMtUyt} z9+6$Xh1Bkz>K;@_Gw=hH&Yt4Vb`&biD-Ugt6A(yFU{7}<)!|Q&VtXxe(6ixEf2_Ok z>Qo1sU+Y99tm&3T7z^lUr^S-Z1BI$L-}aEX5_Fe1%8O9kR_H_WLG9({o>aaM1LXj~ zv`XKQ<=oeI^2SMP8g$VAVUi)dgJ;3GST zli2KoKMXjlWf2Bac7EjzVcAUj$GvX98{|KvFloMtr+eGwL4q-k(c+mC`_|4(cBN-Z z6V154ztXeR9YG?cTSC-MAm}i#LOY$_nG!w^w^h-K;PTjWHhSM%JWfGYvldbzwLH*o zb3R<4On1umiAF262Bw&GtI=U`o~gFDJV#VesMu10ak8o=i*`yM7a`YYaXr=MeS^am z&N}&J_04?l)ljkmy`|#ikvHS zq@ynHPPn{9!7{D|^OnAn@MX#f_NQN}YHJAIMb<2u`6LegM%$H(B=t{NCO)(VUVttXAzEVNWW88XSwRPS2z>EoP6HO+o^-kTRDRoo))K8EPC9X-!p$1)crnH zx4m}!gL-mot0nTL5iF;g{Y$Z%6E&f2*x(~O@#~78I+s2Al2uX8ms;}Q;7DZ|6TD?oVB1qaVcr7kfPJ*Pk?;Bi zE7q#JAgoa|KN`ksasF1WDY@)=C8*x`f_}V%v@Teu-Gf&1e?P^0M)&TK;?bxXYU=8u+t1=&Mg0qIgt-Rb!tJQigN%p*M{f_)`g)LQ69bbB68WeRj zI|3e?66j+%fbz9r(}m#IBy_-k+^Kr!S1M`3fH?0DtXNc*XS*?CE-`hlHGE^ttu)SdoVEI9a&AWA7~bpR}94RF! zn|il2zr6adGH#R%an8?rry65q1lGsS8 z)GX24FeUq~O6$Pb-iEcj6<8WD-+@3G;SmB+m{=ZOKfVq*&`5j0h_2gwkYRjBoX_$= zn@Dfrr@0ot&sV)CD7B~-^E~BOON=ZE)*|Eko>rRnQ6lHZL{q8=WBToGx@oA(>Hg$v z+M32c@Eqs&6d3N%#~|Q1w|8@{N88Ly4RY-y2WzWV6&}Ba@zV8_|GDsmd~#3-$ej8- zV9~5WMdWeDgm3aNqi{pTxKG^K;r3uHblX-#5f7;&Tgs5{z|#@2s1Y%Ytz(x{$phID zp87#z>%iLPZqs`>60BPK?g{c`xakGTO3ZgpMJSUzEYaR?2bufvDnjGg-QIA69NUJI zXFz5V7V+u>nv?s7r=TF13w!%L!adsWqv!_Mgt%UMyCc=4P2c$~IkhWxPMDqN8>>;T z^*gtT6tDC_QjU>5kOM(MeKKUVb^k^#Y(X&byWtKCg}NHxdLflG;nZ;C%Es(k$jQ3~ zvSE2bU)mjiu^8RHPzc$!w%FwR%Y%kHyfopp#)j|;ec5TV2ImBnE%0?r>RnlB)872+ zi`5A*^kQgs)}J{etEa z<&0q_cN6ZI94`Vl=>GD0h2(%tQ)c-XE+CMWpCv$raeGh)K=cexrT6%Ldp&^A!PkQO zp-k#pZhYHU3^td4dAGa1eiz6Q z11cD*YuV)MXe<^1*|nM>KCp&29mdja@v1eaJ10C&3(cuHyRYWopUIxAA-Z~;0Ab$3 zxE|GSc1tUt3n373#B~XV-pr(S3(%!M^DlWF`sJXm4?So%Xz>1{>AIE_ z)uQMxAsFCMP*5@w<&7vwqQtMCMORH#-`hRi1_aJNJFKuTNGAn{iqwg`cCQjOu=!-Yl zB*Y-5X)$3%3Z_tusxG*AwON_D`-b&X8lK|}kqeKup8F=ed4vV~utUHn>y@taVtg(5n0md^~(Qxm$B9mt*!wDvF=Hb4a_mH(E=0Y`tZ++3t zEyotbI@j=SPsMe<5^w~>>joVjJdp3dUiqyLf9zTOg559V56Tj+q`MI3nymPNI*MKS zy%U$N_#G)V=~mAX-9lVQ53Wt?#{qfe6d*Zv;c`NXP`C@#%3e`N>w_`RqQu#E*~RQ0 zZ7&Im_T%mHrt_GGgULI*cza^yg0s(-7Q~jhOVAivRXzF)zbBe^e}L;A*e{YTJL?If zlSan2$>&(KxmL>eIrv?tdUvHi6IOXlRJm_pL6>|`} zjJzKh2))v*#gi?)&wjXyaE^WtB>-*#@_?GAYt!%Y(FBBi(tce5r-_1RPpTn2e}C7Z zC)Yc-kXK%!(hwrb*~&YQh+ILTylS9rF>hQ;K&tPrcdG`ZrCD9`H%O>lS2)gmi{I-Y5O({NvfHGwc}H>1-b??Rdlf#!>?XL%aEIdiaMLyE2zN zZ+okY4M3|lVHI_|H!ypVrQt;Wlc@GG+11iXWr$%U!MJv3gN!;kF@kNc9qGtp1Vo?F7d&3 z{r8cLRZ&xe>3_=)LnMGFI~0tGud=PCbLoIkh7or#ZilK8uTFDh+7(3p+oz&se$&$- zn0ZgZ>!~LOAp_TBIj~GRC&)j)*B@)9&L3o5H_q^p!^HKa*Isqsk1lYGd&&W|k8;W_ z9z@}Wq0q3Oe3E$Onp{))tITe7xkcL2RTy{LuV?8l8}a-4_Lz#~?{|7#?kRn|*+-&K zVyAl6dgd}O<)T@~)G(5J?)e38uxs8*NQ8=?b!AV{gTd4mlac)rFzM%=d1aEbabPImn7w&;C^mquJ?1FT>Cf&P0S7;08n3MM+>

2wklZ@*tY`8dx$!0z*t(!+KLkA#Sgrv6ypHDS8x1WRk)ShZv@qSwb zR|PY2<4?p-rXVBL=D1Ucz_Ho{8I-l(3d@P>R{1SA`5A^Oq#EFq+c>{4G--d zR=%I0kEMLR%4sb-H{56)0A#)#i#~IhYscvzn?A1hS2({<$rmZha#Ol3Uy9&QodB~i zjsV0*aGyP)Prj~C&wXTd9`o6`!@^RTZW?K(U|5mOG%)sOB zG&%uZJOtr)WOz|8==+IAtlUFHh4}8qhEO|Uw^y#D=qnpBI*)HbA zd%2n|1I~3j(x#<%_JvQ=jyhTt6jCiX3W^VyWiTtaLN#m4Cw@5NwQS!WPN-^;5daS0 zhf`XkKeIjn48>oe>vNEmyhWQSeGW>rT2&p6X0+P`?3LhKCp7(6B;*_89SqSs=nlcV z3X#~rKpDr55rlXvAlt-(cXO(4evHO9h%2G@zi^M%l=XQn)4# z*Ducq*+@R7V=OcCbo3aDOowVQYU^*Ff%h-&=Sz32*}$%r*HAy~43W^qwo;Mao4UX@ z^IUM#PXZN4OXf-%Qszkj-y$l$1F_{H3$E-1tX68wbB73T_{{9$X@pG{QUNshx7j2> zR+T-+B_7o^atK^8NwLKEOeO?ubwD7)b8dAhiAP$sJ~=7?)+4B6>HwWm$zNJE_|I{@ z#nDX<>NoYOaARXY;AO`*8G&loFpJ;x(r4`jHTHustw9kYVC%YGT}Tk0=C3)Src_OPL9AVEI(@X~b2m@ot>XI7qAsO^*MT1k@#)-P zy|Hh|l;ks137UTxfhtZ9r};!QwHi@OxvQgpT+v4qIC9`%MICU7nwh zR_R?{+%MII=0dapzn97CMR($sJ=i;WJT6i}P6!K!quo{B6884})EWi%6b>)V=<+^E z9XG=*e#z5G?C$9A2?qft<(D&njD*u4o}jK;J%1`~`W$}E@$k&DaC7z(1_is{$MF~8p~lPlAm`@|Sa_V<( zUiMIlXVB9>*BnY3)Rre8g*^An^2>2zOLUYBwWpkf=x3u1hp?iFenZIQW3xK!t5uTJ z*C~GIpCedgm8`9Y2b)tRb~^D)nUKJkD(%bni?Uxi>3f|_3|yMis=a@OzO-O!>kp2i zLjr%^>sI2>GHVdq+IyZ_4w@?n7`WAgL)-p&3f=x%077)869!W(gsk4XMQgvG0bM@8 zDRj>)Z*Qshr${fy(j43OB<+(17rIgWaXCf0VdZzIFib_59u?V{|7^~}{RrVkU09_G zy7S@1zMQEw@x(n>nT7jS37=|hIxt_~j~4b52eIL`v#RXpxS^r1=9nvVR`F;s7}sjh zk&k)W@qMkl+M6ZG%lid?+`}t4cKGSGFvhptGeIz6r?b-UaY zfAfDt6H(IAnDYtv)O(!q0YuwFuWet&QQ1=9H4hA_?OQWm9B#1!q?JH~m*PGMzs=(u z#|w|Sz}=cs(GcU%dtVA*8?JD9ItbeOvdjTi^UP)LA2)byhtH@+;ajlYSM2we+sP86 zdz5JkZ7E^yr`7i9-UE$UL!e)-Z+t8sqf7^S=MQ+K={Sz4aO+bY}!|;4~dG1L-PZ?4l zTBb~wpsK&eyrcoVb=tQu4StKF7%y8Fe60||nctg4`x&XljV7R1XI5kbbWTqhfDPaF z0v2;T{6BA8$7R#paQCj6zqc2g@#hPWSzN1o8l=Bx{q5eroAR_h9R&d%Af=1(8l+mA0ilF_+?VRg^vMji^0mAPL_14oEvMlkNa^<&RI z-T)&=FYjV8a4H?8cYRJTq7tq)_2E+m~#^3aL`_Lg0`#AohH}IS)|V@Op0j?Pi2HAR+0Y5 zI|p|q)pA@lu2}0so`L>`IigJ1)>ks1*smO5=K?CmLFrE4z`#MJFh!pO^+Lb+ltY8cfED zGqVRK+FV$F7LAYzOyNDAsA?NglS*Z{w_TLC@;pFRecweXQ z*IlQB-^2tDgC}u5KCTND8B#tKM~6)tUy*{`CY4;?**jLF;i%&?7^?B=fDgAJJpS^_7`I7cm(q!{OGLQheQug?ce2O z4@V)TF0lbo#$=EB;UcV5F<-rkxqqmkz{C-_Y=qC|3X&0}iJDSmJay2)l#De*Y%`ZatTTydhd z;R~1aMF%FyCGw(dZFZ=1NH39d+?tNd2&$sOGT^|hM6U$d*`JMFPkxt6sXhis{ z%Fp{GReIwysRtdbCcB&QdMo7lq_py-7ieNj&dHk#-`>z)f7NKK)K>p2)_A>Pq0-*+ zu5|SjyiQp2E`W6vVLP2&)5kSPwFEwbH}9DGzU7LZbVf{f1|ck1$jX zYm9D!{n?msdA4iOPRaCrXB~k_+sU32fwQwcXrvFRV%ji}*PGvY;DX_Wd`R}eeB8g- z0i^DkXTWa|)woFC>~$2pWP@0be-F;D=0mTObZ{DQ0#|z0KvWKu%aIX|#tmT)Ev+K5 zembK_a!R%6pg?O`e{3cF40=hrpojl{bTSQu>(v?^wbd&T- z9M-(`l)AO0qJ6t^o%3GCMzNb-_W=se<$^{GvZ>nuNxQelC$+SD;&^oHkUz0}G^;<3 zhK39KYiwB31wG<22MpcuEy^*3aU4_4^={NL&I~XizR`>_%YgZpHIgBXo77- zW1(Py<0QiL-L8WlK2Lq&yPqll^Miq3%8HN3Pk*1VcbChXQr8P>dyn8W5g=195BI1G z5Lbe#$~eu)UNv1@HEV&Ee*0->==zBnTq?7juuqgJFjHCHa|sY(irrt8f=KwZ32 z*k5?C&)r^mk-$Lb-n_>xMAs9P0vJj;05}&capNlP(F_)i+SwK?O)pRFZ1vuQ(GRN@ zK_Fx;VkrMbz)j-s?N191R6p$FySoaJvi*aKi|&Q3xF@zhQH=4H>@;Jy_zEYja9`<4 z(9&^8@{oYcCOl2vl;r7S@x}-Czc+fMyXEd|{v^hLzDXmr8Ny<@GY_)VZ)9^%f`A__n%Tj*a!Q zPQI(3>nw?j+e5^3yA?)dIaoQ$cDA0Zo6H{jbuM9e3EMiI2*QCS78ky%QlL~{w?=1E z>!V`-4i@Q-nf4eNt`Z(o5`>?&?`-|z9iPc_fcMF|_XVTB-R-(Yz>hzMb?=DMlC4gFd<{lTyMWvZtv1v z4k>x0P}LVG1Nq5;H;5W{&EKtc$Hr%WB7bE!i2Hn}7le6fud`9nv6gKKd({Sxg7l^y z=o_xhg6#B|u93dv^`~XOY03fwGpEZ$5+b15uU%A99~g9dpd^XS`&5vc8hsAd_j%%| z6MV2CzjuUDz+>M;@KxS*Z@;nLuX<#q>`XeMw|6W*C9lkW#_emJMbj@|r2vYH<^AzV zf^V~D^>+q`$A@GaAj4zZ92P9Fski#)js{_i@Y}!Xr&@qk&*G5$nY!$J zrmr|um$*hrc6fcIeSJKz2KgLvU87#HTPs@*kO=W@NBM%L zz22;SMGPJc{B%Zk@7lwmKwPQLg<#zrbv2>x=t4=a(3Y352pc_o=5G-kX-?tqHwZ(b zm7WTT`mnMPHzR9VhDJWGj>m|_o+nvB#CHtPfvxch53fB4OzGS+3;u_>N&x?4is7#i zJYS8qqq@6IGE?ol`-K~=d!8A&t zB-bxFuA??w)f(7(F|qshCDXbr8muf6uC|esorqV-!;|3ds>UKbyMRI?KYyMuXb4I& zfxH|e3U$nCxuu9_hP#eMMLY!n@Pqa>T^jB|9d9cno>77aNb!De?F1k8#4;9?l)Sa> z*E16vEwxd=3qszVPU7u%LyN^}>^t1&?6GeZu{}yRvHNDDuT4wOo-J2ml=KuGO&@IQ z@6up*=id*WE|cvG86aOcLAO^Xjkpdwyv2A?;>}fa5frxd5;3rE6}Yw^=X8&@tm;>H zjnNSR!!P!M@qwL{Z~7wGFH{RZNOa3lsi4DK^spx;-N-+8-ut~YoEw{r4 zS7tVX2`5GjJ%u>)8A%Z$wz(_FIo^Prbx|66_bq1m1c3D~0@ zNN@TsjDlaaQP9mJxL_^@iW>g>^3d;ihg^QTJl7g9NRinhbQ_y$3JVVa+`KpO5W2QW zLrn;1ypi4w73t5ZK3l_4dZ`1w9B{6b2=}}8zNzx#b{O%>@j-kS-0*9sN8|QH$=hWc%KrO?cOMcomaeO$V=)}oq*Z{s^S4)Te&x`Q{}K3o4xUxj^C;Nv58()Y^uiS?Oc3Xy6H@ zDunL&>+@-qMKZL`cJ&EU`*fbasiF^yiNvF=X=dgcADriqo$62kX7u0=`yH;n%XT`R zg7B8;rWhUYt7kw%J~&GHk(kL!duhYTh)lC6e;b5lqrt*K)ey!zH+o-%e9`ix;(jbXAGQul#wi1pZ2X4uGq3oA|DWBUC0FQ0Wqa#(yjz zCH$g>>B$14hIs&V)Q04hs_4Y#5<6e$|z1C(j_edE;NYdLG50tba3m8;N_)$0biojiCP4$77HuheSi zM|jvjD9)54*yx7N9z%ZLa4%m~YrRI(Grjli(T%0#9h(tPgr*M39l_Gc5M~~^yf6F_ zC>+?{Ko1e@Eb#z!&9M5R0X&Xpb%nnf-C3 zRmG0^UC?BL=yN;j@sm{+f=tp1nJWKlxFWQrQubC5n>UQ3dm8mn37_|zAa`^r588}z ziSy%+;9zbq-=X|rqKQ{Z(mCZ!@=Jlm^MOqe<8bMo{2l;yDJ{aS`+mE3s`C3R7FJCN z=PG>O?v}F_5_TBk?WGzzoLIhaQGBwGiBO@>bLZ`k1m1@JtD$~DT_FNT-KWz-PN0IIR71okLkH_@ zmo{JFud^8w(mx{rAZ@~Pz)97juE@l`7lWaEhZ&v>{0WpsBU!&P-#ZKuj(Pe{qeg&}9cVqL82mf-B z4~9PrjP}(67~l0|uz4M5qC{Y%55s{6=AO+Sf2-PdAfhPEz70cvR(S^G;`voU#uP?UF$ zy655g3~DXFFwM);sK+zu3I_QAXbx0jnf@6^5Pp-xo-(Z_1$sygQkX~+m+OYA5$mW$jYtLy121&q1dNXs{< z6_kyAw#pvC_DN{XNM0!@+HS}%3QvO%Ek{@9;Yly zGfsYkPQ{tj-x#G1K4#`DzC?0TJ-5aCY;1gSU|G#CnU&fm zu=4S-uaW?3L$j_vqkNHO*DX4QdrXrur-|1)Jh7NvR8FN#SHOeha2MM?!0H-{p$!ev)+MHf284rDi7K_4&~UAd|xY#D>)$9y0-^ zs~&v-+bQp2wpd{*HHXo>GQ*CqzociesV<7*K%@_OPMyU7wybdrcxF6zt{uLj6OqdI-FBXA! zx62{c^X!EwT&9E=4EoBe`*?)>DKOF~BM>3!#^7AiJ&-|HJl_X53u(W3^S#%uZutz| z0pelX-cg5|nA=J(3V?HOB<`Y(%O~qnnnc&xjaPvB)IC(=%UP7WW*xlx3ujv)@}Qd$ zTQFK&hdt%OKAuNEQh_$_v2>)riL+3?y=K3|aFTgWpn(O5*3W!RdjDkBKxkqs4?v^B|RbUwLxI6~zDh4dgU@fj}{#SsYK*4BEk8Tsiy zY@TaK;xMHbP~5HTqG!Wwd;VN^uQTy;L8*Q5S`I!DX$`f4F%iIN=Vor+=jg?rO9ryo zUVjTnn#qXgNS^iRkkwL&bPR6?k7m8KuTy)vSy^e^0{TaFT5Ya+?x|x5*jpEs<-0?Y ziuL-}nS$q@J%7b?9WeLN3T%kSG0qnHhg8GqV=Ns@UOmewl* zDgN^0{F_Nn3FF3D`w;_ z^G7k6^w)RWUP5jDNq@Kpb-$F7{F7MsZG0`8Dlp|DPq!}g-&GAQbNiX+@3RK2uk-+u zfD8Uo_SK$QI}N(>=T&u?H-ternJe_oJjwBi8=~A)JBP2Su+{q$|9-;R#x65laxK>m zXrw$Lzk55v;6AFZ*M%l9-!C))9*!nKHhuuAU(nZ6!*s{au;>uVHN>gZ2xhtMNs`Ku z#bZ^^%~9`_-|;;*fRRJCqSM6I6FSGm28f~nsCSClx~*v2Nzp-Whix7}CQSOhkWcDu z%qPGRbv(3xxw&J2LKho@`;4d6bnfFC7fiio$EF{vKH&m%VX6yKh4g&`PR%rZJ0sM- zWL{U$GK@+;#DCs{hkPdFVkQSOqa*G@pPvLAX7MKay=~_fE-2{;;IiES!MqOi%8OoD~%AHa5r{a0v>)|!=lvoHLH z-mp@U%7s(Zy(jwcF$7qVUL)$k?ty^chnsK57Jn{;8Exrszs0YCI6HDpc+Q;UV@q`+@med=_!~J_o>%1Q{Nh+V0j#7Vx3Hd!asHDPp1=AH~X4FPJ z_u}EtBPqrh5wAg!eb*JBukQsQE}Z3`e$fXUu6ureC-3dUh=BaXquPqgbJ5X33LXwaoh72)%Np0>v+jrbxh>z|qkLl&VDL7z)gRjKuz&$Z zQXh_;1MSK7;ykRww-t52p&zV{2^!7Sd&R~ZpXZ$?z#gb8jy(B$Mzd$>cu6OZuCVDz zrTKEh*^iu;4jrS9RdhB4r0G3O-4*`&CWfe|unZyS%ny9=WmCxX{?dV?sZU=Nv@$L} z+zzr!vhEaNHrY3o83t{&L7NVJ*VXRah~Bi@htbM~kwWN*8}1)>ejft7@cH;tcIV%a z-c!B_yipLSL9GlXXb3|;-hiy7>a+Vk=^)UwJMh(S#Nd9TwV@&@Dr)A{x9cixf}M_^Fsa>V3*d;W0c*)~ z8Iul}1kJym<(jaYZ+-V%9v?mCG`Z2{}=+2jlh4 zWyU1)q-7Y9`9f~qpmz<}W(GSf&uf%aU&wu1YT3qm zTAd>*CbF^i?&sRT_n)WF{^qPdu8rBjStAEYT?S&Pce*ncE$`jAjOTqHra<`D1F*9Z zGvf9_EH9|X5fKc@eo}kCK02!SxQ=W=G5_rroYvzY?i+Qc*Iqn1u*Pv7kGEUP%Kd5} zy73eI^e`GD?vQb!1vTd%_uu;kIR2g(R5uJjD$lxU9O)_X0Q@V=X-ZV$!WHJaZ>)us+NilC@VS}cjuZ_mn`uEqb~$)5sxV%%Ixz=#hcqRXjP>MR{+ zKu==*ZeHZeTXT?iR)_Z9#vNNt!s$Kgymh^DHwPMax{?dC@*Qw0+5TL9FUQ;(U{x8k z4;|h)Fj!VJQdN7uxFCcXkLvX8T6KBUw*VHJ0v&!fB86_4X<0t}S~lop7?|FVM~a5% zJi-=Hw}%tVywC~LJmaHg%J=>D;IFEfD=NZvgPCV{jL!!jI~9MvXt92yehqq_*6VnZ zzzTPzB0#$J0c$5c3J_H7FWY8Eq%Pim$bQqQ6zK~!@4Ien7`Ikbm&*9lB$oM%DW3Aa1to|SVRbdIn_R2Q`RJclo+}{7 z@~YBPLe$O3TX+~4%z@(S7xTi^nLp>_Sy4Laco={SFP`Q7c-NoafgEli-*4hRnS7Rx zirLlgeBtc&DukaE2@01DjGx+M{+!)Ys^$P+onX#*@4nua@f#GYQ|}Q5k$pF(T^0*^+d7pzS@acuXuIG&gpRWRqM4k>G`C6 z^_B;6VDExGQkw07EJDsC;4Fr}LVwqMofKY>g^#;Rz7G;v1xsIo8K=mun6Ec!d~I_kSJUT!`#LobWeFncelIA?Z*E!fPZUH7p!UeR zUYq;*@@e@wzF;cRZ~HnQ=5l3PqBYOK4n0L_dyGy8z8bz+OHvyFLdp3oHY>2l)XMws_Xn z6fmP}&W$yi8XV+l0V?EKSR=2V>b3l^ZzEzE1Dtx=v$2neCg+~f;A;ZvroY6D2Ksy) z%STb9trnoiEMHn+K_3|qB86+;e)H2y!=1J#w;WI$lCqy!)$%};sVw1xV|nRpwUPU2FA zxD4=#W4s#)@He!L(ilq0WW%3gY>UFB!kHe~xJ`TV5<;#KMdOxQ~rC}cR)!pc)7}B0r^!#eZl;+a|d`#5F<>vln zQqAPNLpYWYC*^hex<<*T?6F!;Ja~#94-}mb_Q>n&Hx$e0@4Qn`?X9iDPsi1CD^`yo{39V5bukkV_3jkYOwJ@B?k1Bg8bQG5oM*?_><-Z zP|F2Eh&2Z{E3eyr}fwWXBzpv^h_vf77|nD2s_!ga7=EUGz9U|zT+RCisZnuQ zq%(A+=1n5tJ={|DFFWZvpN&o-eV6*IWKUcZei`5ti5iI~TWz{?2Gd9QdUN$z#v7V2^6#b%INAh_&jF3O0%i=L1;uBxkbl<5;Ucj}%E9m=l z03BFfCYi$SWYR6XxLa=op}fxU$0@^#$0+C^cP@B>luI)}m`bEbT!ix8FhnZzf@l;8zf#;A$TXMzQ6>+`~+?=E}3O8UNAM<)W> zUEf4`c6*%~PHq6*Lh*$zMcR}>f+m6#$?7-laI~!25n`7p1fJNv0BExTQvO{Y+#JH} zBX=ILW!#D-!^HbzN6YI?Xd+N4WA-+bZkxp*g<9f_X!$| zE&gN&hd^*7Cd0$CFG1+{0|6GZ4V0ozhYs(Z;<^eE50uk#rL=9Y|IX>>F*|4s zy2L#)@_BDpu)~ep4i65M57fpbM`{(1NnkO7QRBX6+&x+Z%W{FXv#>AZc(gBO zw%4?Ziz~>=(*2V`m?UWWJ(h+90~4WE2IwI==nsAJsku_M=Ml zM_CZ2wx^#J45{xOBnU|N!I8huHnIgm1NZY~AV16NPgS}*hpd8B={do?H$I!fd~4Y; z@4Fv2!6GPGz68q@e%|p;ptW!XS5p7QP1${UEJ~2<}m*}lN+7w|! zH}oWik%P@kHZEid+K_s>HZ9rai;%*p(|kk`CMGiL1#UwZieFN-iL_t28usG`A#0q- zhVFKU_nK#*TM{t`+7bqV8#^U27^!%@Z0BX4zSc|?$3urMq6Mg{FRrV1%86u_-+TK? zwgXhb)%CHMr)$6GXVRVuNGNur&aT(?Knsuh=tf7a4sZ2zK=!#+KJXcD$-FCgsPeff zl7sVFZ+F^_P?qgklo!=2HHu8qWkee<;1Gz0mEGQGhEo%pQa8dme)nKzdf&SI&?NU< z5YVIY{;8FlX#$(2zh3lvC?;4ysL#oM?ejc&xX>>W>Lq%%CK$wfN}|phO=f-}W)vRq zzB_P5rS0$mb#+MO^m@Myv%o^bFaINya{!ZnDs!)*`DfXF-im64JoX;;`rO(N9r25- zS;GZxiHD~$?&(S{5q-2g%2#IVK#J_!;|-e9+@x^_$ruATtC6%uylMZy@aevU)a{Iu zFD%|wN36K8&-f3uGw63^VD4PPG)=f4z@0a_*FJvaAV>P?^+4<>IDVGUd~r3bRayDd zxxp=e9JV3yALr9Mex7TU0@LHZ`f8jiLJ8%gV} z3vLZR3vR%5%Eay0u1ZjP;ytGAmz8Kp=vTfvk`m7{$)47q2y^5NJWhhlrrWx|)wc-R zN#%R0)=XoTD)yYeQVTh61$B-_Kda8yg)9!cj<>rR6tEp7L5A4a_y-j%=Em7)3%hWZ zOAvP(M&#H$U~>M0JihPlh-<~krl~gahp^w_QXq^qWi+k+#${En$D&50vxfHGKzJ!_7CknY06xs#~*Xg{$Ke=0_n>jVqT{Pie(VUx74 zq}vttL`Dp`lY3RXc=Caay2Io13voCE=xRmdQcLfsR2BC+6Ug591Ox@yO{pd|K0lna zuY!h-aS<*uHCpGBQA!~THyCL7|Ee{J$lX2^l6Jm^Ch$m_9RI6A=1m92o(0kM9s5zW zi2YckP{lI`K#6rs>mUItW@@i=`9T|;%NbDCA@KH7I3IC<{CL5cWMPKQv6O#t4JHK8)ZcY$E5tECEXt>tFM+(XKhB&;aC@zF3qjPK~Dq_pSb3`vZV!-tW2^~>IJhAZUv9a3#S>ge#6aC{!PnMx?gU2mb z6~}$VuV$dtHzq`5?-hkr*es#R`eP13Y8KFCOl)|B%jjZOXm1|?6;#U)#yt8%Y;W^G zDW^A(@0Q_k-Ejf^bx*s^`Ll;3ifojnreG7=W$zg1Z0f$(vyM)}fYPxAlF4lq^i_yS zoIl|#8L@~#UtIV{`SE(@JV%Mau@fiQGT=o|0b87Ctx6+W_gtV`^!9cFCpb5!WlW8G z#>|>M2Hm6*k6Th?^Axc(YbTN03eyLB=u8Zo*yU2=b3$6#O8Bh2c7O=QzSdQ=sD&ul zsQx?w!e0mseklU~_8hH!c?f#c_?1Khc0+%D2=%PNY*KPSeNaG!UzFSTA?Rb}S+u&m zC$OjydHqS>gk*r_>dPDV4E)~KuQ94j2*ALUE%&yEGX6-iZqBMssQU_SZajw&3S+M5 zK*WrYs;?&%)SrWUGY`d%~^zAXZu}m6MQAMR__Snx$iV-BemC0pv=ScfaCY&R&NUvNj2Y6+=Mtd_T*dv-HL{W93FE)M+A@ zjEg*0a}C+BifCRC`P#TZ2Ce+$D*{eygj)>KHdSmA7E5qiMQcqGuTLu-=fcnxc4)o7pJ*+*ifSf1-2LZ^LPGa zahrNAJS#l^g@NVS_n}}r1mlgT{cejy_HLgyG;yzk!ppMWf3~E*=`>Jl1qBQJ3wl zd!tar?crv2e-#ug0JeXNnEdzb`pSlmNL?XY}tXnlb`bK&a z&>?`?Rz3dhw=qF$X<@_kOl+d&m@+@k$sU3`=rVf<Uy9^ZGrEd&b) zu6+Td)c_U5kA@cP{j6!EbD5n7?z_!m!CGbKy;*-MQu$2IB)EcYgDw9Zc8F=b{5!v;-MaLi9L{$Zn-~g0 zo=Yyxhat!JeR+Azr~A%eZiJty5zYO6qv{>{=#C6fXhtSsKj9~A<}7C2;(q@@2*ng8 zCAZ(W)%e)EsjyhSbx!46m;3#Aen_ulnZM+6JiLjE-jllP8;HR?l;FRE;)03NaZRw2 zrd$8?%`xh~g=Q<7xBHeu=cFLcTbv~%^!X!SDd!>Ygc}Fcd>!|i&F$A(r=V=5s{%p8 z+|wp;ctiSL+w)!`{A205wiLyp=r4ifM^R9cfFS8jBq~WVe*J8!XRYdLOHom7IAI4- zIcVFy7!~FTnI~HhnT&4z4}_};CAamqPaZBfXYh`P7|JxtD4WR9>3BHp-dJd+bE2I= zj_J%81uA&n^#stG`shL@dg*K1&zK?2G&HPcIG5W4K-?&f=EEo2=R?F%+kNA^eMw#+ zK*tpCdXehD5Ev~6aB+;#9afaWr)uXhQI>5lZqF&71;DaC6z+F6n51`M2p-U@$$q^U znreHHFeH|LD&?Yl*Ywxg-V9c3l+iM|YFJQN6>QiBP<$ERx|265t}vUi!&;0S3m z_tpa{Td&`JDfl#206gS+m1mzC$%ORI$rJ11!706&c3@0{WuMxtWx5_tjPkRW@deUl zGu3ZZtxpTmdNDbtL`tPEH9_WdhfLG8`h;F&)t!S(fw1H%&+_{0{GLxi3B6eaG)oOv z6Y`yp@ub%pth9?_mV9ATjj;*yeIaa<;L5}zXswDNuhPCTlPw@_XByz5z;X{M>m^@T_L;?J~stGNtG7gj)2Z)70VolZrlhRvYHUrtXWi%+u-F z(LUb!k@JrI0={B9JdHhS$@W4-vb|q#MTTZ)p?Zw=>mN}9XUyHa zN2uaoX*_|)fO0>uM)RADTl{0*RB(9Dzg{jUa6+@uzfp|A3WsCN!#&aa{S@iySz?w3 z6Vk$r&v}&B@oJS^o_|3qRLI<3#`ucq*R8m~8k^-^_VlQ&kP1?ReSuSyy{=^U9QGt= z{nJd(SHLFl8l!u_*>ki0Y;DUu ziWH%5C`+47$8In+i>-!5ak(7BjH@H-bFE9?qSgrbte9{U4TdU?{@halwGZE%@Ho5Q z2f#T`H&&H##{7bbZ4&(|$r;U%Bj#7BYJifkXI>|7DU!+Ie&m?M=_!$)h)_yiC%({7#y zN+(zn9=lGqJ$s zIrz2E&}O|d3ipL~aEr&|@rQ5xD~rRDD_CE9DXS z*Eggz&_0R-MxlNISZBd8)?fF5++-J)#g(v^qR!4MeMN)mU2TX^Su~G2WpvXI@5}+p zxrd=y$OikhNyuco@Sl(7zV1TSQ@?M1UTX6ehsM5nV^U(?X~p5z?HqQoeE)4t4{Tpe z11+G2jLxLFUf63iI$o>6twMy^!+{B*xGX57mNmHu?+QHCH8H*5c&p&|m9yYB{E07n zFj_nUJ+_ZEvNzFqK`O)tB)>w8T?@wNTF!5M1ZBvV6?+ zjg~r#WewAQJ}(P8Mf5&N_BpO^mlfvY=iw5_k9&@s?e(Dci4Chxw1#oxWPK}D^|0{E zV=z*LnX@Bqo60$Xsj-gYoYj#p%Zy_HVYWjb@1LC--|7a*aCX2jdcF&rD;28;+%q6FWEqV*LNllTn!j&B|=-lcF&+f2;bi@|8SP}deU zv%N|yD~jgN`{gesYOd)&QuvVY%%-86mlue^M97ctqi#t4Hr2OO3K|oY zw*x@kKJ^G@io6Nbcg@~2K9KWZvkSaS;8hQ3l*SnTVdvXHj5onbEwT`y9Adi>lCeC^ zPBc6v_3A|`IzPoF&^YVFR6M(Hs?!ewme+)|#$&kkA+}~0CYIsJyp=-c5feUKqo=B;vwiC|t2YIRTz$CIF)Jd^_FA0_6148dG z)b%6qkVhhX|LH)~`sXijFshyca;~Irmt_R^oygn;;PZWAU1iAFpZ4%UUVu+CYK>Ii znM>T4-|fluVQT*(BRi{k+v#0>YY0#jaPS14P$EaQL;8?9{v`YipHnqgkd}#*p+4W% z6*TWBbf3CB386EnMCADjl0Ec?x}P#{uNYi~3-pRpyFYgn6@6VetD)*|9Udt>v(H{K zt4S!lUj<->UL>Wq=HzvdSbMm!6{>DOX-sYz4wj`;T|dm1+maBOf&Yc6uf=CFO^^K6 zjPW|SV?#K1L%z3Ut&>-JM%D1LM`|qd*Npi}27GPgU{=IE#216ZC1rgY>26>Q?bY7{ z1NMi^=*8=>d&e_H_<-EBILW0Zq|+7Fb(+Eb!5DpD&S>=aply=#=n88g(h%`#pbQlU z6(zz){2GPHS5e;T4Cf~?{xs>Njrdry-jeg7sKeDxe&4QPGOt;$XnA-e39PvbOSuW^ z4mClxpMZh3?N6rQFlDJcEW4rL_{y8bK?NkQ_Q-?ZSCO&Nr}K(E{&2uw>ke!Z@iU^K z+??yT*h;2f_(SLeG?K>`o3{6KP$bUZz|%DdPfx~fZ!VK(<44+r-EMGQHb37lb$8H3 zd|_t$e^zrv!}vChy-U?~+^6Bt8 zzMRwHWEQA9Nb~Lw^t{kke6yGs02%>%^o>~*SNyUnd0fTylTn%AAOLTzN5fp*>B_&R zP45`>^eh${_==9cW=7dt=vkCTmE{pBF(=qI9{&_xJL+3!8Ueq1bD@cdId<9}n}|O) zG%2;V5ZmHgmbnKE=rix*I>uzT58U&1f2Wm-(g|D_m_fP<#jcR zQ@#fV;t%Wbuiw4M z+r599*qEAO-?LwaL`Ww-hZgQ4R0_8|_tY{~Af$HoO>irtX3(Uu4JL9eER!Cx{o7YB z=FNbb?u^d(>57Iz^s{ldgBOGiM!CLf4kz6GmKSM%tgGvPkRpk_SUzj0zRMQ;A{OOd zq+yi)0>pRwssIibbU@+I7wiiwQAtr%5}Z3hEn!G?W+(=6I8{cqD~*T=5l{eAo)%cy zN%N5`?KS2H%l%sBb$>c0*RRwmqgMx@V4x*1Pa5&Qc^M^9Zq)U?-!Y&=AJD}*g|Ljo z`XtKl5;8`8c=(y70aKxod>3fuRc-TGObFZao*7bb-i6$;mmUiSyMKE1B;c zfikOC!7b5CukayxPkCtFmTqM|r^+>Hf4NaG_kon~7t4coDDh0Zwd?Po=>|%BKOb4e zsgP7RJRG5#Nr8s{;lng|24X3>e&agk?@kNTKcC9Om3cP%kOlGa^B8f&OiZh4_KAP- zjsUiYgb@!JG!VB=QU190*X8Fv`FA`cWR#2CgmmS%m2%$O)%n&ixZM!wLLTLMc)Hp4 zexjD^DPMQE2@ipxf`{Nq3M-lIw^nRre*SqkZ0>%=KNe)L4sh)@#+YT9vwW=FD%%&Z z_ZZSTR^m#k;77v)C#3sy9SKfYc8A#M_VB&U5jy4Ph{Xhzi2_1c;)B~72F}y|`ZJ!> z#m@g`T=$gP-{EmvzHd2savHoO#N=&4kl7}p@LXBwAsaC;&eO4qZWrf4WxJU%z`8>t z--I(TWmp5R0u;sNzI<)_G#w5~k`eUT8-?voQjgv77)T2LS5n$5fp)g)exDl5l2dIt z#)orFuZi{idGnw{k*q!3G%=Wiw<{5&3XvC9g|g`$|8&?}#2biP7?S&5r_Tx%+?)=c zI&RE%^lraXaX&we>oJ9qa}{5%*aBPc0(jOh z)k_FD^>^4iSvPLevcVTrlla^k_fn!cc(!gdH_0{(#=Q5y$=v>P!yXrBd&q;gZ_jnoJw|J0*rhB6#Rpue`l&jNK*!&nuP?1;^5g%L5 zHImKFv8;=pSHo?nAnwl5FMUS&luLQ)$)gT)ozu%KnXFHA<`M3(`UZ#@{=?7pC(Xc3 z`~t@QtLB*}s0l`)Ozm6((KP?m#XxzM&(j(>z063wle?|C z0_W-nFu&iX#BAzWAs%W4pLdW5UsO{V)@(wfl_q2H1Z38yq_?a3%}<;e+C=$h=1WiK zTezsj-v%Q}J@Ca&oj4b98z}|DkR`{$;`UP;i^w5s?Q*+7R|P`B;^_mczFYQQ2pDdi zv|;d>_I+47D(gULp@Qld+7nl;?`nG0GsRDY_bjlkrvjN&QDrCXV;|5E1+J3$&<=0N zzr?!(i4dIvMn?mnPTCfRO$bH6w{c3#scRO6OdT)Hb7cIbdtHNvW6 z(jC!=fnDGqmWLsZL)#3z+dJHZE`E81N#^clCL_7RZ}!{K-+i|@ps_$N_O%QT_mO(z zA>7Gf4j@!i^&w+|{15uh9xwEMlIym`F=oRR>Uq}IsC@0wQFRBu=vTJGCI9T7i-E}4 z=iS_M{ctQaq!hR>IpDV(q=Y4Sm%#hhXfu4Db+EW>j~thMR7LtAXV)6TvD59lZXWFF zb<~GBcwn^4AEB-9y_u*g8AT_90g`frH9Ca9?zTlCw@^3+3zQrb%!Id7)8ecGjK-@+ z`*JFzj*X6(Vf&{G>EyIe{lYk#YmvdfxkX|3&Rx%|Xp;b=<{DdZC7;!hO|aAQcFfzj zQslVO_E7~nb~G}9@d-&2aAP2a+4byoH+rPyLlSKHo%*8)zF^1_UzbgN4g>#?k8{l2 zczWc7A=>9V@$5i;vWjvdQdhY-h1xe!Z;Smwzr2bp2WW>>WsrW!kGgL}IgnMvpGuS2 z05P}(GL3t=P5{QI>J^R+)eAiAyDbY>4&ENp3(@quE2E!9(yO1HqKZ;XRRmuc`QM%I zj2Yg5vU{pw;8s~;RHi531Ek<{5tz>s$)51LLxKNx<6GVdcaFGx{l+-qC=c3wy*!>n zcD4KQWI(UKS9a#a_#M8qDgC~>YX%3FO`HkEShjQy1t8zwwSGd#ar?D98V;H`QPNWd zP!iwZ1w(IOaiCwOVExZ@1_+y2;vrcA9tLxTXx_QibGt`5?Z?8^!}!J5eZ#5R@65wd z^z_^};{q(vVTtBT4{6W{0;H^Yva1P5FWh!@piFozrC;4B-??O zCwI>1Kv;0yoVaG6gPF0yJ}rs;%r$*Me}_6G)ZFOy^3j#o=T1l3f_m0YAJ#+&+b%hE z+E;R#@SxTLT7F;r>BZFr z<%NR3#yW=np)m6iaIz> z{=VO@Qa{6Sl+yKlRfP@8z1fLfz#N?K{5F-JKWmr+s)XvTQ%cGnAG48-@3%Y^+=FjR^La)Z;&-3ZvNSSaM_9Ps0cT_J?C0F|JpxWcZMER>Zf*sGl5QS8hB`lgp zRAMPcAeYgO^Evcxe5-w6@9_MLVV_Q=5oP~G28t@|3+`l{|F~HVqe8Gio}3;9-W^LJ zUoyDYG0*a(6%Kl&=7Mbt|Gth*w7^6r2s%h~yUWdYq!{ zc7^_UHwIa@=seKm0+0dqXr2uMBE=5KknV>pu7PH2FKt?WbmJS#y6!pxqB`8Bx$B(+ z!TS5EVO^z$NPAMetf^gv|Ji)mfZo+r0A6+we>3?N?{wd4!h1-oTWH4JInfasIQWQP=_(+{-q#FKVGD+yQJ%u`xHHH_;5CI-i90i9)8_ky>d7mbK)4F-5$*2>u*(A; zKHso=YMKO_qfbQ;Z`4)y&=>K-5w3Lho^2pP5if=jv7{OWuKot?` z449^VIZ+x@VzdYrT@)v44EWMQ3}lzgH@RvTm^Ve1{!17zp$>S}+E?b1IYGnz*%_r5 zWlPMMk`<2o+uw9HC$rjsoevJx_D=<#Fn)`L2hQ8RaICp?&;M@l-P|oe9mm(7-`Wd( zA-x6a~*L z9|;FH_Q@M<2nA(DF2AgY#$)42G#BRGXO+DauICd~N4v(i*z5EqexMCtOEF;n-gO$F z%XZ(xlm=p3&9B5Q=x7S+dD;#gxCyxhf*I|7Am}Ad7}$HVK4q*$T)L-)qva;K1qxg? z=@86M1cClBhJsq?!WhKaDH3R7QI~H!Zf2_vkOk5ED@*`Wb^i<}PA0zJmjg+Fld)s; z;NgnW!JwQM29q0QOuH?MX2Q<$mhMnSpXl-O`SpO_+`G@&;%u^h_^S@y(}fTo*yK5z znIiJ_9N(}Bt)4b&Fh5AQtd#jd8JUDMne6=LA(_}S)s?k=7VFz^y9<~`Z(Ffv4ds}o z-al3_!rC@O6au;K^72pE{pOhx1jLhJ>FpmYGP^^mfe!QK4xY=i!)2FR-m4+f0_{D=2-uGIB=(4T%!owVSsDW*M}Z} zA%suPRQS;xV`i{=U%XW}lYAp@0@Vxw&g={R0i_qmmgjUs=p7>sfv5nr+0h) zWu8We+fwmq)F+S537^)dvNuM+}MW^(1Is2Jw0hwr_%- zY0A{wsYefYi~QX@U#n^M!_}~)K1MJdl}IwZyvw9$v0Lq{35<=_W=R?jCFdG4+9B$a zDnpO&KFOcw#YlNbL1rkzFaAhk)ewKj7x|X*80NCGV@Pis16UNh0?PyUaLXWvMl0Rle`Nlzp<< zZ-?dv8j!I8<|9NqVcIdw*3u_SLxR+YfJrX08=bEMcGY$>VSy zVjof(Ee*|c^#TcD@-DghYurP%gL}N9g8J$9{0Q3kbM+;2@3e6$_#01dr4H^!+E2vl zcpN`{aarTn$UVn?B_5ix#^jZ=z4V__E8gEP9Jo4$^}s}K?w!ZIICXTH%a4|eqt1aK z!;-JA{V2c($BdnBr+`Fbt?TjJurhzjY+ZUb=wh&NfaA6lTeS$E)cl;v1yu4yFjt5yC$^_| z_D+0QJ*iW~7n2z6<60%k7??sc=B^Rb(BmpIe!r;Jw=wzmp;{_QJ)L@MgLR_@F6vSn z=%#Y=le?W>Kg#8wC&)STgsbdCPca&VnpKhV-B2ZsIia2W&zd|X>$DswGz70x3Co@C z_=1w!M|z|s)c&3mbgMEkbCpZ+_Of7K&5YAitdz-85ZiB8(n#r%S&JIeUo+?D6M!wD+OkQNQ`ZCsetR8eb~!@N(01DpBntw|^(T z`Mt5TZ*JK;cjC9&M3J@$*%WvO&U``+6mGeZJ-0dQnm*%^cOsR^m^;2}`W1%_wKguv z5`!mHYYX^(GYwEKeMNeXw*`Bz?u$cfdVh?H}$CmOP6x zfXYU2oB_yI%RQThqb3^bx@P}cgf=hxW)|AxQmA&5sgF~Go!6RUGLH^J`pDN9I->9g zY`w|)6>Tz!VRpEF-(u{gypz#@-p&>ueW1PCzQJam@a{gER$2G<_Vw)}PS%lqoeeqy zzqNf&W2TXO`liHhwgi>(uwh{u3H$gMC$#Vtu?8l7N}tz}0Jydtu8F6*cb690JzWbf z=mnh9BK0io7QS2k`5^MmpEy}D;aAvFNX7#spX0uMy=)OGMc0zQb~=WVNqQvYK+l$T zcV72&_4GT8)2iP%tkKU)1xUx)D9now^!GK^u*v&DII&%6w>;oN$R$zcD6=$tK2UQ; z0SfQ%jPDyY)+``v&tWDx7_NTK#@)HdDbmEm*8+8=bMXfbBRrW~6843@Lo~Y-KdAthW zp6Xrgik0=g6!69x{XFkz&TUZP`6~UHm|gXAcv|mDlc8AX^GOYBxEJ&LOk+A-C-=zs zdK~UsAbzfv9Ef|nd#287)!5{%q^{YW-^+C*9mB2uK*czz?Q1|5;J9!6=k$Rp4!(N% zOK#~qiw>9Hn;8MDdG8AjT+m5H1(NF$en!-Z`#W?P$C;0uB-77uVWqrderqjK^8{gD z!RxrGcEpuVBI?Rn<4pI~Z2q5{^bh@F%OSlewe`aTZt=sU@^8&39QVM@ooQ~4vWnf& z?}&{~FG_avHHUAwg)Bg(z^NF`L8m`YGE8m=tz?EVffFbaTKc14zl?d)h4b*~JuSn- zk1qb@%pUuW!}#EjJ=o7rP?0LACF%NN9{i93mJ3_enLON}_*kW^J-w-YW#X@= z_e++<``CFC7d|+AZ1L^i%-omVl4_lT`TVS_j(YFces6MS_W=O*fsbf+W#3qg3ei{9C%|9O9`8`K+z>J^uJ7vU7)dGIt2becwm+g1Zq1o|f){N@vIb>YN))i6zAv13!3%;NiZ z#WNXed>_A8?ZeL_f^le?e%bhi(LD5bo_KegGR#}*y}gsb3$IVnyi69E`(UQ~XgAUO z2LOkg|2(?F$DM=(YvpdHmU5?Jx08B5Yr6da%3Stx?nl;93VF02e|Wb1KxiU!^=O&K zZ+R$TO&=jOej}t{dtNQ`1s@86d^Joh7a@>DSJI-=-HNA#_Z=pULCkp;eHt23s(Fo^abo)+kkgcyT$cRN*7OrgNvLUDpmjP13pmIJ(y3D zy{2RmRRxRpdG#nrZ;#CFkUZMt*u9S<^DR(&E%feoBRQ?oxL}VF?*#?zD!#D4{z{w6 zn3jWua{SCKl=L&j2F_7{bS8)&@6F(tTKE0l+RBxdGk7;dWvj_GB5dRe^j3hUBgvS1@EWaaZErj z#!_4NGo-uw_<4=@dd(xlkKoHWGq6;IXu;2~;&D$ohFamq*N@Z7%eRlE59%@UUZA$a zW=g<&nhz$x#3r4EEU}O6^B~^P*0bVEN_CQ-!LJ<-)2s<+EOat;GdyvSi6xe%J~GQu zz97qTK_chV;KWj|m1@OKEa9L<Tva9jX>-)5~isi{tkpX@z%CPqHqi@8s=bhHiV5sxxH(eK_G6 zCu}z&iGQ2o@0G2t`f8yB9dd|uhTvJJU*_hasYBY39RMzs=uJ8KeuJK17fQ{A)3)yf z`m9aFOnu3ifTae@wdp<8J@s(qizK`IolT6~CO{WXxLUT!X;U`LUiv^}klw}k_H@j|&S8`lTeKF-6N=@xBxp8>|}6o^7n$4GfykaNhN z;%LS0ZTzt|DmEVaUglQnQGCPx430YpVAS2^eUvrg!VX2>FAUg}@qi|#4 zmp7(bWw5@7+JZda-L^GnYbttSl*NW&>|Zz>3gKf6zP{d8?FrAT6Ht0j>lr=fQ*^I% z^a1922>~UK(~#E>YDgm<#=Lly@3OV<({8`sEJ^&tA7r>t56Asox zdG8NBEU&(y3`w2EQ8PTaZ=y0Ur=T9}pZKJI9^u*EsqZ)oKzQ<+8iT=Kv5GHVqpm1qjxyCdEqsmC$6n+J?@w}aIm?w~L~`Ou$3PIB_k*>HxcxKr(9H$%k*~tha{< zgu_9iel@HWUQ(z{FTqWx{DA;by`+0#VM~2hzh%62QVX%kAIY@IkzCbG|N|UvG&kAr;3828pI6m|1Tb%wrEG1+wJpx$Ud& z@Vo5`Aq#styaxjFEit=WAQ)yGWcv3?Lrn@IfQ_Lr!%$U=T6RCR^kdT5ASsHn%(Ewg&N&8i@L>%kY3fiZiT6Wiw{_eQ$|(vRjB8322UqvWZ|# z{7m(fS;WImp{Wj)bVb>NV{pTYk5NlB^MO^6O6sq6U5zVwTc?8gp0Gk8kGgY*@Vv5) zlz{gc3Jl@S$Y!K`lIExxUwZh zg?tH!2c&Og?}gNBuM_{Q^C^lM^{~(3{P-RalTK2;|y7e zcq<}hL-b*e6un?CZ4PH>wH(g-CDN&WfaVXBNA#y2K*i++=~Z0|VtG4D#l)52mT}h{ z2Cm=3Z_p`?ALfVuIDDB0-m@ir^w5eELryX&2k1YZgiTOn{mv>4kRa^oJKBr6wAVqo zYi2h;R~cRetV6jx%BE>p7$?g;Cf zq3j%?KP26V(*dF=QoX{Q@aB2!E&E*0pM5Ui@CSf9kW$M&Q35N;?>8fYc3|@E3#p)x&!Z#35f&r)=+8u+BOtWQ&tylF8fi^3AJ-*A*`%v9I1v`K2L_ zlkU`CsG-?Yj|ddY(c*1$Z+yZ$Iwi+@J4r}WGL zT{bm2tu3l}{Nq+>j#2KBhQ^P{Q#KzeP$;kqxhZt9hmRVN{QCM@t~-WFoKB3lF9fNs zBocjD3BDoQ-ILXud^O+Ks<-c;NhW?|mnrKWeN4ptAFr*CaJ(;GQY!qQ5V&7|^~JRX zBNF}-U^|UVAQOdQDnecveLZ2Y6i6?|D9ju0FNzN0y%iP;swVB2Jbd%?fv>bygFrWF z?Bu*qLh7){ycD0glik82&6kJHG}L{|y;JKvJ01Gmhw}mz##q87+2_Tc@LUqFSir3B zdFo z6>-@>ogFGx{$4aVo}`&;=_3)vzEa%vU)O2hiWc@c=-cM@clj~$ZtIhSJj9a)0|5_- zPu`U7<@xr!ff#sWAaO8@+OhF>vOK`lD0Gx`n(VcxM|T;8Sqb5wdotWbw)Kc|yS)J`4khXx>^J7JF9%uS$E))twlXL`7}b$e+vs<` zO5FZ7T2s)RcYmf;JxTMa_N5EfgDV;o8H%@G1f0v;>>ANO^5&Pz>AS%VP6{Z%z2NTigdZzjA8J1BW*lhpd5=s34WlM{8wy#4(>ow!Mx3iv z3WUH03+qXI>E{yHN|J=SPwh28AlmHW!Rxndx|rAYJi)+L$2^690!PB`6ZQhWMdqIc z5?%MEUIQ*xaui7H{Q{%9tz3c?6|ZACxWRB3!bURzR!gw3 z#^mzCzL5T~AXwfTmCU3v-39kJe#A0b)Y?UmIwaec2i;@UYJBQhJ@oNsJls3*vfqkY zU-r2@8uT6}4kT#iaWlEb7#RRCUa_@{gD)57GuvxN@^N}muYqKKC$aP|lRKUZ1CBLU zoAvho7t%K`wH`aniG^Y9DwFtF-j8SNbA5m9RhWK)d7yMz-*A?Y(9aa705R6DQZVcZ zV^gTn!c`VW=$FA-t_*A!o=C5Ku*uUcd#JVuQ{a8j z2`QlHEOM4}OtUP1Ggs{D;$w=hoA(F}etR}A?FriG0c6~k8K)Y}xplXjVS1?IGVcvGDaiBe%6Q$w^3{e(HRb1eAH zJer%>b38f*WH8>pzA)%&a%q|M%9QQvbo~7z)ZSys%HE9++{ISN7xwJC2M|!DfQ~1Aog8Ckv|X#KfT^A>KE&(c-ta-vcvUv zE9O)2@;mCZeH-{Zps0fGG}Qg`&rFxZ->ZlNyvskk?TsAcjPucEykhzgn=1bW%w{`uaMokLh)om1|vF zV0Mc~0}heglQJJVfYN8Wzoqbu;eCr3Hm!>n{*b0mp{V0qZZu~xdF|=URstjYBDng! z@0LD9XKpD$|6a`b@FAV>v{mhSYvuw=7bGh9_2~BI53;RDbnzkO_xCeO?;{^Sgh0xl z{zrbAXE&sK(HOs}O7F*9=C7h-hn7>Uw3#jr`}_thlcv(ADEmz)q<=;PT1XbX-I#$O z?LiHinS3(0J}cZS>F_CSo}pWL1hQ6NQ9Xb5=^oN|Y*~?$n1(Q~%}wGxl>N*-Sem1V zj~4OD##QDh8?VNv|F}sfBK+lX4?+e3Hy&^zS_e^zZG${E)~UfM~q+ms>~U;VcKee9&!H`h%)Y@hr9(W$qP@Q=}&z*cntOV}?emSOQcb&En> zCE@gYPYU2qAZC6mM9O$_<{i`z`H9lDf(`X$`5yiJa-C3}kQWwKT2k6Us=d6;RfkIX z&8dzZEZ`FJ6}89xTZEW5R!-S1rh6%I-+G^jiZv+)z4!3&(@YdpK~EF9O<8>frfCCH z<@!p@fG~>&m{GSDr8hO4Xhpc}-)O-SN2QSA`k3-|X_NLO1><6!$*cdPrS~Mz?Z~qXkuBlF;TCZel_-W!0d#nYlGPeQp(UC zsXZvyZlUR=FZ`5FEA5U(R)&4|xd9_0E34 zzfH^zfcxI1;|L2`^7Cciw>lgQFVsF3b~S*ipnCxy>|Z|3+3&u_5a?O`nJa91Nh)Mv zx2ZtsZ=H^X1KbUpsnM=$5wXBOJDrg>uqp{ffcWutk##(W~!WG^lYqHca5ZFmFg!y~d=>=79V@ zzGw##O2r1$-hYCa_U+j4Ut>^*?~e6f0`8fBAGS~4-}Wf~(N+QZy7&t}bt06Oti0m|`7gW?xe7 zcnhY@-obl@O)&&@zkSGW5wo8Le)fUt(eL=cP>g?-v#Q_xygZNu$x{0LdS#rkxquq9 zEXMcD!+452oKY~Tg828^7LnWnK{vn0$bn3lmwNkf#!4s}?8JeJ=I*Or08NQ#z@4WA zFu`Z4Q&mNr&e`|b#_BoZAgAQr19$rrxYpNT{xo~`7M~wa6;@29+Kke^LNU=rbQx)- zbwqKOB1aZ+ZN9%VH9s4QOZN|>oatl#SgG5Ye*@wfpDSFY$J*VCVd}N#FHA z#2m2J$Qvh<_^rsGm!^SMuK{n5xw#3#!Qw~feKLTJ`|I^xU#1{XQ&W!rk#t>Kiegdp zmk5#`MI|FhQg}m>Ac#bPukTIuS~XME21K~wgdNV8Aln-Dp3dJKqOJkx6T{;;=L2)! z+9YXzMt5B-w5r~wtV1w@bk9!Z{CeJ*E};3B?VklRq`B}mqIsa2^;0T(*Fd|( zLJ-h!73djSexABsB_PqRQKbpctk&34%(w>q;=EBaHi{hKy0p% zZ?3G9sF0O0V~4!}zb(K-S7--{;?e4roK@sKtU) z;*5<=MwTNjR>_SL5zPVPui54J;-MxbwVTu#5=*KVHWS46RSCh&$^esPH@Z819!MQw zUcVSn8+}wzD;nO@FirVZB?#AcoLi=xsbhPjIaUA7GZ%6wKv2(LQf;- z(t6z76_VXi*_K8{!+ zMERt6afXT({7wMgc}7A98%k9Ggr56zsPP9^g{&I=?Ih$%N3cWjE^^Pu&&*f&X3Ba& zL$0bV6?wIE5~9%robG+^QBETuxDn#zSbFwfDjb0E>sFnhB=KsQDtkvfagL!kIT1vE zYLXs`!iV|2=O)a=OQlqj5fgzsQP~li+^P?Oko_8Dq@T9m{T%$`XzE>lCEzHByb`R5 z=ft34S}d83Yk0tVhQ<`u-?&m#RsKWOdMy#2(2Q0dat%kZb?eM*Vnh^+F_@%Yp#yq9 zUHq+fu>F+xJp7g#yB#o z3FUPQ3t7D#zn*v9KzH1DKIzMj`@$1Re3wmqNd-YD$BaLC`&q2! zrH|TJ0{PaEVON4D=4oTEI(alGuz}1t#6+Rp*s*7T=hwNv? z!%L-KDiZna{Lmf+VFu6;MNJ)VE1w~y-hDc}oUSg%s+Zj`B(E_!_bULY1pV*=4A9n< zf|$NAEYqnwV;q0Eho+OGO)ga5tM)Yt*ZUYwP;T5N&3iP?1W>xy-BU~6_d7mtT-NL> zxj4{Lc)cHr&}v6B1W21RpT5|A6jwP3BxIfUeu-$%P=58!24&$-S$yXCnS!NtZ0#Es zz-ajYa}Xn22y4|<=wI!iwKRW8b8hAj^Nzki$s3@7xAU!q+e!)3@i3rSba;XNX}PN) z$!q;i(eV-ao>!{hbl#9XUXA*8B2Q^~gkZcthe<|3kacWQ2womQuNVAFB&G{l9U)e% zvk)7DOiC7Oz#ocCp9?O<_Va`DYOOVJUwmj z6o+u<;0ad4w9j9|QRNtlqS9M@GZE!)+!Gu`c`&qjZ-?RZd(DaaT>CRkZX~Xmcs+g8 zLv=G2sd*M}eqWdCJ@3hQ%DxOVeR_<&aF23*Xd0MDIbTP#-T(`cdC9*MA0!@a@YVi6 zUEA=U&xqtBC9Mh&iPm=(pif2c>DWoS9w zRtROMwCt`>rWSMZw8%nZrDs_-9U5x|%wcB=E?S>wkjvDGIDP@t0gT`hCbZP-16Q4= z@^-GLZrS~n@qopOU@!-ta`Nvk#K@UUWjt-n-0T~x=f%T@_gK7*5d6R|LH6-M zx45i$^1Ev;iCMSKhxj~`YkMh4?>sH`csJI#a3b;}QM@RSi)T zeGMtHyEMEs`7Ta_J@`ZQSDZK6j|zWwB1*U^nPScG~>n*I>4k@TTTfkn#q3 zLrc96aQ>nhUT^Z#?q~TY>0z<#TkVeqcc@eard2pA*t+_8TW)h!XnZrqjn(y50N`4zDkSeyoVUtIB_|#VM@#%LqIZx0WAx5M|qL)lm z{ns=`zmLk|)YS+gE6Vdnc8<6D1v|5k_*!(X)u2(qmlcW693W2aN!L&++UZ60{2K*~ z;<#V)#|=UebTro|J~5Rt!I++xJX5)jF3%LHfb@_kc^&DUn5USFa+$lN|h`tw_GyUF-n&rG^m zA*G9RyLXW9#r6wXh{ALWLuSU3|87|*7xCpp1u*M@a3$m6{lOlS2R)2X_AgM!=Y1s2 zA&{XTeh+{}TZt49--QXDf7Mv{bD%rn>=HNPXGX0H(1vW$w(dtt>wSB9GQj3S{VdP@_MnX4 z3B^&v`x|d>sIBO=28%3m_*3A%lyC-x^;W*`uMtT?z*E*5NVfes(mCr1>9ZJ{e$}Z$ zd)SwcD+iCqtL;p#_{uxze3-)w=az?F(qx_5P*>^QH3!@YmcEQ3LF>2idml2Y-`JAg z^Z*i5x`Cg9L&c|;O2xGCSEY(y(AvxNPvKzUzaQLb{SQUK4{*V54#MUVSpYgeLf%Q zLr&V*9Cy9{K@tr2Hdj*C_~)gHRQ}}lfqH&J*%Nx0@@1cAp?mR_OgrVM0R08*=f)ef z*^=&0hyKPqlvobTMYh*a)5`;U8}+e8Su)f23-Fy&7PgqggFI#@J4p2!*e4Qr_50S#KrRfBpP@mcLFMUHOxjd}$%O9SSrl(IPkBwwcq@9f4WWoJk&quUrf~ z`W8zg;r7b~m{(-Y-hRp_W~grbOI7N#rZ9KJ!R!aZ#G0{ivOqD1a-TIH>-6j8 zU|@Z|Fqy%qY)H5+^-2j06Q2JzTFspM2}BO{iiX7PMLvWVF=I{<(*v_An_ka+77mX` z7j$BjgoNu5qNulRt*K4Xvr~37g19Ki`uzBb0nCB-^Znu2KEyaL=ZyMvjr%}!Bk9$Q z8OiQzPnUBvuBT+*AKQ1E8z-~^BEL|*FL0A#DZ<%{E_j`1oqOXhE4rp&)0J28)3Iva znOs+ku>#o{|Ef%{@x71(4}b9%a_hr`R4ii zxMtwUzV3BN;&B`HRW4hzQ9ip+MYQ2^jdcrdaPXB{w%c>r?%fYjhDbfn z<1UwzxGg}8kK9up20Er{ib86%g z9wA3(!vBH|afqRiICB#pJ{XGtgrkIO^Qr4(?FvyHE}2o8NHuat!%oSG`o-1*pyQWL zgvk$xdv+jh%D%3Wl|ngTTALn4pI;khLOHoVV$o)7m^5l4#?K`-xBAn`SiTY(tTw^& z@;u-oo7FOZSX%vPIBR^8n^o$wP}kw7)=*J(CVx%jl9v+y_leGF$UPuBRj}`cf4E+? z`;AJoET^MV4nte-GopB1j?Cjy)j-|?)iDYsj4uXlU#xp7=yKgD_r)|G@^8T%qqFG~ zB_wjJ_LHEWbD$GH2gTDvN9i>{Q96LxF=As&=oS4(-+z}DI^sg(>uF4>x(927+H{zX zP)+d-kr1vr<>qHGen|hXJI6-^x=;W*O;nmHQTJ@cU#|w_ISs8Sc1DsknE;pYSN80^ z*!&w$UkT-Ah~XxxV8d2rr@OD}TCy4GT{KNXAq-R5 zY^oVv$P<04*j*k*u2GP~jqo0;*i^B3 zs@?{=(Z9D(o3GxuwVad3j~}#&+C7ZG5%xvY928YUua{v?g8=!*I{=0EB78MTrin@6 zo4FMqw!B$U+TfgYu!~h4QJ|p*TSBNW4buYTkyiTc?c5YE5r$sR%>tnF8lKS8Y~Fi_ zvZoqm$pM9Lq=y13Y|i4I8P*HMsqLUfcZ&`e`^fNcNvLYX6LS_`Yh(YC>GbI(AZoV! zNc$?$Z5`y}7m7FLs;~Kd`G>&0XI)f2(5~OpJVnlM3C8)Oo8cc!-3hhbd_=5r>ig;s zp)eo;8boSgnkH}DBzO{ebk3qFS`(>VUrk$9>gAj^7u|w9?Rbgz;poHF^cSD{49xfa zXr?Y6_NBnv{i#LP)=rNTI6pEfyu=?a&<`le*)w>~IS|X7qB3fY#CyQ2qnsY`OGk3F zp|Gxx{tzi{0_$tL*o|P&rFRd7GVd_Cvl_Gj;Z=%KqK^FyHWz0jLQdVY^Jgi1kg_cA zJH^=f(SlYC``M2y30L~FpI5DZZjWm|lW5qn#Mw9s`l*TrG$jWihqqF`{yy-0gAKT& z5lKzuESnfQb957ak|7X{+PF|(fH)yEh+`fF*4TdDm1M4WIMMy!xEr)KZwqWJ6iD0cNpd>%QW`qyvd9fT2Cl~+ zj>dz%WGlxNLqFBr2Lk*+RZq!{fQJ*d1gYuFn=|}s)D(1u><*)Axl#Z#WXCU|;Ez{` z9%r1!x8uI3raHpGD7qzk7ZhrC;rBzEg%$=EAq)d`dG%R;8WTKuqf5bCKhPomkbRy3 zOL92?0d_^<{n&NK_|D^N(CoxM;-hzb|4KJ5ulFr@oEZsAljwp>cp~e|`3?qRS%b8E z4jy>?3|^qXX;8JWK!g2LBi~mt{wWxzk8m3%3l3Sj01Jx@`l^iF!XTv~_s|lM!f_e{ zII_d_hp$zAd5OlsH09o&kOgkxC;N z(6ieqJ*2Ov(?wxeJlm_mFuAmyE)a|Z^&9)zpV%31JE2gLXy<{V^OLh{VgFhh z{T^)l<$s$KVtze)UIlv-Qb?hXKn#CDJM}5gWx)@4oJpr}{NNnbEJ4~D*soh-KS~M! zBYMUXEQ$A~;SvgL{rw;C-av^&g56cMiTpJ^;OlFb`M~8`gWXWfXrcY}8ke~+6YXEG z2|e{k6W}fQfxU$C^nu?gntb1>I6Zxq5)=^lu~ zhaaG_;>C%w&}Zf+WseH;%LmpzycmV{V$f+SbFcz+EBFF2p5e-h;9mMDu1Nbgn4J7| zY5autHoFg};`fFwPt|)!9a;$M1E?}p=MxYoVIJ>7+JEx@v2mXAxBGbuHR=c2cxHfe zZSEj%U!y$>`*G%o4tunR67zCMn=Xz+1_+jcZLHl*4L)^^a0M>Ww@)%s{uj(s=Kc2X z@(u+AJU;f+Jw5~gOjcbBsC>}}mzhrj0!}!Zjf$lUFKHhYH^kneb^MM{Rgx^2(u=Ux zXw0McUoI_sr)udtf^sZgxHJV~Pyl*XsN!HqJF>Tj6;=7(rVs*tV58a7*J`i2v?BO6 zUK1PzgG`pHCCpy|e-n7vp#T)=k7N=YGEYeI<^CQ4WYrc1(lkMGv=S(&R5eB|oW%L` z_Z39lOx`D09667(2Dip{ag%ufdYo}KfCi%^-j@>oE=rPO$8 zQKH`Bg{Rh2`)9;p{*j+fFt(h?^BxHNe0d4J!d|V?58i9FurktmSut$?N?AAgE6T7_ zE`Hi?7iOZPz}MrV)kYEYdOpMNMH-5>7#wXGulCV?IUA<0xGyqdZd55eEX1StrcoL2 z4oNU&``Q#Nb#79XiON8{-8xUx)|**$Ff0nL-_q2v6pHja{kizfrgFZ$td(E)4a*@a z7&hB{=aNoBAAT^(WIYjTm$rP8)fYwSA)`69y~|gM)46f4WB)Q98QGlelnCWJ>HR^` z*N0li-18T|iMhUM&D$QLgYI`wEM@gq>K~dajV%G^YAVz_dp`Ch<}GUr0rc#5w2k(u zJ1t~{kVe2A8c%9!O!`@Lcgt}Cec=)dTj-WDy(#3;Z9a{8Pi;Wx#8- z)1qFh2qz`_@Qw;gjMP(C46)G;l2#+F80<$S_?)i-LVUfR*rP%WdsRlna<+W>}e%>CeJO%6eHaD!Rl2dhIep(<(PpCZYGOgNK;pe+Y3DNu!Y|an! zHb;llJtFm%?0PR$T>MV;5~KaOY^+^2gHH}xsgi0wxhmO)&Fysb3L@L;Fa+EQQ=LkX?(n-!vnfV!k`6Jn-*YY zpGeS1(Mc9h@;gFLgt*!X%Acw~2*yXr8K#fh%gN@eEt@3Xi`btM#fL+1&jS&?gJG(} z2Q>PEWoJ_LYkyBE6;k3(!WErRU;u^M~|R8XAtKnmyFz3sJu{sX-` z)0L!29lBm*Xt-|ytI}>coR?K=o!_t_IMwqF@0CAFt3AP*_E7{ZS|yclxF*M!90nVw zNV_*UI_1xeRgY5z4q5`E+zwS~_Ggk9^5PpcE>G=#M976Ox2mP#GAF1Gm8a5+deh`f zR;9p$2gF|B$@o*4N@L@5h0fW-0Pyy!vCo%KOBe3UBm7XP;i2j4BhG!E3sdJ*roOhX zWw6Wz`#s}xxKJLeJ$IEl0{88lo;pXq*YB>x@o1YdP_M;soHV>5KWM;5rB@|G2VtZaL0gO`3SSax{Cq37nrK9u@d1W18$sQB^c=P~*p;szTVt?d4vzf0=*(E1~ zcz+V^fsb1$5`~YguV?1kj|8%nJ?BSx-ydPPS=vMrL(x_EJ%qRFKJw4&g5o$E7Py*5 z6CI+CRs846r4QF5PR#Oai2pyLeNlrfw+l^^Xlq`{V~f!B7$5cukA?k7-ZadKbv&~5 z6{-B`UtVsmW%o_Sj99lUqfStZ=fA0%r_FH{PckE3nVWYqbwRl+=_X{!>o}y@%x~V8 z-@fZR=UOW$oO!h!n>bxwLfxC;B00Cmb3KOv2?`267hgA4W&Jvq>c~=`xZ0brkp1t4 zNyhv=qWE%T3v|+HIF)4^wA<|PD`cV?RY9<%yE=vlf6v35#Q{_1dpS%rzVvW05oVGc zv~JzJ-q7)z{dvK117vWsglahpFUXKF22?I#dJ*<7iwxws08ZJ;fpUDZw$6OHV|k<3 z*FKPbPy`Z$=#Me{JlcN-lO)BnTdm|!5G(ujLTtzOnQ8EHCJ#hY*gXw= zAu*S%I#n-bkTE^Uf|+HI#M#@Nw=A`!L}*?3cv8;3%T&dh@=9mI_mpJlME75gKhB7m z1nKiy?C`-m7p&*losR0YJnwTzTU!$4r!_2Fe$E3|QL>(vEeF5=1&0)avr`|4T-x{f zeQ4at)V7=}9O3TXhY%5oq~?o60cdGoq~=C+@Xk>B!`7p#>gX7?v1SszuHY%Ljz(4t zgmrw=2P0ShepodH{(|^<^M$leS6nek)v~)bt-16)I{R1OwlkFDbKt8P$;)%4AAMSF z&>h^$y^1Ai5<)7moSXWmj{fnyeP`68Ln+t~hG)XmTz>immi6#E-kWE1)#o6bwTF`! zR+&)@d?4@>`Blx-h%TQ=vRJzc;7h)QW1iWIXSkD^$E;yXl zpZ6{dBuV!J`D!?eEoi7YGjjmXGb)D%F~G1kN!o+eRE^Q_9p7=|@vt&3lh!xG`kY8Z z0f$NZbM5*q@_0T3s2=U#48#%US@zmF$2pyAd^>WLN&4VDy1^JtTL z^sslkB&YK!>8|;yHu!5@6b}hHmx@^OpP-v(t=yMh`DV&SaqTqJHbn}ULj*oz^R}?vxpFFjMuH-_0?3lJa z`p4eeiS_`UCHJI2WWfJ##3WOH-5OC(2#Cr1@gkp~5-EY_LmWa#P+0sG#eAkE;bLpwr zhulD2@0#9nKcFx2{CbP3%ZG3FGz+1q z9|DVa%%zb7Nm|Ea_ZX;**|{&jurPgM5mMKL&_#=QPW=x z=lSkn%LiB;1qUa*>h>@Ml!=}_l#?Jr0|y6wLxk{qfLZv3##g#t5!*{ox63R-T5`bR zORkz;4)~ZKJCSU#$t)DWTI0i+7wP-idncdw_4RTVyl;8HQI?**u=2s<^@T$U-HaSu z@Wiz@dea-!djUluXi7K?Vz2C3nAg}{HtM*X{m|m%S(fGxtn_|FCO>I z#lp;&ylJjWIeNU8k!={BfAcy8rBPZ*#O-1jQV z($J=)GLXjO!F|>Xtg817RD5-i!a5JEvY(3bYd2X6o9PXgp&PD`gFrz1as0hzc74K{ zCc07wjUV~4Vh(Zlz9RE{ulIwVWyoZ~&-tFeCl1@2dNm<{HgeUskZ110#E}F-JRneg z!`3Y@ZHUVO9cmC}ej*1$WTmXxa&8vuX8G@rSrr{VlP$y0d$qXSH=xxpJ#@o*9yzbA zg2J^?^Y;T`dJAN%Q{RhPMAb>W2i$vLOxguta?B17jSaU)D@vBQHM|?BsAWzF!e}zje8u6nq z(mmeqTd4SbGM_Kblpio-R(mh9NkI!&RCbo)2lF!gY6{NJ;(mL_N0QWhW&F(?*S$CL zaKAwqC->fLVc&`56+%i32kk8AOhHT))|N#Muam}{htk_}nt(yrk|?g6pDsaU5admQ zr6I}%pDy{iir`P#PBfF6b$kq~)Iv&N4vwbhoT8CplnZtIGctY)5JL$dh3!AUYbAzd zxn%aCG}8)_!o-tpe>YHeyj%X8vs^boU?N^UCW!b4Gq6%Q%9#gY!^!XqW_EC6H7C6-cUeO=C=Eh%tB{TJ${wzF# zP(|;mxReYRBzL;K_jxr&_kPTTCP&aIecL&|JHlPhM08on6`t~V^vO=NDrM69d2*rW z%Q2jDTNF*0w}VPj5Yfn_IIi{viWHV2194P1GYD`0p0CUuxw!gVx&)t{=~ke`o->OZes+ajxfjBa!FR+pDK)Q_Lg5;d-)*0rvEf6bxlwulnM*qs|8 zQsea?e)T3k~}7} zf9h%DvXN6^dn7>XBRKPaEfw5Vbu9N3!ke3Y<+$w|<2?C$sC3L`%9)Jws{jORfF=bu zS9hg?N9ZynHx}6;cvyQnlRBb8wCjGCLt$mSgD6tGz?{NU0>QY!Js)rM;a-2u{cIBY z_7b`Sy_brUK+eXcU<;5t4G#^MU!Yl2?j69{i>Sj~>fq=pTSCP$TfMq909cOI z0zap0po{^pdh7?9t3C9y-*PPAx7pQ7|6Trk0D)rec3B#cx~m&r4-tm)ba>3qWa&W7 z+!?e*+Rqw!f%=&BUGA4dGXS~8Z9F;f?A>(w;l|k)>jse-@-Ti0;zB3zcu>NrE#@JY zKjyw!R~4U=uh20*dcWlztl|Cr%9{i9WW8JZ-6uoMcGkCfPx2-IV;1M4yL$mXLG5R!08=Sq#Q@ho5ziAA@*|GZ@6 zotQ0gnc(tEs|m}!0>&wJbW%n$sP@SBICy>RSf_^zBg`ONrB!NR`~CJlI*8rQ2b+ux zliPC*haO6O>H>&F>UQR=Yubt`Psv*Fqk~@B?}i>eVFn1VDg1o_m=61o|B@)n+qX;3 zf)uzJIc4cso%( z>}{XXFithX$2mDqwv+D{4V>UwcA$%~&#c?A(_esv$9u65E(=|wy+$S)(kerEDy~ln zqg(Wrt3nGQ1_$I8I`fPkD$6e2`F6h*)#>$xTg=)27<(k{ZQ}$C+`a73wEDvD;&1{( zS|`u&y}PvjH#pP?!%9>(a4_gCCWQ(CpKT&U6z^ZhkMM3lS`h254lMbtPd9I>o0){m z90bdfwGPgoef=0B^h;Y{0-x`<3@gkxuBL;^tpDh&nYrsw=dI1E6uzzWid&;`b?;z%mipb!!xjDkq#VP} z3Pv}Y%M*Y*$TTl2U_Y)0O>ya`@CiwLCqkZ17+~K9YqLa!o}E~s|H&5izR>pL3@?#4 zfhb%o8UteCFk$NN`E+HbQosxwf7ot0mujyki7&}m{pg4B43SUs^n&{i+M8mC(&g## z9GBAO0t$CnoFwyTj=6E&rwl%{&c}!O2NC~(CjGwl83ayLLmXHB$a+qhd@Q_*m{1Fg zmyTIQTK4#o@fK+M@J9{%DNv_g8}Q{||m4H%*~P3PV!thW7VLe7ruG z{7B+oNQ)?lq{>zral7G|c(@JLSMDKfa+!{D;-a*v_53ZRpD}b1CBprp9GXJ?>o|mm z0l-53eAJ7t9iw#@T4T7!@{k_vx%qEH@iQs^;|fwnm)dj6#mZ|RqL1Z$Gxq9%UR-Nl z;Uhp?)C?1ep;&R+ldVHW1<+paraPJgE6Q_0enO=@Xj=6PQ{R_FcfX3}yD(JOJwMWO zQ@+bR2v9LZ##Y5Yw`|^ac;@5*YWoO=irw9`#OFcJNdzK$cCmtgRny-j`t*rRBwd=o zXhnX%2MjY?xW0suSo!?thHzoZx&BtAs?6hZqb3Jof&F0k&k0BW0e_d2H?uX_ZtR?M z##2ZZ5)sLMZ}u^jJ+NzufN#C%Rllvb#G1+V&TsB*HCuuHqQUZv9%T5nsKq0CfwSs; zrhlT4Fo+|frZhob;;6=>I~CNQVdqWN|5RF(s24>P65%rnvm~t-F8w2b7xVyn=lX&C zo3n42!OV69QnCAiZwlF2RPC+!1{a?nee(H2n70TbjDqn|G0(>Kz|;Z`nUNB(K*SWUJGGLTmb1zhrW49q0C#}bfB`rjsL}gbYqo?oM__tT#skx=TGdh z3gN0sjJ8A`oeK(bI^%Hub-&fr77W}T3+940u)EJ1j6%u}ZkEJnaYSnGJG*`??lO(g z{U6Uf3Nx`4cw!dc`0u_tW?RStsCI_V+QmvLc$nZpqh!Vz#ERC9$z#kJ>2liZMz#y0;?3Shl62Px;QTY3)}*1xV=q^eF1bx7cra?ZGWh zKW`$fZ`6BV#aGxo(d{3h9M!kya*>YNvw!qgimj-OxXb#RhW0a$PX}BI@UxA*HV_Cs zn&6t5i}obnZZaptdA*V`-#60uJsQ63g$#(~m@(4*#kDA`H+y=xe+Q9%1iHn;4s2A5^*_Q5H%hsDSZN`gh*4%-%8?CphiN61c z$L0|{x8}V-i^GwhjchE3JnJo72KSKdLnMQqO?CJ^HBtkH;@iaYF?hKC5r>|X)_{d({ay46a;i$i_oVBIos*4 z57NilzW$aJ8esR5h`9|ScY3=o`U*co?8NggW~|fuEvVc(=jGj}0gOQB7oeDdhf*N# zmdXjU9*8|8GVX7Uix)&MRR;Qmbnyl$z1Sak=_>FZW4f5}Zgf9JRsuDLi&kt#wC91~ zuFOJw+J}8n-7#^&IudA*z`SMOS_EJ(cs#i3eJt&3{L5jO_eGu%t>Iti#s|x5GUqvf z)+z{*+$R|CX~r`-T~pf|ids-L-J@$1+fH`s9KZfMHpRIUbOzq3NqSC?y&Q?1y_xEQ zBf5{SLw11$1x1+C?dgZHCd0)klqD3aaiEzlE}YJPj*!32eETP{junef*i|~8Dt5SY z-w|IWT*6z_cc0w;@fuBz0(AYr1O2!>x6BB}^eQClFGSD^9uHaPXC+QYpHhe$Ywcm%SLMLQz!j%Spldn2hCV7SflW%{68~4feR12_(P!IKj{FxHw-G8=dIDPzM2qAo#qq2hZp8Pw_yD#-t7I zjq1va%30EDP0Q!#xR$Eiz0>%StV3%IP>PzMC-@<3h%N}^spVcy#?h}X2p7t@{D>_| zj%%~8UAzol)ceB4L2ECAY(yp0`fn@ezH0S0E>K$vB6$^DEmNuU^oBVmukA^lboUY# z@5fIi^;;uplug6&nYbqX*@KT%RD+PFi7xhH!2Nz3vy26cN=4hGd<~%x%kMAu6t*{nd-k2g=8Qpz9 z#|)FyH61#bcK&HeIWRnxv%*?)v z_!2{Oe-+2axe6@pCh;+`2B-Z7xe)h|K8n!#4vhPul36BO$owIVp(G|TPY_8l zHYG*u8xw(=GODw>CuJvCmT{N9JuW@DekeGt5LT{cCM%XF?lnCOJ!Wmic`?e%-=gO; z(6-Ojf*diFg5a1{rQCxMubMCZ7;lPg>-XKL?W8K2gJO{0ypy|&%t77DH@}y^+RgU~ z;S6EE3D4Izmr{$rJ8ciPYWoR|{ob9f+AE6>oWle^Cjg?nu|Lca>v%Q-(b2M7&m>lv84SkU%W%Gpl72WN3r;hz|q1NsUFqyAEH(z+E?x_jpXP-8CdXp{V zPQcB2?u@Q8(}=p>&5i1XVBd=l0zkeueSv_6AYz>U#`hHx*=~hmc+vL1Xx#*sXex%(SMV9ixP?9|&Ff%ZDtOr~NL*i%* z*~pVN#`g$@@*7Uz&=X^Xt%ta-1DcL`4a*#kOODpxdFW9$i?0Iw?Q*3yLXEbB$kvI7 zT4guJ(3U1SJ)9ov_vfMD z;z|d_piUG}XIe;Q9}^&Fz04>WzV*+yaN!S?XJ^92_I_#8>S$BYCxD|+wC46NM3QF zpjgz*YvrPP1Yb`GUw)mClP!J@9Y8bVH_<7rzhJ!!HbdB!+jrD2V`M+5_Oa(Xq4qqt z@zq98fq8PB9W6sJvA1N!r=F$EV?X?=QqNXpY61iaErIg!L$;57`iMii+=3TEzkxB{ z6`kX7sIwU8*jgXz+}QLu1+F&O!YgH7%-7h*6c}xfpOph^#m}d;huSS3v|uTav$R96 zcS2`VsJ}mg<@uQI@L(3o;i+`w?RQ&#*V?l`h0@O#W#F&k&;NRyqmT38e4rq42Rz>RS?wo&!g}Ee4}O%`6xTOX14bKD=BAKt42E`vvH0y{eR=ip$?hM7C6((=dadzauQ_y*UZ9 zJ`e3Li|VxP+MNCco$<1->=+yYNYMm;*XBD+=wK#Vk>Taa8z@-|DBW|*=ZWrzMfO+( z@aixn#79UqV={Wtqm9mFK=msKKp4gBg(A7UVMw61~9QNRev8#pkyf%)DU(qjFL>-CY$UVbLy`i zN+f$i7`TxPpnv$m-`~P_%EH-WCG8Y2V5v9Yspk8Z?jz57nQ$2Jp07_jWh5ZdfcdiOYm{32iVygNXzkg+Az%F5jQI3l7xaVMh~%iBUfH z&t|#YkH^2~jQd@g;s-|*=c3Iyh;#mTNetq`fI5a3Jf>NU=xuGkxCNr=gqH*v#(_nI zBY`G+Ew{tI7RHEaFvOcJJs|ozLO8PD#g@hGW4$v0YnD*(W}urc8$mu1L~x#ee`ODf zyc@H{%mH$g=uYbVDf#?$3Z#|x2$%Gqe}Z9%NhF^79qWfbF7Z5M_XN=bR8)Hqj}6Z8 zpKhyMkL|9xz1@8EUWwncowbZ8(CS7&ANBDbsO#ANI_#arJoWQjIVi{w!qH4m96}(3 z(;{!TRC9h#C6%4amr%|&aNyH7oRZq8Wv+<_sDDJ)Mqu@0*v>uqOq<}R1ErE29xtU* z257lZR<)E2SP*fRsoi=y+{!^iSj$5VuJaiTm#47)z@u*(Z}yGgWld8bNuy>r&={P}XLh4T!q}rUF~6A4*%4(o{sL<5@|k%*lg4)s z25tHLao*Wtqey9;i_X%m@*^MCDJ&`BsZ!%CzLnC*gpz*u*f zAX}M8g^YOK_p}`sEvmgtd2b>-XHT3Mv?L6&jIw((R4AR@X8!#M;rTuidvF4h7nG5u zk5Hu<${xiOJZQNQp69~eui{_7o!gGF>plZi52Q#NA83h-#TG=loSyg$5yT{ObT?iE zp>McpPC>a-QuTDI{8FnUKoTrEe*p-3B*&k&lE24NB2Ew!qRj8#4}@c{ZVTCxB2{6| z8;&36cm(`Iu^~epl50m@p&qTfsSBwA^)mQ(_4Ia6M`aJX5Z2wzRFG|GrQFBd_aMer zIzicZ<2t|kQ95F+*a4h$()9Zvl5z``QZpR7;Cyosfrw^+N54m^eScMmlgk|^oYOp^ zCd*aCrWZ-BR3I^}{<1s#2g|RqZq?5#KE;Qh#I5u9=pOu!8!|jmxesITDl4-F$Ms+v z_e<3}nraybW5m-QX~P&Vp4R%sdEQzp=W2tFgFC?raQuDap$6>@uZve;oUxqX&*Fha zRQf>AdK}Na8N(8b@z1p@9RQbv5;6r5vWE>ERl46U&5_lxPz=I(lq}LrDd@+y>;0;J zN?G&$wF+})kHs&(TJhz6RBNy52I*o6lck|pO(mZ|epf%()tv4x#6%K4@4@S z$k@8QABF1E4iT;RI4RtNmD8;!H*~9AfE`)VJ>_3%0lFV86lr14&KOqXUNRP;7kap0 zPq_1_4gs)#oyz+?~;XOlb>d!O>_ zi-tJ=Obl@8D<--LdD+1m;rK`%S8UxdAPL=M*rxB~2o=L%*$~;q^(i(3v)Ug>Ds?Xx zv3R`*xzDbQYap-%@{JnIbGB9d(-@SYRjjRd;CBL@uXc}iDVqL}#7i!91mk_moXZr_ zpN>z*_aI|0E3`y6ljK+!XM37Clvh9h?4bp_oM}{~-_;Q|&sU+@!mm6Zz*{)btlDq= zO`#OFj<_NbMjCn|Xr6E*b$B-U+k7@%Af2szK~8*90z|KtUf$49@*y zp!zyIEN}tScYKZ;l%FrmdXx2PSI!n+wc#Ng9}PT`UB3MpPD(EIy_=#072z?VNcfoAO(5kO#CT~h$(|+1_rr;l(>DP+eZ|WI}nlDv?ZTU*vijS2eDppSL z1rd~L+pC}Zi>T|lyhVGUa;&c(6pYd$`*Z(+TYdE<3b?Hc_vhlHFTr0m*3G$R@Xh$` zeK~u}=CYd%6Nb|hG9O@6t?9XFqLq|qTn1_RYIl;j^e`14y&}4pzQ68??d|v8+#i}Q zuLtI$2*~hPzSQ#{DX#_`PJmTiI*O&(q?`|C26DH|XvTapOm8 z!wis77ZEnHDO6{kk7xBZoA)94Tp}$+=p?(J<;K15^L_^x8^C~l*)$vv02GP8J56fh zKh5VK%%e;B!@eg7_toQRy zP9?Azu>6X*K?L>j`+nIk-Z?U3kt-Z(;I20^(L<%=5_O&e7aM+abt(J$3b$*X41ae3 zJqUMrOrV=j&kHLwq}NKy_i{d*44}ZpNeuP{U%Ycn_G2ND&zZscQusse)zcg>F5{?J z+u)W4b)KFF!S_!oi1cz+S{q=`$L*Hvi}WwOsmm)!fS!Sq49qPukL=R}+r{Rs(ZtfB zSsE=NhL{6=j|@~@rRaLvJP9JRptRtjOaJ)5+!McT@&X=;eFF>5AAeXnylI7=|0rkffzTLlhg6AZ&WdvZ?FH-q91oT@`QTZ&V2{!`vX191M>~QjYg2$ zNt7!q1&G2r%h?7--)D8iKQ0yL|P z1Qmkw@NolkmkgCySndS4PTB+83uG>4PT!#8m$}#a1M|wsGxt3dX4ikb_yd1}^E{-HrhmYXTbC|LeO6}=)urRKVPDqx&n7{IH|2g#CyN-2Upjh-zIbSWPkYhrT`OxMq&P224c9WilRJfc?4wo;6{ zlbd$zxMi0v1dv#ox<#OGl=zZYj8lXqCW1#RnuRHi-~88W?i!(0tASA>2# zB_KRc-}70%Emi!1n(hrIOU<%=Be3Bm$_Zf^F_PDhITd%Z8!%2NPJpnQC8{d~wQmqq zx$MY?6@1&p;znDqG~#GL(FFlh0o8?EEh(5Ob0x*)Awyz~Y;_C1E6C}5uL;u&1TUxX zSB7QuTTmAh=$?52eyl$cx~4l&Sof zMt&FcfttOqgK4{o@UfEzd#yrldsMH#;v7LGrYr2sDlJ$eJ~8z@Oea(qkT04JdHQpT z_cifx{1ww>RS2(?DU_~8@#wynW&wxMILL}Z*K~U2FSkCjzNqwpdE9yWC{%Rw`D_c- zcqUn7`&TGi2oQJYm|xuSSR67sWWww*=p4div3t3i!*R<&oUvqJ`Mrwac4}cWc^@HM zzx0qLQH4Rj22GO;?!6k8tpfjtKLHdYebk_<_V+!KqjbF;%(~NrBpt&m+8+#<0qTiR zAnmR03m`Du4gQvK8Ovuq-<8+Qc{8t>L`+lzdWD}(V6nt_Nlt~|$qc`%$ zU^TbBV0B))%b$Zg781m^r>grX5Tue+7V2g!7wWjlQl%>hPn#w@<#^63r{Bu1n4D4IJqr^=I9oziyQPi>t3QRDC9D8_IzOV9INN zVrXpPv7f5>4#F1{8CI2sXV7I@kI{I>@B(us;wPN zr88@`{kr<#Zb&>MA9!~UV>C#}e<11W-5}*qu;$hl5lqiQu*(}Wv;dW3ddK_<8q}3b z{n;F^DRoAD70dPH)To9*28QXsW&zBPB z$g$qO>|lA4igy`=COgUXT?zV^AqrqoO-=mTo)-nrPd~Nzz)I(IPi6iyZQn78oL=e7(0oBa+RtKkNr%f0$rPKY?J)u;7Tb+w&$0dJX)eeo1}OI0{sY#Sf6~d9 zL@f??|AcawY8nSopLp*z7gNSkI3RI_i^K#**yM2|-(H)Omnp0En8k#$w&sAn5p9t5 za(4Urdh0&OC8X2gz-OyTL?+yi;2i)TV_qWXqS>}iGnWLCRM(XqKwu(>Z%Sa=6Axv! zLUYq?3%2#%i5g{9%7u6Qf`Vyr9zW)O13M_P-xEz0cd(cS z?#Rpx_Kh$;<5&M2n2>Hvq4i$QtJ2A6AIw3R7f)Ss&^nYzK3Ep}q{oQ^+}z8(&w z5SHTY^$^i$d~C`2Txj38yc$Ks?Zbt0b?Vo{%;-SL^6l%!3;*3O5q(JK&f!d_fA6p! z-(Dx!7z|(gK^>V}8yamq$G5)9A;q{o5EV+>G+2Zg9{amsz0M5L*A`z390Y%qPU~a5 zg38`983HnTyM8RsyDRkDKE-=p{9!LAyntV|Gh`Al>flO)-=pu;$@44zYq~!=INR2Z zi{6E1CdN{g+gW{848+~OC;s-c6CmA#BUd}G!ReYq7i5&>beeeYVZ8*(a1*Qs1SrutHY`#WQachp8dEd%lX1+LktUoL-E(4I3{|*==7YD z+`d$D^diQ#^*&xU_2#rp#&zPpFx{tp5gPJfk0markl0sm5IMtKV_S5aht-sM`&2A7 zYF2fdZ1kLg!h1L&vA<3!p`9AlixWA6A9O<;dMg+l8#05t7%moM?X@yz#?U?xZ{^uN z7b)k*5do2(-Tj0;ryB4bg#vBoAE#E{onNEa{H=34S6x=aD$_#Ly)W!#4^%4mP`y5m zv9;*UH96UK-D*dw{G4+$dL2z;yP6D<<#T7cBGFJtq}qASh+8O1vmh{_8^%>oSGxA> z_dW9CD!jQgM>GCDD?5yJvLn$OyP>1eNnQ1^@B5-3k-vBeZ>8El_R(eqFK5+ZR3O8b zq@zYiJcF{9gF}4qywhyMGa6qzAtY$d>~B9G=|=OhMz@Lc4m(^sbj$DZerbwx>~s^ z+&>3SB)M~eHc=`sfAX|t+K|zH`+HcETXqBz13qOeg}bAjZ28lPf;CdkVa&i!M;~f@ zGuyA$qnTI&`kJ#=&P!+2Natg@I*zarm!NK2&}Us7^FpLttzv_eL|s#Je;XAQy!!(( ziigqEvHr@Bwqil*YZ-PeNbR&Ih|r9f8>5)fuA!>;GpfpC%1h(!>h{J zStd-b-A?0$`KAFJuOM)E`jqe-{MX5O_R9wIRT{JkG%f~c#qmOL8b^FG`+hT$$ujyUQv16JYb z2Jum??@)CnsukU|*g(Is@)-j4{*5B($HSi%Z##h^PVeFTuCyqHj~K&Ew;;L1T(6mu zrn2;2$*-6VL)+#vKNLr#84qKb*=4T zD=T#eo&;_b!Xy8)e}I2mFXb*$vW!n$@oxWJ1=qK8?V0VxgZ(bxXHw%1GnWAGs*^vJ z`*?2zm>77*o*tPz-7Xu|&wCtJo`U;|grkP-*6)wui^{I%Gl7;^F_Jl_`+g>%LN$Pb zq1;b2bDx%QC4N7{>+Bw$BP42y-!owH#(o=z?^s>0msrL0)$)D3;-=kMlPTp^&!5ZrK-pA;ENo67m0M-I?|AsK?XAh5mpXcHF+T$qhAU6=sGh^bQHtN36ErU4! zUb?+}j>1y{>pp1v7DHa@PJ%Tk+#Ni0V0KStt=0Y)D=xTb;4_9ZpB%v57PLfHh2)6d z3T3_b(6G{s{chw_u(*2Szf$s1B5OG=j1#YbLjrYY>XlMzXtV_xOC;B8!1mf&c?TnF zwdeQpxw2hXl}cpDMX&)DNCRJYByyJ%t!`1VUyB(H~}DPrz&OT&oLw7 z>mx}5Rv5V7g>A}7d07-}Bo6lJN2<0bA1fyjj}Yn}f{EI*+Fz(8LGf6Q?f%{A@8fNB zUfUaD^R9JmxVQAh%yl!pjo;HUKo<=*xI|mM7j+2hVshnvd}HLBk21dKDCUMG*FDPc z8eOj*?WBdlgGrlnG#PS6t#uxDf1d2-XoEa{Ey2#^q-g|VN!XcB00#_!O5itq zd7avL`HKdn5wIpSgMI+QLHg=EKWG2>fsIYrGh-k0)0=hQYsqG|{wvfIK(cl#{Jx;H z<2ym9LsEOmJzLh40SGzjD-HkaYqY%Ndyv99rIhzk>aeCOS&EUHL0MDd7lEo4O#8zB znI8+%99e60+Wh9tGekxjvqPNP&b@TcH~V{uZep~>4ZWc4RoyDlf0gxb{W8;ba?Ibf zz7rehCDz`S_&dGm`*E^C@IQUf@;5-J`60DmPe@mIH-vpwRx&i7bYGQGRC8fbo*Yo* z!qr#fRYQ>8|=?a*)2mWON7PuePUZZ4P_k5mtMPTJ{~0$2CAMKPqDIF~;{ zQ{?rEqhJrKTBD;g>{<{lIhX96k*-tDmv_(!URi0bL=Z*o^E{b=pD{hTEc4)(@2uh$Z zrnSp{jfXD1p#DqYwaeB`gi06o!JaQ!v@t^aases>E`7h;Y@%L_UW+3#)GoX(-@;9#4^eO1({~KHD;jIm1hSO( zyF~Q&W%iRER88#b5g^7^ub;TR@uq!$syh$nXsWs0Y@%O-^(p1hJtO#^4wJ8ErQeQj z<-p|`tq(3wK1cFIPpFnfM)YXj6ZrMotjzQf{_W7Ub(4rjQ2)r$9%@-hGRee;GgOsg zq>=voKCcGNs8m1utHeS0)s`2KFUXj# zd+tem-y}Z{_OmJ+@H(=5TaSVW$O6>rjLn5W{1^ZR4H_)jkh9;bW-L)GHewC5_06?32wdv z(lwV!v~AS`@B`QrXPH$$V^T_dqAUE`?<45RO!f3OUB4hNs6B-?Y@6ne1iwxOhD}+zCf@Z#aW~V?+*$3{JUwcK??!kFLxmM zhxvUmRvt9x&m>!fs(vgAS@_D)~2lzHiy@ z5+uAI6-yL0hM@?7R72lIzuP}pFJ~$A^7=%+L?rD%gv^mt=>V~z}>ap*_DA>?(e(zz4o<0z}w`3}_ zM`Q!CKHOl%KEI4hWl#+b%K#xr%EMboexhD4lY8V6pxO3FeWZ;jkp?>zJQMQdt2xoX zJrstp^Ak49UZs1Y_j($~2fBHK>}-Piyb@JSOx4wB$hs}=ttr8=wXRtsnP0u-{2?%f z(cXrx3NuRuGq-*%&%z5LploOEE0Ep!9iOb96TaX~^XX1(b8W(Z{l7_I?T~i?febAfgX())Nr*zE|Qx3Vuo3 zqGjs7snl4v>eZDkYF{E#Nw1Ynf?M3leyk6raY#6#ei5s?!c`Tva@g2RuD79xCoZjq zTW%Z<`)!-xEMdKYn>_2#rLd0;M7KqTM2K2i18^Ulf#F|}J{t#RUJCl~kmDZ4th>0T z@?|aE`yQ5(nY0;>GnU{r&e$AT&^O$L8$0v-()SPmKafg9T&I04tq+cw!T&DL$M;A? z?OLOP1NTlExdK!%T7E=}MH=>+4=r+NpTWn*tJ(&Epg8l9z6MkY^$z#j4q)3E)X$f_m|-_|pGv!kHr<_r zS}GPz0F|W>@@wRWV~rlkjB<&l)#Wufs?oC0w9|+C7G^uMXx-c13a7i(I8Z+)brVnt z)qJ=W_t7>Ftd8J_2DZgXP&b7VH8m-)?bW zN{z&czOp~*#}Bx|=Rax9l)2}fu9(M9Hq>VHN%wC}9?nELhp4m2iOj-fB{QZxg2iBT zO~V<(Ew%Qje15=^xtB{~{`j_?-9HWgj9V(9CYS;%u57ab_$BG9n8g6)ko`Q<^9|T5 z_?W}i(TvJA+xk|2os}VYJU&sdFMCxOPUwuv)7{-|T(!%4Smq;X!f)|5z^27b%>XW- zhcm7E<>MazHt_;_PNtI20wfvq8x{6S<`_+fnR#w%31aM#@bt?|tLT~$E+6jsN{d&X zuZW^{iL<^A#qzid%}PXhmEf8H$%`9xZbJugRR(E~$#lyn3i4BZPfl}(hLrrl z)+Vik;}fU0bJqK7gj6Ws8qVqfA36R|!RlIw2&>jRBk1E}5Yy8pL>}s`4MZ&Yqr&~( zzq-LLFCC0X-(?*oA~bBs)NlPe;b1=V2dm&IQ`e_%y`PCsau;Eu zYjqkGT=M)e7N+?zhTGfeb8SC8;_dhl2srFxr@c+#8(!^8Wd6?k#jSP?c`X|@Pgumu zd{9d6wrtBAZ`39gX1?NaRArRX+iz}x-eE%*Gwf6CCibMOh?kF~7v)=ck@S4a)C~K& zHUJV{6bS2`ateE7R=tqTVywS_51u1 z68bfiTN_VBvnGS$Mt|h*}3pIrY5=`%@ zbgHeV2gNB^Nm$JuU*88RsR!%(z9jxqs7?NHzC&nU%GdIHcHv2;Os+eK3M-GRvAnjD z*UsfOak+ex;Msy|z}sSfQO+4~w|gXndB1*$Cw!ON-mJb5?O}ZNN+v60v-8nsE(^u< z=}~bP-mEU8e>@(o++UK3J7AB1m>in$JP-Powig>+ea#_*!^`#-LF4^yx$wZEiU$3Fk1KF zxWAlN+`TXs!aw|n51Tdr)P46lo@(-E=WLquQJ_@%@Uq88axly*^(M&Z8It1FEkKn? z-1D5@2XYVi`Yw<46R|+VXV%MJy6NuONd<^FNh>h48dis^eCU+;UcbHs%uIU`vTWFk z#vh3QhC)a>l8p6RiWj#l4`{ohg~p=$OI_Y>8r8pxLfl|ZGeY`i;~}}Gey{X6pPf8e z?uSbfau&P(g3guIBx)FgJJe$&@#jQ+eyz8Mk~E_SC_jH*=_fchFjTo5hs)Qsh$1d~ zDC}PMqU2M5{6@q7BloqICQUx*7MUv95G!z0cxue+7!o6Et+_pyb3~d67S-H$ZoAG@`io7vAz! zM7yX}yJZU)#TmMDsfD>0jJawRjJIATuBm@qzU3dL(I+Q7wnv}1<#f=iPVisyz|{hF zkV3TmL+v?L4_2Tic(yQ5#^fU~7_t0IzhjwZzQBHJ=FjIqTGhigsCJPR<{2kpRy={71LXI5Z6aWH*Zz^*O8X2_FFqy)2TfF;o^cv(>%x2eH~;fUCcGtE-D#HAx_2J1|JuG0 zd4!jFL)y`*V_Lte+_ZY3qRgF=D0NXhF%UBSwF68N<^#v}39Q8ZG&kKtT3%tzJu5{> zBJ&308)}34d_A}CF;vIT>4Ez=@}0Lu&m%O_WpL0w$EAa-)LXi|izvzU@2b8y6=UA`$HH`-eD#X0y>JW}8 z==}9f@M`&GHPRU}<%X3~UK7MID7gZ$4VmCRR!zM73qT*~>w_oAt) z_5>Lu3*o3MzL&^<)wcRAM6oN{0B0hJzY8n?JHQt5D9*L6zg!+F`gCgXGV%1T?+UAx z*65Wlzu+a_+_64|Ij!~=F-*g=HcBZcye0%wFo zdRM|#mL}-n#3c;d{02~iJE9?JPr%(T;b@|fx~zUbgoP=Z-~MioG8NrYW>ZY(bND{W z5|ua@2gB&gy!-xeQk29!9KR=czP~hBEOKMqr}b$pzkEyD55$!kN}ZfV(hbTo(wUH6 z86p$zt~3-xWq#x4C&Oz~EpI?WIJ(dP)A#UJ4ecRhR?9>@(b}@dm;MSDV%mm5HN?kk z95yA(5ZEC!w_v6Xjm}AjjDpF1(5J^p@x26exY3c|EI7}m{XWCBquJj#;(z=s)7PnD z{1R&(d@wE2{&a8>f;yEa-;LHG0?&k-1YRKSaYI0f5jIb?^(6DZ zK=XcC3-iGCc?FTrlgdkZ-M!*yLUEqHa7%BOLw2}FsA#>&{={{~`t{0R)R99h{pw3= zDr8Ruy@{g4M!1Zop41fFp6jM(0*YpBo$8lmD6fmRkFm{lezy^Mdf#3nF*cLaHyG)f zP1}r_g8n=H={V8n_4s_KANdus&wZ%fiv%X~=P`ZI0A%l$;!-+~`DkL(koRC*vj_9{ zC{%w2KXS7|BMZ`8EJxICci$5IB{1cUzo%YPyrFIplCbK&X|+spR&i>bXV|)zv%wX? z&xlAyg3B5=zWB$-O-njIuE{#~mI>43c}HV7J>;h%pJnvN{4`hIIqVruNEMowy-RJN z@uoNWZ%^`b74m9|ywNWRQUGP<=kSpD<%iz~wJI3SVkRt(A0=S!v_o5;GwIT3r9TUD7`~FV0!#n_!?LAoUVx<{!!GezA8-eE@YLTUT9r(Pbu=ruabRbuVuo`)E zlCef|Bc(7Sh+XP8+7}N4#U;nOykIxBbf9&hD?x*7y65bvk_|k}y;_j#cxEw=;E}4% zH_|0l4_qIJGJX>|?au?j$eyn~%6?YA*E?;!1$G7>nu(&2fw+An*mZ zI56{V;-dk}s1`eie0}bMMG|CX94GDZV7km`Ah6cBMp#Ee??VA(GYBUF+AXfIe=Ni~ znwgC68hDF%tM)C=NGbq$^kB3&t-NkH#d>=*uo2|#iBAM_B%RuoPJ5NfbE|f_$=dWu#T9}HjFAJ{dahLYy_1MdI>(!W~ zY3`rFQ@*m^p7Vm;?Ksm=&+`fF>TA&o8uJN1Yk-P`rUS$D!WE;RRr zd9!4G&W=ub)k9zR98ERZcTRfmr<)6>$XplkFrJhMo&4Q(wBk(@q=k~A3<6nq(?Cd>8kjtU>%o(N%TDZ0Jh`ddLQc4OL=<1a;H#PcuI=jxJC&gc7N1v(^#~x_qw88REEtwsVOow)$cbT?h5;S*E ztwL$gP6G9jx&n1S3dft4!|w_648`@_ssb=Fg3-|Bnj^+-1~&QEX;m-FU4g#>~jbk9QVqYDjac!s7LkmsXV%kJncabe9@7RrPbxfE@%FB zNEV&hQ}vVhg*D>m*v2|7cg*KI0S1-kukaE{hkfVJpRapkRhZ2h8VV;UJwB)u-)~Mh z8$z$oQO}!VR;XDam^_UnDk+CyX~>MK0{iwB=5`ftyk*HriGwrb0%TJv+2k{A&S${tSa{wRPT4?mBK}lH%-&;%Y(<2 zLgVOLKhZ6v)WW)n`o7N|`!SS~jD%Ckx;e?y4&0?a@|SK68r~Ja8UG6iMtm+!oAklV z@6U+tj*r?5URJzLe6`&kaNc8lR?VGdDQMJn!lJ#<;$?ZGYJol{?Lznq#p;n?|efz3U%m?4DZ};&KRz~)EbQsC2R4Tjfy8z6pc@WZ4=IYBQ<-xMgisQmH%7wwC919{ z0@Ra02=ST6^Ws2No6Pl>7TmIDaFavo795H>v%J+PQSEj||BFai+rx#^s}d-Gr^P~& z#ycm)SncO1nf|48b+p7%;4{BBpSqV=>;|f|(u-ppwqd~mDv9_Qru!BFF^J2Ht0h+q z1#Mru+T2%8t@(}LMCW5@epL=AI0%^c>Pk(6$N>r4dfq@z(DJqd3okSu^ig< z5R;jsJqZlp)N`#l)k3~w?3a`Cscbm&51qE;;1?v|n95SB+wb3!PUC|{c}04dN*MVm zQ1;v4wnlVhiNos)-!}4qPj#X0NAWO?lulBKlPx2R;M_}}tvDS21$4~Hfa2i8C z-!|KhP>JhsFW8X4%*#L`eXV`W8||P-9Q9{`x!4d9mun~D`*l3>n9;uh zdQfQc30xUk&6HNHV10wfJb8J1b5i2|1poZ^x59(6!KY`Tr$A=uT(`zni7x=Wss0Fx z;K|7>&z=(01MGK?<4R~gHg%d-HCP*1;5Bw}jJ;NqT^;`y?C4pI^ET*V$KeTr_9_hl z_tOK8kUQMRhrSTk^Uo)IR$Jvqkc`lCpFucshSEPq3})@H%mV(Jl-$SdUa&Ww`lIFR4|GdAw3b9ZfmPj3XX zMUVX{&c>6d*~LA50)T?rw^0$t^Fql2l))x*z06NT+v@8#8@+w)gMtcj7qN#~RkEFh zv22RxS>}`zaz^R?`E4}719;u#U6F?=M%6CqI|GH}N8OXB%!MQyUKmyMetQq8lKxW8 zvd$bgG8+6Ngb%&XW*p!)6|0ypu|QwPQ+BeGS&hi(mTUWMCc~WAnoA~}llvL2TIp{u zb>;=q1FmEE$7N@GRbWptJVFrwKP@hgR zsmfm1gn}S>+s|TdN&s9}Sqb&|i^t*VB0|1|NLm8Qa(JLL?OtNYU^z8McsHDEXtiu; zv@9~7+4-ijHM0iCExM$5D%sozCPfKhryeQB&Ll`$@D_}GvkK6Qr1LliTVl1j#Y z7U?5I;#e>pa!l#)^7q8vyZ&B&Y{%Q`Zy*1JfLkk?;d=i(_4#z$?+rj7U%oR<$aJQl zvrdk1IReJK-&@1D8_O4Aq~SH67eC)A9z>6oIrQ~5BQ)rL*G&~zFhopd>In>@oC*3HIKHWawZU{@^rnc{k0ateK z3CjttMvaF?-z5%!E=U{T8@jmd@B6vLpWo9szbeEQ+U(SF6SYgsd-c|O_#~t@;gh42 z$vhUxrE{8ytfs_vSkpUrSXl&JPjJIfNS<-u5`X zqEl<92^Mr|&;cdISLcG)PJqx3#q|9wW$DI2lb>^n-DiolCCzafTu}9PvmMPEy+h1h z<93-MTd)gz0kT1)Wm=1<$B`DF=6Hots z)KA@eZS&JxHTCJ*WKZMvbEn?=gYKig$IzOq125u|^B6$n`BL?FsPgc8VsjY^k0|nT zmnGEnV4NX#?^hz7^}ipT+(twJuk3WxLA7ngKj*Rvbc8}3d-t@C5zKh9%UHz+*wFsXX~G^ zj$~`99D`t24c2ePB-9`$rIs!Ol!MQnjc>t>(|p|L6AqUc&cfM!JLB^04jW9E7z_Kc#^oZ$?U}`iRNjr>KXP1Oy_=iVkX`qzGJN<<2mipk?T&}t zn?+-TFM_WZpE|AH&0-ei$$0$O>O7ERcsRS?Mt9Uv`DTDE27)0SP2 zAF}ZwC@`^?YZE1;cg6(83-5#(U90!KYp{h&aARhHFr93H(BS}uawMdI>A3K=Hn5&I?r162&a{4H7{7;rX zB-N*`#(~gZ(V=Kz#COMhK(~gnZl&T4&4a!n2*}T9Cfv`Ys z>ZH`NR^RhY7w*5?2CIQ%h4h_#Dk^QTpF;6?$Ltzjn(7-8yz)N(WPh>Uh>k&Xq||vA z%IzAHKvfN&(p|VtHfT^III`(Q^7L)J5cV>?@gX!NqKn%zb*dv+*f+1^-e=hHXp;3g zRb`=q2-^-_e4_4gCf{>Gy_-;)$3Z7gZa&JBhlKUThO7*80>?4=yzBS#bWGW?N#S94 z3a$OS(WP|hYS=gBTXcz0;scN9s@#9XgBqMVBTRzlBl8tW4oNKtf7eWHG%uU642bRX? zN&K$VR5+)GYQyWXsHIUc*+0>M=lOt{BIW<(U3~Ze)JEC^eaH=FbB25qo_w16We!oA zDLDf-n-#t*M9?PaER(|d^uBzctbmubFT1e~{dJTCD9TXnFR)T3ya{`bLZ#;(NM`#d z#br*oZC(+WaMv~eHb{yNzy4+YF1K4>uvPz)GC{jQnnb>zO3L<^(IPYQpbG>XK+Sqi zaXdRRgmH82h~V%qaZ8`{FL+N`B!@q&NYWjy7zn6ul}a&xlqZ6j#XojF4Y^Ba+<{C| zEW8O0!%ia)WTO!JDTSzZ-|k}tP#XN1%+1X&#c-?MOiE>Ie(+RO-n$i7*fx|a`K2X zH~VY;WVhN2+R>$54hiF_A_%bE_8pk`3IK83Y##=7JKtHlbtn#t-Z%wss75wq!i~iZ zItqNV@~mrm27hyni8#F(@@2;>Ej0_?b%3UXfanow27DHwK4pM-L%ln{eUK^2>va65 zP&d$QE~cvIzfd0V$mQPO_~FSP+52(P;_b6HEv5G%7+DQaP@jW;;N72yw16v>T`Va} z<|q`M>^rvSeS`A(n4`h;)<5#(9Fx{=#v^fo)@9-_LI(q}+$YJO+Bs)d@M1&r(a-op z#D&>AA+WCreoKYBOO~_;1*s}BDC%$9A+C&HdmRyUnaGk@Dxhufix%+6`@ zTPIKRIlktPYXj(4MB?i#Bl~e9?6Nud1HG;)f9|%_$raVCu|8CuF}JVOuXaH#KLr|h zBU1%9=V!>D-bO@6t^%REOiJzABBtLDwD{UGJj9*LZ@T>L$USiGW)U- z9i}rtCe-@`4iNfv%lsLqu9d{m)OFma1M$hmHxCvtkL+Jk z<$caim-2D?l!4D z;3DoEU}8SyoFgmTTFo@IA#OP{sT`gpn2xA;c)+bG6w z%RHhRo94(h0I}t|S~V^@*xv91tra*0FAB=UzlSNQ-}G}F&HVAa{>Dtsd~1!ErDo3! zfXJlY6=a@M={)=3eL(}JhZ->sdHga=t5k3aI1{h=04LH~qjQy+rC}Ik@vnlrpf^0r zJ$*wo|83G&94vr;?qOdk7!n`F>F9(;a=p0$)ttBYOeNr5zPr{f z5@_|WC|=0g?0Nd#KF9;Ri%VVi zd%pQ;Oi*L>W(pZOq@m|tJKVU_OGO~WtJl2Nj$oAOUX(qB_kb2x#{-mvcP@s!?v8TW zW8y@EG4CGV=L2N!EmNxN8@*!SG6L^)|LE)Uy60ARv@hc<_!1r! z!RkWCJvAd$U?cCxOPh*)2RyGQ+`ZL@nQSi7GwlZn__q$FasYau-URspgZbWBIXT^y zYjf#O2dI55A89CL*ljVGb%P=b&3>rd&{eDK3V6>#x~kH{Z~uTHOi+>#i-KPt*9>ok zLH;LtSY0&tckj*lck=qx{|WFF$vs#fR}Ba4fz=(D>XOol5XnE_d2_N7j!sINgO|Iv zO;}G{NdymyanN!cmh}y+4&+m|jVK9wO4_PD$ktD__noId{bco~QUhg0&y}3^(n1U_ ze+E|=T;x1=@u$|FQ3a8lwCR?8b$gmD&yV6W|DN}@8QfuC>lGf2VLP|TIfR`EC!t_5 zG7?F6GU0( z_j;kP#n08HP1fYmjQiz@`KOs!Ok zr>`v4E4LQ=ilZ$A`tPa8emRJ+7sj*Jp90ir@l5ptrk{g|>3Vjq_VM<&%2mwJgE;(y zd?Vq!;br;BzCw+*ZYV)Xtz(~K6aRjxuLD{~wf4cVWnGm{-F^Y3sV%89VNee#In<>` z6_k*e_l!1LGF4Sv(@PIFZ@x%68O4wGX8JQ!$*Y(E4}>8bJ76d52c zG3^yDwf1wVr{W+6_0K(DWBdAOAUOwCTAag*`f@?v!|IA&NfQ}{D<4r=_VRA&vbg^s z0O#>h4ZA^93<+OY`n_}Q)~U~uVX)r&7n@2KF~tr`fF|yVmV4=QMSEN^Atm&G`6jK8 zjDFn%L4KU~a8q!_H9rxpc_@Bc_f^sYD3(HdFcuUh>VARe!9;8pKPzX< ziPRR~dv*+i4|mUBeXeRv1n-?RVGS(eQkn}K&^&-`P>!5BUFH}p`+LhG!~TfkcBSr^|z7-z_W;B5{5z`jN_x78sUY$4S| z4sIw5#kvLSa$5&b4H7c zHY|WNW2uiB1rFVd-}}1a5gio=PZ;o3O_q>J(BAED;@;cWbg)8{^C6LNl=<%&GC}p` zAgm<#0al^j1>d_&QSg%7?W%s3>}hvG-z$*1CK1I&c;XU}-(=Gp8aDv2z4dl+npJL@O>VP=*3q1 zbUF1C`~64Kd2J~Q1yS^u$jBp66eNfs`Ua8&BubF4pF_`DJw4qmDiZ3}ty^cGKVclu zTi!FHQ6RijTv~TyPb?aZ++clKy^|rT-*2}J&g-)os%|>6#-5Cz;St}C!pusJlm!Rg zebp37p95GQ?(IaRMwwaN^Zm6Bci+3kU8|7kX}$7rJAi)=)k?)37BEddi^eMNQKb;S zx(X~AwEbEa)I9z~zmTX?Jest9i9H{J)OW4hqW-+Q8<=9wm@n(@8-Psy3^aAVZa|1o zzau2Iq+SZ@X_`2_pu(`{;XE7Zzu90H$GsG%0l8}{2G0SimCo7Q>!m|GqqD<{lD-xA zZ3Wcxaf&A}5!k(HO4Dcc`LKUo3UiulweH6tlM-gdjiCL+`8j%pEIa$4iYDFxD|qF? zP&V?7c!|bYru_pn{b}QoCYdI5>r=>B-_uu!{P+9UUVlv7BC*ZXr$V^T5oKw^JB-jU zV-EUk#s2Vk!D5E=k%TLIJTy8T67dnRp3`6LZc`^gAt&hpz&W~oBj%?*vHSrGpkbCx zzP>AMGJlMjJ^Tc}ug%zIvfusA{vL=#`(F3>w|TS`SL6|f7VVbkF6M3hKEV%t{mNZF zUSYv#7x$l3iSQ%iQ6}l-{`X-0Op!yHg%%#ajD%|H=Kkyf{x{><7+ktCi?y3 zVlpK=ylBHLro*rS2Pi!ViXXKN@^8le-d^h5A2kC0jm2IyN6VlpAYtO|d=0vv85Ymb zh1+dvF;{ooW7qe1y(!1>F)#bFnOYvsY{s>}es^@#=4+kn+)+5LI8NFpL9?!Nco_FP zBw@5#M!4+J`7xpGqqyDGEHZ|s==MX>9Q-u8w3iT6u?g!o!Gf`+vH^-hN8%12(npNY++_9>ip6^zgbu9J`es(a)15*OV z6I^ULU+wgD=er5Sn4kwuN7L0}ebCQ*X0j$VclL>IZJ_Rz+Kw~=w-nL%2BQ$ELZ2QfRqhRP>|@9jjIe&- zaC<6^*Yk03ZW$W7P)lN?GQQobyS-MElHrUe|5i)_O>I2cyxc^jferfV!2Ye7y?KQu$Z<9!T%hORx5E^O)}Fp&}edgsPMSj zj|}0!$+!a&>29-`z8&|hSi0dKzV<}1co?s5N@lbRS(^=7-v~ho6H>>!O*b3@Gqzdx z6fE1t!pI=9scNqGQMJ#VrwSL(keqR!zVyzu$jkai!SUfpeJ)K4i~Hx0pN2wo2szH` z0drY&)6q~=()tGxK|AXG1FniN``hSeb!AC~o+qBX$ZT;{Uul()f2#}q&l=^lJA~g$ zzV=xci6PIe7OF7%6-`0xI67m3#jmfA*L=$33-^^aZuIQAMid@I?R9J@;f8Nvi zO86?cN5fgzuaN7^yi@tcd6b{mJ4QojSy18sGa?DyyZ}(TY0$9g3i;i*Hu=D)BaS+W zjRRBaN=gmLnUd=)BJ`A_P1se^*LBC!xd-`!IzF+HZhTO9R%@$euPrvIgGEwe+x^Vp4a(Xl+)Z6-eVKvjqZXom4?qjcG zNn&}k(mqA4%ik3J(L-%!n9!!F%D1+Ut6p0Q-U}))Cm}S(;Q%<}@mF`Jv^~DF4 zHQ~J0IQf3v=y6nsniZ`HS+OrixGM90Z_N9>(ckm&O990<{q*%rjD~#HrFZ*mTF>H+ z0hlyirbQlbk}L@^^TMX#k>egOWjG|&J$u=?dXum2=TZ8AcV<|q17UeTDazI>7nXx>Ud# zb-1XCd4pMQkc;32UFhv`-P}_Av*FO;HaI*)}LKy0_{Lo|E4hTNt;Fo~*tcuC1$ z_UBtY{faXueiCQ0r~uF^RUpBeGiuDgL`cR;{i~&XgW~($p4nWCL0cu%Ig{n-c-e?& z)doBja4@)VO6sRb$5`7oX%*bxdk<;4U!_N^sH;IDtyB7NRw|SJdS(Oc(m6n9ad}XR z@_nH7?0ppHxy{go=cH`FI|P&|gjK4e*u4tawZ~ev6vo92o7Y6~&PDPpI9{{3d?cSN zRrxZ&7X`lnwR!MD{(#!fWzziCd@~q}Q^BQ`o6qkd8$-Z>JN>x?x>iYF>b6f&{2^lY znW!gTzP;euecF?V%JRKX4z5aZYE5Ey!=x6a3lHbP_*m7Ed-&?1h4P`FN&|MIsPZk- zx)#HUryU5y9=^@flho;`|H1RP5c?#CztC%frS`msNE2od%IO%SfP``J_cyKI*ttNi z*{$c)Q`qjDt$A8hPEX6ub-z=%?#iGa3$`Z#7UeWv&Dm$D_P3603YR_Hdg%8<_0$Ow zd|K|Wy9jJi)~ip1^1*=`sjf8z8}hM55Rka84`5Bgo?9Ot!uZ$A9&nZVf%1gcwipcL zl3z)OuQ}J!rIf$;eHDj}Uc%vRCS7@t#+=!grG!$66e8}#T{oh2Cs@ZfcNV^&H&ctz z0L5LEZ@%XRH3;9!=fHsARZ53|>w>NFPa-;sQ+M=o)Z_oG#<8W-!otuvnYTt+oc9!k zk82ncckT;Ph^FD!{lKXP^#wi(v$ zD34x*8k2O-p(5@t_CAX4xg4q+RHgp4W1|VhKE^70q|!FL%FsC~*(-kDA6dzD?xjH7!%1l8}8CcC+ zA-7-Dd8!OdUY+xYZ{EoHwZr{c);3QPG-k`1kxiG=3yXR4FG^!_WfM*~&{{s;DZ%Kj zEHrKp*G2oUo|mZ2Rfcu`r~{qNv;Wep;FcXUL zW9jFc;YMP4F)|)%bhtCyn^aMsZVQIJy?KHEBhU*hM5!3dY}Cu%MGpU_GXOn1G_+rc zXupH89*L1bW8gdUI5#(eZya-7nprLGz-Pl`0Nd0F+P-3Uw7oQW%X#@Q4kKC)LmH(C z&AdTb`;cCVd1#j0xfCVC)tNc}PK90tr(sMPS189kxd?w#;8G^!(A=-%^CLLd=f_g5 zAp;Y=TlNBds7pRRTkq+cc7)TLdi-R24zd}y=68m2{A{#YcfNfiS}rrbRFC7)T7`KZ zz5`4h;$D;?lsZK>z5G!FEPdBr1YB#MCh1Q19LiNwM#`Wb=p696e!tD@!*IR9dAhR0 zefSY6*1JRK-@m#f)w52r&^cIrlop1sOa9i?oNmf%a*LG91KsOVs+~&s#K_9T5CtaM z8hk`D^r6U^it>+OSpk?r@BI?|b6X2+-!iA^hyM71l9lKd&vZRhOT9#b{|L9h1_N}x z$jf1`qUii8P>*To@pGZvE%6K0V{$f)Ods)9ps3=3GZskn`dq+Wz4=_<7=S}{gXf?P z=>EzRQ|dpDNgh|Y1pU4P!sc7j%tAk8fObX_Md@s0{HY*a)TM@KzbDN65kRjSN^PJC zk{OfntVY6w>I5Eag6g~|_cJ@FH+aXj-w&PDvm@}X?K}6$8Mas%)ea#XoYgDyy&dcn zMePGCM6d039)B!fM>A!SyY04QKDQs&!?4FYMo#KG%@6RFbU~FTY~m2zdhTTu_Qt$r#m_v;;}CXa?3wjI3$Kp0?(S+;$1S^ zwswU(GH(e*SvlpZ?>!y}4(8m4q?T4VQ^smIj|SVJ`jkQBdp>l_o}PKS%Tj#!b+C{# zWmtHh9|M`ZLoAx1X5{#Aex6nD@f}fpyApvvTVI9c9=mk`Y#Zs{@3ee?x5(dEkaR&G zjJpr%7GDx}h-4P+<9Dm?GIiKpJm~N%cF#Nk?dIA;&dXO53mjvzUS7XJ7s8)$3HXo= zt{J_ODi}!B0m=dfukpI~HIJb21+A=yX``->7r_keJt?`7bMsIJc-lt~%qAbE8thDZ zhP>j5tN90iMMq2H(9}`n?d*j?vE<>f^ES`^hwqH8X0NQw(k%0f-T3~*g;2*Zizx5k zTd9OF0?f_M<9d0WRf4k`?#ZnI0;)7p1UzLP;#K2_eHtTm+id6&^8t9Kb``@QI*iZK z!O)(w&Iy)rbQ!d&^7}ozKOO&-?>7+YL*?<>J9^jx%tCZ{*K(Q~xn6gR?oa*sJA-d` zX$9)F0nU+$*LrHl_3Yo+g8WJhLwpwl0*6ljtr7^}=sW51SfyP8ZVzB4mv1yr_Hd`! za}g61EY~mhyIC;Lj}m`>F%)y5PUfjre>b@?FMXS+q&0oMCi43nq>B&C_h2Jf)k9u< zUo(9&?B6y12_+3%0)YtcZ$7!X3l4#FLfLrxTy=PGmQ%c&w`fZ{aFqVpOBfV!KAo{7 zhQBuBzB`{#C7e2^Oz+ElF+FV2J>%RBjeYX=)4di)v!U-}lkSncK=;xb_^cQv4fUyS zuGa_yY~#+=JudH*7%#r%{o40?+egFH1Z03mDFY;geFnp{BtdM9Tfc6?0sek+2 zP{@$*rrPOd6oyXdm}?mIowDfaJ}1n3&wz;LdtdkFe66RwXE%+uY=Hn9DO|&3Pi3MO zilK8kM~9I63y$%jwrNg)=?9)`Uz@W#Zr$;O{&~**mixt5qD0mHmh+ISJ6*Shc=8~gO?!+NW@El(-mupOW7daOt2He8x}~;rhP`0o?!B31lCmbh<|(7_}qCy z`~~QkA1_>P3535nYRw$rf*mU0kkViH73s~e4|G!=)RG(>moZR!NX*#RhTKzP_iGMS z2&wtOQ<2*lCL%Md?gZcu=!d5U0-sRVSI=J!|{@sJZ7OQY>}f z6z!aNsp+}DV37DPW+IPIY4`HgeuMIjwr0DCPiRcV&B;(7GT;3H+iIq%F{ji5FKgI8 znk6g$1x;cm!$h`Lw5IYm9z~SOsO^R+-j7Q%+?R^JFd_GpH&@WNUVcIRDPC{aYVx|~ zc|t;;yzC8-D#F65!j;XpsOP`x^5E_E)*h#J|Lg;*)7XQ3@V`OSt6kK3P>xsBB@ll! zQ1==48ZWK%c37Ekvr(;)t!7g8Q|5vhIm(@L!&7hhP0?ABkB|Q4J80H~DS3N{yeonJ zluzBl_w94kxz7i^iyv;RFkR3kKa#ZhSl- zm3Te8y(Jz*P7-b?)#tF}5F6*f8rq~c95;}eOybLy9ii^?MgQ%xtA6Sm0XpCQ$@cPc~XYw;-qb3OF>F5kYV-f>B=u+u!zN z+^;~L<8hX{Sb7BZ;hh)$GLTQWHR&UqX@j~S`(LPd*YZ!2Fclmi*~ghCsdKJp2J5Q( zb@<+gUZ=#+BVABV(wJMr_(&-CtlSFIU{+6D@WUa|9_iS!tj|0RC8Hu49zW+x_<2=7 z?}pCH8YX;bfd`)`qLeBX84lHPU<`%{^!Z+@+Ad=#8BqC%B6OlAr`L?b%-Wmp71{V#9e+( zU&9A0U^wSnwyC?w#p+5_O%{bY@e=)*ik_k$~xePn~Jd_F&# zCRA+)m!j5)#N;-Vt+T**mzU1>_ZyX5KketV&H*;pURPA%(%~2|{C(2K`R-*$0zi@& zs2Ky*L?x3Ka&e7Zphsh4iQBk)4LnzBDK@l&;2x2FIsjD4ehK3Xc_Hi=?y2AAkXk30DPO{qp-~Ev%ukpUTQa(-y=ld&|S6PRerLXoLX>m zc^x70QZ8U%hI=F^`Nfr3?X?+&dih%VPX@WJw5Bt_3QQWX-1!D*`}PF#3)9W>nfi$y zozN2>C~7Ld4T}#NW-OxRJW=hkfZIQhQ!$&D0WZD?rN-KxTJ*QW+P&}Czc%WRFFOhe zIlE7BCnT_HVXJ$z?>l`(So~tTtDW5R`mBO`DY_1KU^AwKz2nsm7HFADVn5y#culaF zdAm&W=t^^bx)@lz&v3kkkeI}+?4HW5K4i|k4{Vyc$S?=Hb5J~3 z|CtF((fCZYdePtA?~bt2RkD%X4o!bk?CyC2H6D@#>0=P6?{U;&4~6mNhp3>%ZCK;K z?lX9d<7wCTc6ykKo2`(gB*D|zix+sDcU3O$L-=w>z;-w~K z*oU8&?^$|O7$Rvsz~gT*qMfvN8XGQ7-k7#tW$Z&XU{?NZ>xFYS*8cYtm6$bX{;Z!P zRF&)PoyALCw->g{PG2sv871wY2T=tC#0BO~zQI z)KKiGx+!{NAWkJb_$It3N%{lJV7nJ{jAZ$98dvFqPRDa9pIf_iPd$aOCQYgk4t_#j z(tV!*55loaA&!Zq_1Dr#tQR#npfh5<^weI)@gRr0c3PtK4n)%|yP$MKH0A9Jupi-n z1|j|Y@>4G8kdeffl>FFDIzupcJ=?DR%XqLx+&l4sEPclNjlab&I&n5`WH zcyXwg@NIwZgNxd?h9xVaxYqp%>IU_zOX_7E-~6GGZsj%ozNH(dF_eSeSyN#Had?Vf zs}&FZ0oViPclzk{Z(6uj7{^#)z;L-U3yW?^fb{KQvXR8UU^K433GPj=`whC_pJHM` zSEGR2-1l)tlS<$2ce{HXhTB(Y%eAWE=Nwo;^xm%MbFm}JYp8HMiWkh-U|NFJqYD_R zAL;rb?%}cdkXFqRP$xg1c%68cv}j^A+^}{@FVsQWCvV#;0NBU+wMS?Seh=H%l`Y{c zWlY{jo|yMiwS?BMBfN;vwYI+ur=qno#Muy?$IH*g-*%*&eFzYkrPYW;7a#1Sgdg>A zjK=AmqS)0^Yy%3apE}`V9es^GmtoeOmOT!YXHV$7{rT>=To!H#m(@itS8eR~{F!!- zS^U*1hB=dldBJKXmmL)8z4#oYkdIcyikkdBH1aj7imKm-5;eui$N%_>!Q?Rb5SndbYygQ1O@!2@^LT^nc9)b?&;_(JV9(P2~ z!+G+t8cMo0LITpG!#XZy*bVCC z-^$u64EaiY`pUyHCiiOO+v!cr*AfboZ2;zmdnp7m%)%oD&O%$(KRC{Bzl`NPwdL`&Hf>(HlZkRs zUoHl`RqDg%BMx7R!=TPe0CLNXfdhF?aba+p+lUakK1Bea#o@pEmtGjY! zabxAzV-H#cJTVWGl>z4TxgmKM{ALMC?%bM5_2Vk)uYR^3Bp(enU>JU@3M|#7+z--8 zm`0%L>0vGPBL_P{ZDq4(5i9{GCFiOTbF*v?%j;ZhzJt79lSzGr7kwwquRTNb@bCCk z+p31h!>RwkMxuBVlqU&|PO~jT_E=Wgdr-o#Z(Dw@8jt^>3x!?f_+SA@MG=dhuNt9v zsGsa{{aoKMgy9E#;cCie5Ee=*H-({D#(J&vjnhetL^O z+U{rb?=s|Mf#9BzT!vKe*HxBMH`~6|OwpFc0_PjGDIZdI2u9p3F#4u}4F#tQ(8B)s z9Sy$rWZqBJzLL9SWryH)vw!fG0#I@+=A)yI1_b+okFHr2q~-gWo~w-U6i2j(tvC*9 zaPNz^WEr2AbiW{5IP%s;&}T^IArq0&?vcdv(~Ud7hg>V+9s{SJEsMp^sv z28XCjOkNL;{tv*NTYK^@UFng**Fw5YZ1QOP0Q*OTGXDvU3X;{O6` z&e^@fz&2E%R}YUBduw4kbeJ(v3%U_={?1*k+TLYlc^kzU`I?mM2bf#p0@3xWKGtSc zJ{ruZrO5J_hCiL}Z*%njWbs#1gmYSks;6ZRjoo&Qub;n{0EvZkjp=X?5?XIxP?2~p zmW?8VehJwZ{wx);b=i|hQkU=A<#(3d19?ocM_hpSpO$uMYj0+?*QM~LALVwxddfi< zGDPIN=i(IK@;Zny*X;K9O8To4?at~5NnwBBi66P9&t8Q{AX4sJ1CWVe&BZfXs}cam zPFC{!1*51sdkBu0tg=D^L~lEH@6v`k-@7UI)ayw+#_#o{@4A-$YpXIyxbiltLR07z zjZOo?FkdezAVB=c4imXGPz}ci0IDZJ*Kb1@!$@zv4DugN!Xt<5;V$_&gOZh9&f!r-;p6U zo<09*M9fhx?)&J5CxcZ+ZKuI}9{((!UdF3dIrT(+%{5n>I{0`^Q@uUCJA6RmsHEG& z?BTb8_PTqqeW%diLcGc*uUUr>p-m8@!{^TomB{7Q!s#!L0R8rrf~_0k@BW$R=R*Y_ z?z%7ZNzprd>_dG%?Ul!=#B%wZj1TV6qJdO9CPe3#`{YLwt;Bsz;(b4vh^>;4P{EVY z$D1q<0bk0VccU9USQ3H+t%}>28s0iyC9bvnL+#~y(&S-}JQxew>Ik@#xY{8X^4G?R z@n-^fM-DyJ2ceQSco^=t&Ut9{nXONNT_jA3MJY8_35KnnTETrLu0xC1|kBdjD-=_Fj=aWDFH^PsMn&#{tR@Sc9&g<}v z7}mt387ukl9NGg*&E<#RJG)-zWjwyK`UjfXZ9mS6^~Gz0=8)}IcN0rj0OSq)=!K|FVW#ue&(&j}VH2Le8M%Gn2Y^omaa)>c zHOSY3juN!Zk$;+kO2*7~^X$w31;OI*G9X1$Up9ft55H`W&X+c|pYO_ovn<)ak)<)Y z8TnJ5)k(a8a7k_Zt)L__uo~*o0|}1(6ed-zCL=m_9gUqMXCZhUSUSN#1Z9)lD+Eec6wn;=+{Os-OHTiHLlf(4a3l$}P-$?t1yWO|ZQ#{x1?(@HHNN z9_AOX6Tz9`abdo|YTn!vd-^HugDULv{VH{~gL9-UsWAfa9Z&8`kVR97ip))f>VtkLU%%VO+Z*x_Q6#3Iq&wIvs z@Jhj$Ha*FVe0`?#?e1jf&&6{N=O8r?@fP+(_@usHp*J#TgM;A2UYAqMqowA1@izHO zVK2>q2>QX&LH(;CQpo}k4DJ@h5Biv%VzeGy?i!POAUa7d2b+09H`MO}NUC*7%qyw3 z_ja$2jrpFlH0QanC-w!$r(_Qm)g;i|6vH_a4=M*PR_Cm2F)pHu*}7e zF`fTvS=Pv<6|!@w@^@lMOoxGkN;o5_7Ko?r-jd%D4`NqQi+RN;F8GLujl_F&&)2(&IKo6k}&1m}V| z_*L9zeU0NrecH7gnQr)IsTnyRq>0Uqi_LjlVlp{TKd#%4PJa3kIrOK&>H4m=e0aW| z85^IT;v9-56wrZVc?z;{DSZ9>zt{yVtg~v_iTFU#l5=~2W-{BX_$nusqdpVQabIzi zmeUo3i{*zlavye}odXPzBZp7RSL;8}Db=e%h#el6qa@S(7 zH9Y-IILGO!!W#eW(4l&L;V~#{_vC3Z_u*{!^QeCChbw!(wIbG50s0o0I4qFcn4~aB z{p<4EuPh5i+2yzInGVax8W@}(GMop0u+a`QQ&+oX+y&b;+VR%g!TywA%Pg^8@|fH^ z5I?*b*P?T9o-}l`rH{M~JH2@JvAGxq20m~>PJsbK53&53#UwAYA_w>2ntIHdTE)sM ziOcG-%YPJjaC{b3lSQ)u72w!d%L8mj>{|Ee8FuYaLirVCC#@Mli)P9N*9YvC`u%1< zC#2?G7sGX(TlMbX*8w%v1+)@87H41Rpx^-K!u$)a?XsgjQ{gDWkT_!R*+&oN1N^3z z&pdzkTafkxEKr@DU{h}e)=;A_guafBabW1=Q79)g319NB3okHblfCLD<{)V2vqimC zdCHyT>mh5YmhtVHZ*nzyg5o%Cn&`i>A(OrH_%e9Alv(3XQ0bX=Rzu5JKPx&2DV#Mp z7ah?xn|#CfgHpcil@GD(tHGs*Vo4k%?VBUcQ%A6R?4@|aV-aUaBY{(Xhqc(`JaIK< zky8q*weY|vM%!-$cL?sAC?d31Ap68YgvHTpF|jaq;C^dakb)e}B+zvU$nB_&U^gDj z`&E;!*}PQ%LEg)6bzhd?ou6&KkN<&A#oBAXIH(uiN7`rF(mAYuWgL3qi>18IHXpu{ zF@;=+W!VL4J&7m0A9jjm;=>$%P)e%%+xJ{Vo$!h{R4lz{Ch4(S3+KVO(@CAC0(XfN z#}L{dp6%slojc$6=vPy9#a`BuHjM{@hN%6Kiii|uX>C}P}eUI2rk?TOq|r`GZM@3dR8otDLk?!LOFpo%Ve|_5!a*`M8sF zr5+QQaO?!;u6)Dbefz$z0sDf3HQbB#aqf2oI-~fcH0eaNCp^EE4|;-$x*xfMRuE4J zMegc002AE5^h%$GOqorN{dRS4AJ%VWWY5Ey*wdB#76{Px$(fa#n@Qj=k>SG>st&oU z1#xUz@${g}z9!Ua&zYH671&0pj5jQ=^vC<8OdI`o6bpu!7NG4OXap(O<{O)#E?^OS z7ABx2PRJvbGJmWediZ& z$K$g9#ZE&V0|f{&mZ_{_g&*bq0>p*|c%*#2snL;jpf0uHq++3^Z>f8TO|+R@jz>8P zAh_Reh}y0pY)aEh@M5eUJ_WHH6Q7ukiPq?4&KpWG`n6B zm&S|p`#Xf^ec~HbC4akm&ORZVpmD~ zb$A2AU1O9ztfvO6;KSbL>l=)@9soJyj`fRVcQd>fW|9ZKsGf;_dbwBDOIZNSiJCIS z7BuYdNKY?xG+4(h2V2RvbSL&+^VSm}<{G(lJKwEg5%SY2HfC;|E{U>zWZHot@E}W0 zl&n>Ssnq@jwp=oEnaltEs+}jh4`=3liyh?(qmwhi-k#p@9k~P0tnSBB$N8|_{9Nf1 zaiSSnLX(Cf)@Olx`=6}YFAh_Pp5`UPhyMntOZx&yZ74C1huU9$S-v;)YG=xA*ZLsa zdqEv@MlF=mv8b<~zZJ^7O!I^fp$YyWVDgjP?b$Bb7E}C&&OhYH-M&$J_ayMOC zX|0WwgR$87H!s8VCr3X#yrDkYrXRoEC43GtC-*r-tD)W3Z>pozXQM(m^xfS}n`(r; z+#%IB-u4E!cG__AuWzszIZXMK?;y}nDgg3}+V}6r%oHX=IP=*8_cG`p8BoLmfEwBd zRtu0UNk$F#SfG_&gj}aUOuD~rI6fwhSB7GYn_?XJDVXF~so^~K{`6aZU50jMi@WMn z+Ic*g9Ce2B^~SVUN%6;K51{3P8NH`$`Fe0*v0D#K?~Q7LoA1_3W^dK&5%dKx7GE)^ zW2ZNjs^QhS*O^#U+0>|rKVk&K>09HRz5|K@ra_88uM zazcK*=4r&zA$|u6JAHP-leqI|A9Dr>9S<;E+32&Do?LBX7Dszd^dV4xethj?+j3JE z&5*^OE`3nxLy(kW^U1`^1xB0Krae!!6MueQ!JL#zCOXM^v~AyfD*5o)(*C*}-rv-K z=sN>MRr$8$-QSb5_Qj^B%WiFm7^+2gW8eGpevH1(B0aBX^{vp_`<*D?j$*{3d4_`k zTy`xOa{cO>`?75~zS6FGQ z@)6JM{H((Rwz0`?$cehlu9lXA)o1LP6!qLQK;@wavdfba$7Pt98DdDoss3+=adiZy zd^`@%+{E+)wpnh9%H4O3SaVkHo(RD66n{GYUA@vd(9O_?XJeVnCGqRidjFUV1oH$+ z+~a;k@8b2kABXjO{DqZwYpr}Ql*IMulUwG5dztL|38;@ShI;YU_FMD)46d>ty~k6r z@ubGQe!sneS#zo1o6ml*VkS3+p=GQooJiQk4+Ibs*3HD>dtfE&IriNMzmwg&O-nD8 zdN_9Y311up)lh~mJX+6ije~AVZt`}&HsLT_tlzkXWy?Xv2dCBza=;_`J(RxV5cO`l zE)KCSw9rXRa64n8r8^*VAZZTKXtgW@Jy8@|o! z{@t(B`@Q_$5#o^h+_?9Ai+yjY5AeW>>qFX-(-8!Wui7evwb_`D-VAb7&F+5kS8mAU zE&$1DEnnbJz8b8Z8nacMDgMMa8Gb`{dpdqf5e^<_4^3D}_mS=BoipHMgk=6gH^npI z(tQxZ65J7afd)Tu=t*Sw)BLPWAI?9Ar?V-GPoTdI2Q+Zv`jnEHA}(keloR{>gv`#eM*3>ZNq|akEcp)C0t>A2>8TwKehGkd%fLY_qY7!VDr{v z)5P#b$eP9b9mC6QNYIzxY}D4TUWO}-&wz1V zLwqvC9%jmzeoA07?Kw|(XpJT~{Y0Ov==bppD4-}u2Q~x;Da4vfO@%C%fF~i!UY5Ne zDRfzv*w-$#S?@Da`+koD{WM{P6Eu&`-y_IZitQ>7nO$ z^{z6;`v8Yfbcx)h7t8L+Q-N7M`(BQ)@y|$ukw0u-I|CM@WY=P zC;|G5mSO#LAZv<-Mf3eU(t)v`*~3W;&1q!E&Dwxw;kIMU5|%Z8oA=htA_Y~`A=2GMT8)aJ$Xi4YJ&*Sq(h=>plPa0!~i!*%%!+HV$GtGcJ-;_EVC zjGa!F^=rDTdJfi95aX)SVJx3_zX$R3wf!m?t6|`M;W2oJ8PP||&H?v5K&#rFM)$Js za}5bX=8rXaH-s!O6cA^(f(hb1?vY<=NFPE=nrN&K!G$;qozd`*$0LmC@@T5H!OZUE z(hd87rxMDt-N1~`joWqX>_h3Po`tn(LP(~ccvd8lwUigf5Aiq}fsT4f;Ag`POJ)1m zWTRyMbQSiTd|A0+qZU>SvxZ)!TWZ!iDMhtso=>RZVB79Ulyz2K(GO}9#}cL;XOVJ0Nsy2?GfnpJOF}b6z`j2&_3GmJa%5{J6J-Cc&`_0 z48IT&1o=sic)C6~63-jg&W#j5$J|wfF%a+l^}O?ketHDh2diU<+6fs!rHl0=P#>E+ z=zop4F(vqWIf!_aALG|OAL7e7#!sLbWW_nB3erurh3T^sD^iayi;2v!@!hnyP?mFq^-MP$AAgU|eLmCuK#3+G@JSBPi zw`fS5(EZ_E(fqWau@B`uY_(rf@sNVwD)(02l8d2(8zAD5euiT_6g*={jm^w|ON5*Z zJ|4yMqhBA3R^uM8&Mw#cy?`PaOG?rRqBUsKEn(W)W#vq8ei4y&)sOqpD~*e zmMlu)dWtAcDy4Q3t-BU6d<}Iq<;3(ep@w4BN0m!%`$bDHBmW>}pGeWj`m!uee;o+M zu^|yFt&L93^63WL%%<|@j9c#ofr>9V!+x3&VVb`90?H44ZRiW`F~M2p@8jH-Oi#+} z4U8jql`LxFXIPiU^Y-Q!qCblqp1nwa!pGyO`HTgzkL3?<&|3gku?VD$7arRXriTde z>$?M2ye{>)9o}fI9d-)HDjLGj`$zC44)*bKU2hlfa`c{;I)yRaM@*e!gOPG;Rn+ZE z*4aH66L!xDR!I&il6IxWyZ-@GA@n-iu$`#`Xu&6+?Li3x7`?pP-zU&aM#j`95*1ck z_(ex%rsC)Ul8G^^%DK|6L}xs z)~}KbA9M&B;ecyYI=3Qdkx!X7;eMDElUoswq6OfIc*LlHVT+t$_X*s(gD|D_S;vp+ z%+J-${u~!?Rr+^h7I!w$?kCj4a+conOf%pSl3^MX6>Q0J4_C7GBv+ z=12PlL8?4)&@I}Prdj(4rSsIHo#vJ}&BBk%D#o}!;L|t$F0tU}Oti8pVIF;r0FyT| zq1Pw_-tj)7Com=fgDypd4P6tmZGl$qgJWM{)^h&6W7pfGbMwMF5Q>Z}KijEmlk6_Ff>qJm;S)8W6v}9aeRfrN0ZMnr5_drN2`=Pe zui`0tN%{<0MOr`4!)ck$S!i8444+8HzO)JdzgE7eJ|5d@=0&&%hVZuj*)5^v^_b=2 z@RX!$xzF=q6y6IYkmbyF-hMY&Bl*Va@_rr|ufJT1_??jx0fugQ3M#+r&k+j8%FlIe z5#sMM9}&7V(TKY~d#(%ai`@nIq0C68o)-EyGGlSjv#sYm=!MwQq~>@FOn zXevGPj*}gMp)Ft9T~}?-T(_(cPly^CRK{Ted{g`G)fS?zuAvO9hS!X%ScYMf;fb%f z;?bQW)T6ntqOZXn;Rw&XZxlp2K*kOQQDm>%OeOn`5rTsCViQuozJ#}#DuhyRmFDVe zOXUq*QNvEY+meh+pII_CIv)xN%HIQjC_#$9I?kzyr2H#izBxK`l)8M zK6(&w%~(stX^YBV@Ht)c7w8Y-C96nY*h};p)?hH`OH=ksKi|PVl7>N&~Qo25Kj>{!dTcGS;qF?9(OD6lf?*&i<`JRrL=S+D71kmL_a~Y5k+Lo|fpzyc={_X!#GE-Fu@1ds=}fHvKT}6Th87Byd#osWR zO3n`wvUJ;^JT7`0!}%?Of{AAEq=X9yUcYuHW$$N{nl&^m`hXR%PZ|!yD;V!ndaBQ9 z@o;M^@Th+Q+9vhcHztzEB2f6pH=~)QAK7vI zVNU)g0@$DGfr7c2pO@=+4PhSlBnD-HyB>-X5-XFut4iT1GbYt;Wj z|40V?xxJgx+?1pcA;@?hb?Q!^(`i=J>66?mjH>Ri@3GQnE${#QeMwB4-AvDI=@}?K zyVS?0&9{3D={u-i>p!Qvt1P7$GI#Eb_@Y{_F7-W$k>u_l_tpmO@1B0|AsO@q^7ib9AwAC>B6^#0_;h&00XH#5VMgWn2o zX1b`v3Z!(0eQQun=gSMvHApOypm z8zHOu{C-4@sB!PvKfAqu^s5;P@4e};8jkB7JKWFETreK#_bJt1?%_O2_uI(=2PrMT z2hpCBmyt6v@{fAvK>|$O1O0|~_&iU;#}tggtJxWJP}6FRj&j}CQ~Z|8SNK77>7)m{ ztZK-;paV-q=J3iVsXl{kuUM*NLFtI_EeapA`ELqdt-p1pmfD*79YrOvLm;8LXZ#T_ z$QdGW>d(m~rAqTquygOUpcH|l z8c)?2>|NHoU#B8?bNdho4g8~{q*e;jxj62V<6HHw2)y|*fTYyk-fwhS1bN7B>rCwV z)2{P&4iN&eREFq&bFgQ!Wiqiimmhw5cBw{2C}_T14l_Y~Er>X&`hj;Tt(-ju;Y0Rx z9c-N0IBgH?ceHuzeBRvxxN@_2Z+VYc4o*4L+Q5H}^GluU+vQHb%cey9ec5HoECRS&bbBfv( z53+djdEPqpJr8r{cf%TCbmiKgdfz64osHg*)dn|3D;j+ziRK^9GwbvgJKh1zRlVq z)f z+&(P)gIK2SQ$bZgDiz?eNyR1_MsXC*Wzt=3NiQF|yg#L?-gYkynuPtaim|q<5XwSh z50WYupm6pP@oIK)znoT#>%h~QV2}m$IqQGw(FZ$K5%T;=fWFMFBJYc-2~Gc9A^8=IZ?Tb6B;xjGDB z7aHpKj^u`OiF|1R3zK`U>dRA?F5#GcY)ZJuHX@~kBdn;-C>3R+Kunw*@-)8#2+&ZR zw=|Zt_3^oWSlDG~ZPNQNKEdRtmM;t1+H~e^B*s=o)Q-) zfu~TIz$HjOeE*l82?!r=uOUGMQVs26F-3OF-i9keApK*10%#&~X@>B@L+f+BVLG4# z1m@=j&$wSN0R+f^Cf7JDD0n4Scw=jEzev~hmcvEx)PkF+!j2nqVO0Dreelg0i?O*A zfjfg@SVmykuVwopI%?O`BV-Hxa;&7dm>FO`ZJCRTTlY|>EK*%02)<}7!YSK7W53l9 zWopmu`v4ET&Pn^a!i&$>(*-?0q9=+rt@aKr{wE{k4PE)S6zq%5Rve#H2_cOKYF5%K z`{XO5@eo{CGu!J^ANy)cdXy3*g>+EZdNh3tAKre41_-F7i8_5?>#igVG|aeLq`wyn zP%&_gYi3~|ymP-J6A7)|+==N(62T|i4;i{Qd=UBj1=tSOUQeC7!!6~I^vHY62#JiJ z(%or2?^VSI{~Hs+f8>WqM^ovXtg3tpAJy0}{esZ+XPnVbEeEK}VeT^6;hrp8lk+fKkw5GF5kA>Pj{QyX|F7>t-zXr;YyoYY(FYWa%-w>mW zFVmCq(B3B>`vZijgwmVovcRiIC;rVoO<%iq0e}5?2!!gKD}<#u3Nl3i(AKOhVgz+a zuLual%I`9oakh1e{j6uogjPV?OOPS>d>}!?-|}~@>Xg%$uU?ER`*!-iGsMtg2OJbl;>nY8i;^GFE3S@Lqi4t}CCnNUl@DL&NSKKR=6DGv5|sUgS1E9%U?Q8dlg_1>UZsKUw(j> zdHyhsKR1ddS2SD8_X8Gle{sk5bcJ$2nNBL=NJfNX;RAx)G}NHF)4;Kf=K$_k6KS+$ z-RAVBZK<|aZ%G2yf4MUZjA6sMSMFS7B0uC65nZh;fvn`L!l7U8{=_VaXj-T3MGZ9 ze%o=P`(<2whf?;*Kuqfr_n(|+x~8zxei`;TTgyB4%POPZtV(HYu1to~eY@y_EDu4v_zcaKpKkZ@eMgrfL`~$2sHEJcH zBVmPxW(6d|C$ND5Q*)dIhd|oorGFwGbw40ZfjI?#o;J4;Y`b7kMI_(SIo|_6`)sx~ z9;_?40Gtyi`_4`S*S*S!XZ{HV+B!~$`3wn^Xf?&f!`tA$`{x~5d3@-DBNC4GL&+1; z!#S6CE9&C#*ft;S(@#G_{4XIrD=WHcc^~kzg30&iR$oVdHpEOu^4q~|`jc{mY!z8A zYenV|08GdHKHm0GXW1`M&s)>jDAhBc?<{t++T;Emmmt@0xEZ6jr{fiz{}&HMYH+l( zn4@IwCxgkRz7OdY|1!{ygUgQVc|R|F_Z3xX7Z5RI^iF@+4;`d04ys^qz4yK4Hv7gu z_uNy_mD#Bfg3^}vTlp!gx$ZEb$kfZ<#1g)*!@h!eS#B-xl5|a`8+{N4`n^=hlzvGX z0+5mx0NHUI06Q46Q^{eu^}8IWIJ}dFOTLnwvoClreo!9A;c=-bi!9rceOvUhkDDMp z{(MK8(_GuA(#i;Y?Qp1aI@rf3mEo59IjnD99VdprTK3kNoCvp17aAV}W1p~v7#EYP z52wnPPga?g59ZV=Q85oKG(i|sZ;oW7;TMSdqX^*WaFZF7LPB*&&X%g%usT5YG{HB7 zhe0?p{&;^LaX#gaaDk@u-s`J;S05a#Y~z+vsA*{=Q|6a;y}bWGD%fs{H$U^K?<3pl ztNWGZ`hsU`8 zSR)tAZ6T3RWVY1*01w|-gvR6o(_{y`f?8^n~?c5r3Yb5Bj$X73S=$N5QmdWh1Sc-T_g=I$1a(fRwz+C{g zYAC{a=s-?REh4P`fe#fzHTuKjfI6CWDI};C%Yg(V4(!%A-vV=6a;~Nvo=f`qZun<* zc#!WMyBSi~H$uKqzhS~g4)g2eV~b3%j}+IA^D_Q`MX+%`g^lz%6lLp5rOal#39nG! zBh_nu7abBr-8-ql;dVQ6*3+Ys4twS~l&MxR^BsQ09}_sK>6#+a9+n(KjKF8C`x}HS z^kwua?!mx}KpP}ZW%f{D zJoIEBx3_we*eWp}>l74%p!gv;P< z``u0HQzL^J<^u1mNn-ue0EOMw^i} z4Zj1%h_myN@Zbq~KY*PUk88f-8IpN_rc|s^qN|;iU#x$NRJeG1D_7_)PTo%OQAL4d zBVWr@^yC^;8u_yt>VAbc%9@Abh335ey%_6D@6*w-_M0Xy$9Q%YU~t+gdGixVxs31c z6TYWk|4vWE_i?2$e+`)i$)d>5dg*)ag6#gr5TVt<(>S1YJXa3MRV@@3!XWcI-O_z7?GFv=ae*cY0~qJ~E3nnkP`!;I z!Mw|l*Xa(;k-S`$*~;z_czb6L(N?gzyx;Rf5eLed*YQaraE(Y(%f_#0;*`ptnBb0U972VwOWYyTWQxyHL5c@RydOxII$Z|I z6+rZerYoqT^8FaP2g!i2|4K+OwPzR{e&@HdZQ(ChSFQBD>!kh!b{nvcso*PD|LUvv zHik7Bo7uxH(tR5K$Z=lN)+X*Zzd2;=i@)&U$45}z%EiuiQpT9M1O^rD<&!1x(#|~- zsOeeP%s!+2{w{#cwZtGF4anBL|4PTt`wDHS>7Rwb znFC}`u+C;9Qw(n%l*XWsew9j(F7Zk_aol~$?k2EP$w3Ks-S@M0{7X1mok|_HZLgcg zqV6zl3Y=me2&($LGZ>Kh%Q_*?864%~)m{d*y`sjwxk+z8rx{1={nN0Hzg)hJ=F~lh zr$<2aQeV8+2X*|zJY%3qSK!mdOB}!UDd^HIXU2yb0Vns>dg!0TwTci$^^p;ud;k4? zuUdvE@N!=(C50Ihdel~%44DfbnkUDFgFpXRl*B!)Zo#7f=idCS4yxI_I{XMY!$v1V z99k@zrBC}sp1b_CcOY!KK3?FpfBtg6&>!b1uK`CeXX~YrRhrOZc&W+U$Uy zqdkt+tesSNGa4~XLBPC3_oFd5avbH>uG%4HNN(< z{w|>btMdApY}%?kanaOn5@{9)f!FA$bc8kUIg`pEM^1*ZJS93O<0?y05u?z`S`fuG>%4q|KLGL#4|8yj={lD%pUa1Jfu^8!<}e!?_on z<e-hr@PRDuhvH_n`K3(|LgY zP4I(W=;&U1zHo4n_t>}KDunx3LB4h_}O2Wmb$*Z&IcODDt^9{R1y;F zHuuX#x?jMbrZGYa@{_$n%y8TE7}CZ_N(ZCHGmzbx9G<%B%~fn)9hEa2FaupoY+fP1 zZp057##`Lh_D7Az&o&5EC8SMni>$tL025FW1Z)__QA5ZWo6o0Bvzpnf?lw$!$}W+i z8U6!l2f`RX_Yu*U%31NnLq%jTjhYw0Co1V!J+gO!{`}&-=?tQDi&j)y-J0w+e=^+3 z(4}D-gY54b+D!h~Z%-VWe0xtulZ|DFhf{==*~5?RM?AA6J#Aj@K6!Ul57!l`GT<|$ zO~*%TXEvPrdtHVT;h+KgH=}WZeH&V2x*PU+U!>0S5W?58m&-`h*oR<+07nRaQY>^k zccow$U}BvIBUBC&=_I5&xuTGs7s4@>H*z`8`zY~1;B_t#R|Fi^*2bp(`BaykcDtUr z;AhU0V~*v;RM}i$CWDIO@iGJDkv%P|fjodn@*2w$9D~+AEGFmZSb0_VodQyyepYyA zdvZQ5nnL~HJx{|}CZlH$h>Xe(vHW|r3jkKbCp!<7PMSfpwBT?Z+EfqaSN>T~WN$-I z`V4wzf(2u_E++Hs6i^$WD&oA6RY`q8e z;kpE~`xcq@ir7xtE^>DVhR1z^#1~7$|8dZ9WD4atm+l@yz!t2g zFC00CyjR4Fb>aaH6JbLbBwoMw0f{#$=FFqFAgbx5_xWr2)ziIi!3_tE5E}2PU5nLuqUaAiG>6L)^cY=(}YdL%Zi^Q{HFd?bf zOtXF+SKHdF6JS_)HP4Z{;%fc&PG*54EHB5eU!n7?pAz3AZnb(L>?8lg*e329P`SkC zd#48*<$HTxmtg(6@B#5IFCk;QCVckm@f&?C6zW14zYR^hURo>af1XYaxg6tG5Z>UR z;D>Wv1ROe~?)z^p$`2Mq^QM~_?s8af#fMxgfoAsVw5vbAXSnaz3PXkl$^F4Tk1xcu z=}2<#f7NmLYQAS0iBai!)FcYYrrPg$yF2?mqLlOKQKus+JjY7+?PU2&K(GP;Xn_fgdTO!7p_S7L0yQpahWP&3s{()!Tl= zF-Xs9yV)Y_Co57-t+`!MN6$w+7C0A?gVm@Rb+B;V>ln!rcadp!D$3W6`^4&BmB8zR zKE5wLEs_R1q|GWgi*Swp_Dg}kF?wF>!%cb@t46Q_YNjQtD0b_h5b>m2TGgcnUEU3V z8(krdMbCdiA1Jy{^Mg9eg$*zea;d^h8?$-fs9PNt^N*dQ7Aceq#7vDVVoJ)C?LfD> zUkmjwuU_QymrQ5w>49CPilM{+zWB%yZpAuv3q-8Q)hz6pGUo4*h12ir&)@i>9Y3q9ccTHi(-E%!v7&STi z4-M*t*t$bLjCWcsr97UInHVU{VH)Ep;*dx1%HWF*gMbfpV0`5xr>TR32Pgv)YNIm- zF{Gz)zrW?goiB&MXm^H_fF;1nS-x>N-i;qohLSGfcr*kme{kbqBoQA=E;p&Ksv^j+msC#(&4o& zx!!V-f#4_87fwap- zz}F|bE~#GzFQt<@(@19E<9kEk^^;LP@h98)OiyC?!d|^#x@UDn-+E{6-M-j zogSuhHa*CqUr-(ia_m+LmBr}|&U(<(`ZAHO6SBXKcYuwDz;0;_mt>N;1)|IPmMCWH zXjfI(R?01T9U4g*FD*7Zx-jRA76KI7O{I1s%B2em?~mb&G;!+xOq#S;++ za1nC2F+V@hl3{Bdua&ZzpE#=oP0;^Zu zqpUag7$3TRsXO`5ZZWA>#GxmzEXoZbvz+>knZU{dZJ(y$D0+oFxOd!@$3NNqYi__V z)=7T2*5&e5`RC*Hq6oAJWIa>uNLPI(o;bR)#7?$GEz=^X{6($6iA4rz1rtAX?Y+ZJ+(N5i5C|KM|i>|IK0WjSHXhzuMt6X{Pvl zon=`p6wIn*~tfNzU1xGpS%9K{{Y4xIss`h zZLSSm?f(Yi5c*W2UyOrqTIrAJ8Lmw_I(0>c=RLP)GvJf5@@}8>xU`{E1Vvt| z{JJX8ygTAPZd3X~AoL^X+-f-%3U(U~GQODs@Z&KBIShQL?o;AEC?zM!2h%4Qg==@X z$jy-<=tR12Ovm%dj9_cLhWb23_dHMX^bBG(UsMq2iZjEP3;)t?&jMRXRnpUW`LQ*^ zQ;#b|7>ne7@?ViFQRxn0yEI~i%!y+`UhMrk%l6vCcslYNlFM(c?}tmKe&%)SORkbH zq7%PTwXF7e9a|yIFopCP{=x-_3_#1cBB5W*pVpXVfmd5h`~8~Ut;U=!2=~z`XnwqK zlZZB$z&Xi4bW;6&@|0iRThf)@DXEi%WDm-au^5$C>~kS&Gkjlz;ZeSiujEMiSqVWkyH2B)?sx?DyZ#B=ll+eQwTNbDU?`6F8;iR z`s%j7ZtlSTQg)9QkjtMo9>Kd> zwm#FXy#ROv{g|V12*SYr#Nk`}Z~!`GeculD-q<26PCS~a=|0VFQvTE%NplwI*s49n17+6LNJL^-&%(`oDrYu z2;+WdAG7U*8Lp6ZChC8E)C@-WidhJ@8CvEi%>#~5s1+y1($ z+`|w+VlxycM*wrt!dgJk`UlOmC!s9J_ZNer(C5^QKa#c^AEmr=u<wRxr^?ozW!Drb>Z9l>ZL7u{`xqev8^VlgZ8kbGfQT%<} z2n_su{6V%Lf9~<^rW5(}XoatqjIBI0fBXNB?8i+GFYy)U%JE$%jL+*!=H2biJq7D| zKQZ?V(>31ub-C!Wc77peT2QsplW&;N!z3z%@>iLhRQE*XvWlMFx_U3%E>qNUSDOpn z*OX-v=B5?KA~&ilmMb7B$>z)r=C6;qv>FPFPG*Gb??b_5**&?C2>nfwA>&Q&x?emm zQ)B3FcYp2&sgCQ@N-Z9C<+$`GFeVRWf#S_Sn4xx)yU<&b&m0Qs%8EDrhA$K#;MYeO zX~{uTPNKfJ0t6P67mETSAvyr_4d(+BhfrNDbpx;Q4tpG#HP3fwBOm3QEP}0_zR?=Y zDNpNeycXb(ib+onB=Lg5;)~=Eg9zYbUYT#Jmu2>%?^xf++w7nL_Np&5;ms~A>0Q+l zS+JiV?`ppb$3l)8@hk80_pWu~e9)SfInjafxJ}HpoO_$@3*%uZ&W4gmz=ru6l?ukG zy{^_R+o11mYw^(+8Zsb$Hn0w$W_CdiX+GZ+HW>*u%dc<6f@G>+AIAuk%DLxBLX1Hd zPwy8Tt_Me|m&-|x59Bv+UhIkAr=K=5@)_Sxp91`%DyY5A_po(vkm5+7 z@tX*D9**~5FDRep@K-+ju#HvdKE%AV1bujx+>R!3A_@lEc2tSH z;qMV?VTah&WLKK@5=QQ1?(UvWzw7siIEWIk$PgJFxCI3I_Fc5Ta~0pqXaDRH2h^f+ zWZrLR*?@tHEc5-}K$c1UGJcCy-prbKWDC*=>+=)aNaT<-f_b)Z(ADcNVXKBi>UbGIl)n$1mIYh<|CE?sX zsWC5e2}c6VL46Hu<$eTSSV$qyfTZ8g&=m;*hX!Ue$zs1g>y~_qAJ)C?!(u}@B*C4W zcEZf|En3G%ND(?Wut|CcqV#~8zVX=F4DOrNh5T=Lq=0VK&h=ZP`w|4PTpgsn<6>Sz z_DLWcZqP8&dR4b>B$gsp@L2)tpV`JgJl(ZBluqc}itPylJj&0*d`HU(rV<2I_zCr= z4$b<%8euZ>17Q{I9Txf(AAlI}swuJP8am^2oF1R;d{QRCLdq|FY^)?@K()VePb7Ha z)f|isT)5fFqkZo8tW%!BB-|)=e(oiW>RheL^m9XhaIfg@e7Y{0fjN&p$LS#EVb|v@ zBsF=QIurF!FkuMKKb9&#%~wDZn9)D0=Evtw)Z?|?mz90H)m6DJMqwaCH3Ytw9`79S zFy^Q~Dpv7b_i}O;J7#PgH9V;MD*iFXP?%G1g86V>&?vTmS^y-QAM~aGh&`)WRlCTi zv#-CuoY{xQ^mh@c^+KO2K)*nO%B^RVy^n$fiWC9*c#%R+g06G5VFM*Ka$l;x&o9}4 zo?GBzt!cJyuz)7fpGTWIW;L43I&&FKKP=qrmgsnUQa1CM}f4(HbPMDDU8x+OKt>Ccs`IPW+zyz?Fmct&Sc zqt22^Tkqq*mPn4Oxiw(kcm&;#mgTS=%G2%TvC7g=j5S4K>)qN9(le7+^0;9;e@5Qo zBYu%s#R(AQI|G>*&EJ%eVS;}>sv~`6Xj2K0LvVbQM4$>i4LZ&$CfRbVALqo4Mj%M` z{UTX$+v8QE_Jt(P0U5>JG(>4(H-GOB?B}B(54o7{7Y}+r5RS!jlRs}_syRTfC?4vN(Ucnqd&L@(+4)qpq$bB=Prrijh^lg>#fjxmmZyyOK zbMo0cDDV5IWUu3Ed*2S1=~R)y%ueK&n0|BjsfQAAj*SQqMCPY%yAY6FU4i^no#P^O z$KODo+Q;~8UuZ23A8=m~B?mtnl9fbV#3`4D-xI!jhG@FAXZIUrJb ztG18A-nst9^i?N*hU0->wF-eQ2o_Ar7cJ~B>~FU!0jn77d+1ZXRsA)hq`rjWQMi

?o)}hN0z-sxDu&{v$?Y>y_NO zP%py03CQoXJm&DMUH7Z;gwOQn=pu^hF)o+At^LwZEeg9NdYK?sF+=sSZ@#FB9-XP* zqYN!-{rl@hT$@j)u@|v8PA_5qNpYspz4!0-b`2z%Gj1*Su`G3>jBQ_1+z9K4M=sxt zZMyE28`1;m3VUHq_smY_{t`FYV6VUXm&;A7oYS?mkI4yJSUn~98-46LdLPW#{hoTh zmL9B)SJ%J6>qzTq_KNx9L`cN7e7{2v0q?i}imb#gMY1nipg8TvIUTz2_cD|AJEOg3 z`B(FaXsDyM-2GEQL`(j5=3o8Vr@05?T^v!FEb-K5xe&Ow3!SWJ_#vEHr}>A$5R2$(QQ1~Jmlb4ImlftoK`e2rD$(Ld<%?-1y@QDC@HRI|e4)q3B}#iK6} zujo`=?iKlDk>;~jE;F9|4*4#jjjq2#A9UI)A? z4HMS{gjlKTOrKuvyTWCJR@3PZum_4zi;DGjjX9CX7!x>%7T4c@dosA61aZH1 zy2uG{rZP!sa-p5WSK_mJBs=+7LLMz|7zg(M-V8_^uX$kFjilzc$)Z%M3r*f==^VcR zx7^E5a!EU`)z5DhK8c7qBsK=0MCZ?EUTDY5ujAzuAS23C>>T+5XmXdG+uO4s*dLKi zzwsm_dXAW`?19XVuRtk0o1Jkvr{esxn-yt% zBM$XNAbF%lP($#I41=9|YnhnOt%!NP!%XV;*7*`#LrJoLrp=#H_%$|7dBW)Z)Z6Cc z*5HR4SQJH>w#9!z4B}NEi9?y`cR?I$8W21GwVBG;XMZ~O=_q#bRr9XO!QAJNxwbVW@`IV#r=x6cOW1Gqi!^IA8F-Zn-2gy9rKXSAt0%0aTnzeDC6pobiF7(TS!Ij4)f9Ca(zY% zTSn-U_Pht)arzh?V(e`Y%d}PfiSN(!4t^jnuly4bge8CU4h9vR!Bj7VD+xesuijJpeFQyRe5hjw=X5z^f%o$V$0Mz}=vJx(a*FtLU*eft^+P~{ z9PL44V5-V*ztiEvB0r{n1rOwcWeL$ejoC^04bi^SF@o$*M-TIbrpGCp6fJnqo+v=l zj>Hg)M9^_^@sU55evWe;S=Eb=ga|-x+=UByxMKYc@jNsU5~Rt&73%lv`YC^omudy~ zej@u|pQp`RH;~pNsLk6k>O1lL5kH}$+i1pk>7Oa*29b{cx_lG)i{|T@KNlbf(zT<} z(OYJ#$CSxDp$Mq(LMl^oD0HW~($X=fPft=0ime~^5(*M5i>xD&$PA|iqxlL3E!)6{ce>qqw&VG=kJ&SOxa!-{c!uFMEZSW zL&5bKCsvdqJCys>uoyTf3wzKG_VHb%z3N0LyX5^2<1se81^bK4vA0NZNc1Jn)Po^` zQJcFXYH-<^hT*&}FgD2%fmTa^gL=4<8WJ@}XWxGEWu8=mQ=WaH3{PPF@k8+SP!+f|O1B$B1Y z&yik(OVTVz18D=k*Pg!Va3+S@y*g9!P`++j{RvOqFa5fB@HjxTaY)1UtUU~rRq!B3I0Lxqe8ngHaU$E@{5V9s*62M8>FZ`c>M>b)#-%~r1D z>NiVWhg=dZTZ=F{-bFs%XyGs9Q&nhNP>=9u;pNAt!lwre2=>u{@B-%ABoj|H4wlD_Q(E<<*mE_ zVGR;^i1gE0{FI`F_ME1?CT{)nV!Qb_v1b#BihETE5xb!z!THZsq+Xs@0inuA zNhpj|czeM;i3G1+*fsXSSN7O^b+eTuymr4*qnmj5dGMBD=jzCte?2_jX)@fAzp)2((-!18mkeS8U+m<&Yow{sa zxk8wF@pB)Yea;)rrrJSloe)6S$D~DzjtE)`~^1359`f%6JS!T zl~;qBTsBY@kb=(v?S`8Pw#yo z%(ZCaj#x~0Mc%>A_dJwIZIO1;9MYjtWJLX4GW&j%hJC>@4%ow!mMAoUKn$)YvaqlC zvJ+xEzwOpz!WI(ArH6jV66FRg58Bm|bx+EzOI#+AuUaaT=2=3Whjpo`!Bfe;4qF4EQ>M}N4##ot~=7e;G>&G~lr0dJd z`7=uxc#h|mPwr;#0>76=-(B6ixg(BKK%a*8`Ea??6bz!(A^yt8fXHkNMILg!qem%; zX?|>ije!eLwOh}5dr%!8o|a#f-AMsVf{Dv7yed)rR=`-mmAF;*@F&*t4HGU%NaVdHH8dS%7Xh^?C6 zcO>kAy7fN(roG_@2tF>Xuptnq>T4vM4edbK^TtnF0nzOg{J{+O70~TKhZKT3#eH`9 zji1C|6|cknDCoS$_qMp-gHp2(rAt&>)MQJXBfdejz-8P!GsATSFjL>hZ#G&6ux);B zQl5}@3>^IvfqJax0|h+7*?*bpM5;Ty!N>8J`Y8f!*I5u$GT|xjH78!=#4A z2BvILq(9WRX8ItxRp9 zRFV*}up-$OO3Jdi=-CBQ+9nL1b%hqvcgSohR)qYEXC5>mXF?o^(vb6XeAJ=zp-=IOGS~A4 zBT3c7kaf;$gZ=(G&+{YykOw$>=2vt8c8=0%7=_M>1cXk=f=p<>>tnkeMJP|(Zj9gy*)^V2H=YYsmS%NbV-nf{89 zE`pE>yyTfS`&NOV`IpB27LJCkWt~2Qkt49KldG@aCDQ5oS$v;pw;}EFdkY=O%ATq2 z+>q?f;Ag)cF!{G)xl+C~2WK=qIVl#~(;bYxk5~>EJn^c&RNbJ{sqG~TgwW&YU!NR{ zNqmdA82-(@Jf4j8iS|i9v613%U((Sw(+KuVcn_&_r|p6psCoB~7B)vei=+e;v3&{OdS69L#Vluv@^G(EwNuh}CUn2kk5EPZr_y9vU~+$Q0q0HB2T z`BpvzM#R>BZ)=){nqVgG!(xGYwE#?uT^h0*d=M&CjN%y{( z5i|`DLF@XUjlqucqgo@58b;a42_QE9s1A9fEYe!t^H_yStfH0#v>Z-GDq&?s~K3pPs*9BzrG1X ztI3G7KwvFqv_I8asQn=Hw?M|#PYYVf2}2)Dko|HT+xKH7&NTV#1C`w8x_W@`{)0v3 z)b{|!JQ9rBLd0>$H#2!5b6Z0Uub=B>Ohdj>6EmGgbRGnE-XD`NYsSQrl!V}}Ea-?} zEZu%VQ|x^ud&uMU`&HDsK7$#vcp%nRL4-CV`{^ZFSTKJG&zE}h{RyeSn)OV*32}jc3 zmk|1T^&07FaDo2q+wJdEck`C!AiyAP&iZPs*A9w`93U@dpUG`X!8g&9b`#>aF?k!?s=uW*Idy0Sw|;Y`)wp5vsFHqPNCh4@vS=Ol1yXn6Nu**kijMm zJimth)m`iHebNqCv>Pt7hNT8(0T|z3%{!}wX|G`e7qi)ydS33<~KRwZ_J1C{8&h?j9 zv31RRp*<#Dhd>i)xO#51&1UamORMVj?S`jX{??iM_Bqz@ng{*-yyE8UA*Jt&K<7Qs zR{j~}xp}=mGPVQv!#((^&AdM`Hcs8g0^9z$AfPvKVUOb<)geT|y1#AV*%>XEbZ1TX zig_-u;bS6*+wQBC&>$mx>K@{53+u+*pM)%rY!ykOiC7V}ZauD%Do8ULPUC9{nT&Zg z^qbaEH3_l*Ny_u`#1^H^9P`;#>B|?qhKj%bhR6js`TMpM zXTDDQI_ESmVxPT=Z5!W4qYcBSM`{iZTBr~&kIk2GALZ-51Rth!t<3)eV%+t83_=T` zF;ADv-!3@B^@Dw>uBS?@>B?m5o1T4t_T4&S@X1&|LCMpsaA%u?)%^ zLCoC&Ue47B{BQ4KBW#qNZl0+p6Hqi=O_$_U-L>c+M`zaM8Wcp~zhn#^5k$n07=ky1 zNP?JR`t`l_T6gGsJ1xR-PMxY<-}XJB5X-BfYm*8KF*MVKd=g-6sLeiS{~A?jPLIce zHWXv&EaH12FVkTFfWC60VK~W&spJic0O3@^BK7e$++&T-l6_=fZtILq#8fB?sw@4O zpDiMV3-v9)E)i%+yKRH3C`WvBolEcF?D55gcDq86pPqc2UGW97f9bAwSaJ6*Vj)Pk z@S5j$2)tZ~kDbZ#t^;2Uw0>u%>MFh(eeUPNOw^x6kxZTfd_tPP9gm>Gnip-CRd1Yk z^|1=#W^?fFOAY;!k*GG8h2U{UL&#@!G0YsI0{51S8TKzj(bhWRT(dsT1hiFKu$R|@;y)BCEBt9C>gFxW!g zgmuEde&e2&fN)ad)$^Lc95TFnU%GIL_*kbVJM@#DbKn2Q=;|{!+)U+|^7q0~U1CVt zgg`%{q1MqHkKjytv3o%Eyqb5dqU8R<1aLu~*UGoa>5&9CzkE=Mj#zd%v^R95#-6M_ zqf?nah4%7R_KS7z;#>Ts$MMOQ8FFYFHXW%Df#qPYy-37?Ira~`H($|{XwD&@c4c<%zdsUqKht#4 z8{h>%fOl#YSTOt`xH!DRy?J^zepw!t8h!lr z!}sU;tEF_yTx@r|n@tfb_4RZ9ccDr)H{e0dc^VDxX#eHMY@{lfu`X!1C_&sFL$vAb z0~QU8>Hc@o_h0X9?Mr1T4N*P(ywl~DN5`w)-P;qj4cRRZ8cG0$$Z+T*!{6Po6Rz(A zK|J$qsz|HgsM^2S0y~V9tI2X9rNQgEKfveUHecJ}>iphXHr@Rmn4~i~d+WVAb(Bz? zj#V0Kkps6ciTV7VAG4a|3v_-Uhdrg&gA?@hEZYzDz?%Mx%KMmBe`dSJM!gBt(to;5 zhxvC;C5QT5zWN^|;GRa`7pT>rB)Y4x1NF>Uf0cfjz=60amh?-jG5J~;ihiRVNZOwc z=c5HKg=Vvj=SW(73&6A{d^G|$X_6u_tbbD-%^JP5~JG=|ebK6Ws= z*X@abPr0sKvf26Gu7a-}-rhnUtrK{uUOa=xm`yN;d;SdN+jY0Rqu%V}$6xDs8fW=U z*79K-^XD)=A3c9rbvVs(Cbg4Ym_i7oa?+FwVEcQVsa>ICAwvI6QeZ5scHHSyk%XdB z9`ek`GA)3tvImFc9((yS4C_AGFujz?bMN^ut5E(P9`KGs{OOm1zx!Zq1Fh00Ku%WMYZsq$wePdV}CwutjZS%(d7q0a8*_8C)C7- zegUA=aFDFSzrTtd!VeeLwn={~J_mRuC1YcykfA)ieci*`viK{| ztjK6CKM*~*le1KD>KvA$Z-w5phtjXo?y8a(q7?;azaZ7`w0x@JG7fvlfl%TG7rk## zo{;2!o=(8~7V7sG57duDJ#tY|Vw+hgPSfdbL7*9TztD?YxT5;TY)9OK3K;z&limY3 z4l`uIY9NB1>YxTfFd?n?0K%|6h{rFk%CYag$?FqY`o(UZ#VZ+KwS3y|Orwwyif?6$ zuRnV(Mp7HZ2PF?zT;kTu%TFtZUuN|=cX+B9eLR4IsC+1mvX9)!4_l6PJV+$og}GZS^Q4PA1+s5?`9))G5nZ)!C2wbt8~c`rX=W$h zFWAX7$#s63@{`ZQ&+AhhLjLxShTB~=As=GB&^@5}yx9i#U(x{i|rBO zqw_&6EQTA^L5ME-YoB$|u27}*?@Q(21vu~UG0!+ z3-y>EoFqNBJT-(%Yve5MpejDf*R~NiOmvYAnPQVp_gL$hj%dusY3u1rg1Pd`TjnaCWDMG421B^ zs0aBLN(ud@zK2B{2zFe^>ifM!UK#SIX;!7mAwTRL=Yom*&e)d7!k$ydlqLnVnnYxr z1y=we<305t2A4wlA2$;!ky~WTdH-$Gp<*;FKo z_x{+yqIGUE?YA9eTtfBcV()A`<8ppH-e=xYkZlylGJWu*9T8djwrl8>xYJao&O(%| zUx>MSHl*K{DlkOj_l0aIAN4a@n)E0gRQ=@2vvX`-YY2B4dDOTEGoR3W_KSfVyXYY0 z6mMer_#fetkRA=rm$XO1fISWAdRt-X1$wC42JN0#J|EQ+5-WsKd_877zf zxUD@8h}74--XGW8exY;(Cjc4z@aT&0VfsFw)xjm<6=>WIqOzXjXdJw+zqpUPat6S` z1E46jvw_10e<~yy+c$mO7SNU7DtCO4gtQSXbyO<*@s#iE;AM1AtZlS}?Sk(# znpGyqppN^ae93IpIjty_a|UPaGgUIZmm|gCVVBM#b)OA)lJ)6ioIM}*pMrTXP{^M0 z0&}BQ90cPS$OZ(*KlR{c&WVP*)Y<+neSaOZ&uiM>gDrv&gA$p0$wP9All9dEmW{+e zpHXPyI#;t0M4uxtZFo<`VBrRrt?74$v#W|G6qcd@6q@!AK#~VydKYh zv7|>`{AYyVr7~-f?}yr)e;4k}g^3{GnXP}kZkq@Hn0qY6NL2Tq(@Ts-K3*=>UY|Vb zsa(SKFCZDzB6<%*(cyQ#P#V{-`I<}fRbUn^H?zeEo~`sgKd9S$OFudTn#KpanD&-M zWu%0kP1#NlMjf9SinNE`{G>NjW<7ri9t{Edh}I(CbPAD`dcgwgHjRM5Tl*Z|z=~#T zFHW$DB*J4G@*C!A&0KDu_v!21)@i*Bg8r~7vnKtWRMm1sMtvLr=74s$p4Tg=8Sc+t zJ?@krmE|W)X2j{AjXFK~M%+^P zSKf|MB8cV@n*+QIKc*Z{3VFC*P$o`S*9}h?K_~w~>aa5>b07Yc{%eJzdRQ-OE_SFA zY4Xis#zeX{`t8~uPtO5%siFikvuz~Vl`Gg^bPOF{HE zR&%?52=Lo}@HZhal|$YftnPCbKX0pmgYq#A zyW5`l9lsZOf3|{Xe~~kCFeLIe=e_tW-8FBtAFY@a$h-7SrzRlLdUR*X+VRJmFMFSb*X*cV5eg2~;T}LE zTaXIbyxkvLty=MB#Q8@c4pg7jd7Fhem=z(kriLSN={+a6ATc9bANA9v|HE@LmqDFt>8-E>Ft8dr0dsgRE!~M zLc8$%i6eeHUyF-dKhWp(uKGyg#M@CgP@d+z#!EjJ%Xhu9s!+^RT_=)ZOxMR<9>qgN z&}iJjk%pfILsG+(Hk$mDd>Anv-+;^jjziv)Zi%P;IB@X=$cP7#7!A5Ly;V-{NMqhZ ztYZM_(*P;-@GSnt`;5W7Ik95!XaKsM< zXbtlE4*BQn*JilhCDh|AlRtkomU<^S?A)fY_Isy~hKx><~z2@cm{5{Yqe{e5|%cpW5BXF=Z9_LNi zlfHl$VXu^xG)|e$fl2H`9HZ=Xf*~0hj8|nw@Tl|ol-B*b`is4nl zCzJdmdudtyKFwA+b~182s(QIH`j1I*Iuce1FJA>_|Ag4rwm-B9Wu-M&f}~{e5N@nw zb}%tg%uhTp+SV8!OI@$R9Rig&UdZ(=<0(_=;encQ=kfQC15Fv*$bKX@6D*m;>Dhi{ z0MAN9K}g*D{BK{57(15{`hD&wRD`OuKg}?FCf*;1Mawm6*+(G|o{Rf&gjGdaX)Ysd zWUM1;YxL!Ovtc)YGX^e7q~I3(VZUVR$Y>Bg38|c1S{l7zFUg{BF$_$8_t#{h#CM*C z%@BTfW3)jFmX564>7}k(@Kn*bSr_(*GR(#c!3d3Oe zZ3x6Z?=qpQzSNAso-@uT(mI*CJ->dc;R4I${+G^;P*gA4%>HKik^l#$dUon zt%YnJ=Tx-RFfgU)Xh&T`e}1?RD#4FRx}X zoFTm*Ozo-NG;OZJVz_M3ethLcEQ>>FxjOImNjCW&F5wzLO!Zdq;H#_~_pAVSN!iZy zM>a#d4{_0}u8qREG?vk^PC{MOC614bXLSPIZmIv3Dcr;BGIvPH%ygwLty8SD1@6w# zUWEld+fl2$B1Bu#=N_oe8Y*M)NsuDM|NJ_&!vMx=Ecr^~e8!&5QgP3zp1XUt;cq~{ zlYQmnOhNPP_EG!SeIF%>6-m6}0?qiD$?jJi@$y;8o#M0BYJraR#A*4FR(>|68q6Ff|Y;w@&jXsc-ve21xHA(?B=zbgb$uC-wzU>PJOvPa;I*m_Q zmp~h@9k5TJm5}Tb+w%acv#x>$bC9AgeZN{bL>!Kz`Znb;99X|geiNGlC`Xmm{VtiB z@5_xjd*by7zXa14;2yss%ulSa56V&d&S-iXX^8sE=#P^cS z*bt?-?s(4>4G3@Rr+#lUyc(peSz7bwth8kV-xcJpaI^3g&n!J z*H_G%0DnDx^2s&d;4Q$U&E8`@lRlU-t_x_@b8~6aE-@WH+`RMAd3|h}+;X-HulZ&;JWZ7#pn{;3$#QzWL=w$U((Pi~k`a8fI_7 za&F`VSN40>&TO^6olZ}08P$f4_z6C2$>QjK&}I0FBb*Be`=lIDwTq2dN`US9f&0+y z<0_3~p!?jmxDalLo`EKKw5;Uk zidvVeBOfv*qlA-+i9;31P`QPjwSP@y!(~5&gJd7(A})mKc2GYw*!dnHx4s5jYHp9q z!y@w6;r@O-V&Tp+7peF(Gqc5tT2|vZTkSc03G8yzvza{fa6mV%!>M|t+p1i+gT{|8 zT8f=nRkW>)AYxfq#wzX&!DgeRZ z<&ic~+48<`0j=*QWNzc+R%OA&9o)WdNFVkOrsRJ18lKQdYR{UNyPxxod%T$HeD=Xr zMuXG*J;nL_AdaA&sS%k8KJuAWbUU0%XFvJ;XJaIbVeFlvC>(nY?%I=nU8wr$h1K^K zG;SO&`RQ(nq5G>c-rTq1`N=(J9mfNJGALBh9gA}gK$Z2ce;!L(ru5{sKUiuEP3HAo zn;xVkW#CCgRIS9%= z$oGEFWoop!`@s87I;IwJeG{T@tj5qAGG_?~WQK2qsfoI`KN=^y^BMr{7)Sgku^Z0G zBIv#oZ9tQMr{fKMoEP`TYPyIlt_mN}FHNf5YbDAHfxb!T&0h6Q+H0>wCi(kkFW;yz z*6-*o17}A()(CPD0(=bdi=+qBgBWt?2J3e5X5nz~-gw+2Y(1dV5VL)awP%1w%ojnm zbmrr5FU)kR0?iNpGRdzwDpp9%VEJ6p;G>=Qa=4(*WO-x+{IoEl2zR+gMYDf8m2>v` z?0$h#?-w4(2NyR7_pST6Lyrd0O?#S370_*2LOXOPp@2Q#XI+cd_>;vevu{TwSsbTEFRsm14<3Vffyh=fofD#g1S#c}|LLzX7TB2UM7qAIrk& z#EPOPbe1)m>OSGCwOILFH@LtBU|npZIn!Y&UkpL|8V>=OB3yj?s<$P+)#cmP)ZZyI zx%>Ue-OD8U?g6k47|Qxng|hUH4U3+1i$H9r{mx}z_M)lvI$Ul$W+ea$2FxsxJ z<=uVm`&m>zev>D1Av)rE-zOy;P&rrLO~zdx-l(c0WZm&JK?~d+X+MXP1uP@26K6qt zU6g$Y?G+LA(`CU2=1s6Qu(EG?g0+>vZb#I^vgf~jHS7R7vMrv}+=RDkk42Q<6nK-Z zn`j|=qFd&0g6Flk*gvn`lNQ$0qx{JWgxj7psP`f-sL(-y?`UUNroy9Nqz5>?8MjXw zE$uj-hhNWyxCH@4JgT$j7%?c;x3~})CH&;!aio$RaU!?N3{wwt zf0%|bcMJeT2Ug;aN7+vUSbx3wqo7cZ9O4x!eF2g)Suy{sk)NH?O&_jufbN}Zdqt1{yx zYlL}Lr)R}S-@!&RU34|Hv2f8rSLK){Bq6@(XIQZYit{@^oCOA~q!qV6VBhxYPNy37 z{un&w{q>@FK5o7u6CdKH$)YU}_e)V4-Mj0d7BBV(Lbz|!iDN|lOE;ta4YV6QFqdIF z3=n=ZGK6B}0X495A_eTl)=-cg7P&aD`v$k@PvazB_Z$0hEt4nYqmlI_b%Q;IPnzUr z#Ygr!gvG|G3HX@&<+^+PrJo9RrtwV!vXE*nxF_wyqE zr??^`L74%5-3iY{7zrphHm2lxZFNMYD-VO2R^hMFIMw|Kvu|&1j0`Epqp;PS^b+HL zw8GIg9UQ$FQyz3mz(w2Z6zG3QiI`DhuGYK$c50(%_+&21ZU*Z7dX zGZM4f_h)S%!QHEYZGqYHsim1pc>cLCeqw%6p4fq0CNEK0(qF(Wf^W0e9_f%7m7o0W zGM*Nc12EbC-Fuk_ z6%+yp^=%vq24=9M=(RHMY=(W<$AHC~SOOWK-~>fNiIK6tTKo)lV-Y}_Q-)iuW9gjp zGfi+eKdtk<00x3e9V(yZL^E=5piZ7`EdUx_bD;#)MmB5;M)?u zurauUdIkIRwF1lf#I!fOOA+#A=`4vGTliOWnt?pQ7dfDPc&FgVdm>Em>n;&uN3F}dNEGe}fXgn89?^967UV+2Zn3i}_fD4sH zAEO*jyQ1sRD3~VlW27ls8f>g7^mpIci}XLtx)Pdo|MU|te-rGIq2=_58pb32(8lM> zC0=_0Wk&469;`XhBqU}@t@jgQjzDLPaGX^+`U&`D~1Su+w-(t4v zb<$RDG3BuA6zO-se(9%G?=wwYFNeZd9VC!b9G&*-@LYd*ui$upMs#uhWNuq@0Noib{aB0%z>I!bNG-GOKeTOMmD4tI z@NCv+^^-TG9c$_}qFi*w)TMj?90Vg@#V@80gDaB8QVm?P*2B6^11YJ|Ga@+5S7edz zn3ubN2k@-BW`+H9jTan$kNuH4bwQATIpbZ!TlhpwvbKk0JKX={a|K1o{r>nIvP{sa zpsgP7X5LTti-lq-z7`NpP>&KS{7vwp=OAkKQpxR^We1x?llECFynu56`$FOCnyupH z%sK;cu~Maevw&eAm+9-4XzIoL=qPEg00E(}fkP)S2QIYdEm=A;0htu>3^I&(S^N@V zUcJ$ksSxk$d6X;hr@a}uut2=e_J@aGeywHM`+Ca#qyJ-UEF@0XEv(e)D}>R=%cXrg zzUccJfnR6!r>GYcVCjTJ3WGhfiKRV!z(GGxbS6gw#cwIM_$OsZ=xf6^4(=xWZZ2o7 z-=yaLByo@d1;rMvWp9W$xI3m>l!pOui8*Qv91es(r2t%m_9PiSj(i$R4V{m=C_^TP zgVE2zON?`STw`SNU9R>nO>Pm@uP!{jQN&lfT5j7v4M23aAU zhOah;@%G_7n3~z3l%J6a6Bm3_!vt`D<&)a_qk}IB$S%i7ek$?I!zT!M?FczMQb)JL zhsIWV8Lyc$&W_DPqM(nK%{I@N;)v?G(tLQvHMGT-srOp4IYesK#>6*RjHpd=VW;UO z*bu^(mpr;=aY1NwHAG7wKodkUL0ae3aNkJrUOb}4Y)IVY8M z3yHuIgU4FkAY^257+v3Z0-%}C%n3tnm9T$r+)kWjL^rc%s}Y*S_bP?*u2?~$L_I_EGg_s4I2 zcR<)az)O8Q1 zP`BZ4rPkHgF&{rL1q5-&Ru$~J1WM5|{N${N6q!c$ITka?QwaaWmGdx~+VM5WORL&Tm%T3!=3>Q}w-<0Em41cvuY^0QQ{1`lscK-LGAofgIj{G; zd=7AL+28K4nU@gqCVUM?=zWr?&XY1_TVX}n<4_AUb+641^PDOW!RrVy7xCc%b!mTu ze~jAMmiO35a8BbMT1EmO8)0>RJx+UI`uv&bOn0vseUe~{thwS9tZx6w1hxL#5$x&_06mCfs?G&t*xtA8`7=z1 zquf^Cfk~l%hNUw3iKwj#v|}8m8!P773k57P>SnkT(Rb!0FXiGSCExFBq$KHb|Fyh9 zVDjKg3hV>)6|g{Cq4^q8Kd#A{fvvO(7q9)6qc)KDh4nxdhd6SzM#5-Ec>e`uo1LsMW%&?1XCGfyFdXjyQLMC(t$rlZZCyI=1O*r1Opx z2-vYEcGvjolL*USJwwM-6-k-F-HrWP@&SePKE9YgAJFc2vY8IIWzU~^&-6@=9TF#9 z{o=5%kSwN{;e_Om{Zp$fm%tm%IlpJ~WZ3QD1unc!>Pq2Qq(UrqxZKV+GPvKK%aCR%D z-hxZBFtIUtA32D(SC1J)W#YCh-?^#$evB{@zjlL8wMU`Xz$^z#orVa9PtzZZPo*rcBp$nSAEB-AJk;AWP#^)YbbX4*C>Xh%oS#3zuFZz*p+IAcv z-%FFTl{=kqb5LK5M(=em_N^A>xMv;R9#hxewBPNs=gvL)d)=JPY0k%*62TRinQTgj zOZ~-7^!wP>CQ8(z$w$j?-+h_oP2)(%4_TmboHi2gEUbOyLrBB@RpX&zb z=#iri{Y=Sp?$qhsO}ZzVBk=LZ5BfR0SRUrc_QE~VbNIuM3NHAmhZ{9j4-OL30d8cR zHn?KGKaP6xCjWWdNqY3~@51E-^Yx$93f|7zvE&m;DX2MX#7vU&BA}CdWr3U@-b4hu zV;!oW<2wYDUGSHtysLB%*LRq>>~Zr|>on(i*t?meNraoL6rEk}XrFAiQTpBZP;Htd z2mj-IO1}# z*d>YA;CsIi7p6;Y2oBXO)o$_e14J@x)86Sjb|8>pkhf-as~J|-*6LpFrDC;DyNR0Q zp7dn&MR|thw0e@K?gsD1XVpdngoz#1O)NO84@18`ev%DfeggRLINf7@>Mt0{D*w9` zl}H5&Pt0k3xp9Y=HUVQ%!SH5Zd##6jBvoCBt1ci)KNm#;j7@^ww@Eb(+= zUuf(8E8IR+@1cQhyHiEJ1atFJ)<(86M!65^DUD&6POtmcTzkDOQ%FdjJy>iP9pnr1 z^E3LJD)ySShDj;VTA%Xy9fo6kRrib_n3Y+tW%=5jf#$lt9*>i|Vkwc}9;6JqD8vjF zV2M#YnY7V+xQ7;QWgpgloSEAX47~7Uu_fG~7UAmm^upFI_eAOH94a~y?u&Pl-F%(C z?B)!bF5~AP(nrQ_kg`vhQ&hxQhK`rrIDxidrgksoX@=#v5Jp_j{+^p1m;K?oC zUr`Rj1Vei@?v(0YCcSgH>`m$*eFnli8k8OZH2b7CpV<6EWh^4 ztc2v__4B#YEQ*&mxfZ>4uem6vEv6;|C*-4OK__=>h3h>}>Sl!m&ARM6C-QnGq=tWf zy{o!UU7xy63!x{B-GfIJYjmf*Q7Q`G@XI<(`ser^!n4hdZ++3$-D*KHQCzG0HxK5r zYnGeP$EaoN!CcT(?!SIG3bGhs8Olbhuwc3PIlCdcYnAv-Xv*~ff}vNVQYGY#qj7IX z^?h=`k-%(n6Lv_ta)T{#XWWY^d_hsX1fP!wVImj$|3{;zz=I z{r3Ajj<-j9JsaE%>+WA#VTY%-;5Lc1kUUZO+UJPZ@vz7c%G_`f(TXwv4*fghj;f4z z?OLOIS|s0lJH$t=iaU@+KkD2Ka8-khzq(99;D0lEV=wpI%I(`~xYO~oLid>l-@@S@q{ zx9H$s`E`O<0{P;q{wbL6G`t?>)n$}XJ4Kv};)oBa7?k!c+O-b*2$7=Vx*c=+lL1L* z7w`RMzEs<36kL|_9(N}IKcFk#Z~5=5Kw#RPPc}~nLid~5CALbqkH6mM-w9z(f(pr7 zACJSaqX)QJ68B}hAI+6xi}yVa5~FKf)IBV|9OS2+rgLR=cbr4Zj;}@Qo=vRwdmg=e zpBFIrPM&z~O`g7nLVSW#?L+?T08jOT@DZ;fauQNzw62ZE`nbmhDEy;G(GS}>xC3sQ zYS^vZ<73qqjl{ip!?gzb6fCc`x?f_6nsew74S1DCLiXv&O$J%r7fO?c+(K4XYxSny zEm!6-pWtj2-lX$gX#wRwXS9hHgvfp`?>Cg7gZ_=X^YidIw2%;V>59A-38lM2=NYOu zAZM}YY`7@;hhks4mHR0wmp8bPsaJ@MxA%>_Grw_B6va7*FmFA7se@w~=9PC0*bZ9y zi5VWAcRF-tRs-M+$)WkOETg(FSHsw9p}xoIFalR?(~%c0?4n@=dHwO1-x~I8)iC01 z6z=_uI};>sYG9ssStX{+sB|}SqfKcE$4mkh`{Gdf^|{)R^utZ1Y?r%|bCdYH;n9QHR{?iK^mOwLKXJT0sQK*{*{|jj`&Sp_J6RA6*@*2_ z^6(NMkCa~fcrwSxQ_8w}(9g%d{Cr)M;iQu+n%Ue^EAmXz%NC2b^55nW`7z#amPm1Osopd0%oW8&Xfc82{cBqP>r3dQ(fa;(?9Y&^meYjdAA$twOENf= z3oa}EVOy`~13NIR?fc5r3|$fT)t3q9daI{s>}~iFsQUsU1^)DQfTBMY+prcyy?-(TY#9BpEOiAzprA@3NX`?7wvMTF{9-H=t|zt8x-BgL&h z*C!rdO<~cZO)|Ci*{*oX!2gDK?IV3A_|g1`dDk3D{n0E^S97_2YaSIAYnYGpQ6E4F z*am()vkT7c3Ovvpp(VLZtq>W@AT-wO8<6)L9*L2X`RKq#>aM=BNBKnxtN)lxpyEMH zgjsEj7Dd-U`bFrIzze<9#snWk8w#f0Xm-j$wW!&eTXIQckVoFm{o@ZVO>0Nxe@B+* zr}b>8$ZMzWN4&bDMivg=^QO@t)H0}=*Q=&ZoW5>5P*zK`Ksrp%mcXQI-Nh_bk~#g@;>k-e0||L zI$@trg&Yh7p1Q6|C!U(Vf_N^)+I^dB>DZyHnE=4JvprAMqF$St68wn*m}~}i^L)a7 zQ+4q>MGYY5xx6Ia`&j-;q6A-NluCslaG(E0Izc(X#(buO`9s}`uuk*Fi!R9)Cf$2X zI0YFiMG3%Kg~8};N@||=p7)dX$%AL=bg9_O*o4&9Jf%676%{0+Ta+F?`;h&vOB$zp zTsxziG_)^W3^j_FFoDZ_zh`E zFB#_X0XNSW$&NtsaeP4g8w@AFtS+hLxSVg?BV(p}95b^34XW6ZAebCzaJ(q@AGZDz zBG}NpEZWRo5>Y%zvI@O}oDcd?I#>AjxUAKZgxJt#bN;%|239?C{TNHDp~6#zj{=hy z__8C%OfDCIZZm8o>IGsnn4Ys+*M4UDRunh^!_hYbJ@SaqVHA2i9i!aKgZAD1s(fGf zU6}g4N$-x@TCk6l@Y8%?Rb_CCAZPot|H$CC#uLf`j}EMyXdd*)eja|&fs?pLC;T}5 z%Bz>Ijsq_SlJ#}whAn#UJBPU1-!(WLo15rDqGu)Ud_((QWqHaQ+ZyN#;$y2bgO1(T zf*u8Z6813hFhnrVQk)75$J0y|m0z97ZsTg|^5($3I;pYwb`%@Y@QMAvJDde&J__#l z!=@kGMhO3(lAruZ{zW}@r0nAmYmkeD=(yjO;oj_T1UNO&U$KRs?h? zKv7KEW+H=s@pSXiUdW-ZBI#_^xT8Bwd602}&n8(4CLZ-}h=yBLOL)m%1aGuAHI=Gw zla=egvU4!4(UH^Y(g=8O)p+=#<6KDmc%PCO^{C(KuxU!E6 zbd~Q$lqh>0%4q@hkrSheSswP>!3>&INd!s6`Q!`!ulDNGeh=A|sjjpQ*u#UQlKqXs z`Kb$F)6S>tiEAMR@6%$lRbjbRIM#IRAH}%?!^>%>`>2UuG#PBhgL*V*7%(eX?_y#f zZ;;&*>mVIP&8ZG}u%yqK!k_LwuddSwE&!gUm#Bv614OZyj?f;dj?`z1OV;98*;Jb9 zicjn)lDUa8Q#NSeXPMMg&h}}5Yr|RhKD=RFHufiX_XigLqd+FmBQV&T%6xKeLl?f- z#kWuN52!itCvktwTlikq3|V1ur{;iYIA7&autugzZy?le^FyOpzny=*xWJ#6BLcOk z(P8kRTHjAR#?4D-i-3GJ!LUJicpCMukj9yf(yQ!`C)^phbe~{L2T5nlu{n?VJ&8_^ zk1eXWCBl6@w{{`$Ur3K0$5=Kj$T24-0v|$o!w@r?j{J9C9O{B5C+~cDPPkz4(p@q6 z|JVKoj|3=uS}^Fe5|AyrXLZpN5xWlf(-WkV^vN*SKLq2_|G=`C^G!#^bQH8Ss1Ta+y)~D zp{#U&+D67lU6m6)sLRDH)1G)JETace-R&H9GpN9U@y93sAuz23cPF0k>^gc~Vw=te#jpxOg7{9^WLSblyM=X?&M z=0&fgCcL=1uW%ab6%7U#y?sr@l|M=QsKu|VK#J=s>^UtppAb=~zmPvjIeDIoWQJyk z7|7PuIecULTCX4(FDCKM!E|s1QAczrd9U*0QWoj5S>~yG+mw1u)U12e?BSt9e&)>} zg{{m-$$ltR8S1~^8@zHmUIs$?YLdEf4l?m}%P=t1GtdlvSo6O(16E*JEKU}1#TyM- zKVuqRU=lM=9TpN0NYU@tX08(=8+*Qo$jG`*H`PNwi)0)pr^rPC#r*9dL!Q3AN8&{V zl<;^;t8%oI`2cbD<9L-)U=cX^CtS`(eLvYDL$d#JMQ7piJd&ZOm9LP;T&@Q8tx&pG z`t@VF+U)vu;(k~&v?}PDeBO%y_hYNqJ}3NMAUquZyPB7fOvIpELrQms5ctZs2Bp@Z zKL~kxJ!sZWKsbh7>AM=#01ieUQNa$lih4(<##InIDB_e)G01Mv;6 z#p@cK`3paz$Z|yO4(u|(>^?ERf*U78836BAKvP9zpE_; zqcHp(1Gj(v^8an(q`|z?Zqz7xMnk1`+>d7K$v%C{LS@w+fJF=vJm!8rE{nvS%$!*o ztu6lr(LM8keTpN6$H9ET8fwC%$yK+n$sB6+{Y9xkYDBluK1W;kltUu*^cABec4Cc` z_a8>;nT$_x$iYAG7EVpXX5g2WX)cG5RZRetgiWHT2DlF z1Wjv#+amqD;q|lENz>M1e|f(m?MDBW(v#sY8ecHh>073T+t|HKD5FK98u0^gac9WP zr#~?NtM;^z`tm#J9<0@7c3er=@}2{`G^vg@q|2hrmCI8LIY5R?sB@``Ekwl`QtYGF zw)6QT-1prsnz~n;tcEYKe==BmI-g13O1I?7uwytXSI(Hcd_fZq1`0!xqAG{5i>z>I z_>N*Jgr`W`VBhj}Xb7Z!m&?uXaQ7s0u%AvcwhjzPnr45ttxn1tEH}~?D1IGQ^5eqZ zWBF6?aEg1W94g)$*hx2o{dYDw8*Hj!XGW#HZ4e~G%{Rf{;;dZav7G`ISU>Ivf*;(o zi;($#$NtsIq+_roza9vUJ+~~yw~X2F%6d7~Lu|YqkzKs9I=1y_^^0fc*c+-{LXDpH ze0vEHAuwlS3@yu;I)I}KnlZdQf>{lRa@~fKu_gOc;vRwn#3a%w>Y|Qv#4)Lb-DFp? zCk3WEKstPFp774IE5F{^HFQpK*-Cq|SvfhTUOf4_*i$ADGvs#INiJBw=%W1yI2j$- zoc(6I=|s2TgE}jk&QyDdpaMDB3SJ`<48E^DmG`6K+EOtOncAjR*Npxxa1dSm25x0=K;jqFc|UU^ zAieGVcz46cVs51M3}7&e|Nr?`bJ-jT>Z?i1<8`^9h-pmXzfn~>9?*>mYYSNSS#WRU z*}na-u(&v(>znsR^aJ5MXZ>T%XrG=73Cyi%N5g?c ztD2yToStAw$7kFOl{)XOU=mlK%*rDX0^|byb7uawMZRdnn!7qNu(*1tebJz0BY_qx z%$8H-Z-T)Xi$>D7=zsuojgaEFXF9qIZV&S?HR(cY#(Tw16LsKl{c>-f5^RiD*qT=` zNeF3pzM{?K=Cs=&i87U`x7ysxVMLgS@8m;T24O$MfMz~V4@YU{@b$T=Ta?PV+8@jX zO~%`K=pU2qdY-RvE%#G{<5AKR)hqh7sqTZL?aXTr*j2~AdZ?`CL3wXoI>9rIHCkeM zy56V69E_sIQV)Cs@XWXP!toCyS`xk=-L<4sT-*?6yuX5dL0|OZNPY8~fplm!d_0x^ zZifYZiRbJ9`tRwE>2Y9sV>wwNx$J=#6ogOvXr_41R8}N>g+R8OVB#GwHPG9{R@cP5Sw7_@b4t4(&+v z2T3ces3_-v(XA!#n&aMX9MZboL+OnV zxzt1>D)^Z3`fqGvtg2$X7!~a^7+Ih2G-&<`k0z-incd5mhGH=`lRbvYrn32zhM$9&1;k>|@jejE8ZI1&Yzp4SO_5F*Xm2 zF8DkmU7ZpJ1BwUlox6R$i!RmmSuBi9qTMzvHe6PT;q>$o9whC09eSI$o#z(5spNnQX73+}uF)|O2w{C?MMo%_Vv<400d$;nqp+7{<~9QU z+@s-Og?o)}BI810g1b*&G*1Py;q*B1_ln)9iW;(r#Ga~~;e6q*UBr~}`!}E+>t853 z+~dtD=uH434Z*BH{yyb$+H8jTq$fm!uckB%4^&8j?!M2{qm=0pOxp?A2_Y{YNZCJa*W(e{?-mXzM5>0af9{y!0+jFB^{&#nPrhZA{gX{R$rB#kkqmeOsVJ zUzldz#@lv=_~)#cumOx-dJB~0TxJ#Jx`TxD=t*f8zyM2tCxD2;K=(=Xt<@0`-!+9~9hZ&NLe$(tY3qMq0LbuR*PJ}ABEi+Km& z(BBHb3wGj(G@mGfgva7a8A83?-TFXh({{NjVQ{VjYOsBdLTlN(#R8-bqQRp+e#k_S zYvIx}f521N3-=_mq}+>yU8@eQ#qkQuCLk$;GNoDnY3^HdUPl*j`WW*lYn1lBPaBw> zTBqDE%&#V(*=vRPOTDeSknEATuO^&^A{b;2@iQA3gNtrn48BTZ&>)^p`|H z;87&0WR&!Vvg4?){iQCbfCtZWo7ae6v^{9H7x**Lh(CDt}jp`l~~{@0&=Be3Q2y_LyzI?*f z*Wkuxi~FgL6aL_pJm&y$dFL{#wOn!E7z}M0?mWaBpO-+J$G)G+e%T&T2}uGx4d+Ai ziU2`pEmR`lag#yQ@WDcT36}wpef*i9+GCMAf|KYy9QwXYWU2bF-=JMXY>^?gcN>0G z_n(WLpnl{E=XPcZ#VWkw``1({kj+S?&M8bn0>JWmm8XRPebQ*REZgoLj};HI>XoDS zI%r^S z&z*9|XX?HVrqHa$>Ryl}@M&`OJ6{y_adPt03>G?>SHF9p!q4+;gamZ(eHK?N!OiLG z|4wQE06<4t&qAA*M$vWOKd>{iqZIizx!*ZU7Wr>R>tVQ-f_x7F*8U@o>1y~9EQQJV z!mlPiWGG@4U|Tp7bF&r`^gUN)V;=zVv{N&(Wz`Ne< zPanUn%esN8U5WF@Cv#x%sviu+=CCT^itjF?4=-+I!Nptr}E!rJun13gxD+FKWN-#$h{m4>VJXbdvIq8+>D<-vgKVBNmv} z^|-}aedFe^lCn?jk#`%JlJwh7_l5%Cd2Ov=7{ZX@Pq7?0|Iyps{tedCs62&R>l6)VnY-Erlh$Il6P+)^Y&` zoqWP$eR+mSI_^d0-on6NJzIX_^L`&dlV|^HuO=U!3^ilv2fOAyp#GU}m7lG#Vvadq zz12}%yvky#S)QA(BUBXMB|({Of(r?d5g7mbyM}E!?t`MdP;XA>2J!pMX3_pyL9Q3D z71>2sehjx2xkwF#nnQ?|BK~Cr*;LfPWQK71l3Xd zXL8vaS$q%^j=D;Z2R&ZMExE)xL^7)LMklG#NjzN^S@JcSa&!-%ZhZaWB_5*GoxVIp zVf(39m*FRl>0t4WaCyv!rDvU!T}*<#-5|m5c-ni3 zUdlPz;GC;P?)Gn}rDwE0n(b2jrQ?(Y?^L{uO3!qewcS3H;qCh;yGLwC66alWx*&BE zf^l+L|23(ijri7&OXHxk$2;9kX1$1fgx?g6;Ot?Kw@;IFzs!eg@Kx~aT@4)nQ3@=N~PCh8tHp=q7pq2S~oSH1X)6`oJMutk`=#*w_ zCW-XwKbY-whpgD+b`sMAw0&UQ@NCf3cwI=UG%m1A;Yae$Kc+t*qDprod?2=x4Y%7=VUSkixy_f%qLnN)|82)O$=9(oa}1 zx4^Nk+BUTJ&s-w*Rn+IV=)2z=jKjYoc4@!Qu79t}9-q+9URJyY|D|UpO3J8JpG7q{ z2YR&n@U(7VTBh&fzNgVF_kMSKOSKb%J$3Iw69%gX2^&nm7kB5gx&O6Lvwk}e_YN{t zIPOITnsWZG5zk;o2N{s1dU7e_Ec<{9yY1Uy^NxI4 zV20dIr}!pc+wnlCSLi}ngu%6%*eG0>+zGTB1oAa#73rj>|1#%4#CKZ-190D8Y`dw( z#3Izte26tmg1?6I{JjNV|JrRe-9VBL^glXQqfnI12`UTD&7?VdM*Xv;kwb1T;(&p6 zd6|1ZOf^n|J;md-mKhkNZ%g~In)}y01^095_+PnsI$~3cbNhLp&_=or`@+TH_@^~5 zdnWxrrS`naiJ%|KAM~3nby+*|1l6c!R~^4*cce#$@hqlr7dQ~?ath<0mBfcrY-~{4 zK(_$;-LKNo+TV%pW^!PjJ|@flv>J^#t1$a$A949`4$j*9OBuQ6qe?kdi_L&%sxl)!yYm*yg9b2o%Zsb&rA}vN_SAACk!I@Mc6mT3RKc( z(S9#9x{$w;?IDJFApMUq|J`Vom1+OXV3 z=VgbcXc2Pjba|`nXSUSj>38&L>GXm+PHaY#c;e2C9*2`4!e-t%AG8aw5Z^L{0=+Uo z!s34RPVSMd{D*v^;bCS&8+c7JMqbrM&aEMb+vr|YJ$I%XFzZy(8m~q?xW3?D`2x;@ z_8|eY_6dKu1@0%i6{ytfiz?x)`PpP{`r!|@g@>0{!I@uGrglmJKU3Y~ecItdQc^#> z$2oA|0(4!v>w_w%QrApJ``8t7(91{L=$9>{QU*=P_L4q3UiOj<>X@b9^JQx6-E&E& zeLe-4GNYO4rN}%@7*1^!hJvCp$R5li5$>`Hp*a|>`N;`hjW3v0lfdc18&)|LFvD~q zFVnv?(|=E9@cliOlN~!uh`jXBlmx9U=lEEJ*X4A_+XvoH<;MpuMvA*rwZK;pwmf16 z9nnvH*Sb>TCWC3no9#Qu!7~UC28B0w>v_QomGZeP~UM%V+r@DHM=D3|+AZY}_@4DF41iP>q)^yf>+$1TQsz!+up z*cMGhLJSV%<#&Buy@S^KSXGN5kiP`&ap!}EOYjSzfhC>V*Ec;9g-yf5{j#6dyTr> zQf3J;F=;Y8b7;$!0wM1=;GVcvZz#)cFJ+);_!ER@G?H^=%Z=aOF1RS?d$PxRIdMw& zySRNHoRw4MQwbhy!o@G!yQ))L=3dA@vMfJUi}T)XR9Uj0Cc^xp9O~VV`CX!2Jivr< z^s)d~qxBRWSBVjnQRTF*dcQ5pP4B4N)xHxqGAO^@F&5zwiqil!YP>dI0qprZJVOOO z3qPmn{yE%fx#0oE+Zcp%9EK-?kLxX1ksYW*0L@$V9Kxvc^;t{8)0M1&HZ`u1aCGI z#`X8!DV~iALc;8+F+Vq&_)O39O(`j+CRBu`TzbcMT^7)yfbh$LjWL6r`L_{ah0eb1 zr+No!{qDS8^C???9Pr9cxp*d3VyBa)x$1QU3`yS??t|nGn!0|Q9bqcPtP@9ja-uY! z&s)4KmNb&Zqk_FIFP=XMEW$8ZB3wzpLkraQmt0h&L&UiLyJ(gTsx~mp&b-s*j=zEv=n21rdgoGv($i7E)FU5 zH{n-nvF-Pf?laYc!>+IwfDAXmffBE{sps;WtBj7dyY7?8=I$}XA%Y9#x9k-%Ebth{ z?cXlQDa>`RV(L6r$tIo1kt-;|wVj-_B$uFh=5jC4F1r!!=tzNwL z%WuzQyUnR>8D7e8Ax+A}f~mkGVZJ~4$pLi!8qhGxC_n?!mLUVtJx7(TkNprO1$sn# zje6!*^qaW^f&^k>I8W>b1%5n z;}(`2Fw2`8cQpd!x=-l}wFO1hyH{Ltsebio#?r~7c2fi~rPH`~P76?ZH*mS)B{<#h zd++5tOJvTR2YK%D$K09i-dlkAV}k~GitZtO9z9>=FMcClUxgU5YsB8UYi=?-hOvmyhI;vgw>& zTd3cE)AJ^MDDED$2kxA_qR&Y@FD$B(o-zF8GnqCb=rOt{`7b}v#`@kPr1L$-rx}%KdvymxQ@9KH()z2~@sdXn9cC4;_HC+wD(gvhCmJQ;-Frzs!$oNCF_cuFuq}rK zH#6%jd0$qo6$x;0q3KD^<82b4x$`7hBur{&4}v`3)UCY>FBaq+*VVoOc?~PL_L+qQ z$yk_}NAB~ijFqbXsblV`y9*KaeKJHnS%bMX9s(2J-S&O-;_r#kg?04uE`KVmmtz{T zN}^&fbZ+BD1{|O3y#bBT_QC=~H0Y+^twC>l z&Q}U3$9BdyIGy%t85DJGdI8*aNX9;j*CLTOifOLIV1=RcqJNPLYv1IqehpZ5eI%-ty4`BS)ES8(_nDGaH;gscpgiybf~xt4jVR6-8$piCBQ^ z_xEF6Fu%FiTWemHjCYv3EEY83|6%;g>(bb#_dNN{lOp){W)mMS^YZQy7eK#I7pOez zkCyx@5-kwm_MNqT6ImY!X0Sxvem_#a{yD+_So4((hhmU{&3Ma0bulJpz@%DPn%D~S zL*NTDTjrzqm``=^*}uP+D^dLKzUs4>5GE7S11q_^1yy zzuS@XRA?c;{OvvB_d(gq=D**U`nJT*VQyp3?4#iZpWsP<;zke7V35X({Swi5pno_y zZMDFYf>dKhcjx$V!g;8mn?}|wnE61|ZpH#ecUSU$F$4P|>0n6nQd_&JcS}67M z8-VKugf#rZKL8^3BSnuZ*1F*V%1GcJ?@~$+v>aedt_hX!F z&~2Bw|3h3{xcb_O(wQ&4^-S^$D^XL&1Uu(uuL{0BVkj^w8~Kr*^&vtww^fwcS3!DO zw1UXNLEOeKtRS=ACnN`YDUkWv!bkEwdB;PF%|_B1vr&dM`}p-$t7g7#NW)U^Ohn2} zm|z03tn*6<&J6O5#}t&}y@$;ftRn3Z{3XBq6MNrkRes!o^ncGnvN7v{S07&yvaav$ zT}okquwmtPzpbbpiwvhe_|tlPc-*6%rbW^mensWIu_E!q>2&_c=crcj~4d>%5n(Bi<6FF9&%w!T!^L62XUauom0%PXr ze#OONnzIz#9!s2+%9N>H^$83SINf|kSL4m(lQmJJFnojlyNvahBOL)$75=2;miVw@ z{V@3u0lz-mmbNPA%s}Z6CuvKouLDe$xcN zE!eVEzGgPjvR3@>kntu`xm13TFBR@~nuqR4&aRey8FXm68^5bN>OT{jD#J^E+2MC) zEK?lnC*GL$tc)8&G8}^Ig^JZp+tz(|q-9J{@I1?{1qjVf%-G3gXu=x}1^7;n1l}vW zbXh)YHapd!ZCre;XPy{N8|J(H8QD(`aWAMReB(1*e*DL0Pr5#fwjjuYe^h@a zMl=)ep+<*KggYRRM_58G`j9Hh<>V% zS&n|z(TQpchZT=K{YJ+LFnR~hIQtvfc@4P4O{(_=+Pq?$4CZsL!)dq#1MX738aUPQ z;jOH`rVG=8SomHjMt(<;;+00R$EMmD(x?7V^{dbn+@%T0({%ko@r}9}`LXgzxmUC2 zxR>R75yjZzSxb~Jjg;s+$`x{+D{I}O3lCaAYXiWtEy)rvU+?x{Q6IkouW7>x|61G7 zqQ(&hW#EGCnKpOi3Mxh+VhP9Bj_D_IA42eE2je?IYz-U0QvAE@n?ePny5=dihI2?? z*+k_li>HV-znOA zuf8=uo(7&%Q#Z0@xxezj-{VPGEf!~!q49BFO=!yEl>{ChZZnsQyz1%BIMB%T%7NjsmJ;@)GAUa5u9-DF5$@l@xH=Dl z4IHfV?sWp5OZ$~Hv3BUXsA%;(E}EMr-djqtAce=htZEYZjK0~oCi-J9-5mMU)-_*h zo?+dA|8um1J-JH1wpjl_KxMZzq69Q5mRy-Y|@}hkB z@g>Ny%AhLV2FDi`RCO8`XDQeV{uuFeQz4mB$-CmtE$iop6&+*g6Q1X%uk9kBH zV7fseA#AQB-*-W_eeZ&vGH01j=8_{L3!wR{IThXa8~8`+N5c7wAYuA~Dkm>Ed-g)8@O`Z1d05~0Il@BP#pNcmO@jW~* z-i9EG=T_=Yjr-wk22y@da*E5Zd;sCcIQ}+D-eWcAQeWxx4ASFtbjn+Kef3!ny_K<^ zz)?8q+T9lh&e=ErX6Eegg{#i>4znSl7E$y!-75+Xu^e9}-o8 zI*wiuChP~eNv^)6rTC~Z0foY+@YZ)7J$|(yN}sE5^g(s^Ni%8pMx(*JEj+r+$NAf| zI-)Dj-@s60W)iSnp?)O&wO65v0wM*&EEv$O?DsG_AV%SiysPf#sog&?(k)>euk!wp zTW1zhDu;VF9@DG%P(JMMyeMZAK1V$dovK%>#H4ze&}Ht3-WpOFoh$$68c=TNRm<9b z9Z62~Z}QI}al30=SNMmYiVKj|q|8W&6WLxnEw`BeeJd?wF4B5>pI}7&=PtqwvTAAu z+(If{$JKD0!}0DhRrWOiD>aZQozTf_P@;>UqdI=7>+=Uv`-P3#m>GO-D~xTFp`@aJ zNEVJgaQ~2p1HmI$@P&{b$7s2w00lTz^nUEs_3$gaZ>NsN^+^haPRgW9JTel=)MjX(P}g{&oxx-!84Mp+)cm+@50qQhY2|$Vlv=3U1Xb6x^afzU44} ziJYZRXZmhBeofPgeoM+LZ>rh!>uh|Y--=BxFQ%L3?wn54yFL}-4= zm`Uf#?n3JRyEeXU-p1gY2^R~XspNOtEY7w_*OsA}Q@r*7y<4^O9I2C;Oiru{W5^@s zjbweutv_7=Tp_FeM(LrijL@<4wPi zp7S;|=j+em79ZI3ug4c`I3>bZ1}c^p0fe#+q5$t-W%L_{k-?R?D2rUIZ`E(W}zDTULR_bo+7OA=R@sq<)hm)NEF zLjb!@JDY#>;hiw%)}Q>y827YJd-2*iRPYnf4_=r!5O;3g;R`-Sm&{Dvm%x2%`vX$s zGaKs&));5`eGlP_CT-~lhu*^g1As)~%MnD%k;_UBIGVCB>>q*$7eSv=b?s+9CkL*o z@eXg}`?sV(1u2me?o7!Jaw^E-QKX2~aIu+2Pzp!umv5e@-6uRT@8^E&kHq0}^X1$h zt!Ffxnqx$h6P1?^T)}JWDQA2f>cW>a<3W^<$^Eh9{8#!}9<`L{sqgFRweP6#!2v}P zXZwl{cbK^)$LgofzIj3O8Ny?x4NSIc&CF+v{Kj@JkMMpY0CrLKJ8`?R3^W5JrHOn3 zZWv%0UEPd^g~Z024>~J~yyi||AwQx>&h@u&vvgJUBS~PH8!_6G!2c!ex zEYfEEgJD?sM()?xbtxxJ3 zuez;%wq$gPj+$92K6o-tRAqU)S-}+e9LMsmAc; zC~;NUUOF0nNP0*{K`EULTdQ(Ph^UHf0ysuD+`3(8C+U+jl23ml3U1%uZfOFbSyI=> zS~f&kJm?_qzY28vdF4)%1bo{D!)x8=On=`1ra}DIf&$_OE=7@k z_f_EXodVwITWYqta?GWF{0a8E+M<{(YZkpTy{iq6HOwW4g*kr@Zn3RN?To z=RqgK!tvypfuR8n;TlV^g!7Zj)O~?v$hOBSux38n?@HrpWVmafq05}cXLEkU{H&t^ zo}|*A)L#3$?W6sG&OF6z)}Sh%GK4F*a(gWfWR!;!Y>{^gGrulxQ-({PgRZSp$NN7H zmKlHEXAQp8NRRcc8XAuTuWPed;iE6psC;)+cm{Ib|9-bBym2jxaqp;z1t2&7?FRKB? zT&fGN2K9;Bg733n*HzAON}U&kGBD9xkv)N|o9v;6IN-qV_B;OFRc{Jy-`{ed~P zE*g8;=`XcEd`h$^w3F_n=6wKFML&4Qm=unU2 ziq1fzDsD3h6&%3ut?$<%M(iHz2+xtjm(ke*&hC%wkWD!mo%MRIX6->UcSHSEb_nA= z0!$@=zhv>LRK3hq{kWrGlYP$Sh(5kqv))ws0MoGR3uMeJgOn+~VBiP{7XkO!`VROMP>K(d!`TGf`MT!P9Y|>+Pyyp$N*pN4V7!YFNTj+OW%6I!6uag{I=!~GO=^3oY z;~i`p3(+AP?p;ev;p~Rub8a7Mu*l1L@8x}&Cf%`6Bdz)Ecl)QOLg1mBi)NMx_}M2X zCe_)cEg@}^m;T{Ac2K2tj&rV)#ocWk<;~tmNc@x@DqS8J}B<2+OrG(JB zy-dnyWQiq#Zv%=IR_lP|@+ERoFN5j!Rp+|I8)% zyFCG%>1Tip?UQg#diI>(58>N@QYW%u3kI~+N$<|&uD?am`IUAa-d=9$RZhJ_v*O_fq4t<=r$ZW;6#}gN^&CbVk3f?d3yyW~+O6kwl+X2I!^f^|`?d zWZO&8h6x*Cg6r)`OD{)G7q8H`ruaz8NN7%~aMdCqetw@G{uMsB9G4sJ-q_$-ADB?M zUv=eoF+*E_{z+!P0=Zo*KMeNOO&$=6CTdAvW-mWk#w?D4I&C?@)o={as6X;`AwG}Y z?Ho--5_(O@Tq|$79+cH@JVZLvdaFz`zA2IAYvvvNgvmH~AK_R$&i0cg4rxIhaW>cc zTtcakck#1s5|1g*7xsSgi&0uBhr%vM! z?F$w0q*mVB%1eDYW|1iFSRxph`PqgrHOml@WlBSnV<=hew_d!wDECKo9$d2D0bZJ< z26Hc}C$?Yd@rg_T^McYNEDs&4>9!m3@bi6cCksE^FG#Zyf@AGQzcOjvcofgh9`O8E zrCMu2)LDt91s*_$F{s54%;SPH>q4#e1>_78E1nHIXiX10bOixHik8g5@M+omb8J#Q zjT=ggk2>h;a6&KDnBa!0VBf>!b}j5|vXwgD__HAfLbdzt@aa6fT5%)#JUdZOk2$Tu z;TY~7aZ+}AB?~B{ic~i8$4d50-rUzJl#($okx){}BR*{7+y(;`4oobeyD@M%P+O6v z=VHpr$53rmNICWU>+KtADr}_9r|_6!yb?>mvDYotKS1KvP7hJFGJgd{l9=fLX zn%?AHV{QICeu|`$p^J96?qJeFgdB6|A(o%R!33iC{BfUQad>nIvRL!7*VMs~(UEgr zWtSv4d=t{!ox<0uKJz{p-q##gCO+*(^?Ruzqh7qhKcAIJzWV$AjR&}wBw7}D zdS`PzIh>Z=5VP_4s*CEYJ*Wl!+BXaz>(P5c#NQBeUD)Qs>N7@=guHTaCygBryFl3q_GBt69o?Xkt`F9Bd^@aT}5>J4LUeNYDa0{F5p>w7I&leeMIcM2L}iyJtr6X{x8ri z9?Vo-gcJ#Yu>h`klNVRHf1yj#(9Uu|nO}K^nkFRQF2luQiN1p9%tAnDiaf*V%n}%!vcqov06M54r&+Lvga#VZSvbo91o4%x>-+sIA8){ z#V_*o#A8P`AEUuq={;kCGG48az{Ld4v;PhSkkr%TIfAslSM1=Jelo67I*cSw{uGGr5Z5w4JEkldc+A%6j3$ss~uq})sb_9*`7z08C) zkD2&>n?^T*L)z8!V^kzF77UZWTwAlCOQU}o=i7^DA!VFXXoPO>Jj+C3ScC zJ_{*5z?T5q!Ur;V!wn9i>Y0kz$Ub==r?Q0i;ZLY=C88FGw@ka>Z&zOCF7s2e@I(ouaTjf;Dp%&oB)zm+1*&Z*=|Lw+jF&G-y?he_rc1)=9lBV23V;V+Aa| zq4Uy^ut+gis*f-g|IKN`9Mc0GkNe08waOUq-;3kt_lEbceSA2s9<$v019?0;E@5W# zz`?40|Jq@BeoY?J-csY!<6-TdW~si8>FVN|!6lXpYmOzW0&+hBu#*oBV-$aO|9;%S zugo@vm)8;gWZ#cEt53^KRKa3xCdGMlw3Is=IT4OssTb}tgpUb&9C&6P_SAT5{3-1lBYF&nDgGE!Ak*w0VL_hz{VC(#8KYOp6+&1F)5e+`Y8)pT-?`ob>;!3HXH=N)1BmbaJK(Qt*)euS8+jsDXX?b>S?x@RO?&3+?6C?GD z#iQ}GT(~e0UL+IVF3!_8yi5N*XG{Pw?3Y=bUdQ~H&D%=9!#A9?AEz+E>>=X-+PmIX z=5nk?p}EqHQn%il&!(5(9qJ?b;FSK)Q=r_S6l*yr6*fSc^%dh}G!vYW75o012$4O* zlVH`>u`Sc2APzBTXwvcSHdL}Lm^OWFcWRQ$Bv zzP-DpA{?uL0kuO-rPHfljVN5ewU{T5rJ01Hhlxd^8wo}kDMm6KbSutwIJLeeIB#d zZBO#KF0w?t3weSqCYpfu1*tjKkyTB-!@jlO0<>+G5>hZ+CdS^A7NZrbDLRq4z31hz z`0Rt@X%V;c`m$A1KE@>Z1M~q}j<&)dRg4BV_^)Aq=ii+Ks*!SgzPQsKB4Ee|ZMxO} zNME=rR%n5bl4M@2XN|A;hxr|w^u`;_MLrk4a%iCCCp9jukJ;);Qa!Tf^uUwfNzY7? z(x8cp-*lOLm4m0jL-b(jKPIpBqxThmR`(EHh`U1k8AEYo5IiqlaW~OP`PlFj3VlQQzBrHL#pWBRm{4xOVpHYmY~u8I)1%bGU{7;1 z<`R6=)n`SnddTkOD1JCnJzbSdfC|%A$x+M#6M8`AB>9WF%AE`r7zd}ER3K9mild#k z?@HjJoQ2{RZbxWna&JzJyCTzkpc{1X7--C(fy@nqkGK?6!HwThC;fd?!QJXC+M4oUM+{BU? zDaS`|o$j8&I)0(Z=+6S#h9bP%z6>M*!B>u9BURgZRFp?be~}e+{+&`2AN}cdhe|A_ zq24URhma-^$fVXOC(C;t56_i;DOGXP#nA;R5uQh{0SG6__A%Sfpa|&$v8EuIXsVv& z;j3{2VFh&S7nec%rQLW*Sq31o(K@xG^(WqKWEj=%d8xy!gm`?`)cu5mV~oOUAdY!^ z^#>+bKutcv&$m!H2O|CQL63X*$HA@A^>k(18PuPk04pPTBmg3}4B6t#q|_|Kc4 zj5kJNYo4qx2B$fHIYNF#d*ao@U%OcF(On)dH%>!YMFZ8zM=~U{Os~`m95Me&Yr`Sj zbrWJ%J?zP2fltpDWc^Mb8$u9Jg`&9y{it)390cB8QYbXt4h}7_6LN6)o5r`*Kno?= z_vNZ2hByTm_{-)6_)uhW)6TpEUS61P!-Wt#1$w}(lgA$TSSCok+`xpd65d4h=eExC z(q0#MT_ce4^6^*RH71gqaXIK)z!=FTjul`Me3YR!eZNK47cV^Cgb;3m2iJvAQeUIB*&chUjc9h1 z)RJW*yH_N?y64<_1WV<3ew{+6{9!KZC5MF~%whW+lUiD?7RJu@{K@*k4XUe| zE~fPu{C&YD(A7GYjB04vNZ-NLRaQahz zdhSgt1L}F7uL+%cR@Y&}SYEb;9H7@0cYoTP*vd7pnA7>S5WwOtJWR&))%e@9ZNV0- zZe8fi?H*MBMMtHwrg<2?Fss4I@~uWv%d}1XJe3+Z)@vdOCPgfd7J0m@A(f8AqtP}oZ3*v{a`HLdSMa4X*WM}B)-lD&T_=d?Efg|59~+!5r`P4Q2p zb@ay}wa<3T()%o&&y+*|y1o~dpyJ^gy47^;esRbTkE_i6%wxOd2j`}VGcA5o^G!eG zBrU=dKM#4of9|8pT#6gXSIh;Fm0^ra;o@^B7>X%SpsmzMxv=lYPs#q}SoI=+&G+jT z5c{{u6A$1mgLyK!Ya9UUZsL`KepKk*;HDUcIETL-Mibd%k5-lx-jb(tx$h^g+Yt9z zp355M$e z&sEW4Wh#fE!l3PbuGFc)J4oXDkI)hME7(%fH5K;V4WM_R!N-kRcCnB>lU1l#m{kWC z$$!s_5LjY#Nu9gN{c6|+vFlXqwd>N`12$ACaO8d6oY_tH`@=~1GSChl&mQXTg6v!} zkEdHCiw^?nA%49N*JIUXwNUL(dIRKW)2r{5a|0LnLr?Cf1So#^-sYHajTzK`d%fv{x?QQ#^5vhKp6Ib22l569kY z$AD*p@r)+)Dl1m0^xIG%-GE|Q)j~a~?X%MoKJst(Th^C5%WL_9MFf>7;OI{CO}Ub3 zbA?WsiWTUIv%+pGB#;l+KL&HS?t8rf^OJrn59hhH(o$wV@sjKXd(A=H5WZ_Q^d=0| z$T6_<>1c|t$wlr2=pBv~yi2?}O@Jw#&l{XF->Q6JQ*=}+rCd}ar;^A=rx z`SyH2J+j+=MFwVJKPZ43FhFrs+tS>?@<^?B&(toL*}lRJwy?`@R4Y%r*IuYT4s-R< z$5rwxX?|xU?35rrcl@$!vcVo>S*Y@6@ zZ#J}o=3?*>fPjR{lU)+c@^H4+>-Y@S=jBS5sad&fSIeSDxc^u>vn@rjAd3EyAmgLV z2!b-ho6Lxa1M}DSA-mS9uC7cG5aHgq5pnjp&3kD^Ky)PJurxkl@uFyL>pJT>fxH() zUzvD+-rOgik)BZRxrpVuFyuW7Pc~Snd^5;~wl{ys$^CJ;OF8MAwmZ|9OL52S-#U!$DDL#Xd-bM4akVt3p!hjM`B?_RSF^nF#FQa?q@AM<> z_uX(aI5cP$^+@Q%&V|`W$kRn(FRvq;h8ruBE;_~ca0mgfsX#@>Da+2E6uMERPcK1Y ze~$xy8H}hkD(X~+rXZ`G{>}7`XtYjIj0}_=MO!u0is+9;rk4P>FXY zb=7dW`jGrOEV-b9!y0CCJ`do5TEYPv$8&L0(_6&0_WLKlzA&sK$px0Pe`dZgNHP5m zB7^#VwO%7j;ua9fc{uCCkFb6&Y9_yVggF`M+PQ7}3CaiARjp4M^Wli^8(qf?7+2P5 zXSWEw=>^k11E;}>F?1wet-IQy!T-iz%*wxQCCezCbzH-Dsq%O@_J_GXBGwR^3T;RJ zzr>vsHaR5?EA-SUFCFH|Htk6=}PtZ;kS~QmOBK>F}?a1gO>o9B>sz z^f&6ZU1C`X`DQ-@`&%V>a#HR%U*X^$)Y-!OTi&jY`saJ`i{$oQO$y*1lUSi0pDhW| zL%T5R%?h`Z3b#tUu~b0o?^8Oy^{W25(sUQ+_vk?#s{KjGhg+dmlT_&%8CRz^#tJ{! zBKNjGYwQvAw4ClJM1jJ0o37V{i8jmm>-Aq7@-Zepvt+w3O6XhrMyEx%ZQM-kr(cET zTi6HD(NNqw46jiN+Ni=vqOjP5)i5K%J$#d*7xHLFhsF8q4}|i(am^Y)cK;V9qE*#u=C z$_2lT3*m@K8lX`6ar_quIBsMI9_*|yeSg}nY7^Dy|3z!}fkM$!GLM}t*Rm0II>$8J z-S8enriL!FL1={qCyIkn+w7qTgLYobY_R9kRdv=P`SCIX9zd>VG7SWeobmp=7|L8y zS!K}f@?_~SQ?J1uxz2xHVxi^2%rXz|1WksapKePm@dN6NkHBpbZwnx(T<_Q%hua6Q zWc|p8$HJ{IT)qj-F>?rKDUC{A1|vQ95unWbU1QTV?pq4Q_O zeKdM?98k3r>l8cD5EpPXX7FK&r-W{B@_U^_6gT>5MwU^r^vVK$q^N>ZoIK<>`rWK4 z=gw2VXDNlpLRBZlcAw~!MMYA|l#eKt~{RP4IGAO1{wWuy`>hE$8?n%t{3&4Z-1kU-wTp*gEbL z1-=;{Kz1{7Wy0VLU0B-vijr3~4KdZS*7V{aw^?=%6y>iRu?h!_RYH3_<{zqmfo$}_ zkD`Ww2#X#1haVyXN?Sxu?IGo4d3mF6%YZM*@mVW-o|D^7pL8Cin@{Mqq%ntp+GkeW zwnBqJ3Hi|uaS)2U^v&5{U7yrX z;B-z*8qHGkGURu0{Tk{bwj|45nP>^3*wYG|fs0zwlx9yf^*%%<^WVMoCSWaZPgMk} ztACIBAm2y)eEC7qdu-Kb$tUAsJQ}^-h!?^Yzh~0}%svc1usyUd5ELIqc9>+z48cKX zKj-2Bb*ud@UR+`&@CUqYx%;Nzaeo7z_>gs1pE{(zN=smD97eTypUOV^ZTEy6s~U<^ z%LZ%JeSC-2)fs-!RIKQQRQH)tJ=wHM$gT>dbf$DL#0_gKIq>q(PuZ7!7VwD?I;tO5 zbaS6nv5d%PUcwgzb`s|I~$858-I;mv;8kFk`W|;{N zpFBNO7mB14QuN^Y#Wg?+Y>JF!-(9)`T`tf5N$i8*l$zXS2>5H-nx-2UU;F*Q_a&%h z^MWF%JZRjcBW<-WYUS%RGGAh`(Vl$kt#De=B9b}wgzfK~_2heR61bW6+VP%fFb2c# zbxJ`UZ7rDBnU_-7NvbAQn$TCsTc}{6e(MYUK-Zyg`67GGx$JYQEpK{&Igu?v_AWOf z({85%%g%@Kd?@JG$M7J)B6{{FQDs!_h^BwKI4;glGn>447*w1X3Ci6K1)dmA`*Fk= zp@ck^Pr~lN5ld)8!@n=5e&8<2;e@L0zP?ia8u(!z&@WMDCRK3%DzPS`g z$@S<>RhYNLom`{-$9<_Dzh*H)$@ljYWd6(43#T~FY|b=(xC$F@c{ zG)6~QV+}X!r#3&0Y<2bd?3J5f+j@U!Kl=!yuGY;VH#l0O0$4yj`SoqREGqTjKs=@0 zBDj{e6T$THXS2^k4xtP4v7c(6qQh8Z`d6f6sWMnUETZ$EMVqVfh}u~+LlSNZvK(qp zQ>UbPzpQ(6n1U*A2fKD_hhDNTs z^vKyPb7^@f+Dk{<&BjandC)~&+TbYdSV!S|N!JH)90+Ms`Y@Uo!*D6!XHIJzF?%!y z@V!?`^=$r)wnVcJUBE5eq2q65bD7rj#=IZejD{@OTHwX*rI~9tmNzXHfbkR4}nFI3-Yb`TMWuu~`FAQBK7Y@~`QQKo`-a&Up=HLto%21%d06Bky z!1;Wk2z6!IU@+DKQ(L7L4M9+z?^H%zl~JxS3{+kdUr- z_Z|xj+2BYES(q9DISGo!De#$fB+6W5E*tmCo+@@tR+0VYv>vj~+vC_671q_RdD7AH z%bF*mR*@apW8J}Ki)0RTb$3P+xM{J`A@lL!WfO^kxoaKecBzbPPbQwoH_j;ej5p`d zaL5?;g667=xisS*ThM*Ssjn2`BV;zdfpaFkP@I$iYOrVS_{Kh0n)3I1CSrC8+&rEN z^>wuwt9 zqZ!v>0K232YK@{Y_x?RWdF)wncs*PDIoBuv+yuxL*_TS5*4;kmZ?(~aX(cVn7S+ks zpw5c8Ns%K#3)88CJZ_g;FWcvlDGbeM#ma(ti{ofW*+P^P&@T>Jxb+y;>cZY)Wxpd!cy9|JDzA6x_$_sfDo&9rP0R>AIsvoN7h1T0^4uR=>lQOCAdWI zjRsy`=;8cc=#;gfY2vlWPk4?)3oti)r#vO{^XSrjLbl3hA)N2Yd;lHU4UFYtO(VR; zglx3*ri$$~3+?_|#gO<_2H@-^-gFdAm0b`hE8V)cL;MN9tWh+#^ja=ZIsERoZpF)t z1=g&qUe%NKEht$cUU}pIYAEdkm0JeNU#SI6n7K=675WL#n^`XGoC3 z)&|QUvy+>TDRZeq`6bxiaAl7cH~& zny9au0#CoRK+6=crDAb=rKoob6>R z>twubhVy^{t7(4Dw!@x&dAtuitRKQs(!eY)7}$B+({3EWm;)>ga+)XzAHr{NYfDF# zu6|+bbC7$Ve*6^miB@8dO$ZOSBeBA4$SW%b;(X%uap6E+e#xozGk~wJUG#YU8;3wZ zP6HEz);=zF`&5{jV-gg~!*rB8yWbXWd<-?-ylO_KgM@P7amy79c zY3nPvPCAKu^76V(O9Xv_;;+q}vN$-4uN~2|zGNt$M{xAdCoM7O;&d_MCJpD@HM(FL zu$(w~ipp(!f>L>3CGSemuTY%Fg>E)m90A-V;s=i09(3zRS)B z3dG`cJ<89G7fOlhv~Mtq!=Ty2`I^Xg1~d;4?BCt@r?jZIu(Bw=Z)4?1j>cwL0LSlFEQ!q$^kWnbPFt{C>vBAD+OTs;e#|RUUA|IH+ z;$Q$7XR!^odf8r^Q@;n`c+q)uSE)?@(n}HFlJ<6e#QivY*Wb<0lA%Lx`vyz$ZeV*+ zyQJ-jtja5tB4l|S(7%F;)ExqlS9FM=zM(L1{ap#aCJ)_MX#DW9F`mGyq4SI%rTE_A zapr}X5sv$P3AUB6PmjW<5%;NzIiG37cS2z3|qm|J%VC4UB}Rm z6BFpV{W1S=k~wpQ{e3B1m5s^s_4|N?RwS&pGxn6>`w@OI&bBg?vrM-NArEw zBG$B>437gq6$UOjx@Il+_Y6<%{$cb#tWl|2Xy70~$QOg!Pf|1Vl<)8;NSL%>y*Ttz z8z_I4S}qT36RR7*UBbI}3vorcAW8TmlO}o4m;w~W+Z)}B!s@<&p+A$>`@!;W34?v| z5Y$MLRXBgI2TrrL#4f?c8JI|~F%Dj%l|8l%?-bzu+Ei@3Yg z58U?@W;6sX9vFbHpJky}JInT{ehl9q;E~^)m)--yq?zOUa7<_#yO@6}qE83Dp7I8^yHX zaxkn>xK9oO{UE9XA|sp<1l-)VKY&M=S)dtics(sfb8%g5_WFZ>pCx~-sz0XJ*o$dg zJb3PUxsBiDn?F#y+xL*dOapXU$4fUs%3dlsp-F7rs8#fTEF=7kcalHi@FvO{>=U*V z4%X*lVMQM{p0PwAssyPE0?8||!4rDAEO4u+hrDG+?U6$p3HXgXTx$c);Di@`RV9oG zLdx#TJ4FG3yM}n`scV0}WzsEW`?I#*OQkKLj5tqh`(SQd8SK%f4yezr^6XjhB==46bUUI~x zeF%>Z%kJBK@YIdO<+xXn-#_~qOs@4!Qe(iuDB&1epXGj;*=|ok;)XJq`-@zHh68u^ z>Pvy-`<uE0zu(6Y0W%PpMU(*M(655uN$wyVskeQy{S8w?9w$wc@ z3VO2hVuc#!5_{G}U{Gwkcf)XP*ZDj>M!RZvOa@d1(H`c?hRlLg#rEmrPv@{bc%>h} zkH`Fkt)9>7irQqPnCJ`p@%y<j94_s={t1S1~rN zp{b1cl%iGa*GdC_EoSij8JMX`k^8)IDi-q}30PZECi>-PYpp@S~PC=jnZXd+2rR6Nqq?MrM z+%J1LC9(YB%V6=X?DO_|jrrsZrW`6;JPa8_P(X+VgtfpDJ3GF@Mvp)DY|0e30c=KY z8@FdOidQ`Ig7$6N{CV3j4eevSlSSGh_kKw0c{CZbq*dlpx3SzTP*4Lw`1LNJ?_xrYp}$h+jCbcnK(b#R{B^~dZ}Z?hd|M7ii& zO^)akTW(iPwwJHD+^UP@PZ*~J2!h{AAW|2zeZjD2-LSbH|PbpKnp6W543c)TQjkal=m(sY9Vj>wnQQ)D}FauVU)5y zQ4czO?TaMQp6ulZ9~yaoE>Oc!34MaF1{MIPAF=Fru<@d{P`fv0>wD;CXxZhh0`nHG z#r9D005$mVtjJ#P^tdti5?sG5p3aFK;_21CCfXaXET5faxaqkP;I2}5u=gdl5poa& zGi>3+*SF{r@LLYjcY6krORk2XqCQ-6&QWW?y@J&5w~6%MSrYqAmb1p+#-Dw3Ez8dM zmnx43JO@JOJ9a;wPD4>woV3amONgy%_}N95=qC`&y%pdl#5}zve}Z$k@tU9CCwbhy zb^L2SR9KE1Bv#nw!`A6gOD9|1r?HbkCC>$;`=fvny?(Jzr|rulajXPM{A^wq%ry&) zy7?@PJYXeqtC;T-K`B>Z0d|Jq9}(Z=^#HT9{%e_vq^(bm(pW z!U#2J#_2%ozfc~scjr1%aXU{Cij|sc_O97H*2z6CuOU8mRzRj#%kguiveUz0vS=P{ z5=nc|`((95^Z@SM7=NT}B?>KwUM3`8AtR-2SSFW@Xf`g13I6TuYi!{ToUNf<&6L*L zdv)LAq7L`|^EdStUp|wAKEUhN_cZ!9Y6prCm+FI=!^-9Qu)kkU^uw91Do2^M&zjl( zp*Tx%BV-YJe%Y!>9BA5Vtb>KLKSVR?-{)p>y;+>x@nF7hXdX51aOB>f7SrQ@`#uj> zYx0juBLQ4wiWv-**CpAX-bruT(F=y+;AKONndnX&u)VV)yN;Lh*t~mJRf`LDjlK`q zOkVeUDW`P(B+jIH;$CFF4&texCA4Xl8hw#HeV7LSiwy2jSYI8#%o9v?)J zXfKzgVIK>Hy%NVu=|L(!zbc^Ss}WT z2C#oYAQfKjt+wEHKq4-j{dhF5Un{qfI>dk}e81PM-_0?FaZX^7@s~vEqcawL-OXtB zyPF%Qn5Yrf!BOiG@O5h3d2bhND`~uj%zeL)sA2s^1%(G!0S%*`PjwR93&vTl^GxM%i6kgtg*`M2fgd;Z^clhnRwLYm6NxI^N03Ea9MZPUp{?>T6 zkBVN&>*IraGJT$&?ju>jyM$GdnS4t#;t4dP(9r*|!5!SSUabSCL=*jCgSZA4pG#Bh zR8WKPOmQ9B^jLVdyKiB?rOL|ED84uCc`rH%<6-~hQGgxMhtFCq#gRZdh=$}d2cEX< zV=Cipwx?cm;o@N)5#rif=81a5(1a`^ajh?3$R(bHDreixYG}rY@W>*B5->LYi3x%w zsRUC0l_hig)%wH7A%_ru85y}G`rOa&zu(cJD3Wy2qFr{l7_80nenG$4MNjVvwBb)SK*2#_E;pYYE*XfE2EoGp?r znKPDrR`5%FkUYk(MOzA)3s5zH8bw-(-$9QsKdrvi^f}loUnzGEK@c? z-~%$g#{FscUe-r+P8x(epM6Prk+FbxrVJnr-ngLw76za5kkD46NWOM~Wo`8Gx`*Yh z0GA5IvsjA{JEmX>IMHuy~r@0}!4<$(F3KV)g-=hPFS%;w{=4-OAj0 zf0Bz@dldEa3`XG<1`GNaMaAX(DR0;mOng=^l&4KU_G#~TlJwy8V6;aw+Xz_+J)_E; zUEXj**l5PgFMkGQhthQ&r*6eVEQc)Fn`gR3@mP5p+oLbj3lgBs4TdCl=1cv!lQpeJEZdoRVTdl(26%M``thLQrNu^W%BG4R2q>7pC0N%tzJ! z{6o3&wdz>p79t0_JYM2f+wv={@-QhX#Cd)N@Rr2y6Bf$pEFo7Il!Xa-k~na~fH=}! z{#YWqUht0huR!Zu@TJjd04B^f9qksfE=Y4;;HMxju|JG`$$siP`<4y2hrjLj8FgU(9fDn?B?OzjT~~d&iX!K6jqkqUXvLEKMSkQN|Q~&8he4 zLaRK^6A>pHLhM*V{`v;9B*n9@MV}?tAr~0A7rYaNHwhsjoo?W1Y7F<%es>7Cepdj; ztoX(@9QyHaBm(GMi^9jDHJ9R)i-wfp7$)kl!fnWcqNe%*7Oj1l?K*c?BXZqbg{SM% z-=CZ5K&@wO=%Jj`4U7fJ@x>;1I^q>>WM_YalJ-s3bll=N!0e+df%ARa-&z4?8Yq$_@uC;7RvQ#mt_2bJ$L*$PGS^>}AP)N-82>U6~ zwZenW*H-Mxl*KJe_rYh%1h7#<(w31hadWT0`R_}sm-T4C-ciGS<_8=o(GJ~phs*sf zjIl19K>dm>$ew@i?qS+TeG}+69hu+#vzOUYlWIgWvMChrvfDo{BThxbj8_*>BKtyl ztEpzryzaLZZwvl@HG6liyYp|HmOdCga=`pV*5H*|b72g7M-~9C>!+WfU?CVnM z*V%$;uAg4wH&mP3@EB6F>JoBr>i+%C*5}g=nl#pL>J*v&Y_ai(HU$e-f&c=YT+Qx-8MxnT zfz+0R1!Gr@-|`yV5h5tjF;n2C6Rb?)3C~kwVvU4!%6rO2>38nKD#u*HQtdNRoj}%h62dGMF z(v=vD%*Ya!ajZ+e+3hDsh(J=rwrs;RQpd6G&t_>rOXX9@-F){e|GSU0=ik}(_K{G} zjF0r1(_%0v2l?CqyHZ}gtE}rvjK0?I6Q+=WTpob*#0M8zxmJgq?rX45_KVk=V}86F zjh5<)Q^wm z{++fb^(VYWd~0OPx=zKlVrSVtRKOhnw2(Ym=4C?H837#-*2bO4t>Ins^_T$wqDgKZ(Zp z`XVStKd9)J5D z52)dc=x;R+_5RQRPn(~n+^0!<|;m%M6QIrZJ3Aw zs;Z7o2O4YA~wLfWs>dOnSebx-V`tcvL>FzA7AHjGh0K z?$*X!-m+-F2zmTgK?dyd~dDaF0%v z_cMkI?BC&k7k1~xsiDRz!azPH>w5F-6iE*V_*si z0tvN0+F&;i;)92cg7F7YKHrBLWI}8ya7Vi=FbBN1T<7dBFC1aAD{fb5fQ6NE&Z87k zbme|-+ab(Nl_@gV&-9~Efq z3x9y`6QPR&&Y4+-2bP}hvAUcBgoFyCjxe05xc!}j)91y?Y*3@dVSpT(PU)r}C~{Y9 zE$WKm*U7`1m*2pdO{n9h$X1s2MCHGc5ZdLn;7%nJl>Z$t8RyAE8$r!~H(z`&hsRAg zpW=S997G`JJGz7la5puafjqFHwi3^@*1w+s21Vu-$qlgnk^g_g%WY1r;A7^xcDn`o z>ve~DdFwTM0CSB_(%pQtf%)DKepDFn22>^nD>Y=ZOgpfU?BVkZiTIk)GnQjUSoc(i z?>7_rN)Hs$azLMD<2uuyALliewqJdO9~4P;>DRelh?l}7Osm!a?&vbxr6a5pdde@? zJMi}6p=*Sje>qi(ya(Y?oTL7XVMk#r(#y3j%>Ib?F^6AO;{%>#$)P#E#<&wb6QDDE zLBg>#9cJ{oNN-C|Hl7O{9l(Mk&`Ox;qbAL!g&B>ymObSZd?WOlH?1eWm+wlPb#i*H z({-571D2qip{U?J?h#7=e8>=$saK`I~c zq^kw?Mpx}lPP%>2TR(6Jzz6+3?!PbmwJ+*(eWf*X(7)C};~nUCj0>20oXqX`TgCEu zBm~R6@v9Jb=iS&0?qI~e3tzjR(_B_8&H!2W zNqE{LEc%b61cvB*z-at}3^KHT1qOiT^MP4xGwrt>(X9aBMqD-buWy;kk8juwp9J%R z3H?p+>X&%h>K`N4{P4)^5vz=vwFH@-pQ~fdotlkF%_ulzPq_h`jC2r&ri70SH0=w5 zd`1%{E@88O9Vc60r=L%$uZPGUkSpc^O!zTqO#}4}OfPrR_qDiHp6-B~1$;RFK-V1I zMOn{P90c6F=;P+&}By;J*`VmBNB zZDFosgf6Axn;6_3_P=KKn~C44`rRdt-^g1xaRwc z>aXJ|a>at^p6=2<0x$v^xSDY>+tp9l(=~tsqb#w1sVQ(9{{2th`4qgq`{q9l{EU5N zgFQ*(GwS`z#3H)=+|?fugVU!r7nH2lGg|Q%VX@g-1t_gTmUCn32gb3tD;)@TlvPr*C!`^v?oTRYsRC~kRr1W-pgH)m}j;5fmcpRh#H&e3Xd>jIO7o*{D7qn(%# zPM0Y#rFI(qF8oKmTzmFxJqAtz@Z%ol_s5R}7g4kk6tz%qpcj1?lcDGALTKWTaykLT?bH5!v*|dVxB( zzW4+6H0ls3(B7t;&&J&(8T{2ROHjS+^DvFZT*`yDgZNAv{^<^WR5O(6OOaq&h z2lxv=7K#4Hy9yyk*(b+SXkS0y{B%Ev4f{;xmI1r&1cVe}q1O7nU5e?&@bi~nTU)C4 z+^`f{qlXVesfp76zTYUo5q^}O(X193)v`Hl3Ux~JFu?kR-sMB^NBYcu(gtfbo2d7N zS&~!SuOzUy=ajy@RBFwPj%>06$AhAh>szwWgLc^$P0P=!)xIm)pSwzcT(wvZ*0J&i zFfXrBuEO5xa7JjQz^Lc`rMIRTg%RdOYn<#)0sKma-XHTV+@GvZBAx*-2iim`VgM>p zQRB1$tMj~iJ5Wa(luPm-ZeJq7M>~p`MX^)*#9u|S|L)%hOw9i|7icsW{%jZBE*JV!e^G1ND?sWRf73?3Mv_F3o$IQb;DcRqI4Kb67=d#}_jG!vgy^{WM*fAf*~fTvOQ1%q}1x7J*AtJ|o_ z_5Jw4t``${E$<-};$0(3qxef0LAh? z3sNCJuai4pmWSN(DkqByfCaIHP0HG z>b8Wc$p%zAzbyen);#a&AC!x*x}}4AM&SNW$22%E1fv&^g6pn-ThNheWv+1{_qpY* zo(OZMvlGV)Fo8OGZ8#fGk^cGS9%IN2DndQWwB1Nd(Ix@Meo>`aJ_Q=l7BXPRFBygR z0wmOB-`)I5Ii#wUIEIf1^bE^4fq~?u-oHg%dwl1{v8x-@)RX_#D**H==cWIdZg40p z#31jqZ?aSp*WGTl^3Hip@b*tNVcAF|Z^z(aoixXJG48)KUjzOZ_aTKP!a|f|vkunx zjJA~o#g^Akxx)1DU1S1hHOEK%PNv^?avHSA{vi0&8a z`?t$iCWA_Po?7b_y)nP5c&EQEJaaLt_RsDRf=IidYr)_@pbJQ{Yr*fPOz7m6Cf7PA zf$(kj-baDuPa-82=$Tkf>!H>=c6!G0LjUT0Ii#$|Vad&qe%ac_CKKgm-ah>dmC{UN z>ZGy54QfG_JkD3?mdnNQ;(p1XY2=2$B&+m%Mw7Z^z_Sb+xJFru-xbTGc{*Kg$igFG zdHYaz^^$*t>=>AV-^2&NFBlwTtgbcm?aymjf}VG#W?XDVFsP4a?zCco@mR|}^wE)* zKwIG;MXXHCJ*n`OK`MU(Jr5gI-I056@B@OZ)-Tk;Qfx4N`uNvoiDXkhmx+Qi`?@Wt z+`!$H`&n?T5JR=AYFr*=YOQ?$GS6Ty@Ygr9-ebmLFtiHq zj2WczD4^Tys8e5Qs`g7e;evoKF!rN#7r65Ni`FB**Ij<;{wVyuAb_Bu!Qu{jqta~mT6e$R}(LAq@?U?yrU2eghy6>`m+e%d<%$jBNF~1ztHI++}Jt}W(Px+=C}B;9^aS~1pm%!KjKS`vc7%ja_&%oLea!52pWYE z*hP*k#UI7-jQJ;2`y|N6jDe17^$$$58?OlmbhMF%;IvT`o!F>D>nRAm&$&#cpejj(^KJk@J>KtnG{J$BH?|`sL zEef7zP%`tz{znce|x?`tP;)vQYBl0*iLcH`3!$P{0ko-gL{X%?02s$It@KcYYN*a zpYTVn(DyH(`qgJn0CD|QnCO#8|I%_FPi+|zY?A)yJ7U8@TfqgdQ$qo^g!c>+Zbkv( z>?0eipN$Hc^RSuZEawOZg{gP8QqwWYgC)O7&YL|QoAXRKdb6+C1mJGa5TVuY6{Vry zdl9D>#U<|9(c@>)vXIyDUt@u~uW}*9LU@2rLVwW1yxAt^TA|UI{J94~=*s8cR0E-u zTlEo1{)|}Mn(Drm3V2E4qfGt3nW5Pyyrp>K?*vrT;QMy20Ol2=@buMQ3A{sg|Co(; zZb<0C4s!J%V%4*M@neiaxWVlG=gCX#Pvym_MY;B=X1}zPx$Ul(%BUM&uc1ZOl9XTbn}BRL@)grYI-EV2mXFbZ;T@ji`<~!&N)a$(vlHFWz8V@{uid}dQ`9Q636ns4Kx+)Hi3dDPbrKf1+t?Kp@kSd?} zMA0y84~d`Y#3`6vv-j4==B$6hG-i*sw6>q+#xswbu1R`!>9*wAZu*{>F>A_+7uHK} zIC@vd!BM+^-~g$=>*>~^u!dhBCJmT=4z4?|ZitHU2P?Wq(=q9?&%orY4s-q4+i!%x zKm%WXMxv4<@1M&LCYqK7^9WxL4Tmgb`ls-Dz!Qw;efz4@!h|8>J#_Z*UvehxYva`G z`_gP@mZbpKv|TMZf2vJWl=GAyUgGtkt>2&iR-adD=-4XSTsbUpsXOPRRe`aRcu z@@~xAu+Xp9uBm$lJxWxOb1y%od@vHuXo$aa^;!<$?|clJxm=i|@bid#Q3Ay3N;-Kn z_yGGDpm(W%kwljlf8IXvZa359@fo}|zgVEPO?yD=ovxNsnFJXV? zH6bsl=5YUIshg^GbHJDtTBql4qtf}Xs>PC_y#X7F*wd0Q z7Y4`LPo6kwyz`c*R?Vq2-KyGrm5?_CKN+O8H zPqQcePN@-_ANU=H^+l&pA-!edtpyqjzHD#r1n6C8PP_`*T5(f3(~^C(DFGATft&z_d(c zW3k4Qv|9HHy;ptvoAQcA=G+(2#$fuxtmIe~aj!E5#8#?}1)2O?KU|2QyQ6WC#VIP{ z8vC}~9743NtFGaHh%Gvyg|MMAkoR#!Ongrt8YgehM+>T>7;|`inCJ>Q-pkLz&E;ep zQg9oi&)*eI#0WJ_gs!c=WF3Dn(K8dn^Y@(3woN+qk$D_rV_!R6;-`3Su4KBc$L7KO zC~rF_hV8Ajnx>v;1K;E11P6J`EU@eCb)S@+^XXw96H{oqujp2T<4RZtSuXDas3WlU z_8nrjYa6w<0EVTIXbk%UoA+pt^&h%xFrz(dhg;Tw++vI;55t?Vem+v$Pl5IN?fbqf z7bG>5!-D!Bi}Rzh=UZ+CsN~TLU_V`*57Mwd@Tay7DNB5VSTNm=*-7X}EWm`@eY2}G zwjDcWgyik`tpf%Eu-Ngv3pEs!t^8Gzm%BWE8O|f$>=_!?pY5Fe(nHp64$T+ZqewT? zErPFLfYqI)=s~`}8TPM$qH^gWR%|%R|*Xp?_oJXAA8(m&ytjW zAXG6k%s6`8^p5+2>VbN-Mz`Wvx~)y~VZWYEgZBYY@>QL0yiADPRf+GSWkK2 zZTRC|{1dO}U{4rin3d``z5)P;_7JdmAE2L zY$Nt$`gQkvI6O~V<35!b{@ixMkw|VI$m}^~ z<-GP!?vpkxi{xrF!(U(T4~&Yj4rnros8_ z7x|KyRtP&Y=)#lcQC?ycf$iD*nJXM&3q)h#aun6%c`43y<~1{*^`HHU<`Dl5$3>xk zUR!EjWu}Ixf63}%spa*3bUOZGi$QR>r$6B)eBF~M!i;AD8 zh63x}Zl8@`a)+YkfSW2osAnHLX*W$#m{&l{Bq9{zz5>!Vp)LPxT6w`%iJKE~x!y{G z`=i=vVo>f&YWpL9LzJbn?^jJa=etfi5Ew8vv#z$B^k$5)OoxNh5M;H>1Iig^AFsO| zT*|ZV^-Dr$md|F@dB{*7Xz}<6pr+AVeKG!H>CCniRe~t`OU%O~D2O16AfUc6$UIL9 zUw;qPcdhQ~>MBLVBr`H1&OR4r-#kYyiqltZ&Kp%JJ+Sy(#HImo zoKceEx)_j5z!+FaSYOlj;FaOqyqMJURWwve9*-p&rflXv38Sngr8FMfSDYv>w5#vTnc&_H`2Pl`3<*+njYRrwJ(v)y2fYm ze$Q-mWnO`&y5U2FxQxx76G)dgd`n97V+xJWKQ1J=FCmv){^}#yhgt5$+p6$L47Y!3 zO0qeJ zD4Z7uTJhimb@W9i)ct(*&nZ`v0}>=&3~#m1{xQP(iXjAJa^gNlPJPH9t8@BhKn@-e z{;2ChO^d@ltdy%1m_wsnb6)&I%+9^!!VTnhW@$VOADB#K2WFVJx_>3V$B|0M{z`A? zSwrX0ioVZbJ)MqOw|O>2w3v-9*m#S|TTwU~1PoPUdvu2G*Govt(6~3w9#X)_*bwy3QbV*daeCg8VVTpp#;2fQw5Xx2z^SSphb4pG zP=#b7!x|Q{AP;h)VceR)*!)h%;}5T8l9#8$ns!U#x`0{@q*B+$-51Wp)7N@3wCA@A zK#%F9>p}s#V*ng+{KjLi$P-`@+Q0oM(lcERbm5!chxBYz6sY{tcIdUP;3;ZPs$min zS_wmWDvZY$*3c%sh3-XN(P0z=uJKe9G#B99Pa?hUdV={@y5eB3=&Q$!c>40v2Y%w6 zdVaZTPQAJ9bLPm86@Q1zA@2Lv(Lb(IW>U|BUQ`ZEK)zG9euR)v78kyUA{gh%&KH7O z4c-LVr9Mv@!{CQ+zW&B?uO*~|W!@F88DKZ@km-ZxA4QCN1 z)zq(rN3p)<ljpPQzROvPtAl^cT+em4wteC?4>9^h zr$4b*{kswji+!1DSqkx?JoWCup{^BXR88{S*oUwxl^-IWCm2fYGv6L(IDIxVS$*Pz zoP92i_tLi^r~Obr?a}Q4FwCVr;<0=x6LMMbA%6O`!}}>1G{@#9xI^>%S&Li8JWn_$ z)tlCJN-vW8+gbs?k~hUTS+9J*)$%neq9VMD#mDID?TU2%<0f9y&cOM|Jo)B_u0Hr{ zV@b|6V^#Unc%@OB5Q3ayK8Wt6`#Vb~`^I6>ajpBL+(2A)5cR`Y160Lz~U_I z_6hG-Bt2rdTh0Ch##$GY#jqEZYtod#`3NoFH8}h~T_C6Z1DaOH4=`&V*zB2X`%D1J zD!aSi#I8V!`LW&Sz|$O|wy$L#$>+u0`RGehW^8ia^Bp(K-18tHR-O#&&m|_Jmg131 z)7=iA*)=Pbq5Ia}rwnT8lkfu-x1gVQKExcD)^IAXkMVPXz*gu(eo)@AfcsufGwn47 z*rVSWjxZC00qV0`$gi-WO`W0E)$=$k+28VD;xhU1E$vWue0EZpZ{B)mMgE-ZJBO5o zu+WjFH*&}3<$;?n?5c>m0{WW#6x24hf!nVSJ4Uyi^DUvcUY84XLK&c z?U%!kbf^YbVh=v;4&!};3D?Dazoo@p7Z^lQQ#gHC&Ia^6x%sV2$KqODvnQ}N!yfcM z``69ga|lfe7>TOpXE6EgZ!z6s?==~p_{8TAZ+}Pk8f0Z_Qwy1|Z{yDn#_3+kj_u^B zERg#>6|fZ$B~6-PXCYS6MDc84x1kbRPQn=hNv-mq+!yaB9 zj@Mo4#|fZXj&MI+J03$}zOX|@M(&*^vv}xOmWTjLDju(`OHW?|P3Z}!{lr+ur-1M; z@TzZbfa3pI5b(@d2RVuwr^r=Hr-sIFn$(X=r2EE+%a7@PKl8tQ*c`&0d)(;|4=tMq z8^gTDmDbGT{s=p!Ci8~%=iP21!s!~;cI{md8rVHJh%JKvw;);q&^6#Y5B-iDo3=SL=UEPDn167>DcysL+C=+zDBT`J z`lQ1LK1?}A{}$kd%Yw4_%!voBLv@wTUJt-b%7>95+52wT=@Y8Hbk;kZjO&@7yc?_` zE&9v;4lLdJc{eVgrw9u4Y0cl-gz5N#T$rfm92KJx&>MC)m z`av}wW%s^4@}{mEeHIr*|GoEQqz6tm{&~^n@dQ)?4v@bmsO^#csvb208SdLZZ-`FS z>7g}WJX9K_`F8-iA};37KDl_t5chMaFJ!{XeVe%T_c_lGJd~^ZXQd?a?u|K3SH{y zQfBxtRGZ!)hg&?T-a++8m&$NT^p8M-fif`FFI=VJ_Y~_AzFgX8#1<1rG9TEWkVopn zNYU4KtN{XMTKNHh5IHlq0_8?F2gBH0GejF1uasx`d~3+0J2_!K&A~TzX)~snV-Z~4 zM4!-XT3sBIPdw6fg?rg4+PwU2dOjOLo^T)GMNg>mfc1W`+`n%2^b2n7;-ZE31F*RQ zMx_?MPuBQM3wtz!=ap~|G7VLa_#*yH=qsC$cU_R=$YP=L^3xBRK1Vz);sC%* z^i4sp#{M0Kcj=vAtu_inhDUaJ+*no+#O4i;#fvr5M`2j!+#XUu0^{`wU#q&02uD8o z8i`!c8A$nPpA)JyhiwxFDer9*>-qO_y%+FhwNURnCSd;&b>qH$#Rv9Q+t^zSJdH*< zOW2#Ecb{7DrB&f1VS`apct=E8hW9-XDz6{mv$CJhWzvKExczXPn5_4?;fh_)&E!PG zTC&^yu*u3YKjig9{(}8BGebBQk8-haojVatD_m8;g)uVU+o+Brb-LHl&AYtgh|)us zXWx}}nXgx-O|^ZKchBz80NvmRr5!G1IzY9`;{Xl6FbI8+ce@r&ZmM=e_@p9vTCSg_ z47s333KACH%F$-@gQ$`&Ifl~fqtyjG7B9_*J8tt?#zyPZt(o~A zy)t0rBB8{3=)H~Hah|D_p%scJ38UT*G*^bqbX8B=|4W~F{xv&HfQ(ubfFx!*kVv9B_{NpCc-d83f z*x5eQDR)k>qpM^SLr56mSMNqd~wXa3yk zF?F8ILjyQ<&)%z40A;ldwh&Bf@!#SUbMG7Gc)3WUi;%@DzMUUsaY9zP3x6+@f(4<6 zTR3`qO)Dd2SCaz3UI-5Kvkh}c_$KnR5zeEwhfj6d1gQ9rr^uizh=H1;4A$A6_95dZ zNd-<7^AOF1`^kGwh~Q2=9nIP(!S*)a?LH^k`^R?qbVaZa_XmE0e{RO<5I>26mXr>~ z^wl#sqN=0B5gH40 zuPeq1tu2t|)X%lPaAs^Bt2=$;AVH=9ow{H9OAo3lT6FQT?^kqlmF7VOsH848;uu-t z{>jHO0pI0(wIwoVd=Xv3U>L^u1%Dyme$_KP1A=liz$>$Um-%Tu(|OyVZww={hKOw} zd?!QsY#%1`@XWIlawTv31{z?^sS^+P7WfA>_QxeJhZmXhc2T~xHGR8|qH!|Z9jmx$ zUZ9(*?klDC!nrF5h zgLAu8YtXLU<%Y zMUPj$>2YuJ*p{nx%^O7#1$W5}sn$MRXklm;YOTtvE}qyd8Gj!ZFnsxXjD8Q_xkW=P z8VtuCI%U+-p!g=j#4ppa{&9P=+4n14kLA=lFopD8+r3|BMR1#Nzk~1xo-FVuy(qm= z+*D_-w$vyr2RNYTaleq6_mhqsAnM7VFCat1%`ONrkn~AwdFDn|NlytO0%G%a{}S^O zfd@KKS4rV3BZ48_p0Ij)pTg_Dl=6M8`^H99`GXfhDx0&3k2ZhA^_7H6kvpdHsAnGU*c2}7>35&M zaT1hXZT+(BG0t}AjGpdI%@(al~TXRdpM{5_qe%b~o#y5iDx!H{ni zsT##(ra@%&?KffV^a4ZH9((-&=EkIaA^Dk~b1`1|>|mVowf2=4L!+l=^sVfQZlQgY z1o&r%QIp~rjZx+gYs z{Ox<}^$kZ0#z2T!L@jUIS4M%kh@(b<+ixvR#&n0k@1Pd$hGK`kdEIah8^@r;Ir}oxfoh~g z9&Z#^{8p;ip*%7=yZdE@zNvrj8G#8KV)Cb@Xv6j3jH_+B>8*j22zAj;^!Jg&sr9Sr z-yUO|zbrFLEGi5Q09T>46MMeVl#%K1ta;8#mXMc6<}}5faa1*W6pzu2_F?;?_ZjDc zFaydouo>#NimX&(n(}-^S@tipfdCwW2krNqJn9a*R2=I7$W^peCF*z{?z4=@OMYfn zRl|Z~snf(}rHxA8LamP}ZWUQV>!MU2X^R@x6xh(^h>OFv!pq9AHl8rSttWW#GOVs= zk)*KSOpv{`oOY!c{~P9EVelRs8&MHCeqK zzUF393P$vGJuK^*0>-ajeR45U@mK}7%vA54h_XIRttR5`2M=4^KeilR^sp|(s)%0l zt8=NCd45pgNCX2@Qw{X~`%K>V$*d!`zlbTxDq@aKN0r!bLr2^m^_z9CJqEAbJeF=c zqL-3~pB?Ps$d4y|7+Ikf8#$jIH|!ptDV{Q6wUu3>_i+dYYThnAX3RoardOg1vU$!q z)OdaBw(oryi-Z_GL#W13x@hv$xpo9G!{Z0JnAB*q0`ATFi0t5fRl=`%$200+eH^as z6)0Erq`Y2}F!=)y3o&hFRjA`{^pnfrGsV`z;qwM16Lx)>GCqH|NjU|F7yQC(=p5L7 z8GK+_3_x?-W*^`F@Ta2#6y40VFZdOhiY4+YvDj$8ulwg&JQoH?9@>S!us_CB+sXVLg*fJ(>G|Py(owow zvwc0t_lgv;&zo|&f2nlDsxU;Kt95)A9JY zEebDVhEn0XNfLQ+VzrYKghTE9=o)qvB>Vm~_!Q86P|zya5b|Ee%)(!?@S$^adnO`w ztf-7eQG7i@;jG^13QvH1q@s^#0YY)%qx2ogLbZPrWr?_tXsk8ny?so@>vxeqMq*`K za3OCU=Y1IYA6$prF?vL!C!h zr7#^h$Wb>i!DE{4N;=oO_!sG*R{5B=D}TS;;>N*8cAc2)X`DUTI6SUea8hX#rkfkk z062Q_Ie6@T=9@>u$eDi+g4>7hy`>|!@g)mfI_K`!L&S?(6@ke4mG0zoh|fT8+C)d6 zs$X%gmHC_^LoaAq%=GZ8XW6bfG0&fUuM4#vOcdV7*V6aum_J*=pI@A_eX5h3aRIJV zl$obQSU_~aEB=Oo+}`!~VJ+Xxb?t!gY{+?kq-b4F;(lHTSnbffzJJz)%n2L{@9;W{ zCh28NKg)SPRfR-+BvTiw9J=ZyqM2z&X~}AGX|Vj>*FAPz0q%mYp!YDE{PH#G7aNVW zBOV`H@`ab9>@lV2G0K5-Dj7CItI1^>)C?K9h*zyeVSJvy;Lh)}{0dw;NAJBq@}#sq z{`ncFeK@2zYHIDWoO^}dC8X~dP{gx$>qDU|V5JM}%=uc0$rL~{+A z7mz$JP|E04Zv2~sO&^?G8>QvO$W^%GbgI@Feaw08hZ=4Yb#UdaUzjK>A8$aa_II-G zlVY3?cZ>7-`*XNEsRzO`et5#oSY4@`>jMH#xtbj#D~%pbGDj z0EwVCL&<3G^!zw}{z$bu0%Cc>&4yGoH}*ALi1vEC8hPOlP^$Bp|8sdkOZj7O=OFS6K9T!}j8&VS=LTX$*#7#ywCyif zjFSz=2rw$i7xQ`s+h44jYl?7iJmGjWwZ|E|Ihk@SlSAOA9R#@YVtWt{MR7%rrxDKR zz>*WQtwYXOws)zGcs$Bj0c;GzVC%G5BtD;E1bmCW2<#nwwpzSjDq?z%Rc;Aw`?|m> z26i56`#Q~b)dyMcl#s+s|^kU zaD3-ni0c`dz4XPDSHc?{@gf1XX`NW(x&Fnh;-tHtm9S{A@_lyfl2VQty7Invel8?< zm#o$Ipdy)hKc|=hJ#6tS7c}e2qwLqYeUfO`?HyPDrJw7wl$Q8+lgkSQ>VyH|&Ln^gZ= z)>X}-Ipw|IaKURvEj9?*X&&wuVV78{=C`?21@u^nf!(I6&_Cq?5F&v3OxkGtzBgzK ze=v{vrY>n?s-PF$8|o0|b4@aKuaK)gW_Uo zQF8$uLqK=0gJvR)v`+N(21gBu+JyTaqwN&aAr9y?N7)LKZCSM-2O#%-AbcXVTyyqM zFL}QAusix3q)YjeG;k8{G~{%6)HiJ+E-;`?>l{zJdHGychy`<7DQjX=q7mtaHIVH!ogH9tZdIMNa?$ z>qESti)6{Z{W2S+`j+v&ZoKzUHE`^|<$qhLfw=fD;X7D@C}dpajHc9W;|u0$04*6h zylsA@x&6H}xS&$yO$+LN?Sx2H6=<92Z?rcFsRrB8i)VaK(eLFk6Zqs-(xg@7Ta?2e zs>>H%56K$I=ReTskpVdq&-!d|^2&|#{1ey#yzdnWJzTqe3+2{WTE}>S6S2am7iS#j)>ErOaYM*#7jih~m#Q&jAK73mu?_)?QhF~G=baYDESBDM*DeV&WyfCj5s7!AezVZIa)Too=Atr)LIXPs0 z8_`22`N>7xCmQO7ew-_P&_3^CSTOzl7NdHsA7!Plg?Q}X5pDXFJgpbjK9W!EoZ68T z81>`}V>-8c+F=w{HKP@Dg(D+f9AOrRONf8 zkC#_OgGUxVqY!>Q z0fZppN}Lpm`nqXJ-KQVb3-NSyxPDe#ys7>E0wJFj`<3m00XebzPuxEKFi+txF#dx? z2<$rVlasxFz|FUfA(X@3y`KVWnz>0VRAQ=Mn-+d9r=Li-^gf*mq$l1&bf)3^+t!TT z&FH=+1c7EB99sMGZAOl=b;Ya11~~?p*zAFL_D*kSQMqBG0y+^TpMCM37|R&0y+43Cgt`LJjb2vm*W>Of0w_okt#+Sd#z;7M7`2>1~{ zZfQb;2kR9{>N7r(2U9MHFeZ`kxIs9l?o_t>GE1s=g*x2&vp=yXH=ox(Oe`C|n#ZdF zip}&CCWB15Bwq3Q=q<kBYXVccVqP|skz>IIzJzUwL0W-HGW61_zG3V95N87Rq{ z^*WtRUgOS7Is5pzTL-cHD zO}y9kRV&9L@)b-Km~UbGlotdh>b2ar5mkD51h=BO@%Q)^pfa*x*@`~blBD7DcU`n} zpP-}jn%+M8C;rOsMgFkbMpnLBatiaS;fNPPfRWG;@?z61_e63!(6D>d+sD1hWF>Fe zYEAbs_=x{_1mRq4`&s$Dy}b7YaO=LmDt>9N-npEqhb z)%3UQ(da;1vioojElg&KJy+0i!jX3$F}Z}%H-oqj=aqtB4^S6~Ebv{Pr#cUk>rw3D zcVD)R+ux55FL97L_%d)nRY3__Nw(HrIV<&negt4)Dxy2QNlwhTY6s#}?Xx)wog3D_ zF#LoWO<_m(UZ0pLsq^#H+Ul6tAjs&KcXQiUtYg=zn{y_h1$B78Q)4A!?p$>4B;uT@ z_RahJ-pBiNa1!jz>G&0MhRAr^{)t>)C+T+*4z_##)=Jm? zy5Sm;>&JQ0L1+O141>6n&vYKf#5~S0ALvH zbId+J(b)Fx@4I-h!d{jL&Jx8paY~~+sF(DEW-DwSu=iw%-%+*>_UDzxqEDq)vEpwK zZspua@lIv^u2C$(G<2U^8ObZZu^1r~NjFnm8W59CSlSdOsGh)XdXG=^vzzG-mJmIL zKwbLHK3);6fit)$8v!Rz(Drx4~(Wx zZeXgqxp|<%5AGS`Op$*Qxi}<}v+7`U%tcVF-eG;eyEm|bMOsYx9v+EcLrIZQPrTG$ zuXr;VHI@>p(dZ%wU;&!rfzq-a+S5jAibt1=QQW)rZQE0X-fkS5&>>QefOmxL3I5yF*9%-Bw#MqN zA@^hbOVZuP8^8(LvhM&??IgVRYldca?mm)F^swFX8_Ns6xSjt*BJW?0=mYp<@Eu0$ zWq*-{iOKymYW2#Vswbd2iHNw#vI|UXIA&sy5^iCedBhtUPu}_v^U~F|N_DPF>5-U5 zcLyuv{tctkX80QqFd@7AF6H*r`_Fx>eoas`#{w~Rtc57&mQAZRFI9NA9Zh+a@Nhr) zNKZSN13d~Lk}Yp|LdNRTzi*3>2dbc@`3z${F}OcQr!nsneLz@`YJTa@I78KaN1^-ch)KfY4|fhL$>p$BQ)Jr^BGERQReB;vU*U&Q z^@4_#J?;A-L^^?>9u;UB>J-c~-F0jY%{rV<1?Ml9+ z=4 zTo2L4I}!;q`k!{So`@)dt=#97;++kjgrbGSxx5rMYChtaG~r)1s(QVpYv(0^4wNPH zyl^B}`zEzK(J7yKSQJ%Ts}}EY+{hXkCBncuh}Zr1M^E^=R?n%we(Q3dYY(HOLx{#0 zXhIjVcl@#MHyg1?dbata@c5kNh&g}4^4ts27o_N{b2_1&c&0e6VcQ3cNi|(IM#4e) ze)qL(*vvQ+i~Pl<=v~Mu8(aTZXjYfi*tFHCKIlFU9wP{Rw=}qQ9NW$Q7Ld}hd<`{- zFErx=TjJ|Dx2;7AEwdziLKr zW?wC`JzABi;b_qXl0*+J^pqzLzfuyx9?#G}F3FwfSV?Zc`bQ}eDpK7|1Q9N8(FVVBFY z;*AefJpj-_ohjv2Jj(EIS^PeKAe$VPd|zkhwlcH6z29I+#^St3eF|Gcan78X1e`Ju z$d*gj%U+d{8MVwOr0-8h1xxy#A)M!abM#9!SATT& zs9`^mjNK(yYv$Fm`Zn{3# zkq}q&(NzuSQqYD>b~@A?*;u`*JKtMEjeBSniuK_lY6?Bwn-fP~C3lbX_M!A=y_Z6Z zX8Z+FHTaB=&-^~0sL>8)p?1)!oo+RtH4hj7#&MO!VNOO@M79a%C(fU$O;uo6s-Df! zq{!nDT!1A#*j17>6r(=S(!PO&bf5(0b-|*|?dE{8YD`C+Jy4E!3)i!Q5>YFd_0J;< z2Sqd<-b{FqxQX}vz0bii;lcv%LK!zW<{{m0gr`o-s97~M7cgMF5t=xL&6V+Pin%*befVVF^Gy@!DeUU7KqUTpudz6qVoDZ@5Z_yKNoOB zB)07+Y1cW?@eb6;7ao$$%L0hlcKcOqU?zh3dQd13eEnE|gglI0~ zpUJUFwnaW$OZU2OP!EF?3|7cv6}6p8E3LRK{v7YiHT2x^g+ls3#h{Z---+Xw zaCoZ|6gTiojGJSmXvH>qdxqiHtUqW1BF=TgXhz_qQke}$*{Ava_L&XV+|&8)aRb`l zIp*N*AQ<_NL=K!mq3vv!eW4Hp0zyo^3YX;{eej-Yf0s2~Oq7DdHz+1&UbJ zq@FK574e;`I)x-zr!;-&Wc2RO#1kxl2sbto%J{OL+E2>fTqhg$!jKLI$B{y0c}7}o z5YK4G2N&$pg~do;t>igH+OS}OhHQuU*(GjMeih%a<56sFpz@@BOi{v!TPqHulddbj zkC(|4;erw0Rd*kgg9}@Z#ZD>h9(~%{P2xERX=<)A_)z^WRBYy%H=H@RU(|Qo&qy3$ zFM_iv4K|DTh>7I+>Pba`n*a2roWR433++@bqN9w{_Ml18_2VW|q8#aqQ?2#uneQ3D zy%s8K`(0fA?aTUW7Am`2C-ADZq`b((%RF<<0FbPY{nwd}cq1bG(U5Cn5EN+qP3F=; zyUCI5VNefA*A>_%@8jx}oIW!89NF?R5K@F$`&!WMa$e&boN*P~8mjP3y-B5hiiH%y zlxs5r&EEFO^0hV}XEV&3yT1|N_KW;M5a_wHK56T|@Uz`6Og(DqUO3xdjS^}M->YRd z#H;R($-#$ha+V$r3m+40IEpV&I{`rszLh1=lRVR6T8iUY>n;0(c7UP!0o}-eSk5Yp zt1$j;lvz;tkv?S3mBVl54jOErV^4A!Y-^BbY0S_!1i;^a|=%QoRGOQRK(y7dK$E@f* z)>&YxTYTX>F#w5XyG8kU+Ax>#mqGu{>82#u+3nYy@t}fMfQ4-@!9F!mmN!KKae_OD zyx&(&#C~3t6~f#5wm9j*8&j!?lzk>$wnG(cA6a?4FLlb?G6FUW((-t_d)jhb!=HD4 z$gpgHqsSwj+$cMkCzfxHT!L(FI4VTLa{Y8(Aor`Y=N+#`?pX~E$*OlGCi~f>cOf9p ze-_b>OQ@hS`wR@s4&)Vz(4e^zG3p$tg~ z`f-YQJU(=MZD&opgiIizTJ?CL7s6baV5xvBpy5qMW08k>7#cB|w@;L=#iEhjzwsur zp4My6Wuj!kz82=j#;^XnG`xkr9~7AMLz;_u1Hb^}Y5{E0=d5}rJVy3M{n?+gwt5z~ zyR16znmnBd@#8(Uk|my*K-<$Fm=i$RG7gM97w7B(iNDz(KWV4eCdj zL<_OhG+mO|#?kK_eK})5sF11u(5i`jD>@EjqdG=;Q2w!2nJ65|>rF%11D%remR-My z1zh7&1e?fvw^!SLnMC+x)Wqcn;;3u1e0@Ko8x8xYE=Vh&8Gn+%-FhaoAN)Qu&M8FJ zd1CK7sRKxUoYEs8@Iw$Fbu2z(}0V`2sEm ze$|cPhy_e7-wk>gJ_+4*K0mNrLo#d~fP`${#0AH>I}m~4-}2*421v}c?r4wfxhKl> z@{9>n9WSmFnAPu*GLG~z*^{}c&iN#Y1Zf|juDyRwNaa=U?y4W|iO0btNm$>We8`4Q z9wMH9#;*jzB@1Mi6tni#w_g?W`6#53sZHE ztK8p->fUYY3;tb`+mJjsKm6+S4)IHgT^x1~IHT0T4~KSat7aBque=A2N5>u|SeM{i z{CS>VhTl6kJt$E60ZAofhY{w>>2t`s{)fG^EaGh-xhL)y(f(_bRxUt=hp)0Vcu9LLAOE67KC=hOuV$$zf57cC;59DpFzn(ern?_i}Sp?Kc@( zcU#D^!`(z9oa~{}E%GjZfo~4>x}1oMr;aZc65I7%az|mgAsCkLo;b1xxmxdTc44RT zS4Sf`{)!lm4t^Mqua1~NgdpC^9+FZ0vHpPj1D3mxpZqpOZ#@N{q*C=X&K|Kd7yi0p z8>P5JW`O0N4!=BF`E-i`l|)};6- z>HB#(*N5DH^1zT(*ris(&~=y{P75Dpr8!$wc||D zPtYh4Z7uzDebO_1$*k62(OqqzAEj%~mmVC0ZgP(#TygV+Kp(R5btm%5m#~ljdg?4& zx@{&pgrjP4q*%1h!ymHryy{NyhTQ<;CMu%q8#t_EhdRX#uIgEUOw6DPHx< zUb#l4erH7kNFJSp5kbo zT2|gi;SV%`49U6hG$C{16jvc6ij&VCoAhCR!;_KlO9TsY0J6|+*Y`Iglw@Vl#YsbD0ahBCmHNgE(pKmm!s$F?ftYIHWu-*$aCaN?Y2m`;SZ zt5CxypoV^*dLD!|eBFz4Mc?hMRoweevcX;!FYSG0_9%8vZUgWMFtF1k^q7?1R==iT^Dq1wt_@5`ePHP>*NP%yf<>G&f9 zNY5BCCGv`~jzS|Y{^3R(me^mTYTvxu=8!86oR0TbKJ{O^{ICOnpc2}7;I=4~W0-mw}W5HJQme(p<=paIT62Vo5(sB8RC6(k6%hSK(3lZ&D-o(LNs4xWSc8}<9>4W~bU zUM_}jeSS>OD5u4?Nr2!Arz#KCIUHBs_0A)+FR%qT_b(dzp*s|vdNe_Nl%VOk;!kKv zJ&%;7yTNu5?(}x?^D}t@IQ@=gRz_pv6%wawFaw{X`3bYemEf5wbq5{mOh!ZZn4Id~ z>D9suzw9!!W|3`2k>gGQ&wn8O!P!HFzGwd^Mo(-04bZ-4VvAQc*4b+{M&@%Rob^)Gt(Es#E)wY3l^$zIDI&2p{v z7loS16Tu?=a*X+yO#-yrvE4$X!ZuowDbu1>na61+7g zFzMdyp%jxrOSjaS%zhQK7SrLABAJ780)7xlus*-8mxNBT-i2`t?Uk~*-{APOZv=5I z)TulpwWSIO`Nf0KTxa*$75oH)CdOa~NhLBPFWDZ|qnS9?NPabukrc<#MlnkJt~kOK z(UU5;H*F^%%bE5&$;K)a(W8&crEh0{5usP!7n5^yt@S6zI;ZElZ)>xU*o$x25M>YW zj@&Wav9~7A9~Vy^fZTm5xr@$diO>4#)EHiW&a>b`9N==V7n?St;zjed;(5V1KQdo@ zSx=noIj+7Rnu5(K8gP&9V(w!a8C%=>Y2+dOl7@HMs6zt-RP}Tb>Wn?%X*!S2` z_^Ga3s526BOPwG-FBdQ8H2+3j%6a{q^;~}K8wrIJl(IpI)27(YaX#~8IYhe0a(;c% z+HMTGlfJT4!NT=8Rf7xPz5MZT=;eg@vT-ea!3xac18;6u`KL^Kk_9Eq{m|E6d&^z` z9Fn~phb${m5uLy`$8`5#{fmT6HO9~4eIDp#OBy5&o&+{w-#nqGZhl=Bcf2W_Sd1lc z`gRbL!~aEA%6DmG{eCS3X1rm`D1RRBc)uB^w+AD^*u0{Z=9qVT=;*6;$-irCOyn#N zx3XI02hkuU%T#ECPDdQY1ppQQ0&K@cJw3YdQ|;wZ=kMb%JByFvIyY~t=>uxK2Pph| ze4qfJ_iBU@C`-a~>`m=BoQb*2!BSqdEG+z^yzfU}(d~Td9xuSZtyDG(jikj}@_;L2 zuqO$(E$;19VxBhVyyksUT;FhUzqES6^)ByUKP;?jXyvp@$$2@D2ehwA6~|F65NQmIsmwdR_0jCYXg z69z{%B@kbbydBomng!Z4dW*QxsT+TJbMy5;Jri2p^z~gmKR&)u+dRQ8p0X9(JPEXeg)UK7n$pLV+5>dRx#nE8F!To( zz3+?GQ}=dE?BiQAMkKX-2cmp|?n8<3O?A5k#WdzEJ}&&r%}Re`*$QwrkveDEEk5N` zY{(Ac4`-v7N{2$OcsA2fV9{95DvqQ%D_uO4YH1hJT z5mxWl8o>1o`@tdljtE=D59i|NmX`dWknDxj>tC?kI3g86Iaz zKOFpVcpt&hcmcC%!xgtL6jl%)wI8on`$?KhKbz#71~g0cz=ySD!Yh?=P%82Z$%`Hd zB`oQ{U1xb{U<{mw9AE>Lb?1X%&nwaedX1QLnMlZ+?`uMSwg_pU5JndJ0 zK-*;Qf%O#yh)Qo)$N+xkVegh0H#(2FXu+W+!Y@e`WQeyie8L{?%R4f^3owsJ`u6ut z+$@_P?D0N*geN60(^Bd~ z-r~AgC!s#iM2OiW<)is{Z{RJe_3$~=+e=3tm&C&`YEa7Ky_W_`)bdS5CHnPys#oc> z=dH?wUW17w#OENOJ*&2{KcPR6GhrZ~Y58%EHz{4+shz$_rkn}&2pYn$gCVa4dDP1Y z0S+n|^>%t$fK(w!<9mDLnRuLPP0$zE_0PKmN8Z@rrhJXx=jzhx+`e8h zF(2-K4p3v|dlQ1k7z2JyWF4f#v#XhX(z6BU>1u8}Izx>!a*@l*p32k3oZLG2Ab61;d!sb_&n>D*QvQb$A*3Vao*z*H1+}uoBi9b z#$O!nQLw!k6C~e>zPGxEdaHzc5oNM}SFFnt|E;n;WV?1@S!eWJZnWS-m?}bvvyI2UB_0i>r1uN zc94%C5$|eT?fF-Pmb=N5^u=*LMNEMf@8!fNY!ZG|uswaP^M;;23>@m;Em>;eg33p=k@8PwAb_2z+pEv%DzRa-sn)%8B=Xa(_M&c)x z-;th{ekQ=7iR~?xj{OkcFT^FkwrGXJ_e|XIN`jYF-~NI%1x|Eyc|I^t^X4Oc?A*$4 zz4>DA036~JJ=&j1ykD0omaj=24czuSKWw`77S8Pvut@dG+zz? z!K(K2e#ci!3f;!cbPVAw7PMnACovGp&#agxyn{cFwTujG{#@tEN$(0-L2rk^H~4`eI=?TinS*UwSC`4ZM5b!f(6ZqC^6A0{$U^Dbc%#7u6QTkcDh zKhCxmK!qI9eeh1TVhq@doPXt}Qt5aD;jYSfzIg8?oHb7O8gYh(;dm#rc>MGBb8w_yb)@NzAF9Um)>&?PqxNmxUWul7Wv8{avMzqGL z0zCKr1Xb}&`E5-0F6P9wms8~?vVWcCDAPU|?}qpCE0n`^Hy z+9#RopNlK+`3U-oM_e>sSl&)VHOA!%r|3lIFjFt@wrnIzEb6LvoB8(b8NYnMRMCfPGXjJUzIz%QD4XnLvKf; za%3Pc@W3cUaHd9b<1wFBQ}=xQA9fFIpmH|Z^Xjtqi*!F@FglyaB$NbrraHXnOZ;da z*7uUJZCP1m9lb8%018fawzs`db8Z%L+1S=u_CmmEWek4G>l-JW@0<8wv`wF+GiY9j z5*@4dp~AY{qD`LmG##7;>K@IrcfYo(b8V>>E`p}F+t; z3km2eRC&SkVJy!S7;%cqxO%@xtfrl`9kK zb)7{9NSZ&{h8J7&34L`c@}qr0Sr)@3+Bl!9Bq_Rn)sON3(fI4Y{KU`pStsWwQ6E+~ zT{c6MxgV?OuTJ@(Y4rI!#Q%5?cIY#WG!h~Y46=IbxfuF{-P%_iza>L?^cI#lGq#UJ zC?@xFVVFs=K?EoJA<)Pvvc&2KC%3go}2%WMF%3%C1Ba) zl05JC;BH^=6XWTt_}Y@T%p8v5v+d{^c7xIS(_~HA$3ghbOK307zV53gjL-=ON-b~F z$ftk|&!|Y+`zdrf?KQD{-G2tDI64ex|G_fgE#x`w_Nmh(_VueOqQ{Dr z6UZaX9pbZyDP(yh{X)6Ko-_$t{JO2c_U@G)1lQ($AYfpBl7)xuSG{d0eZOyNX!c@a zFIptH7#uA!e+~@ptEnFn=()fBm-?Q0kLg8!Qc@9qi5u3;774k6y6MnxvJuWu0Z}2WC1kfl&XZ;beJSSq^{1cS1)9tAi0 zoS&8;=MHl3!>>&d?%`7@AMVsQ{qy&iTqz)})wo1nr<}-mHX$kycr#}HCKx27IiiVI zO4U$|oj&Y*kUr#oiJeXwl(0aiOFZi1eb+dUd+e~(jF2ml7xb+>pkTPqfp~I9*kRu9 z%@H&*_g3A?zw(+r;BGis74^+dDW8XYt_u2deRUjG)Xe?L*ZsD-JUmj~PIb^aUMS25 zn3a#@ZInoS&i9V$#La~o?%#eT*@uet?#2N01f~zTA3%xb-%hR%nX027J4ED!< z=^zsk3rva?;-n5YbNJ8(-d};HkM%vsEsH<-`+{ZtB179ROQGK*QGoM0eieO2n@iR& zqOT(m#PHlNk_;T{Lf;js7G9_Cx**47zJn{JB#Vr?U@tzf)x3<`j>*>!x$lt6xcL3U zeHN}lqL$o$hY-p5+*0fpgg8HcD`+_td>&WfiHWwh@7#kZPzVxAjdPwIzJhGC{Ys%H zEZR5csgi=W<;YoN*1+r6**ko0Ad-xT3Y=n%*R_(lbG9bJcF+M-YN*^)(-6Bm{zWdHFZby{<>g`agH}-mI%i)YN3BH&}OQV+M2+l;~ zbAL#ZL0g3yTm?Mb9Kqne*tN2^H#jBYCUd_|6AD>E!vz|~zt)REC%+$kpSh~2s$)$% zW2`)`(kOeUa|Z)GvELl&czxh+&__zA07I1CG~?`-c2U(z)3%rJEW3~$PZ9*Y)v6NGqWZZ%eOJx=2%nua z3*LF-NUY3UEQj`duWvoqrqbh8kGU)=&7J|w9#8ko-nX26w20RV8C8h)y1bl!+I|(E zEM1cKLUrHb+jm9U*+>*A{|&;@DF%LU_AB7`sH@}QQW)Y3!PtZxx%<9`PvF0o_L+(d z^nVZJZE>pz*JND%yzNPcD6J3m((=I!HS>KAxxY8RrpUC0_X$I+*QGT~ybUS~4#_S~ z#q%*Sa!S7qF;b8|y*n7>y_AMx8j5l}aPVepKN?qh04)D{SgmS%S6PV*LA6gdbALsE zQGni#bl|{kWI<_Oul&hN!TpcHiZ6{w_kB4Ye&h18)(Q^LY21F-?|1pQL}g!*uksX4 z>d(lGF)sEI6)&mf*!>EU=I?!+^$UDKKuR~qYEU-q<9=`bXaBv*oWi`u@i;2eQdE!o z@hI^F!@qCG*w5eJy$Oo9GQFJM`_|M~#8ItpnI;7YbF8If!a_oU?_&7FbX&lvX7vw3 zv|O9G7a-))U6knBf+<5_)Kfm%R~smpz7|rdtijIe-+!#ohJWt6@n;~T0`ujxEpNq% zyp$~*;3ALjd-L5Bxi9)vs8IO#=lsJT>T@y|o7I%&fR8;t)(vpY8a^umG8!k89}+lY z_hr5L<|!zW(C+&8Wi=9V#0i8UapWl<_pw*CM-+l_Y090w*aB@A!smQ+8E>P06{Gw3 zi$T{?p@Lq5@6(ydnfff|bxcY#!93%Nq-%MdN|Jp=(v>HF`G|+@3!UzM!|l(uiv|E^ z+|E7|ZE|+s&ai?kW+B-;R0OyxrQ&-o{YT6lzfV=Dv~gpWgFcvv$5^+ic_|7X2XEK2 zq5&*~!@COE@i{;#_%5@p&L2>up)j=Up{d1IC|70a$3wF{)lHd6e|Q80?+)v&$T0cA z@IN!#PCO;mq+x7O8r7D_o#OFJ4`5JPZx&GAD6=m zN`&McF_-Y+w&2I#Xialj*{9}d9S|4s8Tl)do;A_2L0!KMjXV>5?8YW2plVEnz9^;U=FIqZcawpP3jq5s*m1 zDcuXt@QYsYYxIii8#kazvV&)Gp{2KvoHwt*jU|fboi9MzX z(DCh+{eHuKy&huS^72wLM8LXoD3489P{|fIr+ooJy@=XwdEH8DN^0oA@iiA{mG9I2 zY@gl-g-s7Otcqg{1WKQg6XjnzXspc5mdz6a-j{u~nX=(T(ZOMHo$nDAP`=HiK%jq@ z0Vn?XcOu)jE1jETE{YvF5B5+@4gwQ8AZSFh+u%vWll%@Fq)W#ySL)||lUz=~I6N)# zOp)@vv>~WPAGva3VTwj$9n@+mss0JXHP_B$;Z0^1UdRPY|A^ZbO4G zCEbBm&=z)~NkS3HIwlc0HJ4%0AM{*S-@AW@U~6=;(OoRad?1)wJ~V$5>J{2KV&<{~Mo4 z$mO;A*F(AVwsOW}n*>Ave6oBV%*;Wa!6}=GcWeq{78GCKdZ_A->yQFP5fFmC_*Gpn z!RdE@#Qp2}15}T9kH;<>wny~DK-1SZHbf%cVD#I)DOvJ#e0&nlNxHl{@(Xoi0r2}- z{G`M6XDy7N zZ;iaau$cUO=flzSSp4H!1&dtUv#S*SRqjmAY2!jUeRJVL42pOiR)_(fch2fu#d{bZ z_nvYX;^6oO4;7j)y@UaGt#!3@LbFKp&(sAGmX}l=el$;(YyLJsz>RjZuA7S%<5>UaN%FO64n-@ zs7w(subr8QUeNXN`^G=%*NWyPKybx#`5eYaaT6zmN(mQ;Xz@(uL8hIv!K*Oxb_)M) zCR(~Dm+sHxF45Muw>aAHDu5uIW6^^tQ|zUY^YCFKYo}I;a-huj6&r5i-Xe8Ldp!yv zK2-fOwBGja!Z3b-IRN!G;+MLb=k~o+!)~VjCfX2%to8k{BR+e*Vzsopw;0H0JgU** zHGe^4uY&z9=@DCQ2g7YU==-j`K9d@h4#b zs?NdXWbAj_+<9|OG8~gg?XVdI;#x{yzqhblQ7jB(_$tN&EljWZE8x^jAQ7~${}5+? z5}N#}KAfPF5GJwO%B#6nZ(HFYA&B?m>UXlIEASAH<_`Ja*l>8R8LblOp!Fxdn(O4; z(W}0C4Ft>G2a)ktd==AqhA7RPHWQs!2-^@tg?=u zok?sP`@-;+-j~)pf9Yj{M&xvca_?QpWAfq7-k2LQh8Z#IvJdeM8!f*ZGH?8(lt zfJi|xYU6yBg36I?$ByQb$(RGj`u5rK$pa;Zud_}k>ht3mm!2*MULQ% zS0~#FbEsebf)U3zQvmbGumMA}2QaM3`aC~fPJ$~aqAvKa9!eo^3EdA`!be8jfBoe% zDuJ2G?|&)JADw0{^{hgAEKDi<>or1O-qi2DzflD*KT^|%JM!mQ%A?DxOV8{lgnYo* zcT-?GHgljJ{cazCNb_qy@>M;e+^w|UnL5c8jzbu zkhL1Z;G|vfuJ&*IC#5=jf2)~muwzmsR4RzC-amqeNQ?{6rZg4lKsV&^%=5ZXIQU)d zznODJmRGS(durbp+St=%F0+*%Y;{@r`f$krQipo zb2p@L%o~%a9SP?fo!j3A16l_Q7M{1enV56L57^nS6d!;Da7* zeIMA58TxK!?9UA%=^qNW_Ef;c6Geyz7ncxm{jgub(#nd5@vkEY{Viu#^sc0~9f@&} zKFpCfrFcL~wG`9ddx|gT?&oBB5st(6u*2u1kCxH%_lTcTdNSKPtTJZ|K$B#|*LJ~F zNL(GPQ|yTon1US6hvCsJPleK%ec}1zNQXaUUI7K3hwUylxpR;2oQn4LJIGh2akln1 z@MJ$BTuq#za;|ezc(y-0^it)b>%=nr5s^{9EqvdYJHtwXP^U z1?kvVqG2lfNdnUE1^f!#RPHa!apXqBl5XBK_|V^azmG~p2j04N+Q5So1Gl zrq!)MJ>vFOb8o3iph=vLMPA!&o|FcM6O*c+w9ZF}bF~~J!k8YIeDlebIg*EE0*jQz zq*O9o9w5KBm9P(+e9$9vz0M~j1*5oD)63y-SE^V3g_=1awv};rgw{T8Q2I|Zxe=)H zwOQx=6L<#K6^hQ)j_jK?u{^6xTAJS5NnP9^cUm92mKaX$zL?;DI976n-Yj2>6cR1; zKmPkYN&`tmkF`mWL3x{LD2@lD8*C39SR+`e=Gfgbk++po(mK%l-+`m-jr~TKNKJL~ z)DOWE9Ff3;5U%^|vl`TVzj1571^rah_5Bv+8eHI^oeb>dl9AuX?@)@Ie~i@Xv>eX8 z|2J`hWtaXEpbZHZnT`&)2S1MLqoBCN_jx&26y4BrFR7U%W=2CoO?w3W`_6eid ziX#r=o8QegpG(>z?Q^im+-ZXRGl4pKK47Tcklp3@$@Y6EMJ^3kME&4b55&Qd@{4K} zMsIFEB-lisd-l+fF^31ni>)`07xiv)`14&VD#MlcuK+8KF7nQjL`IQ8n2_SRgL2&NC3zW*Q!!&-I1D!hS)2 z{z@C@i@2wKlDSpcuK;K~j!!s8_lB(c;&P?~BOJt^aiWnC$uQ*Wqiq?7WE8UdKx8l$ z5wLLkMuVK4DC}3gtTS-oXkJ+}_G!~V^`U}<&5AM% z9HVOn?1Sdf8Ex5_`S(+Pz=lb)YDd3Z;o+`rpZc z`zeUl)AfqaGZ(B!uKa73B9Smg z5r%V%C0k%Dm1WhbBaM^O_%}@hDg3Jhl$Gt#zIkN-?3}yxuw~T0!XlX3NTA;aQ5;#* zC|tytTHF`q{~p}7*7!M8r9;-wba+11Wp6^ru`MiIQwQ#Jasu&ttrnWI=iLZ zTz{mpACyYj7zvCKg#KcuO%0vKI%?P6~R-up=qaUx8MFtPvAH-CjPUjm{#bFNj8*A3t8c{aWA~|{YWuT zdsSL9U&Mc=K)evwTR$;^va+ZS_V>Doyr=aMNxMMkuK115&3?>Tn zWm@=TddJLHfHSI!Q92N?H%=~_7_Ce?|W@c)%`M|?bvf{+@YJ@CKnHC;)>qyFssQQ zog!8-X18V2&NuxR=MMmUYWC939v}Rs5EzSYu#HKJO+By(sWWj6geXT|GjIKuz$uL>U-%FL;BDm^j50{ym|zqy_GkgWa?~P> zaXdW0#VVyf$_3s}z5J|6aXXDoSUe&J-@dUaI@Z^{doo6M>5)HDDeZ5(mvw0dQAVbI zCE+FI* zNwkIVZfUyQhr?=5&{jdCZRM=rm9XJnlj3o`!2XnC*f!30j)W>a=HKpD=N?l4l{o^2 z+s!eZrnv3u_@S#oK?D=TT5arFq{d)9F?T%TLc|Z2h$~?II65)GF{(dZ0 zckdoJ8gzGxX6q+6l_;0)M)4iIGuuX$^S;43%{G(>+m!~jYZ>}|=W3^^p6Uz3q^bXa zl{|`goHSaaMW=QFjost6;AjMF-;)5Gd`0Wkq_(uq^Xi&kIxZCX|I`AWJoL$X0U#QW z-do4jwW0)6nhUyEc^E{Zbkil|EpIpd=-h=qO2k(YCxD1UNjAw!)lx`=ACHk1UxXwM z{0QlDo*fhCXE=xI_a>Wl46(Qcw6Sd6TPto&!64CB^4Q*_#s5hcD*sm-V>WkSJ zO!o!M>QT%VZ^V%H7kGL!i^yex<@@+bU-oxM?P%Ngyp-E|%P+U~V@*8*OoPdN=pQfE zK88M3u+H+#Jy<^Sq4z)X9YY+*4=rr?@Z&LmorykvU01-JPP%-h7qtQ-&k)g6ALb-K zToCQpBUwhc2D84-kP4Zz!9Y4Keb2YNY(VC_{O<1$yPqt*XxiB4v-A7YJ*ht_`ys9H z)fO-DgCI3^I2@k($(&KVojwWKV)t(3i;_cvlBPh-Ib*Ax3dF=*C{%s`)@(*~FM(v) zl24|-1mwY9uh9dQY7)RWpA#TPhGXV~^{T84h6!u0M5+sH)Y?tsi8>qGSp!o5IT26u ztB}y*pSAv6LG52z;mIwS+eJHoVL+iwREuE*5~Lu+<|3eSkWQtGkB)aNmzXB=8XScL z$WD;>G;(mfBfLY2Hnkr86A_Jxx{!+J;sO^^h8AE3JEh34Rh71I^^Uhdm@+<*v7v{J6g;J$A)w1OeXNz4R{_@p3cz5~bL0e(n0(_8k*C8Z(XG2Pl5=o1Oi+O4$-zKzrrJR8X!6VAmdoA((`;=c7ItngqPu_S$9pL$? zLsZ4poHA=DUeZ4X6rPC}Lk0Zmr6@nouVU>D#t(tHigY>RudeGF!xlcXFLC6{9zlli zlICYwvU@x6_M+TBY20o93y!*7e7N~R!>TuhFZti2Cqt5d?p3M5Us5VGIU({{Xp~oMbZxv($Xu{xpftYQm>8B2-E&getE~)JwP@9DJ}U@{?2nYk zb%5^XOiCl%fIR8hhDhrR(+*b==Hqw&x^aiPDqu?pzMt{yi!q8F>7o04UA(V+ zc5~&wSnW8^-Tm!&2cqsJZI%db$En|7dF@yCURVsBZ;^=< z>i+44y~tPGs>+SZ`HTre)`6ZHSz$FEKmtb-0x(CE^WY~YYQ~Ku9Wt-yw!a7{r zq9Bw_Xc)|KNI4CYMSvcCB5UJM&747i-|zOTJeSA4Rt-haW#sAn6_UN0^N(-ye%Mba z;jJTiH1*u~_zv`C2^njz!EC0@SXi(L3agS%VUK@i-sc`NAzTI09TJn!M%rDoN=!!6 zq%Qdk_U$YOL}vWs04cC!Hlrd zzHGMKhg*^i@*`l(u*WTII8=@Ma{Goa*n{?XNfd@q!#4l>SA$#IlZovXsBg@Duw@=XLIf za^jvBNFCH#kyCoK>Tc?%i79X&Sthy&-|&r`xN&uXL<5Z|=??-wYL`u+26rPd$1(cE8yo9)D9u zV*jCUg?ha7t8GLvUSj_1<~6ja=0b)?x!$y3aCFCrR}x?5*FG|MfFDE}sSi`XSueN1 znjN|S4Uh6R8Ohj_FPF{AdY@MmyLGy4QG`K{q0qnmhNMsfKiXtq3OL2Fi>TII)UcJh~fg zV>F3}*1!81zjf7F4#53tChOi4$KnDAL0^c#h-Yl+INPYSF5FM2GA~aI6F&lwa9?wc zfz0&GyABaLiFPw_jJeQFC`i{FM{DT&E6@D!sGqBbEJPOO9R?MzYLRYAX7JEU?v3hA z_;4{#&-7|-Mo^!G!&n)Q^rKjXIhu7qngLy$N+Ly(?;U%1s@dX)l~pi5Per$HzwZ)P z-?+jNP&zxGtn<1g;Vj`YIIHj|N1iUn?XU5gMhH{sD*n#YNX0Z$h-45!3b97x48Szv zl?5oW@ia?d7G>w9Tr~9_HOet{6792U#04JDf{I>LdRI<}O_i z8FDc1reQiA)f=?U^8q+-a(pUJG@JJ8n&xZqE}DaNQhW0UpnaUZlB=C{!t1;}Ya~uR zw6~5|alz|8=WFBpF@1nvhBAN8@t{E7yLRk$Tk{8XDd87P_~^%W?g^y~D$QIVPpwOU zGIb_z)i%e)We--pVu6B!G35rvuxB);JuP-SBHZ{zBL)V3Vh~m9N-N`1eu^K zZ(oXTr~~ogn`>F61VC~RVb}c@9j9){kv99HhCEF@MLLVy$uFthwWmJZho?Q!5}Wk> z^1!;F+B*BSMN2#FB~f(gkMFN3zyMK!h+jyalPlE1Yo}|WK0{_eJY_XY3-OKPUvvwk zYyY?!We%Y0zB*>n)Hm|JNduFuAK$O1g_utKbKj2;_rs8$i>0{C$CRpBW5Z1sB30Y@ zEwWyHFGpgbHzGZ~=RQ9i9@51*!qu0Bh&ER;?*&y z^qIy%(vz4+0_@0qZiEXP^ked6)s-u_UyyUHa5F%wWmf+hhuXfQaMtqbr_NdIBmcmg zrB1Ii_#a$6cPx}oc!Z3KwK>IahQSXgWgY)b0q+lOX5bI_!4Qu1K5!pZ*(Q!d2@^i{ zwihnY*>fLEYFyFQarRpzylEK=1h<12D?Aa}S!khh(p>CMi*yK!-;68L%Av0>1y`Ww4janFoY=pLTApJfz*N=AYC@Kdp61Uzlc!qK9MYdU^t` z$;dKs)jRvfZ%EvGbQ5s%H;`PEBhlH;s5~1Sc%TexFEMH%DH`O1YY(@x`0lAtM-27( zxHo5Kl*THh&<(x|^ZJ}3!C$Q+dqjc5`t1!0Z1P$N%nJh5`cT| zh>V0i5bVzEh|$~0@Y$ykGy#AcJoTC$kZgJ(QNgK{|6S@ae#`iVYEw-!=)C+lGpr*j zb?M@zjTHsGOl-svhcKtQe$ALiby+`QRBSZRCH8{g9o5Y6sA*-w!P%{qCQ|I2Uj$~BD6b}&sa92M<3?*+>-DaJe(tXqL3L0_L?PTqKG7M zC!}p9&ZojUq_bFm=ySdK$+&kw&JM>C_OV#>-_t~M>x<@<%`9OuFNzzP6&$lj3|#{# zW0!|5pcMEUtK}CHw!+zPBfzt_JDHq!1;eZ66eN~_z{0sWZBUth)Dq~0omU^Ohs4;t zSSo>4Jss*H9Y^%Nv24hOc z?Us>fH{A0hHHkowF7ETk=H1rel)ZL5I5$`Iy+R}h8DL+;@7X-mtEs8a;uUeX$D(>X zi@?)6QcUvaR$N>;IPq8ZhvGCD4A1@OPyR}v zYma@tIvamJN+5R%dA>fri_QG}2C-1QF77RQW{&95F~@gRp`Lzr+R@!VdYZqF+eAwge6u;E9H&8@z}9p;d>F3dvh?KiQ!g2B*{gFmn4>;%!2wwRLYANjiHNK>BxCiQ%W2Q0T%73R^mp1!v|QmBJix8b zM$=v^lX%f@&5{at?=d)Q*ce}qVb7Ka=Tou>6McCy+09Zcw_aQ4b`PS5b(_Jw<<`}n zr{`gggvq9!Yyg2&>RV*HordGWLoqcaf1WsOZ#<%>!$(X*B6&v;wf-0W zRs7Vm{6kMQCLAo?=Xc@j`R&7-v>i?(@$%aaTE#>%x+3f=lsX2K z5l5%a`ds3Hk1qk)U|%l0$RAe+_T1K}JAs#pwj-0A5bcZuoD5?Op9>OW4y%)K_@dUymeGwVE@G_WOCs zGTv12{i48!9rs*Wi3mGEBFS5%;tkh-p!D<7!m4)nS-00qoho!iTF0oCyC>gX@u40* zr?G?r@ic0AmS}6=-J0s~nc>Dfj;}TfieLAx_EU!`bd$KZDWpRO?!I~?^*8Th)s+@6 zzrgM>w^O9-BQVJj5%tKQ3k;FV5??_YFuq#>4lfmVj51;e!-b^&Yc#0!{|ZU zNs|4R8FqbcgZtIkmsyinwKyqn=e z(enoO%^RVxIQG5vgJp!N5Ysi?C#7xV0#YCytIuX`k4~X6*2~X|bAp42nq?ur!{uXX z%gV&J482&N z>6XYO-b|G_$5mb_;jyHk4rT5RR+rA}%Y%Nb%`=zAY6sdjvgkEA@ z7;;h7n9PTge=@)^av5@0#WN}PHUg@wZ>sR<1_3|;4LPd#>e8pQW1iyaRhZ1GJilID z|CO0)oS#jz5yk97nD!Fl9IVlxDudQuxaD)da!UhB@ThOHyR_h+n^|^1LGlnkks%!u ztxD_{Q}*U2wPerf0U@#@1EbCTD8pcYxBhe4H_`GUZ&*u>zGDt3Hjy9yYFF|&0U3U6 zyIUcG;l4blT#y_Z`fQ|!pGcDKODx?I9rpRvLkj@$iekbe1t;_nlpZAU%f9vIBxr+w z?J6WWdDj>t9Gqh=IR{!pb1hf}M_{=XOFJSop7-*Uep0Vf;CEeYx zX=)SV|@hlG?H{sfkZ#{0+r8r-R_c^*mJ)mAXKM1#*<2CfdHZQD| zT*ZXBsrQ=!{w;?Lp6x%1fGxtvZX`F zSCWK?>CEB-1WxFAo{z83n1_oBZH9(Jukog_gcx2t=7 z2nqDNp5h5w5>R};2^8jBn=Sc@Xal6=a`EG!Fe2oo6A57PKIa6|%S*1`CYg_MXWz?o zuhj2ZBwx7kz~fC(|5zxhS5+guLILHPblB~$&(kP(VACJK%DTX*tE{!NyhwggOI>Xp zA!91*eU8bjoNxehKWmC#E)z&)Mh*0MBm=I@2-)MB=z?C9f}~jVPi+76v~;$zuisYX zcFO%~p}9|h-t{sAFY)u+;dhl96NcvrgzQIGcvoo% z{zW>`{U;lj!yQ8!DJ#J>uWtZ%7#LjI#1-=4UPTIf-#_BWD&TGO5QnWg4c;XGWIc<0u+#j1USzHjIKxuNb2XBIVRO8K&$X{)#Q^Jp#-6E^%5N-!!1A+esHE4-B?A;QS z=kgn%+=QLdy6I1r6)5fY3U*I2%$+`i6r%J{K6tT?O|+a2Xt~i%q^bD5?HwEv+9mF+ zkiB+OjQr5-UnZOi&ie&x>45}?luPIk^81iDTk%fc*J}X+M)YIw(_Bg|Jp7R4WJ>PP zH*Deh9VW&zo+GZcmw$wBUype$z?H-kX3lHt!6F5{^Hx9qP*(ckGmc(-8mf)Von^WqS(tD z^OT>FO=XS@&?C?11c8tn?0f4NFzb`s=x;Aoc<=YtTtX1E%d|=M`u)~+Rmy8MvKadA zJD!){KXE&J@?(4^fChA}25Q%4zsXt#@L>JiBRZWh!Z;(_{)QZ0dRZN9&K;rBo?>oIdA@If1+Jde@k)C?nYffmHCrs6^ z28M=aueJjVkp)Oig+{cTWhMSM{v{_Y0z?a&JG3PQSRIT+vk~g3kCTqq;t08mNw-c}*q^ zt>w9RKGV{ngm{L532#u25yCL+zi#9sY`2dwy+TnS?qU9nr+ZfTpd25?AN6y}2SZ?9 zh`^X6_#(WAzRvISF}pF-4_-ERSqc$PXp&Xs|5s1fqf2A+c9phbq!(MyhvV=KKbi00!JpQ3Rk{dt} z>AC5i$jp#lFwo$m&<5{EK6Sr*vhE(K#&Ub*cgILma9+P!q3>%O`m!IFIT0TD#=$7$ zCW}(wj_$(roWIggo-v!c+@O**VSfnT$5%BnU)>um|2FQqHW%wB zUFl~^oX=OOdKr1F1>Vg~4zD4Z9qX6W`DZ_L8w0=Z;>(BXqQBWK#hquO zDnUdtGcqFfw>x!-AN!G{%0D?TVTg{;KSTS0tMP$HBXafN`)2uF&N?{;a9mKixOp-M zrF5g9{yTF2w0A8i)gi0s;@Y7}SyWQ^lx_yjJM(u?`#Y@0P~OvH-X1H=&Z4z;cl09+ z5D>FrJerM2J$@FKMSN(H?HBi`?u+&3Po2hRa%z?8<4Jw8Uy#nU6Gu{;fuH)k5a&A9 zrz|gGO^VQu|E@^jx3QkKrgXi$ZyD2YNjTO_F9W$glWT6=9=t)Eau$w!X7>o32&=^2 z<%Prx{xkPXX1Fp~d7kc6#D{SB;COJ>Dl5;E(+KzGnt(f|qeRjHf5rK80Wm)M`rMT` z1ftouKlq23N?w+m`II!fde-mqy~OqN;v@1VM29H%CEJ?&p#9GNY~Ip)+#B}cdiD$c zJAG0glrH}LwS5x>+DPCV_yFLDp6Fc6+EScxptJcdJtk&ens+@Ym|tb}uWsw%QU5)M zKiQmKEU&M3t9|zwo=5RVaPl5FuJ;;+J{U(Hd7wLdFSAGyeQ~7^r@Z|IqKuRh(ELsa zOav5Y zNIH7`b<1t8sN4?5!(Y?p@3p=|u@YwS2CeTX6yngSd$@Mca%$Oxa`g&Rzt%DMHzqTKjU=0@~`J)R0 zYKL#lKgSJq>e129d?%wkpW!($+&`s%T)_=eFZHx)Ir?&kBaBdvM~0?8*bB}Sr+~`B z)pD*E8LK$yO|h}*qon>;Nqu>k{E}op!{K6*-pS|`yy=LRjQl;?lpTW;b4eblvh`Q+9tv;RBHUdB*=p6R-lW4y-b zs1b@VuDd<>Y-#4lJW_J(BYXb#pT*M=7xr_%o1^z-RgiU&0rXdCiq3q5=9DIIZH!smQeyK(it*x;=P z)v|6V$ZqDwoZW8CCDu2#Z($fAiO66WaUs(^Iin|72v88+XABSUf2&!J_ecMTf5Q1{ za9_s9QViWbwe~1z;IF4|i(b+6yd~EC`qVt5xhe!QW+kdS{$96FmCzRsbJR;5L12mJO8q(F1S?FV8*B_~h*GFHy7aXV{$3eYaF$eMn7!Ib2z_JLn0 zr{~@M1hI^kl=w`-_w_XZlb{xq9V{cU_OWPEDBdceg*eNw(y*(yVcGKO+fZH&FLNw11-n zx!;Wr?o1fo)cS!gan|7LzJFVLa>(XhPTn3iYJ2W6#Xem@*&i8FbLJ2D2esA5*cj-` z1uM^^Jg)A0PtxeT{dyH|SGmS{4=O#U5GJ9nVe6$w_vFDHueNis%=KTy?oTc{XL~g* z(dc}B;+=c@D1MK3Mc?+oVCu523_rBSg=C+Insx9S!2(%WZbQetCjP;OPcDBB4$d1b zVwWwPEjV*hM}CiPk7y=m&dPjK%GELs{U=WLrncy%rO>8vz;RU%h7QgKo`U7j%%fiu zeEe*&8zpxAQAR%iUR!Bx;Z9v)t)d37m4S?hV0+;^d|hD3$>Jldj;Owv0Z!^&5*T;1 zKLnhc^ko)9^lPc?;o%-Rs!AL<*GfMCQ6R;moeNsfkzIt?;0~w)gY$f^DUD++g3%C> zfQ{2ZgsKYBUnB&7J<7M-?4U~d>oh_XeD*?hVD2NIFtH*G4GVK1DC$o~MU~FIDV(C$ zvw6ci2B*HAYAQ5VQQdCygB(KI{qo2HNZJX$r?XMKjBbJheQmL0`}v;wYA<@Pz&dGn zVCwaBmEa5YgCbxL6Qf@o^sgd1G!q^U$it$rZSQ1qui!!mW_kZP>hwfGe!6eaI<2ZJ zvZt1BOG*Hw>|-V~$fr@vHSDE6#|xb8sSe{&xLZhaNO9gS-u4E8CbrxAoblGymoWKu zy!F_AqXr!c4G16I&lAtL1yPbP9;0X_*A~6T_IN%y2<*^~y^pfiG%iROP+fH|Iv@C0 z{EU-0z0KN}K0kYVWFI5422Wm>7uhH_7O{-(r0e1Q`1MEi-1Fd1;0FGnHrNjapT#^s z4_$0?_$hy=%RM6_?R%t4cDQ`*FsWf>#&iBgwQGgLUnIk*6+F+_Gat4E46#WonGWZ& zhJDZRhapdU58QJxbQJWU{LO#)bT!+6+*Npj6$cEoDW!0hM1pUQE7(OS-|lbhvBd-1 zIWi@Mw={f{CHnp<8Zzq*6~sgG+_&+K3(oD24g}El9nRW=@3T;tpT~${4C?@3DqKEM z0|g=YQT12$?)=#ABYpgoS^9~LV#-(ItPyVLmF{ZKO>jBA|C7NnCE^sTzkI=Sz~YVD z1vrhwDq%TO#Rw)m6o43_Vhj8h2TuE#?fELv>KvIqe!)dQk?&&c8UUGQGWqmh+T7ZW#m*U(z>5rT-aQs%LcI^|!QlHs-tKkLr{Mpa z@KzuLVtd#xSopD-Cy_7p9r*JjXSxA?Gvr1z)K#iJ6+Df-bcW99_~}C^_c)prAa03OmMnTjH))GpE8(K=jM z>vxX7FH&W1BS*Jr0ry}9^2qN+cKNh2>brM!d+j04$tZqHGu(}zYQMo|*w3oP6??Qg ziRDcD8>32|5N40p{u$bxomWv|ZbNV=*1uD}O<4cMb1yyKE3>Ezi8HWK{_02g7lLNu zZ{>UjkdfC!{too~75zAh*>=YPl1$u8pdadE6?Ep_E<3!IPoEBlEq~o;%V`tjW(`jH zs1Q&AyShpKECxR$8Lj84&t)ECR<9GoOSD6A%+Nh75h$Fr1ZmHwfLu?-r}Yj8 zU|9|jTFJUWm*)A$E5}?co(jTgk(Pba7xplQw{N3Y>P7uPdnW_M-S<0YInL#KjOkL^RN=NNyX z9vn<@HoJowt8F1Sxl&Z@J2DRY^FsNZwhI%qb-+Vypf2-8XyK_Cs!RAHb0t|ei zHs)z?a$S6gc)qc2iHPd*1NT!m4ap3$^P{C6>^68Ff z5hfUco|=d=q?ho%{gMr$DcB@QqQ5UW_>+pqYtLQtp1v-hwb@tXV@JD9uL%x)S?(rW zQ6izsO;e zw>TX*7n1#9`M&$VWQaSj(=a{##`d+j3^$>j>3z`i)5Hu552h<$(P#k0e9cmI-36&>yGQx-`u6W#D(2<5ivjK%XZYoUpmYm;{LJVLCKU+4~rl%!=%NO7nP+6$aNOu zI?!;gYI`Xrf`0XPq_UXI`i%RNnS7Z$01PUP30`#mzpeaJNirKpL7590aE=I`?r_3;iyx3OX5Kjt^Fn*j$G&0 zu8nF3I?znX59-06fOb1mjB_ircsh9KE$XY40rN=CD5r&vr0l7ILZxwdx6c~)FL`}6 zXlC5C82Z%pz$U#si8Fd%O80RS-CwVwaS>Z~4-B7o%_Q7WF)`1;YZcGVyU$^Pwk_Gg zkq5;4M4f-D%5=UI#D^Hg(3_KZ#nB$2Sf09X>E_w`jLy`r^ZUh@?Vn-zXxTG)GO(qL zq#Wj_xCalo_T|`|AW1J$UY3to;B^h)5&igh#}~4A*d~Fw7qsNYzJ1k>-)F=ZGR%zj zt!0KBnzWe^GAa^NZ|a|(_=2$rgXv9_|J*KcZSpu(Q#YRKK&`*?XGEJZ^Z9t~IkODR5>Sp6g7S(0-x*OJ;HN#1 zE549%%_LK}A2@21r)4%l4f=Ey^k>b1nQ|RsdAl)tiR*wHf&F;W)sWVnh{{K`zZo~E z-djJ?sK4wP$6_8#*g|r>1RBB1+f(1fTmln*^0LZ`g|~Q@_ieYWzbi;vBj3!OJu;OL zG5km`1_9+lN%JQ!Ms%3{B)Bst!570m^)0v(}RSuwUEI#!D$( zr;qxfUHh=s2-`c_W?&cdpdb56Dn*6M#)%xmobzj)|~sY&4B z;$x+Z_M9xU_9riG-gFWOXpG*cAs2>GpB2ElebFf^%m=V@51#NhUi^85^7GYWga|~$ zRji=N5ZTf18REqlQ15V$;HF}qAp*oX%^ze5yN4{v;#!NM_hmA!&fvT~s;F4GFy$LB zf?w5YgwtZ94g#`*#THFPHdJku7p)($c*jY63%hhGUYCd6ueWm%f1X6NkDZ^+(6{(b z^81DNo>Iu9Fg#~8QE;D#cuzB14>l#3^jgXwPd>?e-?q|##$aZ=?H8MmU-G-UMZF0D zZkoruuEA$r$gUG+u`STBb>B(&D>`} zzwh}|u{|b8L^0cm?rh8X^#tJ&^K17BvG#Jf9X;)Ox$3WUwOf}I_CVsMTbr#ZZC80q z3C?`D<(?e|cdn`C2MQvuch8T`VUj94NB7UL-4Af__{8pbP!doJFI~D7n|J8l^cqwe zQ7&ypI@cc%#Oxb16)wp4G{hNLlo^zcMSUMn(*a7TE%UAf0lq^f+?{~4>Sj04+ZQw# zbGMKpyqyPi*5x;RF3b~69mC>-4nr?AX4#oxR62LKd=Kw7bPF0dnBV#mK)Mo^F6CH; z7V1t7^XFrwpV)Ek&yIQE`eYBPjKp^Dn&v|*n>WK6eS_Xu6M7?h*HDp9+Obl{BI zV;WzrKL7kV@wW1+39m&aEayp>Y;KmPIIBNx2f=jHzq9z(M;$Oqt^bZ~k}GEtDR$y@ zRDO3gkk}-AzP23vyb>VMb~T2MmfC*b3<1Tm7+y}mU+6X)=R^s!-Vm=RWGIwsq;w~) z3E-_SImD0Xo0;<6S9Nt-*xeM`!k(MR(#a#1TJ`a z;_kQo2lr3?an@m1c)O~N9SEByi$`n(Q7BnbD8f0sSxpho*IF+y`|659WJ&SU4EhZ% zT|eBmi(@?ZQ_&A7l1~KY@@lg!^^ZEVlUc>Dv=7P?t7z3@WgaLqU9jc#87)FnSL#aI zl(-nv05Yo|B6qij;7=TQJ*3TBzbl$*xj*V&Lq;?M`oy?r1Yd$ZIE8xfAQQ}r{UfpB z^I8zV-sz}?2Pp_rGYl)!(kGVlNV&!&%u%?9BM;KjJ3yAhantkPB~i_N zcX#7>Zpt^LrC(V~5ZSN557Dq_Gn9FUgyB7RRMdVOWwoN$a((n6D2kClGw@9-9oX>R z$u3Zi`%!_+4Sl|jp>g!BlXbX%Z~6WD{Y?+^DJN?Zh%I2NXTg>uz%?j>Q; z3@x8VDg$CX>x-_>8f}Qo2N*5iJTxhQ60hdw$ujcmJ*jRza-K|* zecFeUd-^TB(#!lNV~(U7Z;+$=zS0XlrrP=ryC}G_M#wzha{z_m>*vR>BrN3$LVEuR z8TP==JOaAI!TG8(su^xFGkEOo&>3!YvTqf={Xu-GGQ1RN@0-V#A|KZ{UiJ0;lv=56 zto!LPvn=Ff$4D3d-Y z0m{Yez88|h*Fj}omvllal5Mv8yV~uDNfr(CM#tFD^7U^a=sL&IFt4}QJQ$6D?C*S0 zd0O1pQ4E`!cI;EYm{z?mTdMlJa z8_XC`I>-rQM{MwXS6b}X1GQ6o&hv8E;3L;)IwXh9kU!vjwdtuElKY&RWOzOfx_vVs zPQG4{JkGoCJ>sbeLlHi&u>R_K+5Z*E+k8j-QWR`!-7w)@;&ga4p^~=&3yVRUd0Lxy zy%xeCQC}bmh0eLw=l!YCx5NZo2*cxhkApm%Q`?7)|yd8MPqe}8RF zGN%MEK4N?GXtpqJtF38QIO<5hy}Tgha`EL1jokuXH({dtnsP?!io^7_8USs6>-_-1 zRdzrVJ`xFH0IQF?X*B%lOI`Q5#OR*RzFP9BB2c#o_6aNzmA^ALsC=;Z>2D=4AQ4}7 zV8srx4vSd(Go9iJqBy;Dm1yhPFhXtAtv`9V&CZM*|& zW!|2kQ`qg&?~j23T!*)P2o!trRVoL8AWx5N+;p_8nIU|E01G~y<8cT5 za|P!qd!Gd=*}xWiYlr;vGMQ!i?Nj%_JvgQW1T7_e1(PTmqmj z@@~C+sY>%Cs=XL=O*EN{T^36#sagwWj1v{-qkoFgie`a?zdaj|TW;s%p?e4pTo8Hh z3Mz|crewo&v94i&1S!5=K}G6(>!mmGd!A2mt|jq_dA3iIakF#4pT`ps=}1J0ups7X zK`=iKjvSRiCZg^;Kd6_?@<@E&*M1Q^JuJ~L8Y&6_`A^4A# z(}e@e>Zam;s&l{1{KD9{cTJpIrqo$U$9AXPNkixvfQ|Dlfidu;MA&`z+Wp+K5AUnA z46bw^&zW;I?5gqZ)BUIt^zwMM{jL4#z2>59_Xl$k;6S8y#BHc zmAGf8M_nm>OTUnf$4DQ^{0Z*ty?t{q%I z{kr_>oqQ%PaMM`WEsdxJv?L+(-WGtzFMv4LZ&k>Xa9u_@yW-ih&O8mA-@CfBXthpl zePrRL+`r|}SA_RGvg#Z?=J%y3eDl-aiupR7E<|lQ_FmS2H~TEbHD)-W(n?W91{tBd z5L_hVBQ#Z}W6LJMr6=UP&k`HAyZ!KuP8n*&Y*kL`9v?glbF4 z^;JBlMxu$gcQSA9wR_T4YhUpVyNo3Fi*D@)+@86b?(Al<{A;qmkG2$FDE-OBfBC6v zJZk6w^FKKgQZ@R;_cz&~hD~xs1{>{nJE`pzMXo1+Ps!yDC-`;vkz}SW3ss*R3Ee*< z{5tyrWgvKvN<;FSAnn0vhI{KgzWXZK=2^q~y8nsx2tN;~@=I^?oO@MC(W^avo)aK| zI&{_K2U*o|cx0-?*v|H;FQv0xDQJ*p-rp)MO7AOxhV=^&tbl*KSivV%Dn$5W4Xe#i_i2Tqk1?EbfKt8ToO!49#m5Q;tu`uueX&N*u#blh>x z1oZy6`dbQBJ;_75KAm8Bxt{09KEOi0Sm-yQW!Nxic6LO<HBH)mY)5#cYJ%@D8iuY;sB9lf&fs}rbN3QF9#7yyx)5yf5aHQbz z%lz8ILX&yDj30YAnZ6$lxp9%Nq!n_sJvuPNy4!;>wj=6JI7Uaa^yA`#Bd0*W2t>gU zK1^B)Z}fSOk!nA+4zlKb3@g5gJ`O-ff|5NCciy_{UlxS(qA^b@plUKuK10l@rgMhN z*dT~aFv5e|D6hD6Dypf^NAEBhfpZK--UskdI3*XAeh|7-w+A?!Uhs}Wm^ElKiM^NX z#;e!CHo&}6PmW^mrqkexnn4>(-YIPTq>E2KO%&FaCzMoNuj<X^jwb8maf92GQs$MYUb`$T9kGx8T0 zh$xLQTl~@eBYK3$@3Bnly-HTvFQ`Akil6lo3K1tgsD8yk=F58@%H2bCuIu|rw@LA-B)Ii=AHrfxulLLQDXwa)|&hggkmCAP%xrf=ITtz6gCZG zn(6Il)Y6_ZG@G+9r12HW=LJzRYu^vnn+@n~T}9 z?u_b(81VkP@$^3NOYMdRA2W(=4UF2b6+0_1>Sv#c_dSbgNXcpRx=-{=))h5{=D5He z8W&-ApVyu5NR3ttRr!6J*C!GKwNFke#Nx4D;DLifYFqa9dpZn`-ts@}7>7{$g!jo; zl6M0MKr`6zYX!cUjXabi9*iGe2jy#T0(W5i_vL^~7_}F@J+udg6zae{f+G-#{O4#C z!u7Hxa-u1Eap~I_dA=jMh6ZebPQdHwgagDdoaG_WOY~{L;jP*BYmg_-6R0kb6VOo$ zr2Bk4x&t(^f8D6D?l}y`!0%=n(M=%KR@%qw3kHLOk(@pu{!#4HBCq#7v$8zbO$A?^ z0aFP^?e>zPqJ1?go|4nI{t)K(G{={16&ve&H97vXna_@h>YJap>dWX*Tb^*;d zoT{Esq}tpUU8Q@@r^TR33oV`4j(b!?LVKA@5Q=J`s_a)H(uT5r>JA1RhG5+-l?=%Y z`r)P(V*vs{hfA_OOt{_dXxC7KUPoC2ki{1G5o?w2bHVk zG(=byKhW8W2j$!ldwe02AGMfP`gE3}l1CBQLZoztx2hjn+(>8uv?Woyq0o`JVE-kzL0S=^S{$ zpP|`TtV4Mb!LRhZ+M*gOzwTAcN4g1ClaM!dS^cce8yi22)Y(0z5wf)VOJH7l>h)nH z&F>%FDqB)=#RCvZ=I=ku3`NFf>f=io2rhSlgD|I3o|hXww-FFpbBE0kP zLmwj7eXwSs+xq0Ruy(>nJl%Dk+t=vJgMZdWM}JB^Zp~ROiK0$wlwq!}OiBUld=|uM z&5{zwFY9wieX}>TyzKj63J%Gh{p~6OLtY&AWgLmZQ&1x2c_sDnA|Cn5EE9I<7){6U z*|#!mwNDwStjA`(zKPo`srO5A^N-uH8*B>;FeRu?+p5`%jmG#!!J5)yfUUQt8kl`| z5A62RHp@H^b+dewOrxWrVJUEVm8i&IQn!dbA1<$XL?g>jU?FH1XB-vh?>%lSmJd=u z$aNw=!iDMSk<0a5WlyHo#PRpAMkM7TTool`LYTHKUA`cyxp$2`p(OJFJO;uA@QEY`0v{h5M*s5{_H-)X zW=O4u{Dwt3&0pU2?!#+mk2z@XjFQM_$l<1p%WrS#t7^`8J|K+f2sKN2c<_9dptU&q zMWFEf$x7L)Hw*Sh+LSxi`$PTo^}usUqfn3AVgzZoLH%yxQzxmx-RW;*In+-~6SN0D z_5e~my?XRv{?r#>28&U{JDkMHaO zplVlnO|lDd8|VJPc&P39G|GIh-=L_U`}dmJ^IG_~6y2{Yx;f6z<(BPX1^xuX{O#&W ziIbA~IPDG;R4l7jpzUv#FbNs@ZV zw!}VtPamr1L1gzMxg^PX=$UJ9Yn6;W`}d0myB+;iJyl|l%e#G|N9`-;cS2#G9k3shi+#+=s}<)Q9h=6wHFPtIjdUW}0?v?=>LXc3GBnzdT3 z@M~^GvvE+G&8Sckm?7Ii(TpA32cr+JR@fVI&;pIxM!`o?m;o+VP(4TBV#b8=F7Uam z_1EJ$#Hj9l-r?e>D!#54iDUxv1KM|Zb<7z6HD%^Q`7Y1lF?$ye<~2W}YvH$) zB)8X8d5?uUe3ehs=)HSzdtHA<{J@_!PcGg1^x?|7%Q@=0yQyJ{5!Bm&#ZCm(b9{fV zuE6aR(4n6g?ei`&!Y0@y1d7Gh%hagHQ%E?D>;*&Cphl0RkRaLFMzxA*Z5pV7P{5HD ztzbC^^5u0D%W0=!3L>7jVV^&tSUFhOD>m|9 z#MrnH{k;CX^4ekKiubQZ>9^zC^iY>7x@j>8_&&VpQPth;i&* z-eQ2VhHu2?U$^|!v~6`j9|Gv)4isTPpukjx;5)H@V#+PFp0&^0XfxZXN?~R9)|GXf z>!|lunYlPy7mkf`DlZFR1IQ{z841(f)6*q=Bu66#8;~V{7Y1iTwy*dX%H@p z<+rnd{N8H&jJ_PFe6$*cX%*Zh#nT*vgYwIM^k~=ZLapkaeB*2C{Wf_|u+?~v(>6B- zbD#UzSN`>jArHDla$MP&Tygf}4)5H3!INRc#G4>q#7pp95uONDpxOa2Z3jdpVp$`b zOFmZXhNPtcB{e4Y(fW2Q^7eD1@0$lvp!UXrIh=<*kbq%>_^=W~jkHvz9hv&VNkL|~Qr87)nhwmPM zF<*gtKNLq{PQGYSnB1cZefs3Rayo9$JtY7x@+`k4f+;B#&&{`Ve-K4kEw6cvo=CzE znoOzpe2agun3OZ#CUAmBxcV@+4`E2|aXM}2L&x?BXvUkge z!9ZNlFBreDOA=j+mkmxb^pj!oa24nq;{}dkTF{PNATc1y22c*e5cFPt)RyQ*Gfk9H z(eZXB^1v5jOk83lFVUkfXBSAkJrCs{D`9QEY4v^ebn-_O$i{S0+x|nnbs&C){f-KQ z?wn4q0$G3S+rO0OsViZN%ePWF=d(d@2{I`cdi_$2|J*0UeR{pgKUQtyMZ7XszXxDt z3}!h#%ypOc~I)y*SomMaazp?E@ zXG@mx=5J{8QS>Vr&F{AQ_TaQM7Bya@UMF=EE2E$&7CncO_#{xdvJ?gV`_jjgkr5Sn zT9H~UNeHHG=jGj`^$t!KQe*GMDEMH;{#q1|aq=O_`};Fo=oqs0Bm4jg*Orh%@w_!p zQ|EZSqpS8$omSX^vq*gCEcQw~Zm&zQ?pd0Wppxg0BYzr%M{aYa_XjO$Sn_qXjwh_8 z?Xg#uTqO78kp89gs}SICkQ?wUh^# zzr9YUJ6DAn;_zAR4?i-H@(3u*UkFF9{Bz=7e5ayv$*%h{Cf|0F2;Rr2!F|zU(iJkk zX{|!KmDPkiFYQ~m;Blp-TZ<4(?8!AD^o-!o5703&Q*zl*WeUeEdAyGs@A!zHRO&52HpE`|cs!5VgU!SsB406{COZmqG*~>* zL^gP+6PKOnN$@N1yz?02+HSXe?9B}MLIqYM#lAY?Q;9T}O`l)?qHHj;eZgSvPxrz! zq8@w%PEg*(!JV6X`to^0e=gN5hx=DOG|0kK>;Q3!x8Lh8AYF#fvyoY?h57S6u zGf^Rf%B10p)muOlQ^1zX_^Dv%gBKYV%!ba7Inl0z0l-BN+!W~#PF=l-Dj*R^G)u@T z^Mx?hAhA=jg*1Z1J}6jkk#+Pr6rJV~Je;R;QH-UE=0sE~e;yvbwzekZBU^M}N`ZTZ z2M^ZNVIupI_=o~(x?is*w|&3l>zIdw#M7Pr36J4zqVEv2eCk0sIa3gCTLa8yppallCCziur2U}-~$YZt-_ zoZ__kddJPZTl>i^y5m>D3hVDJ(Q31#@v}$+}p5HgRAsYS$w%V(wn!H7`*kTX&Q^h+bTEJ7x+dei=ffCnLHVJN$ zsZWzx8*RPY@5jdT_52(Ms)(f1NUB)@1dOyigPA9*>ASah3VZAVI@I%-|9aa(&=K*< zKD3fQ2NPa#FB_^#vns)lZ_giCUOqBM^??HxsP4n_p6I_nnUH1UrfHl+$OfweD9IHa!}q|Z{Cr$44GO3n%6r@X+SgXx7;uj4WWy8 zQ{d&3bjq=fXzvj6u;`S}@7MiAeP6$4tfi7QBq_YQksC@wG>xB05;2x%XtL|EFrQS4&G#5$u`PL;5I`hzvQk24`Cx^(i*_Ip?3-yV#r z03=s;*c*QIJJWJ%mP7*^hk3d$IhE^KJ^JcXq3T_hM+%*JEp%GLUD?vm$E~Q!(>AYS z_z<7RuYvb@9^l>3WP^p`!lTJuP8f599={I9vOeIPSU&nVWf#;8m#-NRGyu}F!K(?^L_AW zJW|3ei*dWw0YmcB+w0cZIAo6q3@>w+B?7(khWo&A(Hzfb(XsA7_6*?%yxl??sD`#VhGg$gdM>U1*eUl7BHpHmEQLfC)y@L~cF z^=XVBhD!Ee2wl5&K2>gg_jiKck2o~dUv4|x4%kt_==vkQ=N}cXr4l(%UD+* z-}G+?jn@<$_8pfrnS2&uK;hXF<08C;{DOs$_)b6gT`7>Ya}t~ze;qmt=t!o&3mm1* zv%29cz>|n<^M^<#?(yOCR#l_cPET+gJ!iAsCv5^hA6s=-#_)4_<+m9|Oo$Q0l)_sJ zz^Yw06le4?{=`?y__Tw#dC!)Qifs6eFE{~lAGQ%SBBV#~a<-g)x@t38$6HsRaZ&vw zM}29Izj=j&5>f9Fg}bRU`5Mm0r_rm-m=>0o?}KO*E{9u*knvawV-}L}(d)4Ku01=J zbKzfv$G(@Xs$c3Rw`$cm!n`B{dpnL_LL=>_a(JJ}h8-Hj{8;9>-@4cReoWYXB0Qnf zS-kunvg4;maxEVRiGRiM_j7DWm_`ro!+WkLaTg#A@_qU8-EeJm>`er2pQ8;TyAI{^ zZO@Y;hfvU35omk+^z}eT4PJ$CexIY;Xwjby$PgT_jp$*B_P5>RAY``19`?4eak&dA zka|rN3hjY(U9=i5z*|6-hRsf z4!RGD%!Uy8^f&=CGe4~UA`=%~Ic<&cKm#~G#dTqY4ib0j+}*Vwo__JP*M|4AklcTwN*3{^?I5*8Jf6Vsjb}eU%C&1K4yDE5cWO*r-Z{#33yyD3a*&Q}6 zEcoA@pQP72z< z>ctD?pl>G{|A_bSFh77OfzBmZuJ8H(IF63kw+T1z^0Y4td{*qVzX;Dm6+uPxc|qQ# zKA1GwlEXeC(Ml?jFnssmVM@xn8;xiSLg(I^!+F%&(~}Ou=8buXNw#T=AH1-dt0pRWIp&NG#qUnOYPQsd;x+xIfq`~nI2=w~l zG6nPdxaN>*e^_IE&rOZxP4qAWenDtTxbvWNm*bc^o|Rs~a3}Xe0*`tJ8Gz|#vj-%1 zs2W%8doitIz0pUs)VJ&DR4c@3&xU|CCQidiO@KY;Q4E-o8%@4b`@Kd~BI&m*e~y96 zg=QFh52(RPC~;b7UweLr;q;Y_b!XdIq=y-%}B@L zJ^kXvQrfFL$cpN6zWP8cOMIPQO?-%+VSV{`@fYkh}w?8k>^dP}nXj7Fe zJC0G3oHF3ma9Qvs!>?;miCuJ5S=Uh>VC0kQntGhC=Mi(KfIQniCQ)&o-wvO_kuKmO zkwYu~QPW}RQ#WVhfeuBd63%F9UCp;{4YSnK6$%D>?20)~tUC^Uv_KjW@s|tS9oD=D zMPP$9gZx#mU#f&Zr#2KS6c@a5;&dr_xSn=(_Z@P4Ph1Y&79ZKiz`a+uU#Dcm-r^C= zXG^nTGa=M){79d7)Z6EMQRzZe%Q*liA9BKGBL$}bUi{MSyJ_z^DHB^YnAQgk#xN?; z&jrUlK?IC*_v!x>2ghr_t#Y=PWAfNI}RC0kU@)}Calh<{SM%%)@yX_)m=zfSDpi&W-yDiedf z5}&C%dF?K7f`&{G%NJ#tG*zshIu%LT>smjR?(jPm29BSU%aPhYbJ%?AHLsjaV$rv9<=|5$1=gyFS zmIqSxxq-SnvfGhB#9rv;&vW6-o4?Y%5DJuIVa9do{;*AZU(Zw5imLY+TS!km_nr-0 zU_hRQG6AIZ81G4|sySGtWWp?hn1kGf8LN0W4qE(Hrhb2-u{3>M;dutjS7U52mWELN z@{Szcx)Sy{IKvx_|JiNXFt{x$jGU$_KcQMm-6~#Tjdb%E--;Returrzg-Y{bQ;zT? zlqpotp1a2B{=J+XPh;DZPCg(z*q9o`q~d+xuewN@;k^pqiNo)Q;!96ZXjcm&4o;Lw zfJT(`%b&(t9X~uybK?^-^l&s=2hk&=X7N60-@ppP(x}+0?VRkZ`%=hWSh$P)9>vB= zUTrNLG9LR z&X(@56PSczCV%V$TKENplB<0PL9DMszd7`$nW+2s1RzBSS8%qUzseC)9jO`}^>msU zOtTsN5_7}EV$S-cW$Yir7z|>SqT_p!t1qOX%{a~aQlIhy5KY>z($VMqlTe1ibafL^^lH8HJn#z9{W+jCcE;UwarLk!Ac$q(ekSeELj9 zT9osBlnfSLpIo)oX@=GRktevA&(;Y)+`o39_u=TVZ#c8T-x%U@iX7|7zVL%cwsbbN znHYBFcos#V2-A8#tgLoq?iZ$X%|MCv=|~*+!9YF>?-nD89dR%A&56M?({nA7z-XHd z*xJ%2#qgi?*O$pzc{?qKRAgK|-VDqrWdp^Z$aFgvCt@B7bA}2=`*auR7WLQCEssAl z943nW>-!m|%j>+dUi$=@t$vKjfd1Bxva%c+?@90_D$hIus)mnPW5HPE7M9yJm!q^uCgT2Mu+g!5(GuH=T}>`3j`9N8l)FIeIe=2TpE5 zFhTGG_vOiSo1KxT|VDe+lC)4MB z)aXAizoXQkq>n_wMmFx5v)d`- zwVCl6N2RAiPhCs^u7BuhdtRvUuutH4?X91CvO`j?*NXZr*<&94pjO2%VJ{C)nmHk1 zf^tG2C(L@>B*zhJhwwfbgCu`H_l>e)q%K7InxQ*-{}uj7{W*N9Wp=4g!&$o%IN9V< zuQ7^&ysqlcqnABc)4_2v!hP7SJK{Axu7LJ}ZN|!JyOi~H)0C?W*%}E? zcQZ&mIgG6n6{F4-^xPr(E)AG5$R0Hv_t@4sYpVX#%!c!RKFBdMs$-5IOsF%^UGe{} zYpS={@(7glDE;od?~MROQ|5fhJ?OCu$kJsXL_Ei|t3ngMb-nI8i~!xM=)?Ygvcnfv zcHz)Gj;W?3NuGQ4?TdkdE;uUmiLs4uyeE6Fcc9VrdUT3%^fQ2nq1j1R$yNr2m?y!H|wG2^wZAfn3~Xoo|t&-O+O|$dg!*hxZdhC5M~oip55P zv9UVv?oao=pj6(9ask)zqtB^N8Z&y0@@JX*Nv{|8bKy)n6g_RY+B z0rPa27qCmZ_h9dZMSxtu<%&iU>l55|juC&fY&ct6BjWPZ^r_|LFSXlT; z|3|$t5J2sH|98A^wX6!`9;Uj5=)vs%F9#HSJ&lhEjk^kTA!G!{2fVM{h{co z(EI0**rDd9CfSp0<>R@Zkb)J~D~RLlORV*kVMh#pjA@v@CyJUU%yxs^5fb6=V0Of~ zt4>AlH2q`gO50Ua!|-3qSUzT+NkYCMWDJS&>(6cNb6xwavsQz|J3PZZoVNEpXfjkX zr`YW8eyN7{v!RrP@4KQ}_2VlTYqfGtrM+3{iQ+nQ)Taw31xy>}1*UD(wYEh_O-x_z z2Tc_`5iPIP-S@6qu-0P#prZ<#q;MEyV7VZ5{MK?$fklN;xQ4<~AXmh(_U z7ZC4w06`2CFSW{CF-vp&OcA};`$Zq8ZaZ98^Ij{DyB_F+_dBDUQpZg8I_g*W0tzHx z5p0oE&&!QIkZhQIg3sVJuPf|czQ0)h^a$AkemupodXOYNg>jvS4~1Izr8CLzOc}%Q z)f_){AHZRO3U~|CwPmk)=A5_^SPV*;e)7?X{-+ z_vrLWYMKG!*JuyHiB4|>O}5+mI|vY8OJ6bzoD~ogj?#0`W%R^1I{!RkhroAell1ZHm$yLVP>Mym>6y3v!e>&IJEz#XOW-!Flk#o_a=%93sDHpk*DwzJ zjSrKW{iP568&6tkh@akn-jN4tphoM1LhwnPkzTEm}eYC!oTl0Tz$zdc0tddOp8Qszi?!tC4(Av4mBjggw z5P&mYCv}c&EXFZpz-2)=y#~dVzwmJG4n5K0%oZvVKIflxF?7rBJKq*e*aAAE+wb|_ zquC$oQ>*#bGxuG2Vrb0FT|NlkNqNAo5q{6$QDM6R9xwABsrncncn@I3hJQRUSBap% zri)p0RX?s&CA-=`f7>tiO=Y>w-duMAtw=)nxhJW!F992q@d@+UY?Zvh4Qjq@N0{P5 zc{$4^-;g=DfV@U4cYa3~iJ z;l_r!v#Cz!Wn^(a!PtYMHGiLRt&>pJZ7`^i!9$Jyy??+*JE6~ z?viHuCmJ%Bj4vTp7U3Ww6IWT@W@q8U=v$%!$ZJq4J6v@%xRc&gkRm5EgpFc8igd1zdsT@{kH|pr+oGN8^{W(Mq zw!U(83+VL$I`jSw@3%}7H~Ocnph#4wJw}DRc<6xs{c5o8L)BlYFXHlBQ9h>=8nB+3!s+^7AqW77`-ZX?^PB0fyC>q3x|*spGyD<*;fyo<#dVa zlC`0?zG}~rKU@ooVdRpnM+yg_lF?J|ik&xJ%V+T=Kjp&_AXO%qw}^=%}vGFVaky@ri=fz0l?L zF}JLGYvfzo|7>^+gq;n+f~OZ>@R9Ty-q}Pzn@?CmtdKmKs>EVA;R(2@$CoXQeK?EJ zj}a_B!1(8{Yv!nMGygyz4u58(`I+_8CrCyI&Z%00MTnpc<%RQkgN%Dbt?O{We#KjH zoBLo2m*Cmkgy;@rZKH0mct9uKZ*cXDc1!Q*;70r2#JA!?*yrW|_7MyF0jHCj!u~Ak z_&QjxI}I*ClC63xIqd68kjXP@(vv{n(+c9Yg~xH`?NOim8_((kYiMB>Uz-omv-=&L>D9f2Fpl9p3BIU0G4zRpx|uu zN>T(t^6-S5f&C~4dpQTk=e|_)ESP2^okH%=-{&{RA)9>ba_6bZTUPRfDZ`2TQVoZ& z6cw&KYi-Gr28LOX-F_Z1n$BasAoAdgeAZtF8;Jb%Y75x5O~B$4`=ss7NlrZ;=pF_*$z?2Il>zhx(|& zy-xgkWzV_2NG^0=`oe~_;~@{Ca@6iglYFz!m>+kAiN+qhsHWReIV;mq1t2fp^vP$B`!=sVn6?`?;7WDm2Lc zY!cS7KeUo|fhXFeyzZf@Kg}ZtB}rKzhdkaV*O86{kCulw2*zcy*}$}Jeu zc{{_s$;P$FK!l)W@vlvpH=lC%43yKy5%J=7`VqXBUT!x3TY#V5gW2^iZX^9!+CNrQ zwgc_>l)9T_dqH#@p5*1v*K4?h|m!EXdS?O|lWE-nu zlQu%LO~8=boDB|vp@)xm@u7=)3w*ya^{jejeqe>kqu45;i%84%!{{lO>?|*;Q)vD4 z`Zmj`EaP|wLQ7vIFojV62!;zquQf1fmkG^49ZHwkCFL_BUqjvwn#vWg^JM zS=5JVQ4D#nIE}1&SeXlj7d1|^`furHH1B@{-qf<6YF1j)bA8%>^JjxbH$H(+I$>Kw{$G1 zKxO7|g9PyQIOEWxAt=)d)k0vYIMO;Y{Fy&)*?b>)2U)Txm=7V{h6J%;p%(@1-8}P zUY=;-p!bqCsJv`vZ7D9#v|5w-r=GbJ$p#c}=ecRZEOulWc26l~=cDZLr5%dKvi8sL zfO*0fX_ziCzA}ux?BcR)4QfXLv#YU>SLZ@v6@fnF+mND0%Ph-2;`=tx! znLMS*+9e4{ad@q#**bMIfS~^q)&7u$=x9eZd1Hy-x5sY!B=>`@UC!5gE?bT8_`sfr zPR{#)tKRqaz(o}%(1(Is#y21CM}e{A&V28C$@6t;&Qim7yna(Jd%`SKHRsLG^0*ge z`DZoD;k+;I`=@mmt9$IE4Io#W(WmA38xSP>xKpQLy1g0f>hj^^h|0~`&&qv}`(>aB z;xnP_bFCmdj|_LF*XIH5s76nX+6jdnT8RT8#2b$0uA&1cv+2iO=Ti_UI=^oX^%=?# zq;Y`CMMp?Imyi|gL)gQw^p)+Wh@<% z4J+L>1DtBwy z|GxXs8~dG4y`x2s^EnLPKQ@E1$J75v?F3baGX?@|LOvl&1?TJptABBy@PiD zo}}3oQxt5K%VRyCl0HF4_IktvmE=I|^+7(~7Lkxye+P<HL9@yKgM@@FsOamr~*~#m9g&4F2u;;^EdhSLnIyNNJt;*sM2v-`Esg=-+A5Ghc zZ)FmmxqzQd5*WF2S9|NeuvTNUrT*piJU(oe{2k{#_6pqT3Mvai4UeQ6KNqJG44gQ9F$6XxGWipSGpS^nq|rFeC(2baCb*+Ua$ z?}Qk{yXU|G!nc9B%}%D3XIR_pv$us;t8P8s1-iINSVmfZhQ$a@v~Xm|m1DiJ$hEE$wQ5;Ukp(7{NOoSlXbE+mH*2{FL!%I0ld)T4X z?%8KG(% z+?79URfvN@;5c}-*FbBGtgW0PuMZL0k)K=iVEm95PSw#^#uqEN92yyt-5$1z5$}#A z4pmN?c_x^O49@3HYQ{R!VBLp%Q1ZOGI)@4@D9+PV&6Y0@YL$lGa(%0AmQ?G&Ji1f`B0yVy)Z#H zz~em+icCDsq;}ITK0+^6c57VRawN-pkuy-WBWW5OkKYN-*{D_7`+lqIkh@z=HiGk7-agN(#|M|bWw!ot z41|V^ehU;2T6I3PGXX3$-tu63PG(npnQyw@9H^{_Qgfc)P;bMt(4T(*_O@>rzh;WK z$f>WNly7usz&#%)$$W#d9U`&tc_a(MI@JD-;bQ>XvJKMgofuN^`>v< zulvhU*97$XoWo6vw7$e19$TO&-%s4B3V!XG#RK&F>V20Somn~}SXt?P7$h9#eUoSn z#!vGM+(Oz2ko3E`r0Gql#R#m-yoi@q!8`3C@?2J=xWx^^~bl<;1?TBPN zvz~+12PTr~UIc@2rr(r%#YP{G`wmx$gybqYIh!ZZd>!A=D-e1BMDWylNdiB74nTAX zE9d6lUdi`yp^=w+0DRoZk?ZC_0gIDDvkjSGe7l6Dh2bjZL@es=(^AGb2K_| z%LKsoKksilW3KZEPhZ!gXxwA|X-{UYNFeeSGYB*w_R%=fMMVj?68iPV z&MoB42cA&1d>Hzlztd1Zj+M;theQusK7O^B&aOILJrF8CG9kf&0JQ}A|1HtmgH8HK z5AlO9#tJfM!b>^Z9E)Q1H&H^DBu@>ULr()@o3G2$xk7$Y)*WM?s_J%(r6xE?V$kB7 zT$I^)6G?3sR!zPAGxH2NTH;BO_$2GV`C+=PP+qi?W+rC%3%13Bb2 za@y?!d!$qup6lka3K-gW&s$>lx%?t3ihiioYnT-U*T7ro4Ll%OJeB< zLz>A_Obz*gEP?Q-j?p~JqY=H3#6L}_$>6$(#i=enm@AsGSU>fuhH!hiEM7BQSeVeg z548(PeGJikEB1a0zc$3kgVJ|W)AG%qj&Le`Wj8_4tS1RU(cff8JSYl`q*!_xD)xo1 z{KxJFwr}6-m!-yWn1<;~DDYf+I6pP!xClsc;3S*#kPr^5L z+1P}t!vy&UD7P~6v+ZteVhN~|V|C@P<7gDzwKx*+0eA=cE%LGQ$&)t#+@nu0)Y7 z>(4nJoRIu^FICI@=3u)37(DhauUJGdH%Hf&A4Yh87y&nvWM!~+^K#q%m@LNiJfu29 zhEXR#-=C9rEn|TW*8y}81yW?`F&ssR(+r!QHJ|LsW(x_%SA6|GaeOX&?bkhdbPXIW z9r18X_m7n!r@UH(J}ie}VI`}+L;6R7C|sE6M9BaEs3gSVy`A{c$c*~ZQBcLTStV_gSy?IYCv3e0{ z8~TP~>?`IA_*9el0Sk0&;7PgVM6#bZEvKCaiuvU-*gx^!XO3xhn_3dZ$-=R$O{m3+ zU@ky%AsdCzmA-s_3lnvoH0O3=R-1Nio43x+xd25AIf1Yplfc9W#|}*ffP(cZ+!mMy z@SD9p=y9(yROQC>j|s)yXOt2Gvup74!_qT{53V=az->J{QC%$1)`Y>H2yogg5A5}F zY`0tmNh;y6$&LY$8gd42(7ZPLXA##3E##9KyXT7HXfp>16(lTefWc8}6@jx%p?TCz zTadNih5x>{_=U2AyavqU2vX#7Qq|68igHU=pVr+rj$xqn@{dP7u!yM_lRfB`#rHcF zLyd&Ttf(*$UU|rmlqzlqM+HUMoW4PtyT5&tciG!M(5*tB9w736^DnVK?D!l|&y@Ef zrmyZrCw&5}eYUw`1>)>*6sj`POU0ZNXAizV^?3N0uf>xF)VSdR2#MM-)eok)oW@k8 zAY6lvV-!3~s~jr(O)^Ux48t>?u7(RN-FD+{8u-ENN&VPmY*ydtxChYLs|txd^$93u z1+*E4}P-G^`RNKyS)nJ0)1cwmy3;x8C}^{@C#N_{(eKNGW7rSyGtW z%hTCZl_96#0QRl9yFYfNzxNR0>R!IxRH0+z1#(VBQ|9S63W_rQ9&gOb;m>is?QQ)W zrRly$A#3dLKi}MSOnA5{3K6!{{WBqQsf(ypf0q@CxnI2Ky~iiV(+trLAO;jpf~a|} zzc;|8kOIh8noKTlNsN|9IUZzqNJtQ!XP!u6fl6-Ge$NV;*2uXVHu%@FUgJLlNaH5O z(-zP{3rHTExEpJ}O!F3gyN_o6zJ(08kIw!az6F|i_p8OTxd6!y^!&tEGO~VjAzAOa z@2X)kDM$W1LdZE2ERudW?-)8kCxJK{yp$X734-TI2NLwRHd>3(<;{IpYtxo(Eqwzxr30l4r&6wgEOM-F~4P2|5K-^t9=;s^Ssc zodvQ%+w1&3qilbkRY=8`-$1N5>gc|5K^n30N!@-2=h=LMDb*k5yC{nY^d@OlOb=3x zG`lbR82;V{Y#Dx~op%wk`7{vhqth^GTbrKoJr^5`Y^xx|pKa1^y^*3t+A>j9Oy0r#{wC`F%zcU-~r23i0M9jZZKQAw62!H2YFvmO;F3l9$Cz4t=j7wfPoQKKFC+t1|@k%ME=H#oF8=QyV z(ZZHZS2ZQ-+>2!!E27zJ022b(3h=9Dz)bAeq(o}(^d4TISu}fk{>Y}x_tMNIObhZvPHuV6GXo^mM}AbyF09wiu}>!*E_0cp2hU;8-a z_-FG=pO3#jWn1+*k|h3jm$P$l%Wbt7%|TpQyN6)Q4AZ~rL!<0TJ!-g;SjlTNF@*Qs zQh@tm*KfjiKP5lxQw~cJDhqU=9^=4H$c7$1-Q7-V!ha7cMO4-qw^Y{C`N z_DaB5Tm1ZGY@8D!jvbsNBtJq&vJsO)Cai(8i9zI?w! zFkv=>gJ&%^0KlvtFV2#E`fiI*=q;K^ZP+uVc#Wl_i}ZuMbuWtEPmPHa&?hj4d~uVw zNKmK6QLH@**axndZAD)tr>tP~BJ{&q`bGxVMK)w0&a7ZKv1~b-__lpywYi0L z>N?TMo^Bi+f`kTpo;y<6-zSo2HS6oaW7$1s09mxR+hBEjsGfa~-u52N5Otu+-p54D zP_M-dHq_>J^M+s#em*~TI8Ik2vp}egL16vfx0C=MW3ARdd0~_+_Py@hDf4vzS=np& zHG^QJu2e2KoJDP;v^1}4vsO|vtcKfp>OhEkSkxATo}v@Tw3Ik^1zWjsCrU+@lA zJ!oeS{+Ck=!K@Umbn(_L_yGB8{PG9D&CxB@$Q)g>>IP{AKo3Kmdk)%d{JvW4^nTUh zsJ#Q!+bnyG;5R7D^qY9}zgUF@FOK6~r3+nx(-la6;wjqDoTMmiLb_oeteRq0Lo)>5 zh*eT6s@e1WBGYb;;mZS`FN26-<8{CHG;YcduPU|6_m||*=5_6$pZ8C={_!Jd@3!-| zr?tZ9dGzS)=12sG=f>RHL@vw5OAApkA)vP#M(%EO1I$F8~Rkrua3e$Xe94&!Z5u_N7Z3)_uMz;vcIpcX&6si*Y_ZqCyhL5uU`$ zz`SZ|Us?yej+>p-HNc*C(B4U8r+IyC&wS6n57LFd7yaF>Cj`(+>O!eoKv6D{_iAwP zexKqPAMd(5wJ$9K+_%4NKEKjW8e%uXQPOVLG5Ny+N5a!YmDtH9SdEnIef?RNEjisY z(rJ}7Fv%RLXVufMdoD5-kP!oxRp>ZF?=%Yd`3+~JW{IxgBxX!P0f%pL+ficS5a0=K zxWF3A4@#cj_~yY4?zq&AZBP3un&LmWF>QKKE8?HPkl|Aw6HW*%9ntqpQDSAVp{09R zeuTl6K@O{fv!$%Zg~(x9jgt^dr+7$TEPs3tL)~yrzZa+mC~WmTKYu>^33#$x>mP!9 zzq-w;eGJV?16098t6LO*)X#W!Um#S@@E(AKwwGZFGHl4UG|inPv^#XDuzC9~4x54x zndX~3H&=YJmQZbSV8D`*_8jj7dGC+<&S5-GS*KSEHeqi2!L&CXbspr{f) z^~()*-+`#>DF=d(68u;L)xaGI)NK7ltwt_>5$KfJJ!ipboehuIhP&QG>em~=*^tyM z^JQ^hm)GQb_aT`wHQPD{$j0*B2%fP|t!s3p=w;Jt`Tbp7E3F}UNX&nXzVYbQ*Penm zffxRA?Ww1eE(-i)_unw}ui4XL`#o)JdYEavP%2+v`>rr)5W!QH5QQT=Sy}tqXkO^i z=-v_bhIMk)8-f?_77nkoUti(|d`}n;%C9NytNeGgQ6{TuQh(oP25QnZ==3Ah@F6TZ zlC24oK&9p`0-Ze+vdI%C|I<4tQJ7~gzO#J6UfITd3jPL9?+&Xw%$x{;H=c)W-33^^ z*@IA_arpX9&53No*-p7OuTq6xI=B(3EInK4wRR-R*@`XfwH^rLTYI+TJ}U5*d_bze zWjx+T55`zOG;=x{PkuoWB7$PrM=DBf_{qIq*m!weWo?_8d?3?NT9>tV)m*?}! z_9@igd}!FlpHJY?T=WIu=JrHJAk#*1;{bCz1F$u_t&Q)%hl{`(y8m{ry+}$Gw0_3v zotOK%UJXU|0BCD|n+)q1D2Hkg-J`@)Z!BLZ9FRVuBcG%%v3fafXVH2EVgF*($9CzN z&mIOhNBj_Axj~GXFJPJX*0+3`e?l!~AVMyC*>ETdXdXFl>F3Gzh?&J>P04Znp3@l_S7x(`v+ZLG^?UAF<+b^oMuZmEa2bry9w z13v|GwTmISTCXQatRap~TR?GK;Ckd{bW{dY;Yg;lKqt^Fj)S^ZT26@7Lfl~n$;`3mFdt8maJZ|s?;&u?(M8SgEr!A`cKb@tScpG#jF5hlKH zfYHQCV`22cmM6FRSid@&S^8#xKJdLLDe4|>=4c{E?ob&TTTsd`_c+V<_&~PK88E=x zx886yaHa)J7~!Br6xY3f%~6XwqiN`UF2z9sl>Y{}9`V{oD!QM~3&e{aOLueX{@%cn zXSt1U_bZ6|nvP>1nww0ipNxzS^cS>iNu0Kowqxb{%mvHghj;aR1jI?c7yCv+&sZfp z>H?GCCsK)=P}*p1Y{u~9AuTzG+)|lwv|zr2V-G2Ni#Troq*DpLIDejQ2(b9beNsO+ zznx{HVB^~@?32ai&Rrs^hezGzlfNel=QRSm{nj+&fE>SpL(u2l+E)eoir08J%lyZ7 zv1;uX8l77iuTLl9hHBY{ZPF3eFDkD$F~@rOGEtaQpS|2q8*E5!_pvOh`pq3< z+yV6R3Y&c$#*ZY3u%692^5X%!*EN(Dm`^whg=7MSXeSI7=rNW}^4Z~w_+%&R)uf=CuiP#OUKf}F4y67wfA-7kXxJNay;SJfAwFt1gf*oYJj;ebb zA^_aaKj=-Nv9p9-b$n+c*Z0!c5>y9;%V=Hk{^@iz&_gvz_kKuc+!IF@ET(CZ1UE0^ zi~#EUgYx8+md7)e6j6Qjm_mC)xqT&+d{^XQTieX`tL$e9e;Oa3+aq~Ho})Ts1i_XM zbLQJ$j$Xt{6!-2I~k2b@W zO{(+Y2OZv1-Zc@igI#`+*s78b!eSf6S5xa&l+(S}I|F6if^Hc1#zd7}FhANtu)!L- z9}sZvD~oW3by)g1&33f>8Gl9mFGPR`31*j<1eMr256!sS6S(1}mZ88DG{I1MOKzfa z$NRtNRWkeBz#j;rGs4*YJQ=QbZZV|!l&eEf<-$`?K;L7x@pQ;E;Ku)I(c*zRGoR0T zk35OSOq5gA{VTRIfhPejwCz#PJ@4;fhve>nKMu2Xj80Uf$A&{r>#1ipy73h;dfPgY zK->AD?9Ekv-H(>7F ziLeTT-IR%VjgQ(2LJ2_f2fsC-P!S>?-M&Y(m$>I+!(4GZf7m+#_*H)rl_Ge00Qf!5&;u~gO$Qb+4riTsT)0rWWO&*Cv(p7SZ%3X8}W*c))gu% z-;W+&M8SV6VC5?N%E(?t#5fV3?eYZtjSVa9WxdakeXElN3U0H}KZ%ET98|m-u)X-U zZz~54)t{qzeYV*#zG^3wn0W49-S$$`%ZjZetEwUYD7OrrnMnT_+R>oD*H~;E?kmK~ z2Ynd3GV~iB1bbU4hdV;twGjpRnNZp$!-LGb@cUk|Lig>r|cl9|qEydJCCG0WD!jh~XlVBy{E@_9tuo^gdf0=`$p9A@>S6cwWF zA2A&z?k5S(CqBg7%^wZag&;d=8|UTRTNj=Wb87`aa@e;=&;0J?jq`Z@DijohzN-XU zp>ycsFuK;t=lyZRKjTuoL7td) zgD~DdW367S%g;1}xrozgvf-{oU7{~E?k~~Fg^{*3C(46(f)>Q7a8@=U%X1;lol02G zNwoRQE&M0Vd0vRKJ9uynrdl*hJl4Fan|u)TE0Qg$ z*F_NQ_qx(z%f{zh74>j{DS-FA|&!%olt(?tB%8@PQEa5jWA>2lkC>S_j|IKCP`_K{}OwHYPf4%}4tQ z^5{Lva>DMjrWYF8Po>*Dp$X=axAtIZac9-jZj>hj?g+(g-3TBK^Oi3tsW3Ia!q_uL zY$AVsq42D&9TmFEAe%xLJSx1}zE?@hinJGnZ#IGs<#1IE!?8ys90$t#c&KX_KQsCk z5QK9U-8!S&5UO|O3HYyCoq)0*fACdyLdXlOf$?>Y^y4(beqGW=l8sIeXxOt&ux>BW zkUN+_YLY>iE<~K%1sn~deX@aJc~SeNGM00H_3b@&T?aWgoCv|V?c~xhiWAR9h4ori zjrW{O&>2D_!@QpZ{Zmc{uZeyU3#g|JNU@!bo*%#P0h~E z8u5RtYv;T>$wj85EXFwUVe4CEdt!pT7&HssuPXVd%j;3{+h`xIcJ`d$Cyw9l@ql}8 zlk_Q91mLMZ;T;4J4esLkW#F#EE2M05a{Cj$F7`u|a!>AUnSYeKT z&XEKY`3VpV{1Gl=uiN!oNWL)Pggey-%V+)A>ZU-HI8 zoL%M1$9s$4ySLEh3wF{*a;1o)2tOXS`*0IlbZL(F=1~SuL3Ca3+RYC;T@TIM6=@R^N+C#@G^!z#XM@7HzPpPY~O+Q z%{4r1vX-vGElW-RE&KohB=TGMk(zf{o`-fg`pj+36H9NL1?E?mAYbV^aLGc|>I;AK zY3I@X?&5e(wy9%-O#F`C5J^4F`)z=(eWjs$TWiuoQMdh0($2SlWXlBI+zo$%Tk*3a2O=AT zo<5@I(L3wMvA3yHkwhAh>K+>Im6{%0DkYq|?5LA{Kd3pF|9dTrexp*JOVRE0@ObU^ zw=6GIc5f6h!yW^8tFOLXMW$gW?j0XjD4T^$N+7H2;@?IlOYG5ykS&y-BY9# zhUUS@!QJOD*KqrL=M|5wLEbB7TMe}j)YL+S%>jMIBm6X#bv|ukbe?pk3W`hj_KLj? z-?dLTWd?+kDV>!jY&rp2@!Qv-VLERox*s0x<1yV2OsIX{!cCoARI_d$3Ox0J3;?6! zIL$mSP{}>`fEbas8fr33A*bLV<_zZbk zf^CZ-X73VX@!kIUfZ`4Fo|T4zzgtZ0-|d*@w-Qv`#mNmSeHC&?gdfZle(?p}G(oIH z3JEBja(%1(vTu&~x1D4(=g|58iKKC3k;jc(uQT7$>xIARA`q)Ef&GwkApLPJfjC#q?hs)!= zA|&P6VD$W3ttT9HmLFaxULW!mPShtKLB7HZ0qSGSBME;ye4=*Du`bEl2_G-d{S8Tn zdIk%1L%724_k2(M)C@lY$V!zsWxfrAkD{)u$Fx1sYm}ImgaY{2p#qDve~7*FL(kxZ zASFi88cC13H|(Iczdg&BI(c;dQnH766;(Tm&f3Gw_!sU&Lc?lszdRSd`E-z%q)Asb zXQN7U;|HlWNW837ckK2!3hLgwc$yXg&aJ;IKMrV*iI*S6L%TMfPD32l-(S~pyW#+x zsz~m8z9kRBnioCb z2EEUrcUsh&lE46R+(g8~g2%j-M*NnNx?+^Sg9G6+B5nJWj_V z{@k4#G;sS|{a~n^>ng@=&Qe`)-xCgjBkN6e#BWsjkmcVDjeQ?1s@x;@Yb<+pX=_Y6 zROQ?Jj-0CRlTP?syj0X~-dA#vs}PS3p9g4w$jHfr-d75j5K|~Rvjm|tfv}=I2kek& z{O)soPQC2GI${8ssXcUx0*Nkt5~{dT-!0{Si!E$Fd{=yb;K};?*N2jeJ)H5&NiNVl z&?)A8>?vAQ%tE{yfyj$@q%DvD8uOF;<_qQCF{$~tu(z{NKR<-QVNj`=_DquN^S6OH z!ikc=Jf3V4ub>|7SEF?Og*vV8tG&d>N-!^82d(1AB%HIG26*Y|1jZ>o=2st}Dx|e@ ze&|i7+6xLN`cx*mg~2SZ*pvuCkcMq2U!t;jlbpQO6{6#ZH{90@><1`!QsqU>2q|FF zC%5lL;JF_ROp5Q-jGw(HU14kw6Y%|;E&F17-$g%)9mmYi`Vyqj?0`WrS{ldVaAq|P zgHP$4c#h#BJVfccWxwIDkHcafEb@4#hv7X8EHK&}`yu7QsJ3)d#2uwsE zCsK=vyFCx&^U6&J1Z+?5w%sme(Q_bEn%nVP*89nI(FXt7Ky2b-y@(D;KqF5rm#I$A z#vv^)))OY}2DY=ie|k#=7xsNDm%}N`KJuqR&GGJ=Edos*X3JM~Ls(u@Hi%fScBSbR za-#SQEz8&JPru0=hXwu83QL#=0H8nUeLB7pLcMe7A=R5oFt5Pwa^-gXac~MBH=P}7 z=eU2-%S_H68y1_tDD&?pC~LsL>jAERe2$XhIl)4O@D)K5g*I^a5M)875OxmA415@i z*>?`St!bU7i#noxJoXM@7h8F+447Fr)g_+a=fv!4>Ha*3t{0oz1ZPPN+o7pfZ0g3r z#m-yp%_q0=iW)Tz3o+r?&6nLWjdN7`%L1m#R8Rn33?W``6QkTnP&2J=Kd_~fH?@&|Y$KO+6opIW#-_el})Vtg68x6S-PRm!K< zM0Lttg{kqsSO35*ryM=S!I|fTtAbTLoX5Y2B75I1?-3*JSgQK^!2E===@aY4@!cR2 zg7O_(9EW5(F#bXpe(Xk31=Lt=u9~Hb zn6T_NlJsn4!ohynr{tcH!W~#&F}c7{?JlZg&684({Mj(>OpXOB% zVm6s$Kki#G{uQu-ogSV#D#at0*vnJ+H+(*li3I{y0L{S0_mr&(nwXnrI~~n+na5B`bdy1$4z_(2 zE1eHfN5^pW+^TQ#6p(UZ`GcS?{KJAvqfcA7(|lxlKl~&1(-Fd$!n$?51@TC(!%hn| zx9mjQKb0sYYc5Ba&z?Fu_tWpu?Wo_+-j^$dwxDpce?w5|%iO-R@9m(i=kxFzNjMi_P^Wqm$ zUBMk<#^J$@!`FP#c_1!apj%dmpE2F7qJ1hhyD}B|C2~Ada~p3N!-Q+X&i*jSm#jE_p@Hm^>Fv!Od?Esi>)lH- zn?>nUT9~+5egdZ^&lvCYH3=vSyRaVqQcN82o*@3haSLmW2nlsTl~dggNP zcK<TrM_>)upsb(8^zD= za{0i!H=Nhq+79S}lk(`PCF)y~9bcpsqYk@}6;ez--Q_{}*A!;N@1%UqGvyS0|MSGA zgqiM5PT#SVXowbtd=&Q3{xh!M%%312;~p69qwYF>Jn@_8d4^}J9qu3KLu&UCkKDU^ zX-Z9rRQTd^T6-`eWr;?r{|<mKd&dBjXqvm3RT^-eebMt;<&K;mK8o3jm0w^3mBk^Z3cn z3nE)fy{yn$?hocPyBuk-{s}CJ=Sx0cL|(mKQNAF~Lp81w3hxj34tNuk*8dzXx##^U z1K1<0aVk4?VH4Xl?@K=Rudla9!RKarqmT6!00$kHLv4A2(l{^aZ52Y0l=1n!^@Ud{ z*XKKv!i{-6oFySHjPIw5Hmc%dgcb35AVv6@Ff7;09J_z>#nM`F#V^LSbi&SrI8Ou9 zN%jGZ*Ch0#57lu$cu`2m_KbHFk~|!H!M#B0%GxiL9Jc|$1z6+ceZ;so);Y;&A`l^W z;u9jyF2e!J{doE#4z4%Mr&}|83-wJq{Bu&po}> znp_x-fH2{g!Z9)pi5n|-#_}IYXSSuN5=7Bo0+GQ-P(VcHnKzjP1(X^2`aV>z)%TWF z&X8nAMx59uy`z^Pr=Mp2l>0@S+WndnOU-4+16wtg{u=_rmq$+x>*%a^X=g%Qmgd+q z)!d;6M-0svTJi3HsDLX|(f^D|k`#e@om1i^)fYxUfAS^D`SltUcx&BU>?yr0qXBs$ zQXUn=fwr+uE24X3kMIozP?C$+0v`VTXRQ@uw2fM_iAXGEvV6Z9QnT$^?AJw2p2t1= zXpqs(ySUUziw`DH$n`79bn)Rb-tQN^!$>$`e}mK-EO=KG;-!`omGL})I$ z;q+>rUI_T!#&2MWSBVeoqMJ73W5qE$XI>vlRTQ^v&GzY2*rZg)mhS|UZI!%T&mhU^ z{txV&EL{7G?1bBIUv|H-XO>7*3deK(0h{Uk>e5*Fq^sgY&ZW$Ie+>I61l3Z%1Y0tC zRrXhxnO^?zb{4C>HrAk;{ZkNu0H+aq6hn%szNh{s56Ka{&F{RFj0%I;a2b2H3Xk?RuR_G5NcCtFH{M>4L*2P2Jaja8 z@2A&5OD_=|Q)X;Lc^{up_#%yYc0J;a?s5G3>H($U>EmUco6sDaV76cr|#Pd zQ>yL60Jw-rh^R}rA%A$zxWvcpxhiWdya9^eFVj6v&nHZ#k{Ua-aQf=S^QXsdjf{ab zZu-P&o5Gc_@teQLhk1v30)9~hZ#-R*&?E-bnHlcnn|Atws$=Tz014BH^YS<%LC2(@`1aN3=e!w`SZb&G^(CZ@!72}?h3m7FIm~wt? zzcsxI5Uy{etha#k4F8WjPm~Bb6>Z;%f#r0sWoy7Ml^C2@I z;(Y7x@LOLE5OfZf7cbK+C^+(3cOK2xr{CjhkByg>j|jpewO-J=7W^!cOCJpSY>4A{ z#U9Jv*1%hZeW`t~*%!Q78u7N!H3}8C5urP(hrBxuo^%CLceJmE^IMBvv30kW@9DW> zF?!ynwwzcF^4=rVYk2mj<*rHfnpHh zE#FSIjYWLwAHbhX>ftE(S5f?yH))RgxV&9WpC z1tc01t?XzQ%Izl_fvd^5>=Yzvt_NswEeRnIxQvpu><7!Y@xR&1Oj3Qb7yiDyjS`HS zYw{DdUvZnN(;lnWM-Grad;RwB;R1X|Q|!BCRxbReg$FbLqVcQ9q&mYZYn8=@v#1QC z{%vm+Q67+ioS=_&-o~}!fBPvuv?B@yulx4S?RS#3#;t4~ngP}o`ZFm^?$#$yc;%ke4;Zi-oX8* zM6Rsc>}7LfU%CGKP{}a9Xt^Kte2=%UWy9_Fc-rG+6XqKG?&#c(sjLu zX6X$L8q~`kg7N-l(npZ50(H36kXfQG$^G07owWuy#@H^yB!B`k0XO{qGu{d^N+zlO z4TBE~IBS3T`kTS4ptl9%zc2k-?z{H1vHl38Hy@ua%ztQ)`F$}w2uzTL)@H|}J=ojr z;DdH}>_snx8UarO_Q>sS6B(i)F&LuDav}~UIa#3W)_VS=$0Sn85FCO#0phDkh=e^Eu2&ucpkl&Hxof?$4Imem=R# z9!i#E*y|NTQ8TOCUWqF|w}G54-X0(#4+5823-;&@6T=DT%<}pe&Jid-2fPW3gTQ%_ z1<1}ddkIGBTHxwDn{-bealvCas5uvX&ZkbCXMSbUbZ@Z}3Z%qZf=b4cCLRi$Ng_34 zN^ASkhO4fTBytyhJMK$T@`eMC*{E*-AJLY1n`A46V5c5vrv5rJOwGT_ZGXuJYtp=V zKU_1T3#1OdudjSEowagij(t83`s3zb-zoGwcJfi3?AsB0N?($`N|AL;W;HzXSpb4L zBBBwBJ+9dY`M_cB;ZD}?I6THROO(p}%s+`C>U>dtucyDVsAB|ekRBR06j^MreA|nY zu!7Z`Uf#cv zT?+6$7;}5QvnR00=jBzdQ1|}cvhlhWi36ivo{(lpR=Il8mQQ%Q2~tCY*kL>xoH=}!=f$6}r)AsMq-STgy;EF=;JhQpv<8+hAsCl?oO4}|&JXFN` zi7x^IR>2ljJ@D0+4)ZX2+vDaqZ{tMn(_pKAY_y-g?#;uE$eg0G)5qaPdwIuyR>kCQ zFZc_(z3HRmmF;+v#;@G?KTkU|$=TPDm$PCzJBo)NCsa#Fw3d;a z9*_46UNGbuz7A3Cr0x*=Bz^h}Kfe0dytu4``t-dA1)Z+v6l z&%!3Yx^q^_Guj%w)TLfD%|(Ab!52~y$maDS;xcm17M$AJMtq#$QTfB?en4HZ&l^Q^ zVp|fk63H+4bw2~49sOxZ3nx5OkkNw_6YF=Gs2}_HKggqE!mC`L5FPJ_NWMOuF_C!h zt%RovJt)<-ShjpF1^@B>JQgWi)KP!mOqi^l4ta64_5i-C&dRh2*X1_5>2xR0@uZKf zq}2CAuzxONk2rG4u%z}He^s9p6T&S(UXNwAb#3^@ZS&CyuC*M&0SJ$+r)df*io#9Q z77V2rAb6I-3n6z3HmI(x>)YlW?aN*8bH)NFP7I-66fFP9w*GwlG2Xcof0Cw(A_N6zr*N4 z?5S%}>3=u&1P*@0Sbim;*@@++^JwNx)~E2JVeBFa@fs!Ik%|gZ0%3fW;{rn}=8f|z zy*v^3zQk&tCmdYt!ROC@fqZmWxCI7n5hKNq8|SdqQlc3Qcgd?q0)bKw4znC1e5b4f=?)J=io3x6t(3H!X~j>#X}l zzeZKmm#Z08z~g+Msei40L8abJvH(d3+2*G-9hfKgnJ)l~`yb?c`F#~yz=JtN&%qqJ zBi?FXb)SE%aUQ=>{;N66p?yoYEji>&`)$!AfZ|e-{NglxGp;$IFRxLgNU`i?QPR?z zt@HQc%VunhUcH|Jb7nW#g9k@(U)G^{K4F@Xy5Y{q%VJynIwKvz8+CnaieKr6)8rWD zaFRj$OOiW3hzAm!A2 z($4Y4_xt1)JgSa7{FP$Kd$;`V?%E1rSkj*-MA?}e)Opu#3;$N}Ntp9xn##G+7OK0f zmyZHF`s#A=EcipAX5+*i6QFP1@EKZ8m?JW++%)KO2#1+Zq<{BAn7@uq*?eHIr(LgR zzo(0d{mWBxF4O}Qsrbbi+PLbJ<7KctOw$;~um608XDOFsGQ?Xe5cgrAju zLwJr=p1KJ1`8ga)B;q?nZbzS|iuz=ps>i*>3?ey)R8YuAX1r*5jh%)}y_1t<;$ZV< zOjW{H{2hh-QoY|X9JLM(e}*HBuCDLP1$Ip!rojV(im)S%Z22lv{={$r`AKhZ(gR;W zvM$;8KoHiQ99Y0xzP>f?%s*j5id3f@gjG%R#TKiLYB9mh@4@M`MA4T z2l8$;+D9g?uHESsbE~ z3_-FaEj&S*iHT3*3+h%7bs2a60I&?Kf>{AhO>mrUpo`PHdc9ei3YRB9Mvi}b@5}v# zjKScuDjo?wdqjnRyep)sY0wzS-Sc50ZJ>yZSYCm{Cq4l#ctA&WCz8&AG%by;&08@oyjsQN}n+ zg3lMtQrs>SmtOM&aT8)v>GN&}&9iX{ckbjL% zgzMR&)cnETIp6#&*=1YO*L18~F9uzqh#zj80p+Bg(f@gNMx|#c)Ko?w$flP3rAU$t zNNv1HYIt`(^bAjS)Pvs$L4b-5^XHK@!?9(!k4x?jr^4BM(;a?Z!wXn&aix8pY@eA; zB$Ag9+G+5HI9RaU#Ba0hUt#B`?uVHrJNu)?7^>0{M#&^2Vt-}MYq_>+`MCA{)TjxJiXKAGWZ4u#YeMay?97 z$xHs}X|hSx$+8cNkD1);zL`NYe0&QfOtQ4+OiitCdSj8R(m~H8z0v8EBD?6;KbIcE zbIR@^D;WAK@c*jj_Vl=2>))|@sr2JK@?8+Ka@Lc(n|Mguwpg`KssSdA?2qRWMak>; zBm3sv7@)~(MMy}W&K9t)wy$UsEkB;Ce&uUMX8fOCgvkmYnoBOPwzICVXUk8r)_T#!TWx7?1%)Z>?OP-Y zjf(iE!j{9Mc2h@`y%;L%#Qfwo5c=E!>^NTsBfwjDtdM;GO>mm>deaveRS@(qA7!wWMzd{M0Qj~v5`L)vo|ani3E=d5m7@v( z@=A`b8N8Vkq49y3rS+880r_ko3mTP<6hgAHz|$+2L7P9`Fk#~l$Ho?&8VUacd{8o^ zjHwt{k@AjQGWJhd~#|J;b2KmxIRty3pDkI zJKRs18C5F2%#a3k!q1w(`fK0!v;y}9z$Jr`244Om-5UBhf-TwAd4cg4786C6qLWHf zoX#heSFI{J%Gg&ZpARZ2`XjSl8AdSlf=&M(ppE9aC)g~1J)RG>E9B~$^;=_fjkNOd zPeo6)65c|}t!g~@HU$Ki1q)X+Pa!0XvW)YP_-))!OYng1k>4&ds8#yC?GIBOkH;$BOQgnWOLz`4dy@tnIs5W*#sm9OSUT~^D&;-sk0wE3$8a!s+4My8b1GJ#HnewSj{AtSHC4eERNeK0v^@gysQ( zG{OO48K`{SizT5Vtk#ymQ~Lzq{EkV4u3jft)E?}fyL~@1b%ALL5KC{0v566!Qo+0H z!fozFFh%|E^+U4bNIG9NEoLgCR{>6+A3m$jW%AYNi)az=Y$cfnJ6q{mJ1vqYe(km0 ziTpyDzZ{=6oTt<#SV+dT4yVN9dRYkLaU39%6~^pUz7rYbJ3!|jOQ{Qh#>^7(dvFP2MSDKoJYUbnT=t7kiaE5p=9=G2S+tnZerSi6u zPw@WuCx{X437rcftaP@D)Ahu`%Eszs_q``qG6GkRMD0=CMN~JWHdB~oT#kR<;T&j? z=*DfA&4F~}`dM8(EM(v4bami(NMy19wet9_aC%c${nI_PYsp{j_Hu zSg0hjHf}l))?@WZCU?(u_mfz}PxmUK;QaOTIMN;lOf2 z88}__*z>fk=I1)*=~w);RM0>N%t(O3KE0gJw;=&1W&diA9t~B_d{4C3YoD#}D}6PY zfDFz~^)6$>xZJ-HPNpE%XBmW0zE0xa4DKgabQ137=m7Uu^=t9eDT%__SL^L_6GRfv z$g}vpKnMDvF*ELg8Z+On56Ds~!gW{6<2SmnLk6u>aSR`;u<`)uRps9cGd1@k9{2nE zjIS@el>0N6hr{{Eshe?-lN63Q4>{Gs6cfHMonCQp5zuw$+<=%Hoyt5+{vACqKYn@A zHffUUXM>zuxcLk|#kc;mfkXe9<(8rXDuCi|M=aWBBif9&nTo`oug*P*FVrWEXFP@& ztlYB4ZQ=E-`om?rE5pYl7b&dzb4@ZzTqqcof_mtCwJ7e@NA0T8T-h!B6=~y3>g@OR z>+5*^8BsN)blpMD39+hyx2>q;iARU+oaeZKpC0&HWGh)_Hmbqe7Ac8R)s5fo`N<`;e&?xP1 zeYf{*7qD_6nhpNG7k-tbV@CXx5Zp48vhBm>w9PuXF7~%Lq$nEmM4fH&tKP4ij#f|w z0$U;vn9&!s=(`5Qo&+=%b8{67=M%X=Dd zk5usQitXUft;&ukC!oHu`H&vp7CzkSDLL&D3PCa_@;akCje2yn(3#1B29r%S@2FR) zrwTit{6!tz{Yr$Lbv?sbmHp{72e4%z{9!xqD2X>VOweeGwZ2r7Fb1t8n}z1Ut=?|6 zhJJSEA$cPk5G(wwe^p+e>pPSVV@qP*`uq|b&0qreqKWwm6Lotr}m+}5fatc zEW^_wJx?6pjJfi-%TM^)nB)r+k=<%ITX*J41!8nO%;b9^ky@w@AP_~ZK1m-DIpcn0 zwqiR4P!!ymYzsOl4xt3#<6#PvR4#c#`Q4R79rA4h;;Pe z0gwq(N8@eGI#=W<5CN?G5A%^7`--ncrAB}aAY%wJAmi6EB_NmQh$(C5x3Ma;Xq{(Dm7D8l zDd@7Oq+?Rn%w}k^bf&KjJY{vGbj-IzcFzIkujk>0s#sw?VP7!Le;Ikr&c7Wt$jN7B z#p!h3C$Y%r8<3jh7Ov1-NqyPXTYRwd6KXDhPWQ`Skb^#k#V+g@Qdr=fOMX?A`yIq| z8a+bB9&=xJ<;5vVAhFj9; zk#2vF027O_{N&ZTWk}RSJ}0KP{TngwW65FbEh(1*=qmAHwV%UkYk8MM!jec@BBe;3 zgFLy%!79fcM+Ir|)JuGTNYp(Qq4d7r`D`^5(7O#VAfCXuaz=bkNluQLq{s8wz@8P? zgCqh)qvPfyjo3c}ap}a58T?!-*ow>3VeIPcbP*m`H9sPK88rE*JpLd>{nz>J^Hh{d z=bpJ`_VwqNm`qK4n|srZLm->S^mZ0sj4fm1I}unk;a3eq=7&?Y&W)J|0>H`Hx}(ip z@c9kaIByfh@H;@Z+d1-OBX5(nx;s83 z0bjM~!qapC*PLTKrpFa8z_08|@8>Mf<3=Wsd6NDzZUg`P#1$x3K=CHR2t42YqZtP% zr%RTiV8_LR~BF%m*jnEb5D2>)69DY+XIBq`sksZZ^VXBB9|&n)yiW+wVy3npFLZiY zeWr%izD1g}`-3l+9kXgX&Y((n&0cn^V6E# z$9W@exX=FcWZK8%!EvG=&E-w`u1P3( z(<5U4opKIW7}w!alGGfwd7#KNX8%dLO9@G~UeqmOxJU#-dM0VTZ_p(FRDr6GFa zfj1yD3#`7^XlVV6boeZp-d?*0Exy)i9QYJ(1VD&6+(^Zr>+M+_28PSfG`JzFb)KKz zEPTe!uoY+Dz}@$c9PP7#Xq)GQ*=o2-h%3{Rj}4Lo6sbKexyPCP{rX~|9j1$kCuBgS z`sE%MJkN!GcIUVeIsG?1`$5&9rdQC}^XcpxU24RJmY0CL3~4M%nGpLjyT3w{@6%En z9k{$csD*KEF#?22Q0ggLhI=L0;IEQ;cfS9}DBo7f)Iqei)psD~Gg{{Hbl@^BZf2f4 zuX1eXCw{z}8pEpw)p5)RFAQZ=y$P^V7MRd3^4erlNf8{QnSkKB<8XcYcnCxhi0tZT ze(jBS5T|sWBH_{o{dnwv`^CpPLK{71Cn_`tbjVv7JO1{nG+6r6nM78sw$t?V~7-uIDp|W}?**tJME)zsM--;)Ul35NybYam$?MBz!Lc zbI)Eqyi8)%uht1&ti7x3TWqp;*djZcr9QXU^JE$$tFuq+Z}{~wg+-UWSlh&|8*K?@ zGXPtx)5j)R9D*8tNI=l!HOb(U>dC?1F4jyvH0qNIA1C&N6*F1OJMvetP`vO<~XZOx2B6nzHQnQ6_ zx}L#cqdp|JVPTpBdD6X@DfW`@XqI9V7&`j(q&>$np~;mGhh~ z8~ZxHNFx+wn1mltA-c$XH*a>LfQhkDoQD{!4xavbUJfx)jx4OoLL^Qfv4047?M0G? zYou_TSH~zv*$9Zr;*qT&MI7Fh$^&Om_Ai;48l|17geiGT!tB!RYqbKq?G*m7{STy+ z{c?Y$7LBDzh+!EUu2`8RbOYX3`^WlZL$dW6e%zC+%caNv;YqdtJvAB5g~>MbeG1`# z^z^&9xRPvJ8RnZ3)y6oNs&I5fG+w>29bCfpVh5MRM%ia& zcO13PnESt2jo@lPussByqnA}T?YE_co65+-l&#AsuG6c~UJ2?kYLV3!n8Q@#iwR{S zq5rJGt?(6SVt!C1Ue`|EtUdt#ZOi?deLt0Et&gn2p4jW$-4K9E%Yl2!r^kVxgOekf zPo?C?Hw9603DwRuy|&7ENNwOnpXwJc-kYDn5beE58dh@VM-fu!$&Zi$VZtLrf1iOX z=W=TX;#4AaBA<^|CM5PnN-zBxU5u1mB^= zO{b*TMOGYdpYWNVeG>!RsO%G4uGDdbLTVkQI!rp!(ev&~SI@QS((~If=wHCOXiDYP zlL4=SU+rxu{hq)hzWRS&IWx|3+6Nuvh@U%*ZU~iv9Zf&pFsA7kAgW#v+w%+f(P2~9S=Z2mal5t zvh}1NnSBku>KRU?Po;M}0SUKsycyLGyo|o5;G%$%fHHg5i$W#vk-xLW)?pPonB^;J zB_Onc>dX7?T+3@u$nj39mcH-myEWgufdhxAR8LHZfgZpKWd%D}4|gviyqLjkKcA%`vZ8In z$wle&WsT+!rjA^iu?qV5BF8MStLT_deim-zaOi%csY`i}|#;TZRs!(j_yZ7tO(K#byI zQ}yEgJhA(Ly2C^|&3NIfEm>d}->VD?g>@1`fb>3NFjuP!*CN^cagM=e%o3fYA{uR_&?FRe?k zW-ps8=D%=ufBdnYRsfSotn?`MSa3AO^~C&fQRL4 z3k4{E*WLA0!}l%X6ICGq6L0DfoA39c+FiXwV;#9)6l7_1P~bV$jW^5Vvx0|K259UVz z+nm8MhMVkJw*yHfs`r4Ja`|=b`|Vb4+69f%`XKHT#w)Rz@8dT=E&jm2=jumXc@^>u z)c?xTqF(B5h%KNQiv#1LxqPH_D$bHA*|)glMtW85h5eXHjfJNwbqxJ$_*-tL$VYNO zdhX}lTdt>2pgz$AdRvYerVILEm6cxptMyeeK4w&XzIuJKUad#BXkFin%#tex?(}@d z9{3bb1>Kgl+9Sx6$^dPL-0F8!`c3FhdlBxY9YF{0ssT7o@b^M#232X$say0Z@2_=D zw4pAM6YWUxD9RLa+=9J~H8ap4O~;4rnqA8x@2&khityjeJSbWU8E%AC-y+@wHihOG zhg&$Lq>E<+XEdOed3S-!)w1s^?G#%L?U+?A+n6%&vp}t%g(VaLk-h!Gumu$Ea$DDD zf&rBmnLb7IF#H7tt6Y2bfQw9m7kR4N`$~I-?Occ{QwKb939?gs*{5hz zys&01tCkE4^~2|{1vq=iOS#YN*#4o5X`eR*cZ-EWn9veKDhlh-UOMXcrXicqTHeV( zJ`KjpKH23HJ%1;4&`Pk{TP+PU}lV^txFyPU{a4a)^;ONs;op@BVaI_AN?*}Fy~AcMi6KFNA1_|?|$a* z=P9Px^>LH+FZ5$v_9OC;KHLw7tPcR-6#cZhzpg#GfJH2yhW3(28nFi)Uj!y0vyaiU zmdN-)i5Jum^&;+M-Hv7=4=C7ly?P$4)`OPn+gN*gi>Ar(7Xp}vpg_n?xY3zvxbTAs zE2ndQzK;`ez7GcsoBbSQQRwN`vOKWZpC%&^Gc>zY%G0tWRu)?V(x(x!Aeuq9=R-q7 zMTwQ%4^|T`Am_KEn0LLav1ShsCn zJ))n5lJBqR1B|Bz3^(RLdEcJDwlVL8`6^p1xLXbEKXj3tQ z6`y{06p;4h)qB4J>33kJl`e@Htc+pvX#(y>jOiP4D1f^xH$Lw@8;KL(|Cy z)<5TD+RiAgyrSe+ouZIlA1u0N&Q;fC9A%5)@eAs?VRHRGZxCZ+Xrg|;#Ws$&|8XWt zI-KW+i~}m9^*uh+*SsH2jLDVMbahrVfg5UyaKJel`CbrwVw$E>FffR_5_>iY{6)fle@P+*b`sKO!s=@0I z73%T(s$Y}^DjBrPc>^&}T)ney02vGWJmCSQR;CciNB_k^>}|ZJoQ98$W?-%`^w%08 zZiNc{(qTM6Pn!+}vLHt-H?1?^01f6_k(k~Ro5yMQ`?BC(?W2nt^y8U#sv(3G3Q|HU?(7~szkxu<@OO8V+1#I2-?m``-8|gkoBv7l8HdY^kw&x45 z&HXy;EmD0MFX?;e+RzkKK7*4El?ZpSiTQ2dVi`?BJ#FuUx}e503(T=@$EUv@pRPGe zRo^qV#mFzPNfw#xNjQGKZDn5_&ZoQ2irHjGFj0PM&Zceo0oC??m#E?2*u*+BrH)g4 zPh;RC*H;_-pwj3KZ4G+T3h9UiQ+OWs`J-M2)mN7n_!IZnGFZ1~Ym}oi+^O6@OxPd^ z&tnR!|yh?R5@K<$d4XJC^@#M zLbu59+^4(K%Gsb;*IxCtWvEr5<%V++W%3cGU(itB=R>&O_Ic}rP93z)kbgZ<#qD$( zrXTu#_YfLPF%Oo%bqd!C;eEZ6MACKWCBB-%g7<*9RvPwJ(S<_DA^{V%t4m>f-Q>(MSj5R1@+B^c<^o2AJi||Kf{$H z;PDp1DZf8dC2?49(eRTkgud`iz?iEYqH2SCYMTH?%yTEo$sl`a% zBXsgIaRFl@FjLTUGiJ-})4|c3abP-npOXD-RQ%<3T~R4x6 zCX)h6!zmG9X`nBF>dN%Y&p_DSkK&Yl<9%(&_Ehcbh5Qagr1-rEmHk!nvrWQtW??zo z_`n~NGBb;Y>IgMy+^bLz!vu+^V?&4iTz}FV`cSZpR9KiqC!cA%%g^zj_nLTY9TAR5 z$VJXZ2X*!S9HRKh$q-z+%=@O{U90;6ONNX}LEn$1l=raNcvd$_ z{}@W(Mqeaok7E7n2JOxql|2;Hbm9gxbBBzfk+4h%r1n=m4LMxD!19JIz=`=qvY*4r zgMqO%zVm)4vJ#Sl`i}nLK8{oEh+=#N_fA!pqkaN#4cWPqihkZWKl_09-y*&>!=ibw zA^-Cr_0rn=^~>De_Itn9Ct9&1zXDMRvP}2-GxB|sJKS6MrNmz-^EZ+FYJupJr*~N8 z`OXWb1pN_`F))4mt{7Ch;+kC5LqwUTKdUQZgBoDD{be3az=1Wvy{i3Kvw;y_8o8R0 z{X{|C)RyX?^1U2G0!nAtULEBbeE-InzI z5hm+Fm(vQNqjER+cSk8AfiKdzoE|yK^gaz&r$3{i&*GCf+*1qgQ`H`^9#ryy+V>ss zr%*2Xei`@?zy7G{eYIyt4sSTr<55fV&p>&%(H-qziO%%#88|+?6jNt;yN(RUVlyiA z0(}6t<7eMPaJf%|i*=i5?)?t>dw#*CSgH1mR=m@g9m-GQ+mG`3{61LN^#mGls?ojf z<2w?tTWH0YpDm^Ab6!q9Vl}#+_q+hPk}RWkIjhvQ&EGvc<}xwud-ju|FwY8(n)ek8 zei)2papT&9wacD`!?pSOQy9jPDXq|RH-163_vE6LRA4!AWz7fpd0}3AZ*Mv9bl=E0 ze>5b^hdWQF0^7ymRq!tRF7c&lG$Th^0`7r-m%^(Yz2HgNNW7x+okl4OET@$k&fKwV z7R+)DdRXUR1r>0Mu&!46 zNq@)nbd5gD361=ryzu)mXgCcRI6ziE4oQ9${e8MG8>O;(+KSkDk4J>ec)?PWlxNJK zGalO#N!0dwH2!=Po9p9^WX*7{29W*Y$4Y4CdxEExuMfTO>4xIO++UYZ*(7^h{k~+* z)^FQ2rVoS%RSCzh;iUR-%@QHwf*RC>2nqy-;-3Dw4)b2FwTyHqd%2(>=MZAT`WX>S zPWHio_AhMzPm6Z|ruJbGPo9Avh50aECC^a32Vx4|l$=A-)kNP7p-0s8@lc#wYk^}o z`8Gv&+qSXbF=qaT>!w~P<1TbL{87R?S{q-SAMydjD$@OenzMS_p!7C}dY0V_D1aLv zH($RVUv)ywvpJ||YW+r@9l70=J*4OCJuG$oEtm?llkQ4Jj%=2Z55_!>zAz96>PN%Y z)i`-DWLzG%0Ue|B@hC8w^s$tZ1DK1aX^p1p*h$@IIfWk@=ml#KFhyd-6jBmrz5iGepW>a{rqTP5{lJ;n{)4j(bHMe$w`x!KHMq2jfpV?NYc=0_e8ZrAdm3}&|TuJ-xl;B9HtT7 z-LTIwgkSPXf_-(9Hcjv{&StJ!rW@lP1{v#l3Qceb{HNy{ea45n4{Iw6OQfLRk*ez( zjmg)l=MuMIyF?6(ljN4CYQT0wk~}Qmhr{)2SgEm(lj7n3#9k&M+if4WrzUJ0H#_i4 zecn3Pov<93^L#v=*|$W$mTQJKJDr5=dsdGXEOHZhBH`jic^&;xhq4b2Q0{;h;-mUy z%-Q)w)y=oKsGsw=(b1mZI4m|v2%+!S@h?hBMwB1OyUahYQ#?cN7uj@$^C3Ss#kD(j ztFy1VmUViYenlRFE7a|dB}9aFy{*4V%cfCG>Kw02?)!{avTd?;3`!x=42jimzrsqC zl_JgZ!OH}7SEUl3v~8LCfknO}`_8QJ2%NO5Izx7dD@{V;{rEUOzx)N# zjaRGP{I;|VYuZ0j?tX_}PHvf5m1(kY`w88mQv#6q7m!WklmfPm*J!94J9?izK}I|% zKfL7Rk#OD#lsa)wGSiY-z@6gBevVmNV7$7_i0i)mbIt4GS~C;^3sPlXun6sp*uo~B z{p*D)+zBjB+pZOx1Pk1-{5=>XikQktQ|V!`{UUA4*9RA@A6X8ohc!SN{pl| z+kS6i89&Ne3O*F0YsH%4PKR9eBi*1yV=sM3#1IKxV$H3GUe}2g;3^eF^;9VQSv|^O z?FifXqpq)L|BxK4ZJ-?eZi)NZv*(|-7kO>fm16q|p!#m~JtV1l9M@k|WhZqS@Al-n;WeXVOHwzOe!=E$gC zq13tE7Mgo*efT6=bzdxLDScNxPdABk5eV+cm@8~ZxTio_(SCnMJjsziNH!;)|_}`L~p(nuZ(wcGn*7jNWIQDL{!9gZyS?SdJwJ zy%iE#FbzN#h31owNZy}YQkl}-@RgtLgI1eg&Skoj+G7Pdej7->Sis&Y>T%ZxSb0#mk8{w4;*S^Nm+Cs3`8N&jbkYvQw8(H z?{CSAzd{;T7E*tzUK?90cy=nETH|X2wMR<#kj@RqNY!t54Z(`n#VuXzmSxiNx35E)1=Y%dB7&KBy6y zD7t0Z^3VJk4MowNqoO@^k%hN6d`pUX6S!BVSS9ts@H_SG@3DoC?)e7TZYb~LueaUb zO7-D#9y{ihyvBDyp4O8&eJb9+`Z~pYqTyjyAFypJnJ^6*F_d~w2iw7pH!oXoJOi$d zAKm(r2u8g2zx^(ys^!@_cJpkkcD@Lq;lRK^%&6T0`i>;I9nZ8?hmRlcd`^>24wH-t z4ipA>z;+4WZNf6h40KyO`fxN4HN)d{ghI#pIpP7>sGGgq;4BnH?yeLQbEi_x@pFBi z(*AkJ`)@yu|6H3FLCvdm413EHbro))JsrG62_@GXp0zK|85tAkxI0seZA9{c_myoQ zW0H`ml+`{;y?*phfi?zDa_T^y85CC$Gg&FJCOzg+AW)z+eZaO(9|<#O)MH&-nc+yZ z@9MY!#;JtFAyMB@fk^>c>U@wxDgPeu^T|SD7~4Ql$$F`Z9uC`n3lKWi#m5tYXH8=*fw&$N9t;NSE_jjq=j4l$c(YX~{6XdIOJMy6(@Xq{VktUj+}w*oW@h}F|8 z7ogSJ!FwH|$KnA=9kli#?)i;(^B9h_0ds%9>##`Fks-^@q# zl#TrBa^m#-PW;B}JE!jlcY^Rh*2Ur_!NVHdp4X@ihn^r6Ij^z1K}ApV^J+Q9m?|po z)>}Zh?Dve9%64e&5{;9EAGIj_MojHI#vCvopYh`$kG072T7?KW?r+*;%IH@`+5q`DK<6MAU@)4V$a;hNH;O zsb@F})JY*3(iJ`x-!GcN*%A1v88=e?@scfs&bjQaa0^CZ zUd$>+GZGg&Zv8E6KP7Ct*W96VX1qcF(cX{sT+Obz`0YTur`_U7?XQ@|7h$`02lj4y zR{r?DFM%!Wv%`UP$%L3*;EFDZ#!Sl|W<08<)aSfrx|@Vy%~ZjykHmvR;0ey~6H(SS z0Gx_T7eqkVdVljhg7eeQ3WsmJx+FoPYs##Q9&K}6Q zrdxZ1qSw6~B7Aw`LbLl^EPA*bMeRNo`{zW=uQ**9pRMpmMIZgl(BzuETr@1Y3b{V~ zBYhgmZT;Sugbm=j%mo|i!$;i=^)ZdkbJzDgqqmrC8`Tgi_s#L}21TKbKx-KGf1CHSQh+UZx9u4u@!h`R=JZK3bdgU_+q!*lPl5`T7`w-`#De0rXa^Z4!Yvw9><{`k(8Js5}0 zR9YgvB^JRRU`%X)G-rz>QgNaa+~bPBFqywk(`>!pFVu`oUB<9q+>9&GPMyP-?P@f5 z=-mV9Fz8ygzCBgiWbMcD3GvWDd$YS1)yRSTT5K=VRP9SoCDWWF#dT7Lr?io_cl{}s zYd*3cT0B`Fx9CRm)Afn&?Gdu%j5p+pkx-sHF-KW{IRmUDG<)le>P+x&=e^QNaO5LN zQg3gtR2>SYFuzLbuwVN5PxDiuN2&P?Uv6IlA(XDAy@UJ2B9n7MQnP?z_F?k{cpLAh zHN`Bw&=pbW#QkWH$LyVRkD5tNZ+3;(>GQX*_eT5t?C+YA+?#kD7lGO@xJjXn_I*EI zEmJ^TxDhcjz?_YzhIo44t<`lYK~C|2`|$qH!Q z&_nZHrk`4NQN&@1J|>EMdDB)tnAnnv(roSXiSei3h7)E+Oxi_^Puj~mL7-#6@XyA&t6dp*w+gk54B1@@U?l`|#?%kL(XZ;`x$bs<4cvl64f~5W6c@}#gp*iV z<$?ARWqmEBz;TKWjtnNUga6pX_fB3_a|T0OTyYvA^9BnP|9(Wr2Jo$ZIlfh zNw#9)0|$!l!z3uklVomA5cd7`18s3Lat{_JCi`gF7cg^g*j1?sLQ(l8S*X$n1`c5 znz+?^>k7Sz1jMQ6in<1+)@u7D(Ulf+vKZ-I*gwdxFn)*xB_v!iEft#zTSy$_EC~$h zn*E!Wi7bG96xNsX}}cZ%{njZ`grUe%Oc5D54I1on7SvonTwy~$J!SlQD4$tl#O@A z{*q3I`?nmlT*>~4c`gSSC#@<#AJISLv+|0QmT%ra}d4B`ui$+b7 zVQ)NfC%@rT*eHR~($v8fMy!lDDsQJ;c7dz?EkzN5lym%&CXd5EieR`=${J4nu zeY->^7^>{y=tL;5Lu`&kW1XiOl;aAznkSKIFMx0x=Cf$#!2$Fyh3qc^Y@rAd-HERL zvN~VOdILE4n@-2%{!Z^)IiP2Z229wei3A&BS-h0LlV$3S+|Miy;lR_+wG|xldEGy& zkU2KitIqT10N08EalT`Ab-MZoC`FIMD{Hwu%ne5+ICh_X@LN!HOV7i{s)e{#&w!ER zmvVX>xbEy($FU0kT6(#D;mC-4JG^57BDOQ@Pg;qQZ92r^4Qbpr zdDt`Nz!}|`0oKn-X8KCvPG--p%9U68nlx$hc4h~ozfE$ zUUGIsQ_DQuF6W2HK>|1)ohrNR>8Xmi&5!c(O&o~-r0kBpY-Xetqw~ifc|PoMV28F8 ze(^2jWtHw*vM2g9DYM>Lav>FN+V2^YJ)*R(@nfE#g!!1q#(1l<`SHSMWyp!Tf`5EW zt{W4rc)^>-9+g6XRSW8x)c6U4Y$(fpERBjgi!yo=?n(@twPOAPb7hYj+TJ;PMvU-m zp!Rk3#>tVsJ4-B*alG{GkHct4vT^Y9Q41+M{&&OE&)FhqMjUk%rgGN_Q6wqGRT z0IBG{$tV(=(8Wi6^cuznv4ibzU5d6}qd*a!EV46o&?$Js-Qi?*yb$C0f;ZcibN0;# zBmOk?$-d{qK>qey_x0k6bUOEd@8PFs?%tl4b&U7G(Gvl)iT5+Vd=B6BjRt{$A7nWt zqxVnWzs|>TOk6~FIC$D`_Lcm64`@srMWBWu{m=X^Y%8rQ;*Jq$lvl!kM7B(A<%ubwv$ozJb}ECwE6CicmKDO2M}0710;*$U*&+2>Rty6==mCCp(f5 z3Hm6;eE1OjM91HZpY@DY{4HxhVG8SL%QtwYrLUft^W6%;_l=P&BxE@SQN@xUcXAk$wO=|#K_jsL!LXLHlpWHq=N+VSa~ zf}l4)UfFOa=NQ7$; zTOe?7jBrH%ZWh;y?{DD!Btm5V6sSA)Y5c#TgV2zX6?l_nWU-=?FN z+eoKKm4s(_AvqSi4@QN!<@vrhI9bKw+sD1j5WS%hJ zPsuwJU#pPU@y!Lesu~xxMyB=ms?9Zen;Kw~xc`-?W-jh*;fn4aFF%tck;K$_)c^$^ zusM)xdfV?a$nk%jrN7acM;YqpoW0Ind*I(pn30_uw+7=IO|!}%aLwqxJb8x2s+UUE zlU~?H?(IKkYz1y9Lo8hH1j%rTo5T=J^Cqt*Gq7Qe46otEsNuuBS;OwS4Ss6$+hzdk z_$MkU7uPYb?)r-$8MwUI!Z2`JA636=n?-zn36ILtJRuv1!3qadzxrEJ-2E<6JPU4a zqqT1ZuM~bEhWrwA>pIX)b!sSZ@W&6W6rb@d`77EB?iaQ_$u$`Fh!{LptqKB zqi@&K+k7}CJRicI9rW{ge4jGf_1#OMVA@js8kTR!u#rtQogSae` z85>D{pH!I{KiZRY-1G%C&_x|*|Eag@p_-^U@XI4Mjz=kJ2MKwbND z{p@WC>6IU!U9UB#J*js<>?9c246@m$fFaktyQ)&NFz)rZPY)O83N^3moV_|n{<=rA zL^34Cv>KNLW~&j(4-L{vB7X@Sjl7-#CwB{$UG^oZ+ph<_ajcjJQ6xE@VA1F+)dny! zGef^jCJ&W$PXoW-=LuPAPdq{8(pmB?HIGf;LLA{@bP;=Fh4d4{2Y%dVbst?9TG&pr z_Cw0N0>boli&LQdiXohh?>;dfArEwpq&TY_&-}R0^|tl9PvATS6uKvuHyp@c<#eNg0e#oSKENK#-`x}6l<4joUWzLGbI)E8@pysH zCZ;X%a+kIw_HBfSdJrUmjcfCU5?6isx->pY^7AmUz*Z*nK7Okb?HMq=U{|uC!x;k( zR^Buq3o%TBH2fqSOX~ZGPY|VrulLdaoY^KijZ;|64%G;H`sCO@acu1ZH-INVn|ItJ z;_3oxw@Qa#?tWW?3n098E@STmhmuI@t}?^M>IMU6u9J3aT+wCo3gcRAyy7KKm|nF* z$AbO)p_u4HeOKI8A{|!Qg!%k{&c#ifB9|khcGyDoVeZiU<6?DWjPSVpNbd67vo)$0 zguzPw@TN1r3T~PY5e;2be_~OJJP_puhxgqPV*CQ2bVR4) z-dw1n86ZNghf_4_*^rU9qCSF0HNyR(Ki(~XjLiBrIy~GZ z@~SM9R=d7?OS%A)S`qbvZit=zDz^KL$3B2^*Y->P1nIbFo0vI+fIjkf6lUN0$~2IQ^1I=k+h+gAqm<;jN2;6Bif8OZPK4(A#dSmShc}P=_hMU?->r~L z(7AU)W95^J-8vw=@o=Hw-dsK!fdxQ8wzB+g9j4gYFLv?Z_n`=F!6`hDTgr*hUOkAP zJChQ;~ux|z63~n7P!c|9vWz=dq=fn z2VAOBgBlYot+vmgrh2BaBuapYp(m(bL958(tF=_VNcSVZwlm~gy7*KKcY*J&K0*X+ znM;%ZvVC-XOma?MgWn%-!(EVp%yp|jQ&902=V-Yv7L~Y*`m=w!r=FFqZdp$3du4fE zv=u7$w66H0{paeGWVZ{Hhhf^Q}Uih+@&!_ro#~}U@Ie<;p zf#0uFV(n3}^@R$5c&4TR9d#$5!(wsWzILL9ECCV23Mj^wd~ima0xMqUugIpUW#bNI z0&SQ{tl_t4(S_Fig4285m8U8d=IftI4!KLcx_{q%X##H?Xk(79dWEsiyxmgSbu%?S zSRAWJLHs{~nA7(3u!&aLoB}pc?v)P$>(uVW9Hv;uXAEOg?W^|YAx%T#>uGx+YZq*W z>bY`Oabn^Pz5^7`wq0Cj03C;U0U%GaIuc0*-qk3;nnyB2<~V}5GJt_lHmr}^j7+BA z43W_|frVwc>xBcZS^OkiJHG^~+lBi}SUo{p*NhhY{P^pm{5Da_Qid5<7p99b%_mu>q} z_3h!m{tN%6-jzUW7GU?o5srs5f7qib*Fb(=Y}sh3sa1TVj_@O6*brP&;$s}y_QiJz z6b2yb)07Wjb3xg0nr4Ui%$7M>Pf^#a&23rI!tEWQ1nom427do-?gA_o1~#!v#V; zcAx!*ASK$iKklv6D(JS|OWz0!R?R|X1hWS6uW`1EkaG4rOw3@>_={4>Pxh(lia3`) zD_|^MHZxYF4-8Ax6dYfd?s1*aX5FaL+8Dv+ZfujncH;?sKsb}!(=spSLb=%pkFHnr zMkp_K&?|Q)35&*BwQhoNy6@8|K(3}8$SiX@J@xI9cqlavInc`1v#@l5jq1QK9Yg}^ z@(G7Xrk`KZfK5o=9z`^w5YNN;Wd8L-f3wzZ!Op4Ja&1_`3Anti?|5TwnMx)neQw6$ z9WG(!E&J926oIvEO*oW2C?>YuFf<$DLMX$9FH~rwab@Cwte(jvrY406W?L~-nEbP)`Yj!;+yyNd)?ZGz+&UwFwn^b zl57h$fJ+p8`_i%3*NEJ3)QD(CbUHA*ob>2G<3MB+RZ&^u*@d;AvGbI=ksWmzmhMe3JbvegX39 zAxisyNrwThehM}rIimm16XrI~jjJ0X+uv8jU9YyMYoG!ha*o=V4lbV@ZZ+1KELgfk z=U=m;VifH&OaB;-tD61<;gKF1q;K5}%tW@2Ie97O)fdBlk5PKKU`;A!O(RJhQE?Aea;+n zA?v!L_xu+q;CJyan~!{Qnjb#`7y|EOt|nA*2t@Z6Z&Y)RCm<2Th{Y3b3@H-fn(;2o3<8|`UV$j&OyWj)D@>%2CVGmU~#6}?kQgMKdQm?D}FDy+x{7xs7 z<5W$ger53~Xo-?%9E4vDg0UTgQ3Y0u<5Tp;5mU`Iw{rGMz3|Av41xY|_9Sfz#vz`t zr;ydq5Tg1x?ZL*0<)(eQhR+`dveSCWpNzAU;x2i=^x02L3T9R@p7#m zPx-g*0s1mlp5LC>GsJFit%dO$et8|BjA7^I`FnMP2JQ{4r*|a)wXcILp;HNrD_?&9 zZmtcF9Ob?u?t|GXKKP$+E#LmOnzDz!6$IfT);;8pgzUD@PVXJDiGOnrDggP0vO@m7 zU6a70k={i5=K zJPb5HGpIwarF`~>dx_l6K8LQmoun$5_rv|u3x^AnzXx-vZSv9IU(}PcL6X~USvtCs zJs9ox?_=T|2c1dDXZl~`2-Oj_WGv3ri z%Mr-lvFcZhv9q30j1}P-3QWA5HIlGtw`~^fP5i7*3g;?tPwrm0&{lP4;ipF0Akb*= zBzb5IA*EEASQ&e+>c71LWZ&LU?54(lI(Q8iWP!gI`S7lwDn>)@9M5m8Gy3C4rQhg! zTE9>*;^@0K90et1qxOyJ3BP_1`ML8h*L})}WZ|N!k85xiBACWaV$R69!y{CSwN;KYL-n#TEs*kXb6SK*9 z{D#r(p9`tn(`TU6@6<7fpZ^gLhVh0RIY37(DJzSPk-mPjD~FuxbbQ_ix&KtJ_I|Aj z&4}wFh>iQc{B|fe(YS%s;K#nX;IYrOa9%b@b02Un!p{5&{j1 zeAK>0GM&6I%Lns3{~2%yst2ix4%vR6ncBl1NnC;9#v{MQjiQlQnWbnt@6?d1@ebF7 zB-pM}=JUyu-?u{K?y7jnoM7%e_#mr~AZy!Mt+XWjTl40zd7^C*QgB&+wgQ0WNh7cWQ{;ChZwpqC3aXWv15HW!nWz2p!0s#TQKr|%4aeLKs+zE4J5%LdEn0XiWM z1XT_jS-LFstuIy3?jzxxjtXigV&6Om5KFIexi9}V2TKgrc;;hUZ#_R*+L2(7JJnuo ztz`d#VEj@a*CY1z{?n^?$IzKsyF089oy7ZkCR<={RS6{f(M)hsPVV|uTE zX9$J3fAkoEvUq-YG85d3FnGnI)UXt`9D?$;>eJ^wE}KE}PZG0B0dsKVfnTMoqw|@Z zuRQ6`u*S)jV@BE+R{T!!MM8Ii>#@$`OXe>cBR_9)QOx-xY_Z@48-&fD7)X78ucy2# zCjh!a(vc^oU8CIaa#MRU`@R}GZed@D_lbY&ZUh>;@&o#8UqciTXmxj<)UYb>E)qYi zu!+o}Vr1jiH#pqrg5v^WayokFN4u}?Ubl=MO`sF%2JzG$qpi$Tkfy3VqAA)pl!+;G zG(+Ygdh1q``@~4IWDw65SDk%i3ho0g-!GjcZ5I~`1UB(|Q3d%dMGH1;MLYW*6)`D+ zbv{h%mx#jQt&|>oHI@ntzxpt;r?{heZ&gz5knRa&m34v(HjRT_>u{GlcFoiLp|9#B z)q5Tf<)!L&xZ&*4Ri&m`dMi@o@5+8uDlK+_Wli57Z*H1B@T}ee%N1l z#bBkprfsR&cLMbK%GV|;)ez%vs0wChKf+G3aW59w{_)Z6&US?2GhT?QF90EA9*1Ss zM?j1Jq}-2BlUcuM?hH|`stPUH zF_At{n568_2}#`NkxqTaiXH0XIKuEqg$CcWXuwvIpA;nX1Mc0jUb3%62cG`^MmpHz zna5QxTb*P|oBVy?V~Jnk&lb8ZFZ63GRIJ{xbSJkb8*UUHp8YN^itnZ8QSFyDAW@e1 z;u-rBMb&HJV#P5DTxvAx^qjvRd^9{q^68-$s*8Pw+~=w%5=T*!+zvmG+;;r$pWNT5 z8I~807kfS3UKf#a*T)P{<-voRYW~8RA><<>0NFe{LYvO>;p!(5C8GPRo+hf(M314a zw08;5hqf`C-Z{YNZAk0CF1SV)QKTgD^K;qz@*|mx_aUmi02Y*`ReFvzyj%>CG3t#L zEE=)@I+QR8^c)}akZmd7c{()1isCZ^`F+lozvS3+VgjtH5Q{{1hvxLFLNZT|LdqOf z>g8w36)lCeipG}|B+XB_C)OpGpz+osQbb0-s+X%h^KP2RD_Z);=iFVeQocS0&u6Es zD&2xPuk`Z$wp%`aJA|+5NVVhNW9z=gN2O(btpTwKn3oH+Qk(cfEl*Ixz=spS8Yj zF6!=g^TjtwUCZAB=fLg?x9$8kQC}n5EEcBEW3brS+ z$VLr_>ezp^!atp`ZNe{pn(2WMtx6B)i=C9rHDRlrUcc{)K8DICh35=?{G9_ycx&~i zWU8};Va54-jbOi10=J!Yyv5zGvx{|d4G6eSU5U?E{&vPMW`Iv5{#c}y{LsB7t$+T7 zSN&->l~+8cVh^{jg-bpswg`+Dd6DTGq2EICq#QJ8uW#-rF@Q0~VW-dH>@rmG6)#RD zJ7Yc<^Sgp-BIcC-R$p!#i%CYjSMisl8&3;H@ZL@u2(Pp7zFZ}E!{P(O?~2o|de?Q$ae3ta z>yIw#CbLk7I{nsN2?9HRq{G6nD_jTF*zb8#6|ym0R&bF;xJ+ixjdWGdvm7PxM0pQ| zUG6+rEPKB9+i^i*3HsMVTLxCc+$=1 z7rjvYuboAUl@=Rm1?3Z3heg&@(>@^OYSjV$M6h(@A1!7y1;lb=m z@3UwfzJtGB`gFkc?SW(e%{$if%Sxv0%P{yW}t}HHTow2_$lgC@bd9)+etX4s$Zzfoq6|qJ-DVpN9f-!XRmA&e%WFz4Qeq6+HN`C$pk#6dpn@eY`in}(tN z>2ogAzM6%W3k$v2gVe%X^-iYFsDx!acU|qSIr_7&g&@j`*0NGQHp0=M#v)<(92CPJ za~)V%=iJ>z$wDD%_T?sifh`;nH4$1c^S<|=i%B#Wu_~vNT5+MHZc`-+sEHjI*vU2#A0VH-r!${l`8S2!OP4*nMe!Q@>8!T|#!c`Si1}+W#Gbn%PK);`;6#`885PX?Ih(B5cu~p8625>t zp`mCmJE_tQ2Hl6-taC}TAOr;0&oarB_i}07V#Nx>h{RTDAAC_%R@I3y1$|C4=13>3 z)CleU7hA9Qyswzr^v=IFK>b;k13qASUKRwSR#JOBECL+7(g9_?H~9~EQ49=V)bINH`QiRX(*zlG7ec;%hwnfGHeGCH$3e0W%5>FF0A4jAPb_NqHzs#ePr9Q{5F;YRQdP z9nGfe7bwB&r9y{e7^Z8O>iPGF z>0k&0A0e*FRqz%zea5Q77iA&k(ihY!*x9hHs*et1{un6H740@6>&Ug>TWoMd* zJb9KGNtkQ`@M^8Gz7sWdLTK(dBKz5pW0xdU?0cd^-t|>y4-}BMBZAhqmvS(yk#7?* zQ1l@DZPfGtqqLDA^pD=ocJ@YoId{z?H^dZ?)|qiX)^BfU7e%c+zOGOnOZshiBfqS} zcng3KR7^5DI~$$JXov#f^Z2o?OiRvhFL4T9zEK%*l>cH{8hP^FH9_1LOThHe7vf9d zH~W2Lq%U0?EaC#dgL+>V95fU+abb2-^=QF0SH!8|RS-f?+GijZ`2uGImj%Z8?*ZfD^)cpC!Yh8aBg;AAOB8Je3!7yw21e6$j;ei+E1oZ#el^` zDZT{m7FxV|NEgTh4&TK0Auhxba<+V+fQsb%{{OiSC#$_;0n4_p`F*Pcx&C!O_-9?;u|b*4Mjknvk^1*lX9Vk z);9K@z3*2SHOXlaoX8%iR*?^=+U~RMd}L1Fxkc5~n~l#+a7g8_UyjeLeOPI|O4mZ6 zI^s1$T~|{>S3K^&nu%t#y4b<9*oK71(idf~t!SNFsbPs-<+1-O*uv3g9k`rf zMhYYwfqF{xW9U3H{7a5MraG`4VSh)sJUy!GD@o#yS{!G&KG7tF;8bIXQFbRpjKwba* zS)}v|<2~x}V_J0CW1}<177d9pdp}iqYEul1iY2vti}rEqf}l8=<%^SZC^4h#L#D5d zsD{11o?vY>EW{Hb1(%MY`WF z!D5Wh4pPt_OM-YHZI(T?p#ojDb}oKsowJ{=cj9Th+Lqop(qWonJC#~(G%H|ITz@Ri ze~thjze9+pGi%}9D`Vka6pwB`qo5DS`SZ~)+QWQMG>ggn_WAi|(Z|;h={Y;SryR4U zcKd$Bp>_ok>!TOX>$^@*J#BKo&2c>}g{z*Ql-u`_yvR2M_;Nz=75Cs?Kk0gbWPsX+ z>`54kcIEHn<>K5d+o=tnfdZr9V3M-hJoYY%lZ z_?2T%Kb4D0_rF9p=lmYr(U8$-fY&Iu z2f#g*T}G$RbEHC)%Do7*%gB<-@=0#D?p8uq>9>KgM}!J|zZEfrbDFbw&AY#T@pYQl z!@MeMEWa1cenS&xN_yv2+o{cNwnZXMNqP_?MUHeibAGqMk%V?QpT6Dkit=Na(?its z%=dEIetxNN(!LRwhQDa&6!$g%=U!r;4xX|Gt2(}f%Y9QipP=VEvATO!RP2Ydav?Xy z0@nS>e&fxti*DjFj2mr>x?dt92QASBcOYi$ELa8E271wMAR#6c~t7xkZI?&($hTj6hk()+^_C6d>Y zdmp|2qj}Ki#h*d@JuU#P5|2c0R`}JtNKKxsD|5)bumT9XDwS(?QxG9^x<7M(i3Hp6}x7B2qN2N^~y)FZ$)qGcJzVPS|@i; zAYKH$M1K;DHB|T{Jq6{CHQdVD{nMb4(f3_cgNB;urE`2xcOI?YR7dSHz#S5~BM%WX*X#d%Au(I@2If z`YG@n)0f6Dyr#{8xx$L4UEbqo(&_{vrULu}_M=@3mgklgnC_M@CV_CUWqq0I$7oyn z1rY`HQlsKL!W&$jpIWFo0a`e_JrRY{_^N~dkm!CeR$Yd6BlJ40RW@vQZZf%(<9JY7 z?iU3^u^~Hf2-Xx$8K7czIy~*+o9<*|b<9PO7cYdxT<(@%q|vW1;N47fPgt0F5c+_= zmQHA_g%IFxY<+K(@0t4JE4`|N0FwS1&3B6?OX8aAv2%NOH3Ky$@4t{!QGr@h&yrnp zAu6^N;?qdy5AONEpRy!ei!cujZhWu_?zKIWaFg8NrQaV&;DIGcvbRjx0z!~UB0ubv zmzJZA^ZRBa(IygTDeQw*li_o?s-Kl<3BoLk}^%@^e?=?$GUnboNd`{=ItfilSA4K{i#opnX2%t)E&e~cQl2-ff(`t@nwc; z#k|j@%7gk-wEXUq1mfJ`-Su&(VpJ+VB_q3dW^CfI+Eofu0~}$fJkGJ4L%s6s#gWWU zoqVSs*c!A&MZekbf)qHr$YIr!uoxAV6F?L2lphkew^xNuCeoA_>U;Q74z`K}hzkRD z;~IfubXS{(Nh7#3fzBv(pGk0WRP?rVj^f=Y^409q&pCV7Sa-mcG9O{<9;lN=KNnWk zNRF8THuu|n18=}OxK8@i#pAECVX$TtTcfP|Zm*a4uUo;E4T*XDSQQiNWM6Ic4!`?i z-)rM&F1BlHl(wZ9QU1Q~xHKVT=^jYP=QCSa(&2m9PXXQbKh)A_n95x7Qa-}PZp zLGert)MH85HYlG7C7wQD_5gX0YMc1c-X7l^76%7rsfCHD?5Q}j!T0W5_w60(cV{pM zg+ar5-TR?`5!m zXn=^)hrcF=&}lL)f4{MOiHT6$pX;0;HQ`#>VsXd!VNE%J0n+`QnEs4-_VeApM~F1; z{8vBN{^^1>N53d^BuqD=(nvI<{w~tX01vN4va!gelxFTiD}?X&?{%G|zB&+DxXFuf zBiUiy6%}%!Z&<+1#4cY>X*kD>P;{_kh7zk&s;C%Iy1*eilKwY(tml`YT1xp~(u8uYGr(ySORc~W1-WZwAQULVGOH8k?Vh&E!=UU3F zcRKHTWJVKs>Gn~+XG8%&wGpEq|0bm-!Gz0~sew;#UAntrTc z4+or*M0e>N2UI)JK4le}TmXbm=A^&0>Bvr=?- z=Ly=}mkC@2CiE#i_qVk5f4uOqg1H*LzY`5{SmD90CX+rI!)Oh#3(8t{lfhR<0WUS| zlg^ZPQ62-L|svsR?jBEJPh^6~RoO(`90u2oXNn1R?YtNN*evn%%Rj?z23s_kpWhxIeAY}()j}mWbocR<#Gk%sP{5b=Oa_>p53Qs( z%e|(Mion}7twQc9FC80hI!hkJs2zr6e%REV^@2Ro?-VxFn0#T|cyYuX+@bWGzx$h4#59#d;v_(=>X{MxQo5dur-qx-+_hk*^Z})ijhC)A--}|Qp0)zrrt-HP0P`{Jqjmu7=_CEKi z<<5wq8p}wKwH}}r-d8vz6Er*=nDp46o_A`N)>z~wqU$_1jWL7| zgD_^+ZYFC7AX9I-{sI}gsiN>4a6qiX_+i z1RHuPSHj$bpO!{1+O_A6VI58H^XM6A-ykxTIk6Az{QcJEAvipxpxqabGKz0Vs4nebkXw`Qj25j*Zb3w2jR}Cx9}ble%zmE2a2=9 z2n)blTi%pKG?Hosa|OP{^6i@yujzg{PtzVLJ(hhqOZzNHKb&CX%H(sj3zX%4m8FYo zixOGy!sW;YJCA|~Do8E;xd}k*Uu~l8YRfL34rX(F9TVTXj26e)w`Jv|co4zEFR$r$ zJiZwn8(eY%OpVy;IDthsG3E+MqA|UBp~2iTf{Wz7KHY@Is!Smrw0yk0!ssq{M`*jP zF+Wp*9(}=DURyWIw-$8?<6-WblQYMS5&1nr;ccWMCJvRo)>8$G(w3T@%%+$$NT}ia zks56D*mvrfFU2otw6oYlZ#E)3cJN&zIaq#>li`c|(Kx7b(8-q`aA@@5F4ZGI?UC@U z4UDdTB%RroqCgNte@PJ$9$7^c1Z00h76I8owy&R{=bWCIo^BTeswyip^2Tjp^3R)* z-7MOpu*w~0$9nDM3kiKcUm^z)>Ja41W<}qs)RrT9&t|;PK9GoQF^G$;zf4H8OIhBh z9#oGn+g8%^^t+srakwnc$1jj6-$knrI@#0SK|-F6v}usD5d<(_d{bH^b#1TBykoPJ zVl1FmBEto&-d*6hDGGrN0L~%xzM}80Ob3M05eAFWA1YCLe{tW`SXkVpsj6>BfKQNc<@^r2IC!_pK;K_E z)cIjca%u!L?tpWMTyd13RAqcGmGtwaDo(Bv_*0DowX;G{x7aO6SRLVY;`g3@E}giL zl4fkl{Q@VHxWBDIOd;F1*$oqVG_;Ajwa&R+58gejyasGaJ9hG0vHfs7(w5Y8f43Q6 z*vyZKXFosNWC?0xhJ2mZGu@}p7Yr<;zYm_6zXsjDKH~&_z;r6HU#Tdl(<+DBMJwqq z9MjT82^vd26f3+Jgxlw{P)G~<-87)Fnhe2bJPD?eneq{#*fGd5aHck*)Vp@wCvPm1 zY}>Fl+M=&Hf_zCMwSXyNIsR*Kpofg+5)tT^QQ6ngqSu)|{mr}bL%nDQ_TEX8xm^z{t5gBaP; zD+S7LT}{96s#}KlxK&WuYsVS=zKoWL`+%Ol)2DmhP&Z$nMQed!z(D@mS7SYdYU~oE zBOeK8{u-6$qdLjtZ~|(PIOamBcuk@qep`6yQYV-~N1Jm#2o<%QgUo#A&aaP`WR&kI zEpAskfy+rW_hNzwiF1Q}m2v#{gKZTS$SlprBD|ljZ-lugdP;N;cc6utzEEXB*tk@z z5fj%beXQ#p39OsRbAz|#<9<7-XbDY5?(81v`QZ*zaX38BH|kqupf_;5CoTHUdcumFHN*92+?o-a3K8kD$i6g(vi^zLwD+eh#U_eBL?I z?$LNs=&qJjj$88V`?AO8Ag;l|UK_ae0?hizS{&m3LG5v*Fd>Z>;QdTC+ulS=e!|kNkK@^ zkSVJVFjvWl3-@&)hS$8$Jq#yPCLh(0o%wVD#wfZmmZY`RAj~{idX`R7#o;27t?^Sl z@0G}KjjCjYdwtw5tfnq4m&z~}`oTr{Rx!sKczkjAK4uzsNyQ{Db4r?c3$KTxPE>L- zZql-T?^s4+D~&Sr?qmeVQS}_b67|&aMuWp$$5roEb)G-J-xy z+#sc&`qTMaeNJHs5dl^A%<5yC9z0B*5`xMPc5%D;+sAcbfddUZnZkL#8QX4?si&4~%Q+07T!^QegJI z)5I30)k)4L7%Sl^nJ#0F8g7I*(ff9LD-13B0J}(c(%~*Gv8Pq;SzvL0D=*7`k6^mF zLr*pP3BS9LSYd7B))!LHr^v3$KC=fDMJ0H*1ro&859`LBBiO;r@YAfO6fGKS8TS3~ zNqICkA{VqT=`~U{TCO)pg+D1i62|v&pUM-u^%-Lb=EZ!jUI3?#gMZQS_|W}XW8X`W z5xsysv&Zj&@dC6{z;7;jc~`_@=j-o!`5q*M)I6h3YWsAXpWRmO3jn zvI>%KN6IIrM4-y3$@<*7wVru*vG(=K1?=5;4}{*f=-uR7dU&OR8N7pPzY@fHsa3pk zl^vonyK4($1-5E`!Xh|)TcFfx88(w{ZiAD?E5#M?=3bZBu{RrbkAH8(T`)f-a0cyj z@iZ_2-q%l9+YHPz$<0*`KC6TVTYx2t+ z#Skavwdm%3<1U@MCn0YzA;LQ~$<4YjNLuZi@H_GZ9;(acqZ2C~!oc))MvKVwIEltj zzRi7Fo$AN&+uE%Cfw}UPT6cXH_x|Hml57joIy3iE)Ea4yRN!V#XfFs2~KvrTojb6 z7889kE>IXhtNzS{Z z)^Q|DDIhP$!@B1Nxl5oGN79uR^?7;A{@caYy=FeDJc(r_kDZgh;luqYoy@n8^ck(Q zVVQY8EU)|9@`f2eAV{kkGs~aJEB0J{j`)$Fhv7NP>(WD)|2eK(oxBbs=$t`REa!T( z8GNqpRatu^hPa6PU1d^Fn)aHVgvnK&-yXW&&^ztj=u(~BgP!SSb3f(dp>$t#F5edv zl@y*szblcmmhh}B`rcU_v)^Dc#MgK%M_0Nt)UsKjp2HkGn&FIuiOcWJ{ zSsXqRRmco>p{X?<>Lf?8?N;rGmO$ae_ zCE|B%{Fd$w*+*E8>{C`p#`noEwva?PQg|F_j-PRVmFpkjMDh@TG_O8LhdZ2K0Vck8 z%lqxlEz-d#!`96q&IDu1YVV|f| zjeY1J-H!;y@3g-P=)Y@Pcv`_!2T*v$O zs50g?qGScIIE#eWmEqamN(esM!dzXu7`p0yd%W`b!X)=7RNmV)O`7wP5|6L(Z9oc= zZ08R5itY1kj`xk`1!!LJe*0S{_xDV_QeS6PrK=%>2uQnkehQ?|^7IT$FfB`tYd5_c zW=0yaUsUAhHUYhx%_5#Y0|oD0Apq;$bix!dl?`|3yjoy*c&8y2QC`=SiHd>U(?-W~ zH$MT_nLZ{eP6lVA?2jDY24aSkJ>cGT^54|zTDa8GM-RB>_P(xz`Lm1s)+bL9y34`Z zr+pGgab7*10Xw3OiUUj8Myd6Vy!?!g8V(ooC~37zpJe(2|6Qz$QiGCDeOl|o>HfeR zB$doJI&PjlLTZ%Q?>zrNEUR(*iFBGHu`l^7xjn70Be{n(J@9{BJ-6?1YRei_pS5?A zTRjxD8A~RF@z)65!&NFB3AXs@7p8>S?_0_4Np$5i5q=gbdmOi`&{sT_7;j|R)N3@i zjj^x#@I5W@d~1Adzu%B8%wUu+hgROupU}_cCWM#$0I}3Dv#%+ila26ebi*P=ZDuzzu)g(1laRh zkFzmfzL!>_1HCT!NDj}`RC4Hdw_>KiEhnMl3_Tymb)|=~e-hOKA3<~h-gML2UxxfG z$MZ{N;$Qpuy`LZUBdf+)zRVYS!$zIe+91Er44Mh{j&^v4 z>`v~pvlbi8Z4B)|Xr>ER+d_M9V;)Np?@7U`a|a3p4Q;>{YuyzZ;(20PDbdBgF>(NVZDd#sQz36M1TBs2WEt^k_|`B=ZR|| zvAT`Q82FjnNGGjk(fb}x8pCVs?aEoyajy8zjPB8>JC1l}Ve0oF0XP$Miq-R2CX4FV zwVVGj=~P(n*E|(y_kbA&p0<0yPF*e%i+<0}AErgvI1AF5G_xWyQfK)wAK6Ru1a$)R zIYeNULK1+>0OszN_2<>P&Znw@W$6}tr=5F1sd1$N^z~9RgS>aZ_oAL zwoD9;B3fNGhBgGwA&O)*Ts-A7NbNs~e zuRL=G4s-Z2MdaW4Y7vCcdgQMux+3z&Ltg1Fh?NFx@GaC_hy4l&m4Ah4N;X}gMqREL zolO6IOeikB4r~tp$m`krZ6?t#o+O;&uFW6ebwAHE8I>Bng-Z83Na0N6hVGV3CkC$r z-EUp}`gIC=I`+#Xy_{o=+lRvr@G%@YE&j8xc}Ed2#^XL&7u)f(U+%y`4b6qc+T%^j zOJBpU=J7r1!K2m_ly?Htzcl@7MB&+0od=umbTm=;#I1!qip~ee3_3~d-5}|_YRy!9 z$i&oAvy4GgM#08JlUDb9V0SFFnnOIY+08%E(}iur2`mL`zNjyo1=2StEXNIG?*2OPqhGBi=|;hrZ?J{*QmwPXq#y6S%V@deM@58pcb zqybRc-uQ()*G`d_&^vu7FJ9js%-hQ*KO@((6;UzTlQk(wvncIwGX*J_ZJT^*E*-#;WV!6|s4NsWgG7gYSGUSh1sD_~}y=$tY;8ibJ60AB3A z-VTK5KOB*C{RnFfY;E!<49m~a`0++XaW0bvWg12__bY{0@9P48-ZEP{!+S!=PFu7{ zZxM-Xyb}B<4^e*ARjs^!^!p`Nf>}8236;diK7c_J0W107i_I;Rg^$OFT@FuyM|@f- zN_W*3Ug*?Ak!UWqnAijJU$L~kw!@8)r2)Yf{ZW!=#IHwssqTz#yfobF(x0>{R-HB?$*A3j?;9{0I-*SUqLJ!o~|z_w3F#x_VCy<76$I8A2l7jd?E>pJ+3|9YfKN^ ziy81YthNrAORfhU?J7e|k0kr8WPRF*UwhZ@9DP7S{C7Rhf7|!|*V5m{9U=Nl+^y$- z(|TC(D*Xqqn{4-iI++Yw{y$>*E${H3nRZ+xm*mVR_N!Z%B|oZqx03^w(X-$#0#e8u zXRnrn+++99eyinWajLyC?%?ZP3|M!LEKz#8BSEZDYmEdw)$?HqQ2Sf0UqDAW81ik3g~@#&KyuK8q41J;QOvH_o;DX$C7 z{G*5}cdE#v3x*_KoX)7baiE^_eZMahy?;J$q}zPwSN2_CFB0+#1LwO-^FAp$%j)6# zw1);i)`oNX2!(^5Buhtro%U#g+y8QEhKa}p^(R{B;ya9q(0TiI2=Se@cbKSp#n$_MvOZ6RsZE-- z9 zH7F17>*rXY35VREawJX!W^#BO{=^%|V^^?bEH!%vW0uJN>v3@RHNXX6H7B`{>TkhO z)zJ3p{8l!%pYuEOjF$VJkOS?jBw zi66P6W{0zRdQi})?*aenZ#)~-3z0JuNw?y8wtYe#_R&h%hd~N$DY#`86B@&c@w&zv zs3Wr550Ij|7*u!43bW_Tzt6AzIVElvuB!3{FP+du&(akGgn#-~{GybGqxWeLFX5NM zai25M3?LQv`Ga&4V!-wSO-;p+!x2x3% zdoB{e(^HGX@p|D#Tq`D=RuUyXleoKoOKcx%Uv{jtsaJ2%f};h(zrwA1%mbRs7jd8A zqJ1W%PgEL$>5Zvb`obV;jS|M~?-Gok;?y`ponFLd8D8gmQdj63*}8!lL;{JMkII({ z>dD;Yo@9O>b7g=-eSS_RkoRJ8eFOvmfvcx{)5{a+Vd?NaXSUen*# z7d<*L(FQf_3ogIUGP<~I+2|qZVapbMg;?I-3M52TF)N3K13Yk`ky=MP9^R&i^t)62 z%Cjl*=9A=aahcsGeq6uts9_6S$`=jvalt-F3l%^(o2DnduXMLY=L*$l@x-fj4|Y8K zG)X&NAd!z0mAyVzk<5fku5Qoe!)(Wf+BaOX<(Tc~N^6b79W@A;+v~y6wAVgkEh+6i zo~Cd(G`ntNw>8*@4W?n%|6C8TtH;m@5nV@DSI{xd(m1`GbrP}e;0@N zyFr+2I@-+H@iVowhFIkHsPE5#PXcvSI@FI(6?#v3-?IQcregip56{ldnnfM=sR$Cmz z(^4LtG$d@@#lg=ZPY6wuou6QK`H^kwDB8Ki;fb~gMt*0FEt+SxU0*tkCxqZ|SwQnV za~JB_Y+eUyMgLYqxPn0=OfQw$@_f$ESBT5Kuj$>NpV1h7UGJ{`K7(}UlJ?IJK_W2z zV7p5WujeZ7r;eKh5)w^czA{pW{a(y}I{`L}2S%})GdKQXdpQ<1>N3(AofGAU| zb{Lg~xdc2d77O4jQRUCQ+t*L8V@0kO<0BOZ#RfUeJ~;6emH{QAvOiFkMBWGn^j}ZI zE+>z95Rnj$*-?zDT?Rq%T|6-N)SWc=eRs$Hv1h=HDNoz&0{RNysg_Vh^fiS_?yFyX z_4ZNUqh25C++jbIJo0e4Fi)=bfgVj>L>e3}ndT1Z8^b%TKA^6S9{ffCseV0r2!(yX z6x@s6-ix*l?)%zw>>cYjR~5NKRx^O{a0JAif#0R@R<%@|^yT1Y$4j?f@1o;|=Q@PL z$>YXgF97{H9=(qTVl^JIfvG(@ShroG>;_x=gq`u~zRu_cJLbJ%qvmEE^iRalU(~Yv z^JfgIJ%ofcr1gZ3Pb2~^XbvaFD8|e6+z|$Td3AG^<3$k;Z6+P=g?+pqTAF%z9XZz1 zJMH&BbaL`4Sl2gP>ha&(CabHqT_lGrVn&rWHmH-o=25xrry_Jkcv}^lS!wFV9oYRe z&^|FgP486HiUhWkoxE;O1rm81)ipZxjqUn0uI4K;-j_X7&hc=g2=>U^-rtZ^&;oO- zJ<^BJd%UhV!p{}h>ie5(sQC~Tdz!_7!4W9rW>JsC3y?NIT&-a`uf27eX>)6-$M>;V zgKZHC0PFDhglPYLF&s{h^56aQo!iedzQThw5Myv@xl7+elX)IaO0t!Sf2tiAH$R8V zLslr|aJQQWZ`C*1D~R*cz$RMU^9asUL*H`viXj=tv_A*p`-2z<;*GNH#JhUjr5qBb z326<`pe3pH!JYd1+i)zMdn_O8ze|&PhK8lMSg{0S`P-TbFhAZuH8Z!7-DzhxIDHsO zOZF0?@p%{CqEuQc7Vu+K46?3tz^ms|1lOSxAh!@~ zy;EohE;0q{dZ))mamutNZ5FfhB;#z-=rmgM3&TQ=?`E6#elspU<<&lW8r+I_-6TpT zf4#p^BvP&coCqx*3ZB$%OxsUyK+58x*{j?SB4EJ9wwH_hZPet2Or#4%nGNWh^ z3gEj^vh@!0K0-9ZKvIILZW=70OmFROT&laApx;5J$#TpGqco^?O;%=hUG znzWbw-Z%A`^bz7%uHV~U@p+DJL_ z^pao}S(t6&s+@eojN|$mN9--<@$L4I=$8Vi{S_E(OtsQ>J*&fh zoxo{E%(#Dd=O5EuAiP!tNhbj;K&(HTW+uEau8^=YqshUhq#|IysqQ8TIX0KC;?l4`5YyR)jQ&vQ8m|I%)@KeFv!SEKWqd)bU`A*1Afu_GJl-0%BldSk z=j%JW(Tp=*uVHPuSMTO6TJu|iVOZF1hBqPwEQ-7oDc_E1RcyRyf%^nhNYf0yFO=rgl#oRPeg)@e|N!s$mRr;m^_W z4;b9`HE3J|S?}1kf5%gk?|Y~(EZ8o78cMiPxT=7l=kb`dU`Ap1X5V{5_^2^*jQC}m zmkE)dQkEnw>kHHDNN7B`OHsEDmEHD+xv9+6eL8+A+5iNGs^2^(WKQBGRilw5_+ z3W!tV*QagcH`ER7@#Rx=p5IXdoetQCm%n7oe!pu9Qx&|Dbwl=X51Q>+f<@7{Clnk> z5(W;SUwR&Pesxy^Iw+0I{<8br`+g?yX!V4Bc7yHwodUp6EML7I=@{-DXtFAEK3onx z%0a5)B>Rqwdii5!*>uj2^VS|u^aYR;{`j`BYKI0_Il<{6G6dUobzAFcT)6R`J;2xJ zi&z6P{bQJFo3gbAtUb;+3<+5@4Bh>}gG2K=7iju4)!II0+HI}ES@= zr{>@DQN3QR#~YmSN>dZwj?CWMf%09D8usOWu-4NUOxGjQ6Cp!*8e)$CfX2kKh3iK6 zI`L)fv%5azhCaRniNJH=8%=CGj+ZOi!d+4yV_L!j42;LM0sKo}va{FXXBt|>ggp2n z{pSddcN334&SFrY3{P`ReYoEWXBAzP)SB|sgbSxAp&rpO$sdpSP1uDR_j5kJg0lnJS2hk{DI z3*`Bpd=NqC0>IH`2RN$@?9|XHLkBcuqcs=($`Sf6{HH znX(id6pLrOl&6Rf>{DWw45|B#x5uN`9U3~&%DT0yh;_DCERVsWhhP0vICJ3N%wh%q zm$Eo^DSW1gke{jtKEum-`{qIoYb8T{nLN6E$Vitj1X=Rb^(MOb$0KcXI_5lDuPXsr zVXYDuOM`#<4^AKYxI|yRwqRz8^yuqkP)_#MKd|RgkrmOH2M{jE7+WsQOxXW?nIR#a ziIVq4>cp4r#i$j<4aWw}Yx}{W_80yIbM}~#%j4rWK}*`O4j3(9kDxG7+CI|_*_;Nl z5BqY$bpR}#H(|E^{S#!^e;CoR=`u&5(K* zdTZ0~KA{n!cBX&arlKUD$wylGqShG|tFD?0p0GOZfx6T`mVXsCZPGtGm!PKnzSk6R zFib&rYbX4WEt4eI-`p=9`oPXDJ=Mo2)o*e6e3r%*X7psE;CH9s8zA~C-j~cn=GvwD z>-rhe8z*>kc+?v{|LQLXdG?&IP)K6dLDU)78=}Tm_h)^=q!sb+6zEhm0+yjK1p zxE;=7(WEquUtyIPUa;2w-o+7&sJia#-v|4#c}?lC_xM@)MSPmPh2c1z!8ZpD=$j<& z5t@qov>c4$Szj~dCg-g!7SH@U6dsIS@m6YZ{4(@JeU1u$zEDy#w8d4tJ*UT)Hq#N} zqw00~&HL1C+!lED;Tzbod)Cxp*IfO6h=hbQ>&lJF+l}EAqpQUl)7Zl}90eze7NMfg zJrbq|&``ZQl)#=dq$heK#^$N}my3NcG<&R#IsN@L7ZP2_#p_~$k{ZC59vK^KS=5BQ z+$A)!M?#i89*KNfuQs&nCXwH8dYIzpeckD?UdHH7$}!pkMy|pn4fg5W?V%M~k&FaW zj)V^&#mIO$IMg?J+uA{fH^x!5&frQ+*KpY*A_{%M@ADS+&B>d7fODIMOp_Y=gHP`< zNH5V@Y71lz-Wykr@&|S_T%*Xt;vSacwv0!~=vchWF=^4P7k20XaHm|n83vri>FgB^ z<8;bQ#M21aCH5GtrRV?9c&-Wjmn6NfF+qmK(s`pDnr!J3l&*ARK?0fd`(KnUew;|3 z_9cl}ou; z{ybJ1&C8F?UCB00BYm)#!JwuRX>sX)pZ!yq=ij@x&(e`W0jI$aa^?Xa)T+HS(!M~x zpHZ9%CyfY55Y7)rJff+^s-D&tb3IY5^R^E>Cwsq%V-9Ql#yH&b^wK7Oy<(K!0eWDZ z@9XnPx|>4WspKI1B)xXvd$4cm^x-WH=83O2DmR#Ktd;j6vVFSKAL4C=e8$RAdm8tN z#G#O^Z$6l%By_|InL*fg4(IUtk>B4x+M&T-Q3pD~;+I;pu5H$VQw?S?am?I)Z;lNC z8 zEy7l9ECqqUvTCus)lS!kvNSJ-?%&vdb0iFLuH+5Y6A$~gh-q!!U@tp#^t2yEgiR_F zbjq7}T5|%v8h-YRh^DycAV3bk^PPN+RyaPDr%8X@dO17{>`mdQVxOB!x=R^28(Ig^ z%MU0?6@_sf)A{t7ui1}%%i`m^^ENo7@6S`q?q~p<=RHPbm5?siU%6k^zoajFN>vCL z9^`+x*Cw>}w}K_#^k8aMH9bFuOwd_z$>l4lUliv@ zpj?%0my#^qA3&w{xon#8K!izSyH=C{?yNk5$7?9x7v1&Dq<1nMCDm<7?}>=SeFOXS z*mzd2RjyqDFlX|3JcL>kx%CUM9IW@17#LN-oP*9aJx8q+^SL~OVs59l!THetavQ*PtX#@O(67h`Yok zBBB>c>eUt3Tg@Sl-l69$d1M9)%F)Yu2p*M^SB+#VaE*xCsA2o+$wrk@c>7bD$e)~~ z{=18(s9h(ro(Cg3tZsW0vd3p8f-ec9V2hg|h9$9MP%w14dD~?A zLCzN*-Ye>X5=$+4DgKMLzs+baC;1*7O|-5QioiZ}ORf#Pw35JR8USoP1Iadf#=Kcd zP#d;${JwPq@#K8xxerfvZ+Dwd>NJ1bNmtS=#P)**3FkM1{lZFws;_&?ob>BvDE$+u z#SNELC#uiwYVM0I3D1P4KR+;c(!v;aVV;>q&StWv15pq(oX$Q~b3)z`3b2t-I%nNp zIFaPD0*ks|U|)@xU3KbwI8M$X|;14xpJ1Hw3=dwKieFOg+`$6P9Sy zDR!WnbUyY63lKLBs^HAp3ma}R;b&mYI>0v`bOk_Qvj6p%|xwiEO zy%_{^_r}!??q2-i2m+9=%F$_#edH{CG#fS^7D3hCpfmWftpHf;=cX7O#4Qy?fZ^t%$@ejb2vnS7Qd0d@P$z+$$Ys5 zx2HIStEH%w`-{Dj+e?_a^?JRR`$(RGVytd|7>4Se3U^551O{Di8RwwvdQqw#etyhV zGSa7iRng25TH5D1A6W6xDb$667FT`71d_O5PNM@oA29QA+P)91CND0G;>|L$;<-tMYpZWx*vS3Qy&2cq;cMWB9q&NjL#>1 zt*$N5vG;vydcA8%X5{gk8R^L1UY`|tq&Ox9j!%0u8mRM&{pJtqPFJEzp0><#u5l>d zvS9e>Ky4O;-Lz`Fx>D33CFIq}k0uY(6i0FBFHX&F z@+Y|y2aHiufiGXUup$lLo~DuC=e(jHv4tD3tquG9VGI@zc}EilFcM3>6{DJCS?)YQ zS%;VD!(zg2P SD79s^m>=4sLnh0E6iEqx1h;;ECgCH6-<+Fw4%X&1a4w5gF|c95 zRK@Tmax|i4Vj@%NO0) zv`I2`%9R8bKyZ5iS?x<4m(6Pecje!Yr@iNU??8#kaeKb%?^=QnWCVQMvo`d80G8Te z&OTb{9?W~bE&f}3pg{&kck1^nrTqHIsF$osln+Y*v2&g$eQ-RQemsXE(9-KIHJR5F zZ_z|AK7L$)3RZ5^qbcZpx4jNF^Xgz!z#8>^Hy-_dOW01gqgnXr5pLZ#Qo2FDP`!#6 z{O@u@JWPb~1RJ;g1k75Q&wI$%^**^2g19-48ZG;^c7>vMGhgMK>(Ity8ld^VQ4wdFlNeQybRJ)J!ie+7Ur z(g1xPYAP?^tfi+5KaA3t3CIl)pcr))9#&m0W_P(1O!ex`eaTQ@FhJl`bECtTFdT;_ zfaU`11f!9WpHM6w9fcSLNM@?;c)U{QeKoq?rfZ+y1Z3qLysAXFG6F|1j7$4|ejyk? zl*y&CRe?&L`=aVRYsEXsdUv5VG%f7M`}?#!5-6=~M5;x#rI8dHclR0oqR+;lYjW!R}E=T2S7(=C!*06sTvkzwYYwefOOmXngZ<>gV z@C`i;58IFT5c%lLv&GRWD2=c-ps)3xt2%Jfyma=R^f=i{^X!0WZ4#z?mCPp8mot~$vUBp~jf=#GUp)zrC+YKLmpeUuTmyH7 zbXML!%`RTnQ_nr-c=odXC@3HK5xl-=()B+akf8-9y%*QEZ@nnDQsq)b*{q#8m9 zM~-h+*|&d0@sSihj)F^7X4E)8FKSzS9LDeNKfKN!y0p3RJcQd_*mKqC{Tndn#krx} zaJz|<@wlW9>Q6)DGZ#ESmy212vmU<959_OFRvy9aK(P0UAc%ZTv^&}Ydk+(}w7eR0 zSE^VBQho3KK)~}2;t47H-!K1ysRQmx7@~Qo>M)hOQQE~J^*rS7a#WIqgt2;Ko^zR&cJqk_izEn(vhE}-d{vD+|Ge~OTsIqdQeOQN~GDS6u z=Ir;CYfj(a#3!R_`_iq}(B{WuP%D6MJTKj8wsr8l?y=6o6x>vbmh^AmV_iLTD6%}+s5pYtiEzj}EZIs%kFVy@~>&8&FS9Vku&FPlZISH z_#BQV)9v>=P#BD`&@O+kY4HLkVeh9N3?F3QTJ}TD%e#qm7Y;xgazR^sA<|5>xTmEU z*6Lv`3QrvYg+GpKcFb7ouHIiocOvrn#I)h#Y)a3nhkv~&%K+U;>$AH1pDqgy>DfUP z_52-;Zupoi-y`dG85QqH^32D=0Qe|^ZJ*Xj#Z6z{@loW4=fOlT zR4?tzNWPKtP`kV=@DS}JDn+jT5-W?86izaCnzm8x&fYp#N9Z)lttL^TVUH7Yt7fFZ z;~v}f5^UW{@A)^*y;ciP@9QiML70tv?&CzeF0wDAfcIO0c^YSHnriYTQ{QF3gLEuk z(lI*wxrOKmXd>WE)@*!R?(I}74Tsc7tJ?b-hp)8eOuEDED{an>zLkbL##SP#k;03_ z!96_vNW02lWhlCzB?_GTG>SDU2YNh{K>pz~7{E{!m$#&^w`q264;Vf?@hNOrq2`iE z*iS*Q2eA#wJ!+ESK;!JY9Z4MJ3u8|2UT&W2Zc94(`S6r)xO&3z3CSn52~c zK7)X`-bc|zKE!bUQ7P#AnLSd((+D_#IA_sNzHsn81p|B)uh&f$Z=G>BixiAqIP6)@ zep;eFgzt2CKKzp9cREN{s4Fjx=<&Jj{l>f>j6GlV#!M!`3=i`1I|1I$0;MdecuIN4 zXR~}^>&@-4QbW&P3CE1Xa1aH79^8oQ55E!Uu2Ah$^iW~Kt92&aQpNe3LcZ!9AqVF3 z?;|I}6!Hi)d{#*5;_dKrqCsl>a71g)hDm7iSgvn0(yw~^b?Lci2K?euU5TFTUzma= z1=aa)V$jIl8+dj+CbVA~zwhbsQG~;26UShm3;DhV-AYwPLPx=HunggG?F9YXO~|Tx zPd7WY-@$40)W=;0<5r04-=Fi-A*^59f$ z#?Q6_A(L_1{^4ZoYizC|L}JqTnhCY5;f#{QEk~ZUV4q6$$dR(y__THvl)=h;PSVRY(w3APwC*ILkCzavxe3Qa;iN>kXWbVjQ6w3j zdsQhOY|@xEy{~(fNk58-(Z&-F$3B^2^Gh-F9_to-WFi%6ilt(23%!h2E09^5R1L17 zMWD4=X|OPIVxp7_yw9I2Q~{lPhpj{cx5XFGBb=kHS%-v-tocC^6213PRX%HCYbcQI z#FMq>bwD=n#?jx{G4H6YykokcA+d@iH|^H+V+S9ZBg}SapP$*q=fa|RFGzvatZY(I zg_@VKxRnt#X9Kh7CA=Dh5umU#{TX-TY21jm@AdJRSVMAUPw!Vj($mculkj;Whc_|! zTD4%;0;|_^pOQUnnwNO!n$B1EI908xxudgV2Xx!~EFqN^99V?5?}1DGh|{yb+<`zz$uijHpz}lOy`Q)Z=+!R zVq{orQ=qF`w6yMvd5nLjI!{C(SL5Wti#usRUPa2QG5pvRc$3>QMW`&oalY2RH8;3QIGA;?{OWQYt%xjcv{OiD< zT13AYP}sGlf7UyM7F>pSP7HJ5I6}+4YE#p33uwh;S5pt+NndAS=;_Vy(a{J{-D9!~ z>_Ol_{W@N({X+B{{4|ThZ%J|)O|>Sr-jnghLxwPQ#Gk1LF^c5QyZ12)p|Jr8;VY)S&rT!|9vm{o8?Q!PChF9flo+aqum}x zQ$5s}h|fGaCXMN_haSgq82$8WoyyCp{^om{qJ=vR{=t`*_kU;%afSCmxobB8qQ2hr zYTBRLU)AVA5c6fMGGEUw2GK&Da+Of=W+9*Z73AL*-lB|`B<#xpRR;wee5NzAj??9I z_?%wEgFSRZOdhJr+GqY*RKrooiS2ESA#Vbr2x|z}wj%`2+=bYJlOJVv#i}II3e0c6 zM0{k26!}%IKU__spmGXa;ZlvkfPt4fPSGZN8ZvO1@HXJAFjloQz$p7@la&gq6>W5T*cavxoNvydVO7}qhx)|y zFaJJ8*=;-Zj~tF3UU9$Bu`$XaN8L&SgNLi<2Pmb*mFzzISlY_1G?K>8Maz9sujz1D zZ_#Rz)(U)eCL=cC^6za=$gLeZfxWj$K@7eJN)z=a?^wK`YHe+WS>iD0PF{5SsyvYz zjQC3L4NzhF{w_o}z}cCf;~Ex+`DuJYQty))_t+NiE{bt z{>+|^`P}cMtQwrKqhI~p#je8MjvW6czYsyN;SWB=*MerC`a_~(0ypF6sq383>pqah z05-W~!(FR=SC*m3Tw%a)s zJcMQuv)G?>)|k7$Xx8r?v2*^JZQ%|ru$=a0h5|qFu95B&a8;x~!i1qh8WK<3+Mmw8 zNbx`LEYL(#Ux<;-qds`2nwh272UYHsh>Lq#wDi0}4e;W70BKK8NqJJzugzs;i>9i3tZVQxMxhtyhpC8H!uK6>O33`i6ps@LD^s=%iTGJF+> ztP@2#6B%d=IL?o~JwSy1D?p59tPe?k0mfyMtWp+6xY%AXwK*>H`#Ls*J$rF_PnSH2x0eS02=A4D?%O*^ zwa3gfi${$wM&3?V6PwUXt$F#zg;-+hwVSxf-1yavx zBoK3QyiA`yKttw7bFh+4Dq5kB&wWmhhSKnY24b^uN1$*yB7H+;zIrobwEV7x|Tu;ptmd2H2(XLNP^L=r?V2+Kfc%} zvBwh#%kwEDhV>sy*R`c85=DOrBnXcpqJSVdy`e-23P}9=+4P;YCUo113dN}tb|}Gz z9xsfR`-HK_LSPf!yfZy_`vc@*FWw*hGu;^HN57vLQdzQkU{8IuOz3Q7Y+l6j3*O%9 zErmoK?9^Wf4877}#2rMUcTS~DzWk(V?*$M=HPuf#$EPVW#eR9N$17|QX0sD6$P&b? z%zohFfzP~JpGhANN@>6(xAP?AfKjBN2RSiGq&|<=76X5P9DKB}iXZPkT#7<*bqz#l zzEbt{*NKu3dEk3r6q|9`eeO=Oz4(X8u2ryB+XZdz2?`V;`OQoA*?fWj;vfWa6zEpy zy>mECM_>(Rx!5BujNr$cqwY4uKrG&{gA{OdXHs*sucRVSA@5%vbPCA(9Vp3eRS!IJ zK2*3j$anTyB9y^dy#UDlKDW=SQ&#DqSavfP1cm+G=1e%`$~+fwtS}wm2R)=Oj5ax& zXX`&5QbA|WSDZuX6`UvYL_7tUr~p*p2^1{os+FcsqOOBH=I7`n-0{Lqx5Gk)Ld$`X zw99<-j#deO6s3YW^&W_pxKZ!Y7v?Sw4!hc7$r`~g@z2R4ek5kWLucX=9(vTPIpG1( z-a#Fm9c3q4lAei?gZ_&6Lg7d?5??8?gcXv;^D@mzpp_d&^^$fiPRBc&hPQ-=i{T!< zAl7>9c)gA6JM7l{o5$6`?5y70nu}vx+smMNm)|$JDqo2C_vkzc((Q18dlbVR^baH~ zJz3uqfMnlK@eiv&IzJ_*E`Ljr^FG((e%~1wX{lc+g*dC(1uEzqS7=u-ZmKbG^x-H~ z`R)0wo0O~!(L0Gr@7j|#iETf}0PI?|dg2A6F9y|KRyDhPJUT5`I8O0yhLY8~Rk%tN z2i>02g?p-R9>PhU`v|;91_ywWHye=kOH(A#>&qm9R;hf$o|aqwsk}>NiZN7(sKy0) zJofO8ar{v?CINrMRnYjSD2;9&@Gfa921(y`7BAmAWezR})+wa=A6*s+^QW1fk7HP~ zg-Qibq_1PIxdaP%=N=u+3D_3W%;D}wZTO@?s{g9~{n3Y@v)~;wa|L0uZ(qD0^WFk& zJ0pZ(>^dI3*9|>4oJA;BU7q$|&!7`G9uJ&oZqS!JK0i@eoV(zD{25R-pvHu_nFq2; zlkNuDPy$cYli3ZB12Pme;U8YEJ)%d8>GyP7M7n^pRV~)yEp6nZG6cx z$p+&}#-`!)iO_NQ6ye!T@By`3$M>hC^uxf_H28ejMH zx$B+_Ir#T?P83j5iS-_?m0&7*%bDrA-lS^3l_D&|K)dOl@{X@TDDm3oN2$Mh-dMt*t(wL|yh2zY$uL3?aA%rzKhJmgHVm|6?+_<|g%o4T3=O09eO8 zrrbG92OYC~NmG=E8jm1&Ls#Iqb-H@Ewf3|6wRBJ(mVHG&PuJo_X46?n3N(-Q<*>?+ z!^2H%n^3pCr*W|#?nn^(YWlIEEhdesyes_ng(pMIs7n90Z`$%20Mk>ruE~`WIM&Y) zdVFwFbSb)(qQ@P6KTr?61EYb{i*ln6^Fe;xZo%p4s#dVxz9M&b-jxrzUJ1zGEqc)3 zKO0g{Tjty2N4+#))b{h()EKsRTf8SD`n3vQnFrbDeBZ`q(mn2N@YQTP1FA!G&<(B7 zZlkKQdk52c%gpN#Tw2Cqae=p?817P`AD-zerdoInxT>u0*JwtsPK8<8^AL?O;5xd>AY3M*3z+f{fo-t=(yIuwFluL#b< zKN-0d^4@$8p3;?$$V;Kj_}q5aaPO;j%pTfk8fR~K%BB-@o0L>}p~A31V!OH0yM593 z_;=6M(Gv;2aO7}~>~L?+YXBKFk{*UQOpNjwCV%pwrFDZ;l5yBA6NJxvmf^zo=g|%~ z&we?;ewd!_%yD6=nD`aPPkwMSNGja6i*vNE+B0t^jHah;fkX;rPZlsm(FV-TMRZ

#4|q+yXNceoIXK5y1<>(&MmO{wgu~TD zH^f}LPrH!6ulb`a6{v3ZwjQ@*sf6Ak)DFJZIQ#us-VO51fXz1YAqd(rE~o_j#PiJ~ zKuaDLjR4_*DDvDLHY1G%gHlsaO#G~lq6UoL{*;=%5jIo;>Q-e-02*T9ablm(Zi$`e z5;~DxHl6(q!^%beR|_%t5pLfcW~AFIm~Cx&4iDXPfRtwebsOC?(>8`A-hCeo{Cr{T zdI;(d=DHDO@!WTI%ys&Vc^0p|d?vm0`t(UC7+3oRxkyd-#my~D4e{Nv4JdN)n-QN> zikOX&>^`kq|LkatXaoD7Z{`s*yk2~B*;D@&_Ci?w% zVY`?7(NP)WfY5F37nIx)Ueu5Fa!{{@|7+jhtB-#3cnIe%Z>R&_ z3a%X1RpbkltU{-Rw7+Y{os<37My}=An9H}S{oF~`AVpFZ#)0dTiI5I0Nl+Gg@ew#%=U^U<@Sq%2z7)){@qH^0qWna;W0g`2Ed` zsXwyZVOXFzet@7hPr=XiRWQYqy-olZatkdJV_^p$6i<5wvcA#Nee7FGyD_PujreJs zuF{9uSJL%VRf7+M8V3B9BO{J5oGtKVfp3WV`h<4eo;Ud6_InD>Ju!H4r~UsCxsF+_ zooDcv^%>oL`dyfO%N&mFC=cWsQ)6jAUSV}|`R7QFn|Hf^A#bUGkx=!CoUj$)TQZLQ zu!J+ihbhgnX#d`WvmpQ2Z`6&YmT%l+6@Ok|^C$K_u6$!FFnBR(k zN{wV8U*k^=P0AlL?BPbz$}qqGL7y1vNwg~rM^}A8jH8(JkXPX~caPn2gEYV= ze>%(fYtA^Xd|ZEfJOB|SjOQm{ock3~-gId1AJw97OgjX(&P~6v?dcu^zm?wZgyPT` zSBSsfza-xz!R2e{RV)-(1N>1^ZoZ*S~wZF86b3SjU!?023!k*et zeb@KpG}rbY$jxbf>p~On;zhV3H~!)ArNyO;qE8k0Ml#V^3U!Nhy_&4aE3xmfSvh&V z-#4iVVcr^1Zyktw zPZD3Pbsn5Tt>5Ur!ndY_1{0!TX0}Ll=NT1*3oS))syDr&Dza$HD;&yc|FpFu2-!)0 znJ%aO#7H*zj+Vpah6!mo{XUBrsp*(4gBQ~K=kB1eT-i@Ki4lIsn`nHWFKb`8RCC2R zgoi?sR^8>(#}2}2P5UG4yv6emucRoLk5Ri?M=qzTHV4P^>!D}jjXR@JkpE{-TINmnyA#ZN zcZg45rdJCzIm?h2ir^V14rgZ4zQo~rW=y!ukKtxpq3c{bO% z2e!?g(&Ha37{>Dv^|9xC`}Y0|imLQK2iw0{&uR@$qYjd++^gg}ZDh20zsydYtyf9s*iy zGyQ9sN&IHtFK#M$=v68Yk#y79Wxl@}s<1F1Z(JyD!RN)foX$R5Zy!n?HUD?e`7{Bc z@S;F%v^k#ri?MR8MAPjtpesOstd>NxO85J7pjK?G!fNCj1UJ?r_CX$!>qF23r$dY1 zd3q5G3@5jwO62+z8OJ=CnM z7);Cuv1e+RFpn*EebGY^ud~h0&&O4X_NstNG;^KMr=Q?S=QyFcm!r}zC%+2(fe)6c z8c^dHT7P}PEe4DhjJ9DmTR=u{-%Ii2kv|>5UB*vwt>|A8YfFOJC`0{DY#;dJ1tjSl zH;i;%et#aFf#b%ycY6jdzjQ7UZHT6oj;Qq^^VOPG5bC=^jg zg4dW>6?+9Pl_6-(*+%rWdy(z0p66(TUN{MUcZ14$;1is(Rq=-Dm-1XwXS9`0{na}t zD`YgAO-|04^vrt%)IFvM>1N=6!<1?umUrZyi#_)Vj;IBfLo33LiJC*Wv*Yo5R=1tk zg_9`xY;lh*kYpBJh#G;Nh`YT4g-G@n3_--~lY%|#@jx{PL;HUCqTJ7BdeF}=U6txV zyE6E!HN6|BND6j&;ZIae;4dhPE@~bQu6eX+!xO(sef_;|=_!%^l8_{Hr3zvl-^Vd% z9t%%HpVH&vP<@bRUX-571Z7G3z2qSCYditpj^OA{Jb1lFyk5f0_HaWHOVS$0n}_bc z27Z+xwM)g37=gCKb5w28&26)4;%80d&%6kFecM&NDu~=j*PPyxZh)`dAFnXGY~OE0 z{**s}XMrUFk^~jO%QXPHdcxrzadrjsA3u?2WBR+V2dPM33!NoL6bzUCJ6)zP2|<>l zs+79nrjNH2KFc$a+20ZJOKP~LcOOG>7RDmMh)B;hk@#`JgLqSrX8zaxp)Ba|p0zK{ zKctp@z74oO+DQ!6GVoPRZ|b^=2HHI4z%=e5S>U0Mah*Qp^+DcU!F>!ogfpV3FxULS zI`h?G&yF%+v5PUfQ(ix5y+0(N!%)d9o))k@kINurYskc}K=hqo!QO0~&qx(~wyRI` zmJa7v7)evTW{v>jglcgrB-DO)u4twTF$gN}Z4FV>jLnx59MFb6jSNJoze)xBt_fpiJ?3 ziyq7Ko7!7O(R~$SxWGToHF7P9D*1SC)tLCX6d!FM$9L*B#zmiQxnV|*(d=P zsa^|teBUz`at%5Jfnvf@@N5u0#az5yjdL4}W@C04S3-c-hcBCEmVt=?XZ7oM{RmGk z&A{V6FN)jksiB~Kk8{|V#m4o=9Mw!ZVjhzBbEXjcu6~SDb8?hR*?@Tn?B3<^>Bzm8 zCLPARbAMwtl?ID-4Zgl#pY-_A*7E^_Ul{|8y`N`~PwDAz(eLrRJl+fTqM`=b3joY2 zD8$*BRli2L#4>*xg`WGkK7_Yw0qxPYJ%7S?wBreSZGdPP_Mh4hXf@(9lOO5uCs z?IM!`$(PsnP^IJW^uK@9=}~`htg09{jEv0kzR&QbmJ}_H>0&0?gYEw1UMEd@HU7sb z4(arX+#*solu1e-^<4`| zmh7onKL%mPFS{v}Q6aUQ%+}$$BUu3fhNJfV4B7mn@N)*9>8@Zi1WvjrieipA1~@P} zsJA=0cK&6u<Y+)d9#(fkg`VhSigT}c28sZ(=4)DPErA~` zz%}LT_B!ro(bUo^4I~#{SAD>sF1#bdlrjVZp(=C>lkmrVg(ukX-DAbArUlazGk!Co z`MA+u*4e&v(Uc&2wZ(F~zW05-KEi%M2O5Z4rTgJ0@j@QaY+g~+3H!CFg{RzpQG*Q4 zkmK`bp5=)>pORv}qkoyCu7y-Nvc7H-mqW)s`>*nT`VRHbocdKwDoOZ$=n7z~RP*L! z0x?s}9m0$cC4K|*7vq9wW7hwUsAiyTUw`xvcU06k6{HtCZnyx1oa)cyntuC87glV`Q?5UrCS_t>X<4zBfq3Sdr z6X+QDmOEcY;i1sAt<%>NR+Ys1Pm9O{@z>@1?yDcx^|R19(Zyl*xsZcc`X>;Zjbbk= z7(M+y52B}Ev!j0eoibt-1k6Za@2B_o;s_Bm_6a4Ffw)?)V1W3`T0DQM5y9mV$_`=A zlLwh(Ec^W>zKq>^`S5ujYOYuG%J~+8A@ItB+?OEUOp6=bRcZ{Uy~{#CYC{|#gc^-C z(h%V-FXm(02nQ-9cHuk=uu`Z1{SjimGUK^{SmnhMigY-s0NVO_#& zcCt^gk~hAHGw{a!>0O%q;K-X(8Z?eXTqtz*#AnT1k4UCeJJqZDrF4$I3W<-J{r>(I zrC*|g5TLMEJlgXWks2RdcvbPjG!eZzc@l? z&ik!i$R0~TeyG-8mp6KgJ(~wsxe!07sQ$tuSVq3X@Go@U^?&8A)VnN{B`5uJxUHk` zQK$D8a6tm{4uqGrw~Unc%UMx~^|GACw|byvnsz&5{_H6&H(n!$D_=r0ou0`5RI^Fh z*V6tq?&%5SV6dZnm?DsH($gQ8H0WEzCShtHB8;hf>w03zq_Vg5J)La{3c$1Ec{)u# zyAZgHkEZEkn-}1Wlx}^rfh|zX+aLNp-VBj30b^}W{b|2u1!`7GJ)y09<5=DG&lB>F z0||-QcxB-4LP6D;r=)&>WVjlVkSL zSooVGwBRmspJeGDSEDT3Se!&Iw}glAAZAb>UYu_o6B;(Z=Sj>CB99IHZ)DHDPjEH# z^^#}L=Sz6%A0ZKEn7+9_C$GRO`IJ{l@uI6+7I; z{m;#6ERPd5d(8jFp>vVtW_Rgk?zs`(M5j15;`}#07@*sA2x^`E z0Z2#vL3_!o(c0Q;JXon&7hA4zPOKXS^tm4^ zqFx56jL4qfS$Bv)to0-=eq1^G9%gU-ji@QKS42PQ>pxFTR8i2vV<*OuO<)KIJZ_25 zVuMB?RFIzKrsOsj#|Gcgu*%pEdSM7K$sN!v4=t7J-cY5aB9l?gi}j0xla==;`|wsD z6KfuSPs#U{S(Ax*$tN|oF4+*hq+O`uz~f9zhu^Ajc_)Xk(|=#zCXXhe{%g366NAJ|^>*3kTed*t^+M4SGYI-31b6z4!aP1%Qs@ zvPss`zU>`exW|?TV$~D$#jIkAWWc>g$f`q)m;D1}KK!NaDEiG~*pKH%*b||3KAwSo ze>va%j`!E%O06Hxs#JDFZ=fLfm_u4A)CuXX`$g7*u|cD4m3^m4t^T_uKI+WXq5xU~ z!H?N*@&p!m$>RaTD8cTj>xZgm2SXZ%co1jq;4Vr4)6p_|UQSHw{Z8{|YhTv~%>1HL zLDX+AfNcq>8m(p@uq4BUVW~)l{D$Ut=C~%uclBA3u}`DdiQ=Q$M2%()+NzW;z3SIr zf-cgZz0h*usfj5545kZy=tslDr&Cv@%Njn+8XFob1oO9AOrWN+Q!s%}FFkVd4EX{^ z-_wjk{=4X6ZWc4ltg)^@6C=VWy^GunWh3v&c$6us?z4W5z6gHp0~-(%t{q`BJ`Vy! z$jc*~Vs*Tq2DJ_5UK;4^*U|dmcFT$Fdyf@HO}MdLB$RX$hwKgz*eGd-q!yrYGYNM)Y7s$32+TQhbOn zzH|EdhhL4u0KytR7V2<`G5>|*d;KF${Yd{|7oLKgD-Y^pF(|b5&AC#QeQ`Ww?ng7V zv~NlV=7)kJj-%4k<<$1A3k7x+*1==xf}pdf^w($V_0f(Z#9`*sakh-yqTw>8eU{M=Db;wHJAbTgFOO|j>)l|4Xrq7r{80K{2BgoKI z%oYq8t7WgC{7U!T<49PcbUZ?yaM@F=IC?iRwV$Yyd1Jaso^o7a301?M4t*uQEWp^~ zt2}nXlKH!ZxCE-JZx7}@pAvQkLHO;pNjk+`v-cU>6GuFuU=-z`-^p>-lbtI1zl-@i z7<6S0$mm{i5bYix(l^GSizzhlUXv$x@Ld)@!(X6n502QrXh$Pn-pwtBFpZK;@!PEj zl01J{du&FJC_Qa6X0Y9}pX2+4%ulj0QB>3l`nj;P4|WDocw+hs?jB(h>MvOw)eK%TYWzcE@xC=OskNyzo1Z7_FDfE9 z`+DPSzdr!la0AxK&cCV4RUQaZ(!2WEp8_=_P(RJ%%b%#F{M{%`=W-;uLwI*^t z5&2kI@aNup4UY?{J?_z;SQI#;{dcs(&%5yIMI%qQ_icW^v4fth?E1SIuO1br)TJ+N zw?$ZDB9(Y*nX9mvmk0eoR(xN%`d0kpa|MX2MJy_yyv_ z-z9bX9FC@ObBlI>;H7kuInRJML3v@HTyMnf>mv0yboOh zs|<_3Ax9F(iykxY5I6>y9Tms(GTtTPb#9IszN=7+JTzKh>v+BCw+m7AHpP=H`RP*{ zRRzps&j#UG(6kJI?BHPVmBC-{avpGtM5@|CbpCJNeyI&ORewVLxgJ6#uO5xZTS;Dn zB14FmTK-2q#6pYiP`$7>nTrmq5x+t2@!?7|Qo=??zPZKTh zjJLYqE=G3im0Dyl565@EogVK~RziPb0&ZI|o^XUFzq5r=%A?!JXM&d+Z`)Ghi`Z@V zQ;yNKmDpR-vZg*&?7k88diOPU6M9KxCvAH&E;J=C!LiVq_Y$Jmp!Y@VpRH!^D1EAc z4@iY*$f?eJX6WQk8rpb5K54)q{#ZE@83L*`BXO)ecof*N+EqWH{j$gRQex3x$iuDtHKp>Dc<9TtGI=jSI=c6V8E;h<`5%!AKi0fgxci2Ke^&n>>t;h0<+2<- zR+J#Rf!vKH?tA?6F4yx*dBXjUOzkhU1;(-2tG08(Oh$S8t`$hs0-QKqN(DHzx_VD1 zTTu3`N-K^V@A{pM;$EoX6T|9}^#gXvi*OzV#$B~gI;Sb9{&y>M_{|j_Dko`q`eZn% zOIkWy+?VM+9(Q(jzr?lO?^Nln1Fm*eyvR18xIFSp@M$M}Bx#fN;H0GADvPA@abfUK zu&)HCj4uEM<3P4p~xO!I67ok}GfZnlNG3^8QBflh!{p{dglq|yJvVTQ9`hw~b0?KXtzDa-1izTX})|B2&!ud(Qk3HJ*j>EDK6(vm(AhN zDu3SJv+3TIJ*f4^KLvIt+@rxX{=o{*%LjgxW5*u&j@q_`Wp^Bqa3rLhSf_`#T{jkB zZogKEIJ(mzz>Kfj-)|$)2k0fs^H)7xyex%IkA?XC8oNCNMe$vI|M)d4_@m0v8kM3J zff_}lm!c_A-ozf9Q)xh8<^u1xE011m?DLPVql;&m#OX}x=kd;eyeEXGCFXiw|6szy zfrja31AbytlM<2O<;zQ;I`VV= z6Acw;d%2X`-nEie(Siwswy(PLnk2Yiq+83#msH>olD_wsk&si>gwRIKQ%*#?8Q!CW zG9m*rL;c6y*57TgS4!bka09Z>k3N|*@@-k9KVXjXc`(bLWN=8Bs|==fO;zTJ#^ch} z?NAms&Zb1Xx6s3H8vj#r<3Q$zAl`#eaB$$k8MB#tB(J9j%rMS`xBB>tOg_H}vT7kw z{lsBpbjG)Z*z+!|FX$G%9LANrnoeU_$lTi_xd`Osf6YVi#O159?HCJs-2U`w*_gAv zudlCg2(_#q*wba+H9wrtq$tf|zX!Cl8MSYAJbwa1H{}AOk*2U+?dp9|SV-6Q z`*C<+N4*m2r$9%c539#gTB)7(;CRJa6Lnw|0Vw0o6(YFM+JGc^l2iM}IM65L<R{{d1ouj;GfnmKbWyymzhT!~7VLQ4y%plX} z5n@12uf9eAF0wAaE=K%Lk1~;E`&WI`u#55rqc6#g`6$iF<4w$F>F2&czD5?Bxw)Stw{;^?mR@I|X)q6;qxl@|4;MLQA@SNg8 zHdk5nB*AFHF!pQjYx4$&HxjIP?+1M`-&D((1TO0pxgJ#PNWHPFs@#I=X?`+myL1*% zR^Ns4A`ybR)j%e~6&R9mZvhDl`6B-ebYT2IFyFDfH#v{am1B)&b}l^8B-%|QkE90A z?H49!?_>NPx=WfJeHa65Vc%r8WdA(vdlYWteZux4G*`9m`}3>yjG2SD);v_MaJ>D$ z)e6zA75t;Gn%~SZdS%}h;?onbg~NA2h&~S@`h}MBiWTf^ z?~^or-;IvNT3g*6KqeXUqDDd5Wi0FpET@F&Lby zV4JX8pI7btB_-KCd*;!iseOYtFVgm02>sinihJ4P*0%48pJF>?65;qCD>;o*ToAE( zW5K_@sRP=m=A$I-YHrqt=qc!OKxojhdY|gd)0v#^ntH@Nf5Frx-}>io>tPGZx0GZ- z1>kV4NoNQKG&mI1EM6RFb;Z)W9~?+4Rj)#)c6$?_Wn2{jrR zWu2v7Q zvx6kkS)141aH;iP#Q$#eV_KTUNT#ove9ZiVPN4?o;RASTUY+1M(uv4Yac%$#j&2>u z((0?=GM*Ubf|~n>|C#fmJ)a@+6}4;f=ZcdR%;fNi2bUeNTz0TP6($uNFFb zUUbHjEk9ibcYf=O>8ael7#LU!p^XEb(Zl3P@{?);U>gFY33+g@&W;r2F|`uhO1=EXp|1V`Z#P6oE&PhV=xg83S4zPun=MsX~9Z8~X}iYcwX& z-xf5T`1?lJ;}3M#&jfC@mAI3S(JAKzPpw8uFNxW+hFoko|3Qp7pZl=%U4DztpQ4Rd z6a>&T`W(iN@r$;yuLr+gew$Zj@t$k=@s7_2&e$3ZN+9v0wY+{uQF^oJ7a%2Br>UfG zvip9v8tz{~bdxvR63qL@<|>>aAf&~CTRM=yfOKJfW@S14aIsz6iz0)On|-22XPBpH zdUhS-`0X`gv2X&DHp4D$zwjT{R^E#hQrd&%yPH~N_yScC!7JjjR?|9vmU@KCRPi+? zns8P3>wacFbo#0t_dc2~&*e20f;w@8Y+SBtU%p?L1=-qdjc;HEEr5{Btt`Q-6%-jc zm1zT10Y=K`y22Y2OC3v>Mo%=Klvix z&>)Gf74^Jh26d~ri~Z^~50^ubBS<|SgI^|t+;;h!CihJWp`Q0Ri_(v4;6(a`Of-9h zmNKu7Mxq}Y%+~e}f!{Bwef2APogi#2qT^IxlFCb)3(YV~nb+nGZjZG(3^dyHDSnPc z%DmExcj$ttXjY_TF&=2e?8~T+pgHa_hH5(i29wD+Ef0GJgBnUJNA< zwQ;%ePg$wnDWoLIJk)W|oPO2wb z%=D}Or1w|*qY#o_<;1I=eYKdC?|X1BZz)6#ZucSIylw(JG`K9EP>X{PjLYWVtBcr! ze0e9`iF=>MJ?f|O5U~5Xz8m<@mQ2tj`sbB|Uq$1ccug~$p#|{L38TIY8`E>z_V&vI z%k+2un*qAeV!l)lx4Eg*1FpnSgcJ5x{ZZ}p#QfGaKI0mlRLVv@CGi9oDseOy9PZXSa zl%M^LV?p~x8*4!C%Bdd6!?o&-Akk+RiI_7?VGKBN9TVsE9oY3jxozV#y9JC8tW5fW zd==qw!+RPUc;L+1~=nyMc$(?d`Dg!+~Pa8&u@ zHQPOCkC&;Kfz{JN9i|S0iIf^I$JOQD?%{Ywxi&Dkb3vY8u*&+Tlh&I%Bz?RtPMG)gl(K?Gvm(c7k@G7N3-Di<41KBSpLGV|ER zn=Y+#Ts4%!d@}w;NY88I((8$qmans+b#m$V5Y-iS#6NmeAA(^uY-WV6ZM`Ccv?J|zs?S49DJ*(d^jeNfefS2tilOAoCiYDCN*JI( z)Nh@!?|e&Ac=r_G%HqXWpEOZn%9BKacTc7qIuU`W?ZM#Ccj{(p3)RYL4!eVe z&O8jR>-lzMi{Q!EGSebSf;=o>K|t7x;Ou_-m?~f)^0l}V(7~5||A&2X!mWFF)f6kf zrrkt;Z+N^l;6lEJNti`&4ALuC=hQx);7L$`Pj>jthD3APof z7<};PR~lUEQsC;@eGvzhUR*^B&*!q_b!CNGV;ht^)OP` zL4p1^C+W9NzU%td!~&`(^^Jvp&rKwQHhEJ#Z$!pV*T4%~i1ga-csxltM)TZ{=8C3Q zkw1AZuNQ;Y!9koW47STX+ESc1yD^d+_x_|a1SKGkE$f`-pgf9rO?c>fzZ=zG&BWPIN9xpP10Z1&`eXkp<(u!}Fl|g#t)~#f zcJ;}j{8|>2w~hRgM`c{EwGsCBl51N+H8Q3ZlC(bO&&^of}mOh#+{t%4P zL!>bq?BDHm?|nV|M#UecgMsx2ncOvEfQ+Gyp*5)!9Cbe4{9wPi@(ElX^+1&SnMcAV zjDeWAQtgUHa5$BmHiH4%tDG|Rr6^UJ-^RBoDzhT zI&J*%oJaO*k0hzF;7eYME1>k(GP?&o&$i@3p0uR_r#W}O6(~0m6KL1w#12NXp&xh^ z72&Nq{_CKOSFV(^@19kL4sM+7=g*s-L3EI>rZLk`)lFcJi)mk9#Nk)s4w6D!S4!sv zN2=-vQ$Q-0>H5{2{8yMNk#nTD-V%nPHm|EOp}!b1)S6 znGWSgbWea!P&kvAKHxW>S?H|+0KFX#`BfAUY;ik;`ZzM$ed!fg=VrEYen|}aBQ%Mm z`TIFOUY!;3rmRQLD}TA$)_49we3yW@vXY$++14;qVbj|K#zxB5IGrFuMz{9M&%N{e zc3ccY_bggW>$kb5YOM3J>uY$*YydiM&DEP{E^qcmk<+msad$tL{3QYnXTUNPgyB;3 z#Gd6Z8PFtFK+a+hLHjoRh1Lmj|KQ7CmMnu`GcoNin2TDB&s#(b!wwsf(6JS`1W21zz_&w2~WdBW}mtxCKVecD|1R9GC z08rb_5!t?CoMUM?UWJS^jq!+H3l*!;riILO+`wkZa- zfJQA?(&1WNEi>;PI$mnGkv82p@0MnNbC-oX%6PQ}Q6ReYgJ;CUOKU=yu-=i5{S6W? z-C$vYzGb72C)yu8_6fMt1()I%_u?xPWptPeIEQfjlL)ALo_R}}|Ff~$aq#Y@|n$F{XvD|iR_o$g4;`Yof z(sgH5OMYGN+#vy4a)tW%_aCihjtVg@Ttiaij z(3(-^wiRYAt0UhP4u#yGc7znCE%Cq?gz9JAbSj#j$?2Q<=4|h^;e39XMaTeOvu|2j zje1(;bx>fq4Zj!HeMM!12}Kp+w1({qnV|nTyi&2~U(H^l32`GUlS`S0W_zXgyIjNvN@&OwGJtY2i?aB}0sg&qNRn3$+ z+HWyD_79jh;L*C`h`T;FV{$RyrnI2vb%NsXd}Z#x8BU`=t38_HMrfJ6Z%k--GxgdB z&+Er{s+vOLbMAdy!CW8CVWw15rMY-GgQLBAH6`8``b$$tOa(z}y4$s=;157|5Eh;w zf2H%Ld1Pw;T6oxs9ZrY;GFom3we_y5x4PAFh#J2>l0#ka+rr(s$pK_J~$Y{J7Eg z7y@B1F@%x=#h!!11}$2Db;A$mNeUC~u@{>9e)>4>+c@~_wGDZY{d2gz#)ZitS)xnJ z_k)%y`d*KoQ7V0kVYy4f$z*6m1vc3CsLdlSF4s2lBm>YqyGgLxM z?q4snH16haT6TsUz$HETfBYxZQsJ5K8D}~0rc<-F*R@Q+wHtUk1=l+YUI}62PpCj1 z_{P1%I6saYMCkgbR()^05}P%T##iF8ZdZEL`KhFsXwQ&=_N7;v722LB)hK%{`Fx<Tv0RK%`zE2u|n zjt+($?twVmbGT+{a>!qP7AVPXsk z+oyQ_yb?m*iCYZS<|o51p88;*_Z6j%v%lA2nw#cT+!wpP+=F~QHRvDUTUgvY3Df(n zUzzmQ|2osB=(tIp^ZT&`&@>C@>hQ2;@!EqJ_}Y7LdS-BJ3a2D>-_pz8hThE{ z#NA`nqf;L&uNyiv5R##Vs!HI(YQDMDUs=*`U*e&NkA zA`|P6hR3%7e|&XP8`|>q&ZWwQgH<)=g&OW`fxTTp!LfzgAZUk>a%JT%oNjgT<*|GC zWnyHtPz~`%&|s>bk538+N)lq^+zcZ~9w7P6TZNPKKwG)Xp7gEGTyKlz;N!hN@Awm7 zr$QfkrX^pj^5L`;I+b4h%co`K%{cEN4o_g<5^cV*L$n}^mUomC(s7Ducr5>haov|r zPJYb(BAg!fAP%B-2)ydP?RoK!Dd?g7!-7@E%c=&40%DzqZU(rq0ZmZIwVSMG)fBsl z1~b59K0{6@6!`;pvAWEHwq}vvsH}O?(5E!?H_NPh2%HBo0mXV-MinYq^^;b5UH@gZohdw5;M+lDhP7Qc$eJXC_F(Bh7i)$9Oq%!h>s$m+Nk7SSH zO>%<4fjpqYb$YTvZlKvWLx89E^L2O!oa(9{{U!ZJ(s`|^ssvH^mB`@|M1mwm@|_4M zAP7hhpMEc9pKs30Yy&ddbXQl^`q%wbU)2Y5^Sg%uM}Y7t6zvfm8D;aQz=D<9m;gkR zyMChu@p%OGAp}DPJV5if=+t%qW?SNicemQt{bY&D#6*meT7CRr7@1?g*QlH}_cG(o z6aVVJ)Z@BeuXOt5Hc>e_3$vzMVZ!-k+JlSU?kemXQ2qF1$KTm2$ARR{q7glZYR=yq zHnWd?9mnz1ei)>7#4pe`IP}$9t&-`!$p2oA1y)02q)2&NPj>@Qe3wiBX*L9|jEd0b z)`whNW&3167Xxick_-C@R<;ReppUCRLrx4cnocaU@D+BC_Jrpo#U)5_M&J{V7VrId z`yMz@1JAV84dobfWVWUZrFORNdic_-U zZ{BYQDXO}pIo<%~v8iCRAP9psIev0QK}i`>L_t+%0eM% zKOxK0C>lt6-fk~WQ1;U@t>+8=+vz(?oc>_~o6IxnJN=+!dtTzsl^AgiX)#bgJ^+{T z1GFj^fW>Y9Xz92=1Kiat5u6k&1l+%~xd_(Uhj^#taK7B<1a?k8Mowxeu9px@?@9sQ zYQ8qw;?no;Pu~oEbkaIGmO9OsITZH9aXUDBAc#F84pS-TFCzb(wePzaOQqfKYfYQ) z@H8eNq?^c6QzJOVR`1nDr#a0NsHfdigQiZy9WXBKPsV!Z)CMxLC8V zm?_o5=PU;*jH!$ZDo69i3$y}z==F{1jKg`~z16pKkD4of!@G#7{XU%+*w7{&xMJ4( z5f5@dG$<5(n`2>tx)$uQ`#v0o%fz}w>D>nZS>CN%o5b8Zs8;=L&}{8-0Qp~FR;)++ z0@j~ZS)nAw8gAr#0A>6F8NusV^9SM`3RdzvBT~cT>~;H8Cnt+5>x~9cZPSa}Gim12 z9$6^46p66-(97qGCC|t2*6N#jtoD`D%5lYNGjx17y^M~C$Ce)PYs9}6v%5XM_MYQ~ zUfg(k3gns+lGmrBYh0f1ThJ*4fK7+tdre|IXPfp#6<}W{ z*FJ@2<%7+l$hsPHL}y|tRJqJHz_!w z77qau1N*aoq;}=qz2nytr(>3plZQ$X^N%!+-nFD ze2am4{{8%s!u2X&Az(cQE7BDBR8~lxOc`IM121f8b>H zzLM@J-lY$YZDpOuB0oEPPoMkHE@cuBmTrgGHdNSAqzhnIY?I$E(=Qg>2np!NyGT*| z?k%M;|E@1%>I?u^V*>7tjGgc-6_VO}#aZ7d9G9d^v~-Hi~4`ITwEm&Tuk~ zj_Yww@g7c1yv#cKzN?BE7;0YgHpsum@)i4UchAkaXF_Ge^rF(I18i-69)~X1=Mm#Y zJ*5-rG}Ns`2lHLIyC*>yf6`*X{j1&7tNRti@75f+r>%N4m)7so5=KD%SK0D1V; z+p}gy@$0{B0$xQXHxz~O6QG@1k?Ish*JfV@QHHx*nwJ1yzc+=hzEpmb zw|y#0YZl+%UtmaB2hl+$JquF)j{Aoi6R^OO_uL!4T%A|>RF}4uPu^pceBXPz4A;Br z#Ot+ULYN6ZBE3?Xd+9iEdHnXabzbK_J1{i|DEF8DHE`GB&)u8sUICVbjYb28Q|%Z^{Fx?QGfBd(}(BRESTes6o)(7;#|>yzoiHBj^0Y@=`=mi6y;}RPUFIc zyYXdlXMMa4!C4d(^5jZ~N+jOZ-@JNWj|Xt+8;ggjCCxFqQiN*z>|(bGGnv5@q#nqk z+4e{RJ@EK$-mFBD?uYBl?r-*c(SqZziyzDK$%mRw;G~9}I&dYYgel?4aY=gRZR0alZ&6xaZs(<{Df)NcPpWw$p>OlU+TT8v=1E1~5RJ3M2`W%{ z!WTnwd)zMAOAsX&1pSrba-V)xV@BpJ>MKR(?=Xn0T)f#=peF?QPbd=Mcv=9p0^oV2jSo7cH zWaPU~dNzee%oNK;Rfbe3rVh+NEmTObN=lrzzkz8Tco2bSF)%XgpZsd$qu zifFPCYfP@?$|7`;gL_m|TCOV1X5sCR~Trxn%(JtjvuGM>ATW-RQ>V)_V`3VfZq-1}6?SqwHOn(kdxGlPMN zx~{RqP!3Li)tG5f`6FI&HXn8`U)lI7;-K>?&f&SPvHAkYkDw$|PM`lBTI7I6v&>}2 zB2eGZxAGWWc!qWaVe%?&9tarbQSTvAOAZ?>n_CgY|G}_}qh{J@+0cNPYI4l=>U=7l z-`z$!6tB{|)k45brf>8nI%lu`lsniER!xV6KrZ!(Xx%$gz#4r|%=$pOCGeYl5c_x` z5TB|7@qWq4J{?2erF?Ec5eGhl~ zya&sw!mM09zw5QH#qYqK_79dm&+LlpP>$eJ{U=Xn->|BM8JAUOBGa+V3Qc5MfeDnO zvq?P@k}%5(Gk;F0*!7^8jEa8Ic zT6Sf93-_KG{`gR$_FmRU?yftm7r_g#s)z?FB%H6JYx}^W4-}1N36TyH+vaO=uRHEA zm;k#g0BhLaK-Y|9ZVrislB<2-aNNisUQk1znH9Fu2?Vkl(l4?Bp94g<7I0AD$==5( zGe5p?0Hf{Fz#s2VIWvVY7`mZk;9^J~6qAA98w&T_l0I(Dx9@yH*{?f%InxUs)h?U( z*lM*j=}@g5?o60dJr%G{#3MepJMSU~nzD~8L@ z_ma=I=YnLb>SjTcn`nBWy8{D3rmB2#0S9q;`68~er#QVT-TDGSTaat9xy_MT>TmK_xXW+6-Twvk!p76G8;(>?4}{c%GD@)MIux<^=&Zsu-5?!iXJPS)KP zI{h(=P_qwGLt_!urQfgee}5u^3$7mmBmCW6>n30=(|;V+XI0IJt=rzN@_kIyIMhLE zTH}~<47Q5F@@~ocR5VKh+~PB?(}ETyuAS~`=STa@alYQ{;(T$ty>+V?;rv6@mPxp+$mYM8{LJO$Df> zuYF!ZL&_DLlIQKv7oqS#!?Rqj^+vKCG>`^;Z2D$d(iLU{6GZh}_>p1Ll5lQcNaC%x zk1l5tZ`cwl-%EF2kH$%It#&Ma%Juvnk-2i8`d^(r~jv%lXOc}FZc8y2gl{R+kD9* zF1!7svTr&qa#|s-59?eC-?9mB_7ZAR+NGriQr7rm4t0%5TYZqi85&>;9$TgIollRd z$|k$gg?$9M8us>1;x}t}QZK+zsoa$%7OqE~?RwMkc z3;}iH)Z%_TQwB4iG+#~-JaRZaB%PVxGnE+M6LX|V-Th)?t_ciIJ`wzgmSk;VVxq6-8dW%4{=D&!cPFLxMY5s7F@;>gPT>TA7Zh+L_w{J42%sT$i?!sezl*)#!woc)Tt3}%Ld8s$#2cNIl zdi`q0p`RhbO7-x>OJV6l+y`db{(JbGk6-eX>BZo3tp-W|VNL&N_UApK9Pf_(g>k`B zY3(!C-b*Q2-FU&)8d4ykxrXPbb#Igl49EW<7J2dO*ReA&Gs$q9M>CzwiP{6W&*WHJ z_uGYa*3b7BCQ;7|mrU3^-8EsJEH1HF%2wsmdW-?e`#K=%q7n6tO|krWBh?k4ghHLqgeXxzl(ER4qD2#Q zhUR%65c@gqLrLte@Ie~FU&xzhWqrlvt1A1}yJPN?krqw9-hn4S58q;<_)lZ%R$~3p zy2B$2!7k_atcx;w?s)%H5@QQA{bo9aaem3G(dow_a$^_F8|4i}R z>AO*F2#hiKMj_vlZ=|(W6^O)A*)sOhVq8r1p=XcXNWB)z2m+R+HG8iK2 z=7anZzsq?4tJgn6gZj5WV||^gc7|dk+vn4tOAz0#)S$o8ul)hNaTN1SoHujWvu9;y zzTP&?zEaq_YYl56h)&E8x*)k8VmmA0Ezw@i?fanRs$?BnVOFj$bb?gp!j$F*NY&=@z*Cc`juW71sE1mU#iD zgp>7BHDX|s2Mxox{SQ&Iq`og7vsES<)a@~Q?)_7E)|ZcG&VJhu?%wAMaf3FM(gq6j zJ~9X*lbb?4yedam8ZRfeNpG2TdEYPGOHO@X*z!z9kLpu-0q|VS8S!{u1rXI~=XZM! zvw-F$3xiz#)qTHZBAm}LhGcyS4tYWeT(r+^t5tVZ_2z%(U0YWA z1SVYvn!b=+Is7y=Y6w@cv^&aW<#D+zKSKkm$@t*XyD2Z2%B^t2(Dgg4%5gZB_Bb|5 z$o5nGzV+4ETM}|^{PNbX`|#Baq@QlwI^URDE1jZ(+20xyd^4|w6cWFqGYkIekMU?a zWxU=e>JC#}9QXpw(UPOfuvL05&N!7WUvqR@s*CqCl6-&d+`J+(VWY#<`q9A^C^U$w zq?}Yy$X*Url&K~RLC6e>6rwmfSqIAS)qJQS^DN66DOvV7#hv0YQi-E&7%TqK(Y=B{ zbH2?80E#JATXx+Y$uNS5%H)t12~PR3`rVUo<|P(&u)wM2`-L|~n?Wj#e#K+|{CUSV z|HhHLLVU$WrT4lm=VBlK4g^tG5dj4{y_<q~1Zb{qO18V5Xwz=JL$|YWh_CY8cuj z3L*tqMelZyvLEsXp$c;RQX$8vv&7yQkKJlyVcUH7w5vb(*LVppFlKCDkW6O!<(|hQ zdtQJ9Zkj@8keFHCkIO+&-s53OvuP9S!@LMA%+lK@6nHRWOmf4J@@cpGR5$){e1#8j zY)x}WrP}2D!~8=9Ua7z#@IO83eZyUlD|FT5K%t+g-}1CEnrsmn$ruE5FZ; zN_QoMa+WKiHR))5x#v04(H(2j+3?np70y)aV9+b_6>8$$#!EtLOps@5-R4aA{j#91 zJZ%|ozRtd@jK8{G_m<7qP?OJux_E^aA_4!&|d@C`Ki`AZCLQULN+ZiZDQxVAtk3mx%{iK;;Ho^ zrPy40-HS8)axznXNc|%=1v7!N9b<+a*oR>MrDcY5*bYh1&NvJh4fxKBPlXbD5>T*U zZVv#1(r+nn_Zbvq3egTI3oSF^ z_ig;VJ6VvvH;fFdEVNaIx*#gv#7=tA4jRp4XsFz0!33+CeU>*pIW2tR!S-cZ6z28& zn7K(PYAy~w6;<2eacu*KZqf&g!OT2mRgO`eI|^0o>>p?4n0i785%|q4e|mM&k}uAE zS7Z<_TD4m1Egz!iAk4@eoX;!w&{a(^m~x*uG}&eMEJ!{Ct{`*tgV{q1e1YTkOqpvD zVfvP}TabPW5HInJ6gpuqOOt7)f~|u?d(=|1EDtwUA6r%D!v%1-02YeOh2B$nO>7&F zgGKE*8`+u!qQ}pi>fOWnZjr&9YX-qR($BT{axUY_ zn1ALT*kCVqs>aXVs2pGdTkVLj8ihe6`YVF@>ArSy?4HfEGRZf@2IS;af_C(*^oswj zy^|jwbA1nI3G)F>tQ;6PG5k}tP_0GXyI4WE&VLpyhyj+BYnG_fnE-*Bsk410RN1rx z>m45Oc{v_+pM;Cy4D0gxN>^l)+7y4@AcZh3x~-6xR2%UU07sB*f59*3)x&P+sG=Z~ zt~2$l0wHlnpQki3Uyq4v_UqyOEGoi&F-vTUc8|d3%ejQU*ZgOn zUiL@26bIm55nCzb@CrYNniZ$W$?D~8!8_nOl_dN$#pm;{>n;D%0a)Dg1I!Ja7T$Nr zl*x*QlrNOTNsqqo+hcxriLzxKbN;D>(?k{3Z`wV1rai17+s03Ldk&5&1y=^DxvkO z%rM`GJ9Hc3tEBB8p_uD-Pbmxm`FF|}{mY^RF96q8=_KVcc7BHOuGc7Wrh3P1yxG=6 z!^Zv^B!6NRVxigj-i&lP;w0$;EB#{1wcrmldQJ@F;+g~2jtT6>Cl*LNCZToi__q;~ zJ-CZGH~o0(T`8B$bvEnkK4^$B+!s}}DV)7e*(kiSw&R+MEy$3?J_B986$YgoN!7Aq zD+e*u14o9cd_6JBieKR?-%eDk;#!7k8aLQigmE(E3GojFo9`JnrPHMcwymd#$BDzX zS`|Ie!2|rlC+i>jU3okbIft#J07OpxyB!zymmmkFVlk1Wt~5XQYs#ZZHP9jA>cstp zV6%-o@e97&-E)P{TVH%r65?*$q4F;!jt#dyu#X5BHKY!W_v`dLZW!jcTWvvfT=GMg z9~tvR1;`>ZKWRIlOPrL|$0Pk2a~i&%DeYg1UhyiDwuF#}OXpqH<>yo#3qy{7bQt;O z=gWG%omCz6t>Ke79gmRbJuY5-I|9AyzDabSZ`P9-zGr)UbfyMKlJU*oL}6i*;#86N zGrkqIRB4&FXHiT9u|$>qLPyh;xE`MZo4rViYxwWcnRqR7Bq%=$HVC_PSxfQAxl%2h z0<`8hB^w3m3O{5}hJl+ssn5USVfveq0qtq;`5f?eU3!&ZydSJK)USs&@oUt)-mmnz zO8Ku(9pAhiMC&g8*xIi3xAlv|#B?B~lYjdvPM=d{;#ZEN&uJ`;^ctxnIg~aQBYz1I@2p6*l`L**~GR|L>7iyn@3sJ-r48?-}SRKar&w6k9N;Hklp*ACTNj%8y>1i#3v zjZNIaI1VYwcl#f&qCWY|W*I%{2w-r7Zm{bU`xLKf($9t0(K7xPuJ*-djuK(|#G44^ z+vg8_>cu*L@_I3?%UA=n%I4+pdXfFxONCY=Jm&~vR4AR82x778btT#$+TWWr0hfsC zq;w@CxHZ@gdwKXf5LGR@aIdI&?iXG(_+=FVZpF`hjD2hK+u>8o1b26Vj@aJYQ268b zdOx7`%YCpVV^jN+o4f|6c0f=hQzpVebQ#odTR%kL|2KfptxCatmAUu|kPz#?P;&p4 zD!e+#?XX6DJ|g?Bv*v;RFmSfl(D>vZ;CzXoW=wC%oxEJhs($3gq=A%g$^@~eHEMX^ zWttQQ2xQLBJ%Q65PxDkC(6dO8kIw_#hhR^*2g^5u=Z~6>)PxT}CEpyrv!Ox+-0zxE zAbvRDqw5f*M91N9Sxu)0Qmd2Tj1%o)+V&~&0gJ%Fyx=hu2FD|$Wwg1y}1oUvWIO_Qf?ot04*5EKsiSHGz)zj#(!--n9 zbAI5WEoN0H!iIR=;_`U|Z}@$_j<8SyTp9#X&6#ZXR(%^h1I@=%Xnl&P3_rO`K=XsX zGvrPtFahx=zynB&H|8N;6wXPa8qeUz1g-F0JG^H%{K6wLdH3W`b;q!rZlNWNxz-& z_K!JcUmf60`aR}6^|(F{NdjjaFnrIYa{Hv1DVC-x03tjO*kPmTV7~+)&Ma;`3^TF?t{iQwxF z7q~^!V_A}(r{Dcvt9zU)=Yc@Q=UfKqyb3t9<03$ixu5&$*lyOCkIol`4*p3dNzz|?!Vs6=9@PtbZ_Dg4(!#JzJHe7$Jf*;tK#j8zFrDPlL;N4 z=w6G|z*U{No6+%wmec!6U}5D&RfhC^@n`Pm1;nGcH8N8CS`Dlg4Ij`lmF3NT^)dWP z%2gZCw$bf@yV_(#X31it(Ee+KAzrwu4_lF zI5oA0$rCJN#gsgohDAOuBrUFNcdZnoUo}4G19DxPi7=nsDY%Ti8{e@REB%sP?Z_Qi+ki$W2hp8=;5@^zek`Yf zF@wKe#}7H^H&d9UtAQ+=?H=}wf_!XpH=h#ZTD4;(G8%A3lV4nD_Vks2-t@R%;UTLf zfAIgEw>ZqAvfFUvVc%^gcvn?*>JJ@h=vw@Yw(NFusDt6X!-)Nod!Te>|CS}|cr`Tu z{kEUi1rrBHaBDOoP@K`fRJ8uyTi3+pM`s3aXnUy zkeLRyJgQS-<%cAHa^t=0rBly5l`pH)ADVLCP#;|$T6`Fw^zy;4enFEsDe~nb(EK&0 zzt-}(lAh_Q`k*?@j0wSg<~KlSF1-znMaw23Nw}J|&dK_#-OrJZbPyZeasQLb-%kbtKvhGW1${y7ca?m7Tleoa>TiXzpSamzBw_uC#63<-f;n$3 zz-#TGu9TP{^Cj{??eZ3FY8 z6MwBIT}a!>fx*?V>bId>ZuXu4bf0D|%D$n1O&?Zgmot{u?>WQYM-gX7A6tJ-pp{mB zLgOaI8DUfcJ3>uX!hnXJit3HUe3Db+*ySP+-uY~w9>;50?0bGQ1Dkr) zx<8>fgK_~bwsJ(xgj6m!lkVGbmatx4EW1@a`Jx&y+4Gp_GR@4nD%ny;%=zWV!T zAi_}4r9$kH2i~v1n#8xoCG?z=?!{qBt7!p`fL*&4_J7K8rN_n)dbH7f-R+O?;FXP@H>_NC}x7iZB;-mp-Pd;kv(EGOPU@WLD6Y;q>{p}FK z<$!!FoQp2Om`eMr`O>qV2_4{)23q`|*qR_+(vaN0+4zg136#Ct9+p5vQr=fz6!Hn5A!iDCp#=QG0SJon7e1-(}c<0DtC~azLVfC-CbiAgH?VMAoyZ~ zi`T6$NG39JP*>+|A27AnQ!5++Ac*Q3nM3i+TbSbEt!K7x>LL2^m{JRi<3<5-y_T`-YuAMKZ0} zYwca1C`}0!1ymmMw7gKd4FZ26C?Ebg8Q6i_=M8ZG`f%Q0UMipaEQq|5v+|`PRrZu} zSoAJ9`fs;4kQJzFL(=(KoD2!6p}$Qr46WhwvEIPtQTEA#BagclpXaew*W7%4rqkDj z#yeZ>%YL1_Dh_V5;_I`gw=Sp9kjOpa4C;_w1%=)xjYS>_PnBX5sdqmR4RBs2FD#=t zh{97tdE)z03R+f+a!wUo@}^0BJZNY-Yg{DWFgh$+tEzhz~%NKp;>vl z^2ZMZ$xu?Tr3|4-V2s&SCeqvTNLa>E=xL;)Xfy22_Js)i`x#S=?4b~P^fGFcX*44I z$}fh0}mDuW&xi9Zr@ZcR; zjvk1Y=GiD|*Lilaf$~f4I+1p?mEAfxc@>xysPyGHeu_y*USZ1>zYS_W2E##Eu9ZqAm*@2OYh52e+>;T=<>VT%w^;6R3Ul*lq&Ai(Z5y5lhE>;m@Y)+t#PcY7<-*Y&>ynY*Gd6IAJ{fkK(0Q`@R zJ+BI^!`kYxI&g{lCeoL!&I@UMFGY(gM~X-ny{3L0H0OO90OaC}i%Y&bEqoo?fxB-= zHtiR0AO&_x7KAMxVs5b4vv;gtxF}UA#B8$f6Es44LoIii@BIFR-$6vq6532sR0x8C^4nA(F>bXgpAAaGJWN+rSO zU!WM6qT~Is@${^$%+@bKjzh@FdWF9N5N$W#cCRx*v*d@^uaW&#2Sn9aeD6!~Nr~Cd!(aP^%9_@OoB{v{ zw$E)PG)JAP(<=irgtoqZ()Zpr^7#H359F=&`}K!A%>A}QeNxyFzR73`^}lI6XK5be z1@?=X`-2oN5vsoP^OY`?iO#|`l9|#D_Rz*K%L*(`Nb>Bjbi0YO-a29TjEP7Zed5^u zF6@W)*!}aq9)2DCnrtJvbP`-QO0OUk-2OP9EKO9lB9fDn$e|lkQY!hBN3bg|df256 zsMN2o;bElZz@c0PPxj3tB$h4T3p%^V#%tWnuD^f|&&rUQi>ke9-8I5tmI}q+MRIDA zoH{s0aTB9&9Q5Cs$$n2YynDloF@Ep>2gE(@+!5%>CIb;UCG7rK%7M+Amr3{B*e6{Q zS!;n_x(OLPL)xBr8u|I`zQ2v?|J><6wP+7n+S|N#P*>GQCZDU30?yM^p_8IOF3nAV^ zkQEQMjE{KVSzJGT=vGkjjy|AETl#tNd&1=UJN?0k?KYoB9#J{p&0hw0ywF9ArzuSZ zpCl`OiFF|U#LzhsHgrMZ0n91_E(_707eX-e4E^Mr!`F%Zix$3Kn?63LE+Uv@GrFvh zLAyk+KSkFwU`t2Tm5+gRFp5|M^SxDvoBDw-;ubnHBM}PklMe3(GYndA3O{ZP%yy5d z<6mWD*VnhY#?&964fkH8eHbmVA78b4u`MUYbJW#~o(qQ!cFc+}*;Tiw2w-^~(%z?| z1b$I{bS-!LHhS0ls(`u;8Pka`ZJ%wI>Ml{o$UF;J!SF}ayOpBlzgOkKfy6{ z^5nsW{j>^rT`I~-nm!Mvyn;}wbx9IsAwz_(frQVz2yvA18-RGd>ZfORrsmcZM`$vR zubSPyDvr5li0RDDux zVsYVx_mU0*F?BzN`q&fS zautgq`CdnR3MS(`e%Ic*e~6lcK^E?%<<`07B>2eq2cGz6TX5ltb7_IOb2!9Udgp+6 zL-wP{wsLorEb z`KO|^bRG^3Mm6e~KtvZROtY4x8!+Rm!56i^{aj=v{-M9hw4<4Q`J=ZFynQ7dymP+; zJlY={jkL&5pAc4V!jodZES-}4>qX25w7f!)Q0)!c!j5wX z7htOU?01L?8ZfcThG2&}$hDPheCgWs=UTnMMJwM}US;II$XhQNA}y_h#J>hGb!kfc zmYM3Qvg-)-Zw1ef>^3&i9s?2MD#gO#oH=Lzh#|T{$>-=`7Xe`0!ihV% z74R>&xUiB1u|EDK?Lk4`?(duL_^}aVT?KJw3@?Asn&FN^Ii?xJRBAQ5T~E~y1{Tqfj;+6M4a)rk7JiE(4ANB>TcY}C`}LU5Cw|8Ii^}48 z24?rj){PaKAj-S@)f?UNqqVGnwD(^B6nT{(kx(#E1b-WPszUj}u{lI|-K{y69$@3lidb@ikj;ve8oq6^z zcYpKt8#LxFp=>+Y<_2r0u$~>vrKU*m`Eqinito}ZPX+Q7V)P3NXo7?u6L@V5toWa$^&D|+Y&(iNK z_@FJtZDK<#RNfWP5SIuA@ni`A6BQ}rgw9m8FE~4h&8tmYo-gDpzX0oHm6&79U+;3y z$rZ0AUPt#&n$7l*#JcoA-|t9yote#~Vi{Bk+>bB!a2zcntO|{(9?hvThr)h3l2=Qw%(b{_3|i^@ zM~GCZrdboPLv33K)C5meaJ4%}WP5mCAAqQG^%#be^sU8o@VN2&G~wE!K%D!TdHppd zt|1(zBUW1V5_ewM6J8PT4t|d^mvr?Md<9;(f`Q7d=!e_VeYPw26_VXg4()}`?_&eu zgIm(y@HxH4MoZZ7eJpJqV^986N-vO>UW{Jb?$3KM>NPEH-^TSx|EiMt2d>@USG~_x z>D~E_8sLii6Bim>vkdL_cK&pVZj$?gq?H)*qYk5;G%WJh^J^{dsdjQ1cv0o5ITQ3fy@LrPV6Q(B! zeq=uZ4{D_HuqK`YU+9-ex?F8(xGFAOe{`_o&{z0loOq*dsvKR}cg&(_4m3p6*8yt_ z-a$G>kfk+?_XhD^}c;0Bw?DMin>?QRB=N-y0FS*J_Qie0}>6M54ZgNovv-(M4c6J(%PJg5U z+$a}@#zIb166sMF0OtCHJ!+d@q`u9g`|6+GNOL!z{HevA&3kIfVIEMaWJ0n`j;#Y6 zSsVZ^n*P4rFCY8ycxHqcpWOXV`L6pGNlieUD#B@HEgIboFC~ zzVfzhdaCde)HIR6ETj(n!0`{$q2^c8neopDUT|k2$tvJsRo_1@fn`L?U&8ao z__uu1_i?viRZYGK+CiPVk|N&#e-B|Q`wjfO%J2lu25;_>OsuBbW3z7N5(SEPDz^vo z*l(Yy&S;bAAn~{DG{G|N}aYPQ#{M`|dSPn&tEmHyFKjCl8$ zzVOQ<^V~X*a6W2}iB?XFN|v-S`P{XHN9p+Kf`A})(0^OIp^h4+@W0v^0mUQs#cmn{ z^aBhHBjqKE(DiI@6CMlv7zyL+#12#AJs0?^m-z<9@p&TdP*f#ChztUBk#BFG2=Bi3 ztoRFxEcge$uHvwzx6ZwLI=H&aKJ5uLdlT!+bnCQPIPPIe==~~BZz-6t)mbDYwDlI^ zyifB_qMR2}+OoG{?CXMZ{##RwW*C$2BQcDmrOUU*Tn7X)8AMqG0h9RsYF@d_+5>v4 z(x`pD6Bq*)Ja=*Ibro1)>N^LKQBSG|{oQ*PKrGD6Q z8}JkZZ!dIL_b`zj;dFq*;>wmM29}=q{qyDqx$G?)a3oetkeHGW&`yXVT+dcL;^7c61dH+=?*Ot2eywPzlNxJ)U%GJR=p;Pkn)uw}`!VZB5ZqqKe zkqK>hSIB~fi~PPh&SW}Xc*Z7~%FqS!F;0`M@?dHG{EW_BAIBytg2O_g}79fOOj6b zB*Nb!2La5SpS?BLBUmI9;`ws&I2T9zWU|;Ii+$B*xpG!;BoR5JcJax`;)X`3%ynWL)Xy86)PeIuq;FQ8| zR7{L_Zg;deEYh5%*5fBu?B|O58^U>DNS}8EI))*vcp6?+hAmPND@D~f- zdg)@pCFSihT9KR(P>R3RA2sdwx$r`Ekl03B5`#-Sj$RH7vbPs{`e+;hnO zrau7v(xwzbKC8304+-IAZ=}cx5MKMiu-G}f^bjGcaPx(2$#6>if*iqe0NnXLo~HKq zdKp;(-r>!h!$4cPeRx1$Apn=bp$8hVE$uF!d7bF(p@*l!8%81(sL zDH`uH|JELFdhK%MVKI*qw~h$Wrjz#;CL`y^uNxsyg6)Qz8F;WfK7vV^uC6AG3a++L z8f-9(KJD_{8zD2SL>VU)4_8{JNR|IA3FpOjl~6m%kS?UiFG%0bLpLI|*QV}Hp3CP) zcK10RnoXiVlGvBt-;V@v+s{XT10c75bA1Af76bsyXa$1L&R!L7`#XEUIp=;ZkM#{#yipJ zKkYBJ@r;?wYvx1Xwt@DXdPS>d#>9XI)6AK@-co$~VDzKI2%1le>+x50D%db~xRVqyw zx;v|j9*k|FJB`NrJ|OR$g^S?r5uX!c#jOpJm5=Bp9gJmvA1I*>^_R-sY9`egc3bHe1)Sh!!gQq|D z0FQf@VBaG&n)}F(fzUI(^ya6ZG;RH;{sY+*P

zZHy}=nKwB;>HKoo`yEr%y@@XdV}5R@(bk|gSw1jPhbMm-?&t+~o?vUgFDFU*9g{wg z)7`eOrXo9C+TC`=3-);UxKBh+=EZb)+SeCsB7zrC@Swkmv_gu8j`vyJ!iJrWW>4Z~ z6PNd+8qs?6n-%*BVN*BTb30<2PCiT^CqK`Ne2F0C5d`~^0&x({7HD_F(frL4;3#mn z@N#**0N6b7gRdU6UN=7aQ7dP5BhTF`C2CU~$Gs>TyaN_i++3Fv&Nh3Fs*wD0i{9_I zcu6s*!;AcQAB6tns|h52Q1eZi0-VJ}Rm)fNZZNOnxe1H_r#P8;Y~OulP3TJ0Io>?! zAo381zIi|g_Yn3iHT)Vq0tuoTyQ-zH=n-Mh9uJP?UNbn?@*yC*CP(oiT1tVq!k@Q_ zXZu2bbKDb`bbnTdMJOM)Z*!~(I!4Wnv>*ndkCXPgWc`w;Kd&^AuJz}9+s9HPqmR!I zKh%3c+nsC_lHW&JJ#z>2SU2Qg)I847D*6VQgVwS#HYQQM)2Jd z+CW1<=E|`!%2-Rr-AGUrnW(XYW9k4DKNOgH5Z_6M~F~MVs>DaF@ z^&uo&`w6Pi)y`0vYJuRXBT&oq@PUt=GBE1Z%P0$z^k znV%nB9`-KxBu|PB)CO!`oOEB!8>i;`=qNL0_d7l7?~*<*FDeViu~21v!)uqlY>Zco zjkov&P%ysoZM{&Ec6fG9{g#7QvM%sZT!=_D*9hOwn!VhC6%aA-bHYZr=f$?8%`#6p zeV-?1d%w*-4@;z=EI}C&Ya5F6&F~xq7J2PJR`IUY718c&m#j9~sECAwAjlPut|MrtELc?~5xQES6<#w4!0a&!Z3&eSGW%ue2OSt>DrW<2SkK zmqI*vm;IyD8E)P9tqm;ZEegg*Q|9cx!p`YEi{)T{CB%GQ2|STSoyG6#)CU$r^+k42 zh<%0m$y?{Zl5iV~)1$@zo2vP+duXGm+pKaTI=|W2@Q5E2y4#gIG#S<=fSJr7WOGa3 zXZxo`=^R&_?j~}Dz%1Hef9I>`-*(jf^362%j1V3?Er&-K5_yPd86O)oy*oGEH~Jz6 z@@BFK`li$I=PA~{h~PH}&YBE%Y=IO{EP!+gD=bDg8P?l57U0)=TDrd^fIB#LLun*N z%pqMwAv~Ur_$YbuHo?V@RdYzzzraU{cRD>j_eV?w^7Eva)p&Nt*E2O_cIkpw&3B)vcD@ zlKBjfr-FA~B!!&Ye@C?#J>gs#iR<@|NqJqJ%jNQbnf3k`xY<7ZFhy|-O-hdxs|M*p ze@(xUs--D=c4$f=sLX>=k27P1`L3b(6-emlhAkh*oV&HgM!BprYFNtBB{BDS52O4s z8(~Zx-jh6XF}WUIGvs=&qGuH1JNowYlz`K*mkCE_Ob$_y#F^&hAjvb4^9CWNPt99& zv=@IytU=d3;XsJ-dU&(?8z6`&@24 zF>uRsyP#^UR(~8U%4h`=PNNg=65c~rm9>O}E5fE&>(dBy|AywVz)H=K&nGzQZYpKz%#S!WLSu;F!kjJnea zVQK)OGu_8xN_4`wo&-Vf++X4UQI7S_6z1!$RG;6kw7inXa*a8A+>X;(yVv}5tsX(x z7Hye5t^j>C7eB`!ES}mi;Dc-QbuaFPT?l~MspGBA#7P3lL6tW32l2NjKa|vwW0R@Gh>j5&( zAmrACE>fhql49!ix{Bga?E0^V3|vfF_}#U97QMJJou~sn1_xi~GyN2%;~!V&2q4aL zr&R8Xs_}CA{9!2eF-sSbBLQ=cLPtD=y^I=K==pu``7xsN*9)Q>yX|=5&nVb%n0R>O zqcm$t&E zlzaW1~&<8<*aRG5X`n%K~>1l#sok0&{^p(KC} zn}GfQ2I=k)1*um_u69SU3tF{holkG-cmXpC!`Y+#NbpLX)}YCZs1q+RQZ~2f7gU$Z zT(8{q!@M!5zzg&bK32n58@2lzo@7`nZ2QZFa|-{z*f+7TQs;W3ulw|SK2NU#MtwZB zaky>RFO1_|{|brqVU%)E?wUPx`;o3XUh4h+J{=r_B=);@UtQo36sEkldCGY--}fNI zeM=GTaSHVV4^TY*kIeOBw;=>rM#xVQwNZcn*wJmXw%_?18Ng4P)TqgyHeQ#bU7zXV zJs>tH=OJh~Ki@`{wJnX*L7J5ozmLp>dh^b~u$X0x>fu^R)?qJnz4gswZaf`;m?aa6 z{2arN`U2ACi=?Wboo2{Lc<-JC@$2*LDSG>Lw2-cGDP;E$#Xrm-NYMm-zs(+x zBIJS{*|>I&z|*RF@Y>fG1D$+yWW7zoSnua(H@vNnPQJ*2!G>>y^@Rx5d=JCc4C{NZ zC#^>GJ~@S;i;7nVvMe|2)O-L)QYHl5NcL^XByk9-`L&0bmf2eK;hLdmpJ|kxyXvlW z;s@&xB6t`lRwOe#9O%T3-&r`7%yMdf*f!&)!vkss>^0qx-Lzju_s3&2=qCCi$r`!I z0<$_-6Wdhj(|oEXT{-l*kgkWjcVe9iPt>%e-S*V`Y-W(N+Y<=cp49pTzf?Efi;j1>-nmVr=v$ zEla1mj>=m?`qb?vf#<*he1Uuf152HCZr(sn?qzyE9uWePX5_P~etSPxWY(}Tu7}E> znbAGDfGFv$!d#3vW36^g;}=LD#C2GFCc~3@Jw21kv*ob4_1w=3g9@O0B%0o@LEop? z_l2iR-#Z`Q^*cKpV(C7A+E)-ij#;U5`7O#lZN&4mR_x48kc>|F8Qk>cp5HVG_CqR4 z_UOzKwv7+U)(7y> zebQ>6oYVJD`$G;La=y6wr!L7wy?Y17DrM=!g`pa*vFWA8 zp)5Osbg+96Y$!Cx)ubl{SBUs-^$tc4jAdTwBpdHE;P7!_d`>sd(hQ;|EA;*Bd4KMF zVyoIjR3(WKiYIj;P_h?Ff%x^q$@09HbGXA0yzFRk>4j1`V3z~xq9XAlc}qW}8Xb}o zw?4Jct@VeF-h_D|NrB#qeKBVI#qX5rPYMa($)-zi-q4}>1)*dhVUIgo{<1D5<5I|M zUY1YAgpY9l#n!Hm5nVTV9-8H)wIIr-x@dSArVEV?0!G^S^z>RUzre&mf)SEY_hN0S zZTIJnX(287n*VCkm26f%nwsf&90gnnIzG~Ddsk)rrKTAMP@cr3X z99Rb1@_9XRJ5gMTj0q>PfdIma=j zTOzkLiSf~w`e@&87x06w=7+zls^Ok%vp6?*9e_>88Q`e!_xi?(KHbOfu`e_Q4=kA=o5_#s1(4(14aOoGG6So5u#~EKlN* zZI*!FAPH*Zq(30H9>b|Qf9tqAUg1b|*6#Jwz`5(!*D=1E_vFx8?z6qVtRo`<7|ZDa zO6@E^C?m`;@E7~I;II-vGYU6D@M(FA&TqvELxgo+>!eldhLSiv=n^uBIdasQ`Es&@^)U+BIi&fg}b$sS` zP@=j>g>9MIqm>W^{++&i&6T!@XyrIH5e^1Tr7g`VzDP$$^z?Wl6X7at_FJFEQ->*e zn+F78$?uu)*?@gnMjZ#`Sw{-+{34MNQs+QU;ORX3Xjcs!V)czp(j8qzm$*aQ zR}idtisHqO^WnN&ZES>zs(~2P>~YV+dmXxx)RwT#r}lNkE*i~j!9~iDwxm_leB@Us z#r7gNI9;7LQJoI!eJ*dxEIE=2AMJ@q{B)l@qKk7F*72A6HJK^5+Y#`evbQ=Ld~Yt$Pg3yH4)XOLzM&@rq$VjLwLIBd0S@nFt0{utFP~?kOLEN}f$eZ6 z?f#I-FV4AbUGn&G@5o-i7V1xioa^=d(q~Y-$?$i5EiCo7EB3SM6(h=AU^6OzF-%D1 z*3=`-lsh`f^)~Y9d`(bgQ3ZNDR9=4%^rmZs^rS|M7F5%)a{iOJg2XUj|K*ocfkpo; zxMz$!H|(M1xoUp))L%Y)h_t(09=-=!DBC*{?nU93f1=nO8S?$w?gaWy9e=51nWFA@ zBM8}dKrwKjQ1A6!DRLbhK=Eu;WVPXSm)Nd2TzAs~ENGFkU4C7|hc|b2b%#DK;^ zQF#2t?MR#gBaB{h)TH|E~kIsYOwjRW}v(#E6N*Vv@Q@BNR1vixeF`HiJ^Q7_E2H7)yH?0#t4 zkkyaSzny*H&Q!;>2jebrvcfwQdbYO$j+@IJo1xQ{a&BW#mG=TK$%HOkgMUr{>1#%x zE_~ych#7zD#vd{KBwU&Nl%0}b@_j)~mqW`!xG@k^^+jIk`wR5TsJ%5)(f=S z=^yew>$J8I)WOakz-}7H+(K!MlAGw$dmvRj`QvZd0T1~!4Nv$$$Tm5>X4YhoGrAg7 zZUm>6h=;CLnlAnW7u}`HJbwDzPUeG0H}L4hYg{2k>v1}*b)fC-bF#PF!Qtpbv)^e9 zhtzB?h%do#9B)=Nm7H*KtCV8A`}OMHL7%Z##>QeqzLJ0Z$a1mBeMrwYk?P`9tmbR~cN-vy`Db%(EcbMRRI1SvTbOH@f@7 zej!dLX1~NpDwlc(Ng%T29+E>fZ&Vj>C$4zx-*pigbK)ZnM}+Te zLx1&}d8MBdP@pKfRnSi<~29V&O6e)s*Yd>nI{S+?D^6FLM-oOP>Pqj}iE<(re z$9-%$vA=I}|E=?k50c*q*1k%Ii^7%NmVCKfv76-C4KZp|p4{&BZYjkFM3eaRDPp!Z zntgfe?Yx{3j1J>Q4&Y2@jXG)#e-C?&$}80r!s||V#v8t_6;hDNWsQ=3*mL?$3Nnt? zMx;|O`4y^nM#6G-?8rW#LwWu-tm+*=v z)@4~D{U?9FHTs7Z{mrL08SRW)VaQJH8XtkTp-{T+nH}Qd8T#z$Mpch&Cz1~hr>%qZ zie0P<7D@C1u5dJ!$;%WqOgrI6#C3_@*uIO2)`Qb)2lYcfIrsk4zCVP_d!SE2;rUYp zcN>WJaFE zYbQ#%n{Pv@go8%f^`6|6;pdczwr`43^|ndW3-`{iUCI1q%qx8fh{)8MYF63zy%$a| zjsZ4ba(~?$n`XUH#c1gwnSeYN zASk*^^ZtDxj*y|yHdtFF7RZN`>@CpWyQ1i~@~LaHu*&Yy+_bcX%ERK`>FS=1Rk@G% z0DJcUXn|K=2RFfyAHW?kh#{pJ?)ggLrmvgQngaqXRk`t*crLJMD>BYj8oeoG>ERSl zU)lg9gui3+E~P-L>1*=T^gn2U_7GJ5P9nZ#GnMIJ=pf{YCB3tV`0{erpt^)`Z=9bU zXWX2iy||)&O{J+OE+@Ccllm9;4zGgM6O<4A!6%+nhI?N=zMm}LF9qTKzKpmRnyKUO zl;Oh#Nhf=)AQ$m3r-2?37xkvOoqI%use7)r>KrC&K2=jRm+kUyicP>HGtSp;FAd(< z_~m^a@xi-*cSaD|Y!}iBxZrFXXTI~;*h2I#*f>Dm5&>-Ots*7&C*KCs=g#KMse!xr zC#3d)bH3^eH!mW-W07OHR~0aKTj6SFEun6gv!_{;V(#z`!x4_PtU$l1AMSf`ZM8hN zJXjFbUXR4I`X#%Z^u-f6TAo~6@k#roIy;6V6T=O3qfAp4UA-7f%Suy3N%S$zv5>i8 zd}#RR2n z!8UAyH0Cn+K{R{ikgBjQm zK7-&KO4HNhHE%@*JcyI@@-wMy1HZ_;bDY08$PY}6)ofk-Xij_|kJNJzkrdsGx74Gw zM=_|w$0Qp;A17_f_E~%WVI5=1jPnfW64!x|o;lIJSMjVTZE$OGq;X`WWYgX4bcVm+ zgX(Zk3o-PpnWrj?9(&k0^cs>OdTNB8s-f`-=IX+_G2M|B^yv}0AA{=5XPK#wy;*~t zoI)|B`j5gR#Ob8^&OLP&XLDaAl~@qVE&F@@`pG#*7uZHtdClGAuA{sC+R)F%i&>2n z`*%+gGATS1&c-hu+N3Dk=>psvSmE^;a!v#)leay1-N6jilk#sjm*V;Lv`FL1Ww8+g zt5@3((J&2k6F98>&b{wD=;iP?+#r*;M~gWZ?T)xnb4q8s(?{B8?SpcKVi=*fuqWey zaT#scnSzQGU&z?f&4iUq9Lsnw>Pza;~ zwGxKOy4r|Y4Lo@>d`<^y@^bSk3bE9KbWor}!jQ*!T$1&=B!_{PEaYjNj0BJ-Om*1s}_k9#siHhg>hM z8mg~Hne5f*WTo~fNyHJ!KP3N1MtdZUXj5XZm-ibt!haLD6)AS+t0{7nn^31nrTTo4 z1Gpy8PlI0z3HM<7Dhv0#9nIIKl)E`y+s7XNiy(=PjiTGF9>P2OgrnWP77=ueg(bJ!|YSz;dx6FJj(rb>F@P*LcxApk52a?7Z```!efO2n%o=3YVy=qH&*O z6j4;zzGTlio*Y9Hvm&`Q2)kK*bl(RxC#m&1#}H_?`r1#hC7a-j?ibA$KMdDQaM`cV z<6JWN$Z-o;(ONV$KbKQszicnpvRZCI4#_#JfU7$ckiG#$4*94XZwlI zMou5|=6W06Q4nuvUjL~6f$8*dHf~^(fkqG)Umu9K?-$M5i8X487nI;kU4)w_jXz+E z$<};cuvC0}&Xr7%etLZ&QrEd@Y$>mzc1aKg9JfvWb?3!spVqm4xZ%l?j|ghj67L9T zS^CD?iH}ZP{q~91$+svepWuAwTX{8mbQGBHm*?<}qr{>q>Xjov*#}8Rh@nHY7@AQJ=yAFaX=K@7Jsom#4;6Um8qCIP=@KxGHuch zx_piIo(5vNx8o-kt9Oy~=_N9{>kYIY0-+c3L5S2XoywL8z#soJ8hn<(?tI z#3S?aAjjDp(tqKT{uD1T0>hC8fCib~NpoL*%t1Xc4{^M=Ekk?u={u4+*@!;Q4}W;< zdFdS>~_eK=H|<8UgVREZDyLc#GE= zsek#VSP*VviPWbLQsc7tQC^x`@h*?Q6$~OWWPxTLb}ruG8a5Tp!6MEuQH9M$Bm9){ zT?SmezP)O{OJM4k*;Q6ObLHpT^9QeH7~CfvtN1T*o74?TGN1&(I0b0UOm3y_A4}bO z2hH$}kiuFQH83A;a?w1()7rqfoo(Uynmy*>T?WjNFrScBqzuM#Bp{b_giGk%>kR>t zQqXVCqb0aohdwl)y2I%eB*&CAN!msc&! zNRh%j8+;4tyPX)*1yye%b(@ce>0`a{-to`NjWEM79Hh0)+?lq5>-$xuy#&?LFBex1 zuPA%fftO?9&l~;g*?XTcra?3CK8}3rFPZ)a(OZ0$dJnNHD!?XZ?3(uSV$C9RhU(dq z0DYb9JeZ&4hSRboS%;?Hn9~I*vaoY~A5q)3ad0?E()f15{uYyB>xN^B*wx$h?0emA zndY4ZVRHc4VXuyV^_bnMK=0ia_|jT&1x7PUq*GKiMW0$-5_%BRTe+Nsudj0IpTQZi z*&2D=t~CYkFS6uBox`AFIt1WoN&bC5&+eOA%i?#3p}T_1ztk&M&Zd4l3cdI! zjT*Oxt`v=sRT-AS*!As`wcY&t6*7@F5`j02qAQ%>0@88!f*h+!=02FCMj>Pw+b2N> zfvN}(h2EFZv5;r)8SDAI79SmXo%qA?3)r5Fu-KlX%tL;;GUydKj*J+#@|ti z*X<{tIrf4^3e2ZBMX%mfdT09=oSoZixxEh&&0jv)`Lqt{PSZB? zcQ?A?a50ot)r9uLXM(F zOML-*2Up8D;sFJTv$j@H7tZgT5c@`YuxUM+R{e(nx;w5trcL#{x#22Yj2eiPx32_d-~7KE}hc z`%`-yNBsso*DM^3bhs@WBC30f5WOCK(^f=t_52e^uY4QfzR3BSExIjNIXeNUe`n+Q zcbT4Zmuqs1Dog~td8P$RMj|3$BOdy#CT-z!2NQX6whgK5y^kiNc)g6XwD$X(Ri!`f zQz^IW+RS&>Mi{P99GKf*IO0*j_Hll#rHklEYy;fN%#*x)I$17urR~IflO_)h*7E$s z$Heve04!OfS+~XY%zVQfg4Q@^V>Nptfr9D=4-peLIMaV2g1-ms+u>YNFCyfSr#>7% zqn&x?5#n{Y`!S@GzI8!d4fIlHN3=ig`JCB`Gjt-Y>a7=*L5|DYFMm@w62eV+g2Xv$ zeV}~qp6lABZz7OYcgT?6*sVWhYY$ijUU6rFEm70eV#^mGz`HwUMFFy`v-yroaf~A8 zvzr{m5%$horO!$RUnC>TEt(L?-9Ua8p#*z#YSkY})iwL>AX4eH)yiqK0X70+2Kw>M z^75J)C*itQxFun7Ylz#g8Ba^1>Bk6yEbr1_foMH+g_l0`87W$m_e+aA0|!IuN81gl zEDZbIYrZpWyuKGYD~@mTp<1C3xk~9=aT|KVD&t^zat@%E~e8WAl)7O6%wHvG443NLDeyS)%Z0e zg=1gK%b%3leEtOQYF=hefl8Bmyle^M{hj3=(w^uPHRs8w0#%PLmXr zX-{w9piSVHdF<-(<7zmuM}urb-$VFbWW68XX7(;;y7z!f>V;`Lh20O_?i1`7AoZ9* zs}YZOJ|Z$`K#2~;1(7*2r-kzA`p&-9X_>kNvMn&>0D|U*R4z<1eBEx`fT~w)sE2C~ zxG9lDz@IN`Izg)c9mp`Mle3^!Z+3sHK$qCu6fbUb`lUvzG&*c&LdxM2fR7$qXZaZ zp-jbNWg>DKn!xyQM|T810FNCnLEj;v@~v0*t@bN%zl1)fZZ&5@=QQKVnkUdc$bAj) zl(mI39;FzACbz{HHJG{`1nLnP6C7QqY6pfCaQ8|H-Bp4Do7i4P3ww90x{wa4@yx<; zC>IY*=cRh7C#er_zu{S}KcKVkIQaP`Y_yvqM=XU$iML#vt5&7Ze+PddxGUsC4hOI=-&{Lw#Q4Y_61rb6qTXkz z`)pQ2b*tL)Io;$xHcj~M4w}>6OwHJiRr8*TJZ{c~CYaC8_OA#<&11i$_m}kjGd1y` zq$!tXs)hIu+W>{gXu9AW19--u!<^Z=@lDYpm3-{Rt#8Y>=m&F$+&}yEVQDLu3IfI` znEM+zA95FJv_U$AU&XiEy|t9mJ}kMe=SS&6T$*G&Gl$_)k0&}Nbc8nSt}XuL>%NVS z2$6Sq$!{4+a^*Lu&p`C@K=L!+F2f z6hv#r1I7i8=oh*2ngjmX_X<3J ztPAzC`?1gfSt?s+yaJe<1LM5X@JcAv86oLn-3|3shQRePRc(IMN1ki0RvDwUt=^Oj&rMNQ z03%mWuG4C9QA}0>hBo|aWe5xi#srU~|2BLBP08Qp$F!GEdIYSy2k(LcG!2I$jjJR? zT<#g6P(N$Ke)X4ol|4gjUMCLqOvA@7&L^KyPW{a+u+;CnG?yDr38O>h4TjYIapR7- zW`~)ALEn8fS6;R9e6_%4bi)X?o%#42QD*1Ng)@B*FXL_&UyLa{5%R<97|cGaWce#V z>y3A&0s^yvI*-NjBO?01K(?llSL~U|N4qz-a*>*0zgt%6PKNl0XhfgR-7mevqcVqP zTJg=p!bTs3W!CZP=toydPqBlgESn+ zg8hGSa|KC7GiG%$L2jN|@vQ~f&O~e8lxLbkU5(%QZ8Yg>Q56xfpG15ztjib*l9gUf z>mo&cKN%Il?#7{q4SfZ@?}mVc7bIi+m+n6-E22eF>g-?W>+ixy6kw@-zl#a@6O;NX zQ#z3A)Rkjt{p^OJUZ1HS3b{x#<%9Y*;-5_?b?tzpdSTt6<r@qCvx)%V%>Mj4!S@jkDN8Ux0yYj-byGiT;na!H6)RX=M#dW66;l5 zN!DR|>xeuv?@IPoWINT`Dos9Tkj{S&KGl9>ERF;RG7k{~K36;MGb_Hyx85xe6=VT(+0vA;oQhjf4cPRT}*pLQv<=5LOk=j zmv^=;&u2^uyw;q`S1_!}>5<*a6CC6hKq5kHIpYGr+krsqYLKmF`?G6C9vTB_YTVCi zz;MaAg7SAiv}{;33Jc!g{a1T93!H&_;-{2vGoB9v;srj6lD0E8rM^lcTG!wAXT9&t zPd&d#$~lh6M6vMBvF=ZZoaf`EEdH=}ebP1)B*M6qWlPM8RP5`YF>@cqMT3~$h3ScR z_HNVVoTcmKfPf4bvm;X)CszRs-DI9mg>3ffKeA?cNZ#MW&}s>!E|f#!GZxGHGS|p! zZ(mAjg$JjSW`yYJcd0T!*>WN;`ZV7CtpL8xBK(0Lp3gST9g##BR`2f_1rc@A7vAOD zl8dfczj=U+JX7r?nG~kUk8)BTNs6v#cDNEq6G7Jo5l8P&A!-GUFxhHh&@xC@j4uZ>B`;eKL4&+mtt$! z)?9!KRP?O}lA9j(0ZMrK4ZBPBvmF}&ztm5L`aiUV>UTI8lY?QeEwM*fXB+z~G$p11gkDS=HybCb#_#Ot4$Pe|h1N zo@JdNzq20ZXILielb=#tEn|Z(zy9c3A)StgKje$FFpF~k!x4+OF^8*v+hqGo3W|UF z;5^&6#DRl7d|w!(p;QIIk2;b%S`+^c-Ttak1#M?8qY1KJg#lZNwCQ$k% z^Zc?hqVftSE4|OFwpA($=R^-4rQ$QrUa7)r1~-mQ7~2*wd)|%cb#Ah%Uv@n3X#^P1 zskadxz)q&Ro!>VK8yJ|``76DY*e^KASMyiiKa6H8DOEhg!*ZG$49e?B<)j&l`(>De zymh?}t$Pc(#JAPA>Vs>AKvPHj-orUQ=hqpwCfm3^oTxmN1^tw26#KDLm7cD+WHE`C zI6q!S#yC*gH33h6ooG;18po~dvJl1#Rcp^$cc~4wtbrHU;6D1gRUXx9!G@HKSZu_g zP32X2A!O^S-`Ue_DJm7OiZAtP%0_!VSh9h2zS-~McFFLT@|$%f-dt0wGIlVt6@~rI^5$s{n*nkB|$8{8K7C~O;r;4n0!?z#Q z<^DNI%{LbK_0E0_$SN*sd277oX;Z#>3fhrwsVNvab>p}nHjON%6Wd$}>F-f3910-q zL7XPV?pxt(Mf=&YL>A1%$cT%{|l z?fV+`gas9EE(^apj`8`-3&Tm4d^hYgkf8+G*8qf;AWX;eASY_A=Mj!0AHs%u3im$B z?svhT_VqMMvM4T61gweKLaU?W2kxzEA*Yn+0-=z4HUn79ygW9%4hA9p~=LpDd0L zejS{#?t>KuE+ee#0D%)Go{`CX5uXMJ%-jl#;yBdQ(j6o0x+T=J@v8`J#Yb=$3SkPd zZ{~0Wcfa;ObvPI7K`v{9gD!>N!o_TPq?#14K$Q=B%Y)xg9SdwGlPx@#{I`x)O|WjA z?sGzcH1OY{0Zauhk$$rap#Gm;f4)22W@uIN1<%atO=^22pLF!Uw8GAm@P1G(13~A$ zAi!t3VL-{lvb(mCr z806Qu`}#+jeuRN6$o|!oTQ~QA0`>^ThPamNd7F;(r#(~snJJ#h*?s)F*W4i8i>~Hm zhpAxL2Df7qKa7;!OHZw>I$b&>4r+g#Bf=)lvy@FY0XeMuOvNJ|#Rj1fq?Xko_2K>_ zE%kyVy~;ioK?4ItOK5G_-(w=`k6%vzj_W?bweh0#g6QxJxm-O)_wIcDDO`v{HJZL; zwHgSPkL6ipytxmA`1j^y^X(6%Ig!4x*CIZa`ByF4iQ9Wx9~6BRckI%lxx4KWJV#5_ zvNgEvMS%O5J@=J}wVzZ+L4-^aOJ%;guBY^{U&T6^b%*`xXRM;DUv;lRR1P)Ji#pL5 z=+feb=$a^dSu-*?CTmwhOk{55D4|Aw#RZAbk9=%kS`Trz2suI4z(}F58pxHogp={ijeI=BmzT*RrRYJy;L}BG@D`xh<5<=78sG z0lblSr4OMXd`U8Ic~1~;_NqV707M{DG*qjy9TNh%Tmf8WO5$AV{lQ+e}uvCJnV2yJ+wUi|&}pwGqD?r&ALEF{Tnk22Z#LhNwe;s+9IxnC`1Ty(Wnk+A!k>Gt|S1A_kDx>Us`4 z5d{X1%Bi%7#8$iDuR(Xq@^BW}jj|S;5*8UoOpmgN;LS~`p*6(O^p#P6m8XP26 zpI@IbiTxMW`{(Ub1kw*H{e3eTAOE80YJ3^_hGBj+*F7XhE~95=?&F6m?j+=4Q=9o1 zc(-vWmzISTUx$|;vBE_DVV`WTP~_-lj{s)vjF;jE97T_gSURHWFrFj0PK4yi%wY3~NGYE(BCO{a6a*YC=$ zj4~jKZ{_)T@I%T`foY<-@+CKO)<$+Q4OETZ&$MQ8p7EsHWWVHbvJR)|S%A0GQ?bN; z&Rfqelzlm$AMeZhKFY*5I=SNAtIfR*YO&{S2J)4-?{$)q-ul@2AZV{V6h}(KR_yKj zC#C^cfYpkS&GhMd%ZbT&7kAdk7UheT_t9skCOCEjjS|rMAi_)1qhoZIxQC~)e7Rp6 z=ipaNqdY>mgs*apxJjWPZ|8fyCPArA^d*(^0z_-^bQU@=v(leW$S41EW59;+EN|J++Q&MHX1*qU@n}_3#0nKJ147J{YN}fY5n!$YK^X~XL{POpq ziyy+3+cc`dO~4mLFAmsq%bKAu!9Br4>UwvC=qS=Ks2qZU4A|p(jn1D4kv{Nt292A6 z$UcUw7>wR}zm?LD5&PVM$D5*w=r; z;Dl%?EE;9)JzkV+a{?aZ3@In^W=oyW+>e@;Z>f6Tos#ihM_R!QC9=yMc8aq0cIhhU z$q0%jEV4U&9|=(}!d{2A3$*eHR1C(Q@+b86S^ZItLk?^R%_WEtD1AK zpr7B4>bgSNSjsQboSQKj67p@0R7G7bl3nN2w5Bhb^PZKd!2~4CTnIF@w7I zvFv^6t0wbpR^FKuUx{OTf05E-O1d9@!XnNGK2xuU=|b&RY!OlD*_&8VWWDzG`XpEP z{!@-3_LIeySz$_d&zQc2FBhh&C6CTk#w+GkHo-74uE`y6SHbVF8shg)C0Jls!r$Tb zCH3x??+zV02{3Z2SSp;3C>mdUGFQ=MQX9TDN$k{Xo=)FvAV53prs~+K_RWjRy;LsE z=`U>#I+?!XGa8F_PdE1%mAIyxBcqiOd-Q*0o(O1vEDB4JKhsVjIIZUa0Xh#)bc~3W zQj;(HWoN>vGKAmllJ$kJ)a{l-q)S$xkP`h{_7s; zcjG>JM2<#Z3kf_wju7JG9OBC{zkPlc9=Xmh3rJSPvO8Ant&M%ba;F$7alJ3x zpX*xP>o}}OusQb=rjPux$36x5Fbc21n{-t>ID}6YheD8IvUf-t`WWfq{QH*PZyI0f ze_Xu_TuXoaKVIpI+#(bb$(^m;NolLK+Sb;64PAG?*Vfvmd+vP*xrS0wL_!xySJy&{ zZo23~x=M)>-Tv?S{(ry!@ArQ^SlijzIp=+QyVn6>Ks*CW^x&|_b~F#Xt4slEuB?QTU^+)BK|_K8?j!+A zqawiRj^11WCJ>kgGT^6V&_#h1g`kpu7) zA1r{71)QATFsL`qK?;%|$&MgHlBx{F0ghD<3KT$FDC8t49b}UMh)0k>3~$d`RA|I5r@XRm)AhEchQfi42h5NSXFvyp%|y zdl<_qm_h;!}pN=cW)$*@qV zGe{wD0F0YfVo-bO1#^Xlgz;QtTp>pe32;X89EEmdm>4ESBV4geDVzWb?L$25ad;wH zOh8(NFsyJvjzkj9%aslwH=M*QFL#P4lobH7$S7o25grPag$hZaa3#!x8{my+Qi$qx z>wqR>9R*m1%1vlTr6_n1k|Tj-2MWT3LX6tTp@(=mk%O^xv>h<+&;fww5dhv}hz>qTE)@WF;~nf>!|+G|jn9D79S~Sb5XAu*Cb3tr z0T5WAHx&UDYjD#CczzFlQQ^! zQJ};|Bk6;!?l%3bIqauwo8 zRE50&q6FBMG%J)F=uyDM5*TLX3gvj=0zC;Xz%;gUmAZnAAZ(CGt%?Lmc@8iI067Qs zBq1Rn5yV>o_?t*#k~dXK!V^H06$bL~MI0no!H2kqk*KZ!*VakN2ksLr6NPZZBBcRV zL{Jv##GnF%6C7AE5Q(#kz*$UHN(GKgwO5bt;N-*vUUIx6l?^yFFu`^NDp}~L!i${H zD6FG9KM>9h!g>mrRurMol}Hcr2oXASI9!k(3QD5@A%-^vhQ{$#V8c_Z+Z=mOR4Ays z4Rb@vr5?~Q2-=&A2T>!ATC4Ej1|jVnu_ToPz=m`NECy0%z?>)Iv!NWSz}@LzG9H%9 z;c|lmfWz<0p@B;hoz;$Mr!XM^ z_V%Kv)Ki=&rF&ap++b)DK@}zsahLPuED}V;m7!%^7o0r?RHWhnrXEY7q@dmGnF6ZB zo`R-^@G;Jz?oi+zwhIgUx0Cv?nO00!A09*D;i1Ox1JE_#>PkR&ivtiW_5c{bGYl9u zc$g~+%_NZ>Wp*A;G^7JyFS7?ng=DIm5>Iw@f+DeY1R5$(?y7RNk~x4S@GlRCh_z=D zcrI*^N9gK<15ln!W}v%>hojKE9Vi~|z#I-!ah(wyRj@q~m~>bffffcX8zK}0Nnv&% zZ{iKOze{5;rrEU4iG%>;I=4AesdR6;Bj7wEv@ zggS!s9;Uz*piIH!6tY`TXdq6ALvYlaCIv`%JV9;OLtLo}kSfc@;P624#rmK?J)s96 zw8cx1c1pWY0SYG%po@LH0i2-+6J@7z#*d=V&y za1b()cor~hf4%9GEq^d9}IZ%WalHBP)7r_VFxrfo!Gg63xkflPX zGu{QpAqng}*?>MFkVpm5P!%{005d6=VFZQ?iXTFRc?aMD=NuBPo)|6^7l}QZ&9S0! z)F%pr9u%oN6VPmV$T&zO5$6UAA)v4dAD)m56d@D~5BNZNVP2d-Db5olyQ?^GPh=n^ zFqk10*@Ln-u@@I5Br<|z_U@to^1eJBJpkZws2d9#5Qq*#iadx)s0XNo2fnEw4v2KA ztnBd+jF4d08K@0x%(*O!ARh=^a*6hJiLQluq-bL z6g)mZ4CMX50gsq^!v)2EAf1oEB#PYZ0%!~e4?wkucJRVFla(|qMyhtLdIDf|2u+1^ zk^snVsy*2U2So}Yo*{uG5Mkk}7oRMUfn_>?f&`ETg#u7p;71ZETPlXJ=wciS;Vtk& zqv$f=^JKF{_7onC4QP$QIe7I$dITx0-~dF3rX*qQoncTnslxdmJ_1A}bW}KVgHcR( zrZ|}9LgUieY?`OkIm|H-6XwJTfCkYV5Eu{-QMl2l5T1*@9e~v&5CbJJ9zuafAw@n| z6`MhF-~%fN;sz&#aXcM^Tm#`$v5zysp2+}JqM=Hhl1KBFk^poXDB~fzb5vx&N9Q5+ z26ToTkeVvy5W`3SaZW~-z~ulX1i`kaD;&6FrX$})scr)guTYSJp@4_iS=|#}RzyB9 zXz>`ZHAw|rb)_6Av_+`Y%iEd2f3FK1@}Eh_g0cfvZ@Ig-c#cHI#R1`fENz>7VMBZSEq z47MEv2g(mPXsR87DR6Qkarta48A}4EfP7f+N)7}-sxnLn9Y*nhG3=ChCI)Jc0{50H z?78+}G2%l#r49%hCyWC_N&wV_9H4@Dy1-;$E@8t!;TPl|Xbh7m;lk;m!LETIz9T1j zD}6}t0I94i3Uqja*e1Gr6WpeBV1ys<=~vrh&?+5zzdK83JRg#O4xJ^1BRq|a*2pgkc6lf#^9eAgK`JC5Kb~T2ev>ZL#s$o1}hl& zwE>2b8^=oBQYVRe&=A3PNMMiPflS9!Tos_^oA2y}V#;7pPq8F~Z3oCih`^yK=QFSb zgv49sB5`LiSfKWe%tB)!p)eP<0YhRq2XH}fz(R!JNSO2h?|@(rR3JDA{!t~MY=Vo1sNJYEmbcJHfTSX< z41JO2t!aV>`+5b-`g;{Zes9s)Nl?=o9S6*jN1}VK5a3L5(1ji`s#Wau~ zK!oGDYN3wj<5X$S+OfD~3>KKhAQ9Aw z%lhYWp~=7h+j|wCIH@nvC(!AZ?%I$i3SD5;4k0^0azcd`1K?mZI2ydiXR?|T|R>=UIvEaQk z8Nit_pm-|B-c6+z0!(KZ0?2T6x*#54PpDaduquGF&%$`CO;NCdh3ZL$r6SRx2vU#( zM+zPhYlWf-)MJEFa;yX-jQXhq0JgFO7luNscVIbDJ)u0L_85v6nt*{I=->=@yqgCy z5EUe)DnTkL3I+jo23M|qLqG1I#(R+>WJm<2X_QE+7l)<_Q!GfHB5{DR{^*0s;h( zF+jmXv$(KeJ3tg|4_B8As(XkiMLV+G0)aHe5)>E)TEZ0qF9LWjP}vC(ROMU;z~?M? zgsXeihtKEY(O~bxJD}~|iNFbjcd=K&LICbSkVp+3h2?Xo5^$7+6ovrVgQtoCoEjfR z`WIk8%SdRsY&JupGdVoB`)QbWd#1gCEBoPf0DwNp?X+eC@J9s9bG+?k)G@$-t zIbacE-Gn3>j3!k<2ymK8F zMG0Yf{-ejNzj9M_NyFKKTU6Rp&b+cT7-eU17t*jH%yHBvF#{$J1WvgJ$0bKX{;ik zy^vtGVx>?X90o-(SXO}&KFltZ8sb1itCye=tA|gIk>7{0e!uC z>;M8M&W;E0*F>&z@ClrOQ-b68P?--b5M)%#i8Ky?V};1AXiy-<^<`=Ho`4?6imH;+tQc&Thz8uL>Xj4}918Hj6wX!(bdbH8fCU@;k0?@zCL!2R zCo2jS09~m2!3QRn(K%G$@x<`ZAkQEC7Uw}i$XOy3lm|K!s|a*=V*y52@P*RH8^?lE zfNI9V$VGr0*-Ye@MMD@Y^@0iuR*QiUiXFlcLju4G>LEk`r=biXXD9$zp9{(!^3SHDuz7A0 z7m=KeQ%hz~wg*T{#W_-;p#UpbtrUUZ(Fiz(2M;RyM{g?7f}T8#PR<)(>B1= z9m3!SutNfb8$hl0zt2Jiiz{G)k7+wg1u#KacB{CI8|G}Ln&-VT>Anq3XJ{FG`@BaPi;5`@Dr8@NY7T2BjCPrJv?AWMzO?Tvgh@5Z0 zT~ez)O4vI`F=Y4eZQ|bL=cB>5vVeT<|9so|pSI%YvzXn(#YQ>BqpzJPC%Uv>BC*&7eEJ_ypgS2VCi&{p{1 zJKevmCFu75JVwFk@|A`o73C#@W-HPqh~}1$N9K+YFKojYyqz7rSQb4LJm*+KLe9Re zku&|7DW9J$w6&j|nSRl`rL*JUaLGxLh48^gx@nR&+~BIul3ER$y|9J4zuYwyW9{|z z9@Zn}b3Wf**Vz&BX8TzAfrz%GA~|c%*%kr9fU|_N)qtbX;i8eFwF@EljPD)Zwx#n? z!#ds&=U;bRHwRyvX^hmT%}#dAHeTN6;t=Oe-ub8_a(8mXxX-V?_qdPKS048A6K+{* zlC_ewTimqR@N$%_a#zsH|8|{xvPWZPdD(=+Cv(xh9qEl1{^z9F4HEpE@cYOEZf@%q zU=EId+nlGk(32-h@-x}R7&>7R?%<#^{{2(@)KvIVW8<{q;{6JfKjAigW2!FbQX`|d z^mL2#n>SO#hTD&wI@MSj`mf=Z>L=}-4gnc5>2mMIy6k%3k$nmb`TH4=wj z;aj3YAO#V&eLD^YIC5PNw3Hrg`W1Zl5{wt@Y7D+nI^=UfJ{w?XtefsCH#<*ID9@3QFW? zqV5-MdfRb%oVtGuoz=G(P3tE`j5C2Inp8Wm<{ku&HmG+SKODc2-05bn)4mmg& z%BoH}Tw^=CO4|EwnO$I$UsQ>F$NQeMjVARLk|QDS;mfL=PrKjnx{{TN&x#yxW^X^m z@SKySWmaCdxa#j%li!!i?BvBg=S;=Li<^88ZZ85|8qg6R8>?0P^WAR6my@VN&Aq2~ ze=m1fexN>Jn!lR6q;FsedOc#|Ug@ps>V$%^vYD}*r@rrS-A8U2C-HA&=SYLTRv?Ar zzdNGJSa-yHP5#ieGhj;2%%_j1rLCL#kr4G9e3zhS7QP78Cc%BIp0S<%vv5tsFIQ5E z&FZMh){fJcF0GIU)$67^UC#xpapK)Ww@kE)uH;i_(*dpe+a+~BH|(FcC*;-(qi?fg zIZ-jm4*%Bk^{?PIrC+TEWnm-5(Z1XA9#N9uo6~;`ca)jwEm&24X1!ziM08fxmcsoz zf^(V$cm^YVtt-*V$qtV{a%?qc@FC~@x`2zB%PBZeukb0QG1)Tao~5Q?=aZHbx^LN& z<3kf)cSdb)TkRM5huJ49(q+HFdByghShn@P=+iDid$CV6>eD)d&Z#|Hwm56-o)=U4 z@S&TAElQ&ZJNnxkcf@~Uq-(`)`8G>R^0wG(F8Pof-Qvifrd_^&8uy6<%A++iThira zmN78AmPvWo`haMY~P_@7hT40Ucn zGrGEtn!Ws4W9yf&plJQ8n`1Yfu4B}K;Oe1WU7@;Lr+;PIzHl^)IP_-6le_KnIZYXs zB%`;>y!Xe%?<_?#a>+!8ibt_IrGMv|MNK_`bd3lMqB%G=I>xm z{9W2=S8y-=&HRYGquTEj(Hk+1!bhLvZWbH-D$G=U=3QG|iaPvxF-MGXpWv0h?`2H$ z6CC(=$-Fo9Z7a=p1%I}8J(+Rxm08q&`&%GIgsR zt51r5e13uMy()d)>a=NaN!yyH{0$CsCN2<&cT8QDpucD)uXR0eV7peN);ynee=tM! z*EBo5@9p3Gt(fS{^Z*E)5@h$pZ zG)R|SB0j+^6zy|^M~jc=NbCky29Wu+NX_13VniuRG*J; zd~U}_FJF^1(=j`pf6>wTDyv|9LD-h#g$CQw$Czsu9a!h&SljaKfbLdTqTzr0 zJz)qPe0E4%cGuyBW2P@L@8R+~GRmO+D)n_moZjJK8}6|ySE4`%1nDEIZ(E{$gRZY= zhWHe^rbNyB$=)?($h=2iP1f3e252DpYj$b}8UN+iS>sMGAl1HKQLe}9Pt^#QtUC=h z`Ph{u(Gy;K{iMqnSfvJMmMq>JP%HKYBXmr1x$YK@< zI~?z9MiRF!!{A_~B>4RKG|ne_Tj*f6;z!)VGpAdT-_zReV{DQxT>9)9VN|bSlfI#D zOMb34JUT~5;W_U{u|bP9dY;RJrZ#i_efgRJb3Rcsxhkh>F)l@3gj+&0*$U6K23zUp zk+W+f#~QrnC7kc>?nWNWJGExdmSTB()NDlRr=Qm^KF}dOkJxgUZ9*D$Bqv**>6zPM zPYBv8b@zWbJT+YQqS4z=SF3IPmt5&-X;TRVZx3%0*QqU+uA~>a3|u@=J@LGzzu?wGb7Z$=vs*OVR2y2Phdl3Bwl4SV4_m7fqhW9SGTQs}S zu)R_Ei`LyP^^=l$O$Y-S-Qem2jSe60|Bl}Nbs^w-ZD&QC=~Z1abbiR^m`w|}P#jMi zy?S+MwRPc!kI5(cS%Zz)PtQF^Y4d)Omx;pX=q*@!^aX%5`1toV@w#pYtv|S32ZG1T z8(*bX1UqK@-fJIXCHRz>`iNFk-L$tP$Ewu$7tR-_e_eKPdGr!UC@mkEx$gd`Ajbs`gM)A)kZyIw8mV%MC84O}{ma$+_1mqx*9Tcdd~SH!=fa!R4(0v) zWz}WAHl{fLFx_UMylOpV=&C^`%JYFo@25S45rfGZ$QmEuzvW-uubZNFppIHY(mr&t`Ps>rt8hEqFYh1 zaPlT=jRoOf^h59dxAJ;_Uo~nlPTo2FD#2`dJACS*cw58KpRR?X?Q2SABd3PWd)G#^ z9il$rLs|-9ELoPdMB~lyk5~F6oRa;bVn@)Z^`|Chv7~#4fhHG%^ zaU$|!!LNhgA3IJACkA$TJhZ%)g}#MJ9EgF>C+lp24sYe2yj_);bbZ5N(-r+o`aE&N zNiXN3&`I~SjNMFP&U49`WZfD?wZ}r|I}0Ps6My-mw*VU=Ek!HBUHT z-8}^qHG3}$)k#S2W+nAje)4xWU*8?!vq}hYHVS_O=|M<@FkdeXo*-UP66fAf^uE1Z zXAy5vvt2RqHtsTY z(Rn>g(o@(t5=E2Sd2{DNhOYe%;ONA0S41)MQgzfjI3&`7)8l{I%^$vLx`QibZ?Y+2 zaWeXj={GcosZPoQn)LOZ zMXwRKy*JqU)h62VB1gA)!{1oLqiM%w+2$vG|-*qVPlU z%{Aypx}8^u6YrZfB7gp@>8wmUoP;75Mg_O{hXeT*v#9lkf$9~6dbEILyyoEt&$AkY zR#;5whF|4F(3cnTstn`(-^}Se0#~jnvU0o7zIl7sm5qwT{@e#A<6QHsFH&><=kgVX z(Z2Toxl=L6=!wNQH;h`JFM4A8SL2|~%%X^Ug>x@^&;0U8`taRQsu`MwpZz{VNNdQGvf*CLbmbwZpV`FWbN3xO3@>*n{ZS zwkt*(D=w_9Il1NIlOt944Nk#r^PeY^-4OVp4~d%!slGC4`m4o6wUVIJiQR?L>Y4ET zIf>kuP#1gvNHz1Zy1Go=kxa+$dj;pYWOH-q%#vhCUai{(t?d2`K{Z6pn;e_>3Ght5;K5s19{UPJpN#BdU#=Pa^ z#ya=}a`BBu!fv%$C|@*i8(F2Xw&g-U6lW{q6;GAiuB>(+%Dpk1Ik_=03%+!|L&EaE zFOLF{fYTL$B$I10YM4txCvB5`Uy}eS*GpDa`e-+ec&6 z;emmH#H{6_=Ksu0%}s;8zE7Aogih-n`ar&T`^IHX(OWm)yToxd-M zL948KhpVb{vaR)9(y6&=p~vOv&G&1Aj*TlbX6NNI*z9=JD%EH03neL0Ck_mkwF+Qo z-|JuVU3ksn+QjYOk7i922Woa{hMGQ32;JZ`T;@29xqWZe#A1&{endMP{*;k$1cNj# z=w{ew+(hj@O5FaSB>75jakXR(V$J` z>E>BA)^pOaoBtcw@QfuX$UKE+7&5~%>90I}PpuZ0#N2pu;Y0?fVCC=bvg@cv*1cI^ z1{axJ>y1=jGy9Tr!W#4RHfG>|_c#X^8e{The;*_^+1v*nBu7Qv>4&M0u@{L5HsAkK zfg~~g;{55~P9qukTNloqJ9gJ?{=2|K!H(z8l1(4{c^nlNP4TX&DEo6D{z;=o>5FxP zc_=U_ETUuX{FTO4AbRZje#hlYPX({ny$=%z?slFtc>BZoiFLmrwkv*P_8gxLf5iUW z_`R7DEycTR$q;X9;(5n&_$!+qOTU#Ie8h1=M2pW9?h0k9pZm`@`R+>(j?D~{A6Oh| zzE4r2f2~UEeG4pOuO{Qf7^*v~(_4BI_$UMm-gYjfwZvwvZPQ5pxo`60`c2J+noc+H zL474r92e`cdwh+Kb-|$nufec4kG>zbiTEp9{J65)$>`Z;kCv0Vk(^B&9!6D zr6vI^W#Fh$siF3Tg0-ge9HVnKqfgunYjggtb9K7?=+hUl`ZUe(TW1HR#^BKla}gHa zbM2CCI^S+kWt;=fnShL7^r}$S<|W5mb9-A!n{JvXUoJ?Sw_v$x`1Ms@Q(eBRI&w{e z)&Wb>o_ zN1I0|Ty$Pp;!3x#@tH_UsmTWml()&libtNWZLI7+=)h{@j}(vnzy8qX1!HLj=Wy+& zIiEY*Fe@aV#wrU(KKIzCYlc@Y8Q8T90UDgoI9(T%u*Xs`Qn9ML0%v%%dx>^{meoSE z5*@zfFjCRO@=RnT+FTODt>TU)Z8lWC&-45sjQ!*3ePBcEI}ei}w?&CNk6o`ZJoc*` zSpCm#B-p54hj2vq2FCWJME>{5tT@5uqF>D06yMbY!ldJt45!eUf2}gfNKe-vURmU% z%U&`!H}ynU-iGo-%S*1=TTo=8Mya{20zh|~`5+ zDN%n5@3h>1^L5D|nx}Eqg;fuArSEHJuPON};l{Kg2YdgTacldG-<;g@wg(Jsf#QWx zD`2VvRz}nJ9wWQ|a7@B0(*}P18>bEF@#%H_OYg;Q*HOgYoBJ`#DMo{I-!tZNo#(=N zbA)f&R&j{zB8-+Xf;~2WuP`?iS#M~UzvoV;%f5VGB71egvNqBEk|djN=~^QS>p)NX zXUmmuEiu9txZQzrkE7d`JqZhXwOgFFO?+jd)jv1&_sxqpn%=tC3@k0|5AA+jS(;N? z{%*GPr0;US6Omzt1Af)?n?V$pj*%3G$QVORR9PF7w0%Vp@<3);JMMk}OONp+bYjDfN8V5;;< z=k2@J-2BOzZ@qmHm!pjO1k71)KmS)z9r&8~oeoikox58{Ln{@C=;1}sqwUAvbMDR? z=ib((h{nnpH8GucTW-yXK}kFeHFJ3`u6EbXl~!ol#vHwyzDxA>#*v_aRIeK4kKxV- z+We7Jw`JOFS(@>+rMN!OQ!$Gmjn4TqkF3SdCd+1)>~2@i+q1Jsdpc*DSy|2dKgW#$-v~3wf2rHCs$4Hl3IVZ* zJ(9#feK!&Y_RsP3awtfReKdC@E5e4Bm*tcJjowJrYw5&oFrD|d%DEZ3tP{A27cF1D z@yPwZF}A6KgTA!8@R-up%J-Fpolo6$4+6;===4mr=$|O8J$U43-1Z-7uK9gE8a5wg zOR{uxc&**Xx!JmAAH9P#%)U7oZ8-qp9)ww0mH*Ub9sS%hG4Um#DfIF8oP;#RvxJlP zWU>@eUv&>sxx_=b=l+9-+50+g-^PEPnI8K~xMsaPt2LQ*l&l#IU(0&JOjl^d7I5x0kXBIk7kQbk zr>6_?WoIevL-KiPNZyb4@85^k1?6qLVPm>Qn_>B`@7Cu{Tb_@jIuc-@gy=d7Pib-*TS9Puvud%iQxb-j6aQdkh6&Ta}n{&cfM5Xr`DnsAMJ-P1NZ9hjoAZ7Hl~z6XxKU! z;iCJp>$mN(3G?RFGfU5jKE-a|X+6);b@8n#_NS0oOH6&ms!L;tg0e9)#(v2eg^_;# z|ED<+t88PE^!fg5GG4 z;RR_>cAB+xVlGk>MRm*0{@i%`BM60+1SDgpY6QQ<=@25TQz#2oqtVnrQZMN3MHI8x2lJ2b;V+jf8WI%U28;v zeRp&~_s(2ouu*`@_Wah22M1f$pB?j9lUlvgI)44UsJ$O5U00|&%=XpS$28~OpRR5? z6Fj4{LNc9${l71Lt7vX=Rrp90@Nrf!n#1F{SyLc7r;FjNa3bbjug<>V zKZmo!rS`)3@)|m=jV=T`p3`vcp2|CY|bsS%^d_ie`JtSeSXbWl6P3fQpCos znwQ$)DUpA%;6$9;noCFM3*KEjS&Z_< zB}i*tm79v^jv-I(K>x3e3RorEgMktERF~|MbkCP_Au!t8*EhMgvLkAC+EUp6w*7fr z!_%kODG(U7r_r@k6N9{~LOSV{V`WnMc*?JG#bKcfa$;p~zgF8GcH;r078j)o9 zzc={)C1;6WKgaKUX^1-Xea1M$ohzp?BGZo_wp^)NR00BD4Sc;o`S|H5V@L>;}vy~<%130ekY#{ zmzpvP)9)~X4$pkQ;h3PikhU_vWf^d<&eT4VJ{ZdPJ{|e)@d{a8wRwD6{`BFt7%!+m z?Y{cB?M2m`mC(RL$9PN)iuZQEsOkL5&-U#rEGIde2%9C}WhvbWNsT#MD{tmUAM9&Y zejIOkL$GD*>VEol<+Q{5mKp5#y?0h1)h52+!sqT7b>!z6h}&$M@GIg4NQ{5hepo>H za6e=2P%o)BGvn9b7Ax-d&NY8UYYIyKT79TVjTXJCiq$bE2YpF0;!?l#|PNzqMzt zh>8r-b-tefJ#=MuIt=(R3E#x}h2F9bx0b^ff6@ zIq_@Ph;K`B{~AKz_BAAVR&oZ`ryvxN5^i{e;UPHz4I&Xp#BJ zCk+~9od*RG{W|I7Yo{v8N;agI(r*9XlfdEUoK)}Xh~J+!?oGDdb}bunTo1K5iA{)a z1H`R;i|!SEo}2pE_Q!LhYr>@MYe1m&_ekuYkE0)c60Yqs^eHp^6yDG>L$`(w9jQ}0 z)F_in@&p>%cvT7{+l(8!n`q9VTtzRo{ZmC5=}x2|cL_!x*I81e^=7jlt^T&XTNmFM zTwp9&I14e`=NrD}wtI&8U>Jx?HjasFf`L7d{6Uymu(HcJ;cSh~mN?r~HnSnx=BjWs?{VD)mwR#q z(|@EJxQDa{U!FAm@p@~HI#QasE#+PP-aDF+U0MQV*JI<%DZVi3no~v#Z5mAMQX^Y~ zyegRfz~SY-`ov)qUiaJ0Z#Ff&T(JtH$GTrMHTvdC-kY$`OrE?iTW3EjHV}X7T$MYd z`$FrLA;;|6|KCgsos$|?4FZqq@Ve&du0``-thM9~?kf=7uB(jGOul?c9X~y7^5@4Z zv*j3CP5lRY`JRV;dV`o+(sk>`?mhV)+bj?TImzDj(B~C88t;7C(>rtW-0?(6cR|Nd>pzX- z%R}_&FYc=&OaZw|v&{$+lU*(ODXM|ZD^B9OM1MF3z&_`MyM?F$aiED5_ZyknyREDqHss#R%6bZnsjUiz&7W?g z3L{)CYy9?0XLOI9Fkhpk>*a^+efN91^cJBw5WLMOt#S|8h#ua0_Yqh)VKFzw3-&5c zJEi>b$z>VbXRliv(#l{m4Qy3CaOMY|mMtQJ*P}fOvJkp^d*dR%T|tSBdzQ^Cs=vHr z_~Dx!I1pCMT_O;LS0ig*Y|S(2yto6jAQ?Y;=y+u*uCDXRM9_zUUCIH^R`S zJI7(dYrb}ELSyN%)jFo8tG|`Nl8?OL+zFeeHm@np|7LcwT{=B6dD^(OH+|5iIlg!K z)XG=am>Un|?h6batbcX=;(U{G)X%=W7W>>l402}BNoKZt0VeE|>F6AlrDpirTYL?( z(e-Jb^EVnS>NJa-2!L8}sf+!`;Jd7q`_^^d5@);*&57MHrnvEY)6pU7To-wE{fnl( zO}WKCCdXgx-TdJA1MbcfCvBl%`>T6&n}5;)%$ahP&1mKN(A?Uw&4+iqY(|%h`xZ=0 z<=o|Q5#^a4*o*tYA+wXQAr{X2qxw>h?mC%%es6Q$&s)vQH6w?fEnHjBxX@+-4Ut%{ zT9ETIH)!j{pfB!}wAM?(l_irh{z$bGx#WAw>RH~%N0{Q_z@b*-@XwA#wSIGQ zjXdc=X-_1T}lv18EzT>Jc~ke~B1xnh%h z;d`K4#?G6cibK>>8XA|5*v_^o$gk*gnQ3!ms^FnR+gd(%8D<*-UtpqpW|o8al1{5_ z4yq^e)5G8w$2#hNiVW`7CgHqtzEw!)eRn*c``O};Jv}YBwZ075pD!&syd}1zEdFw^)*F$TX4e09`n!i6@+n)*Cug9OaFnpDst=s187KoMu zwC{Zl!;cATf5l(C?zeD1pS^T`O^oT`5I5+v!Mbl>|_H;b$ zx_zW!h52{xJ93C$@S4(zA7qcmF45uX7?X<&O4gJt(LIt#a50IWTe2m5-Vk-^7;)2N zMS-#0B^=RE{2jOuz5>V{J?@vJ&Nb|8N<#)#~lxB&fjT!OIHw^HGFW>t&YBz*KIcN zp6pLB`l5fe-e7yFap#;o)vR-f`-s8G(#NRd1%E#Sx6M8$tNE=;_6zsxreE@dhVMy1 zYVM_Yd1Ty+-DNMIM=lR=E1P%a&W?Kr!$si*GoiKC^*Q?%>@XeQx?(Kj^!Gj2&TED8 zQ|~rKRvm6MKE@8!Sgi42V|(?SjPl*h)U^ae_Q!|3{>EzB-6=n)f<`@`0SQL zk}BGL-l>79HwB`Kzh&0PKE}jBzg0L6K4158Ys=VN@46zx+s4nGo3dYA$V|3>dhE=K zklvDwYv0(?$_{3gU#1&A9{)X^5)nHG{QvLr#r0nvZk?KL5CzWN_&yqW=LAtBi&G<( zFIsD9vpeSciO+HC-b7p2xlWCB)BO`SoohjQFk3gCrt6JdY&oLXE&fsSY+<*J!;y9U zYbV3C;7kY2>9##KDUj&G2%EiD3#MqlU8%_E9p$*xb5CwopC zoX+oDyI7(PSv)oE&o5ZvU*Avl`5Jw4Yt?)x4!yrD3jY}J?)XL(XCW1lil)2fNEGOyP zHS3bgxB2YPY1NS}nsV?pn+$pzr`7z$INIRUd;ddCTj!M{R*XSRex2UaUPN{ncg?bikrSLlAXW z|Ld?>kzZV<^Sc^;*v4xMRHyuU63vezzD5P+o{fMIb`ezN{vU8TbLQ__Y3y|L(588A zU%vHSUUifZZ?M>F{rs~Xx;sgD)eU)Ni!uNn?iiV+k+RIzi@{1liG4p=NJBzKK>Rx` zYIbJKvi+)VSsL=H2W4Rc=2JL-t%=Ic$K^7MZ-qxH>3 zGJjcvXs68??evv(6Jk&pV%HQ9r z@5Me%&18SK0|yKftLERRuqaP1uZ#+E9u016#B4h0^m3pr-XD6!-)hAnP{(&BV3DL- zaIkxixPPb2-IC&q<`FfmEDYUSs5tzBQs{6;&Ky!%4e z-q{}?JEE>?>}@#mJ&HSW#r%11eoMhy4)w=w)K1&t$$Y;YGscG8S&r-YV%Rhtk~3(b z2wzm@ZoDfMVPvyxlTF!9!+gPFAx~EBDDl)EvA%mK>c(2C^Ddg9aoN0h>fqx@!5iBh zzROKY(#i+Fyu7~r;raP_Vba`lgK4xErkW@{-goMAUGqGp=)d~z4dd11GdC;>52jMT z{6=?;DmzE3(n_2CV;dN;o|$o;diH&x1oD3`NAAv-#TTr5nRe87{KNxUx{u|^o10vq zAtFdAO}XqE$iZ!y7D=pKRb&r zZ1Y(+T1L-qEP^8SMxy?_@f#R;SaND}K0PTbfAKb^&Vq!6o(&6DZ4M3Uc<=VjRyF@% zg0Xp7-V&yZSsUc3-VKe-PpXd^|*9@55G|I7JDn{ATvObQSEsN!sI`_zU9a4gn_nC}^W-n=oW<`K1wXv)cIJ8Lh!&EU zMoJHDoAgJn^v_Q^>=cu7Q@k&>zItA;qLR_gCNJsH=anE9WY)gB{dh^S4kyd<3jKal z6})i5A5J)S;=aD}{=&rfg!uXM+h~WBv4vTVJ~!tuU#%W_9qoJ8A4WWuaQsk1+D7cN z^vuTL-+@+_(G;z_29BrBrxo5^UFh8HfeOSp`eSPYRLw3%&D3?HyRk6)Zl5zZOweuy~CUNZU?RXo-9+!HL^G|#4 z9dTMnBek_K>I=gqMVdK*hu$wWh{r5hY-y@!7L5k@CusjyGjKe8Q)2C}=}&hGexHKX zgN$J)!N_grn+w~YMS%)|#Bx~rmDXEsQjLy}mi0@^FM=4TbvCK)RrE$tV1-yi2%joq zaTI6ljE*ioOTE5KQS7_)T!a63Mnq++bm=Sp(oF^W6BawOuAaXoZ!GUm`_wr9#ny_U z@wvIN)x5(EoI}So2Bhnemc|It&J%Cm=oD@``(JEYNWi-Xj`r(5F!1L99wv9?x}o>S z;454si*;Wt^Q<);s~k9g=xzOqOJlm4*zvPC!o;@?g>I^62iFVxXW|O?OrGkbxf-^e zUHR~d_HkD{WBm2rb9=N-xEvAIAU6#c>)(z--bJ-_H61&-OVD;EVZGxWS6t$mig;*q zMD6x>mPo^7eo^V9$th*Zvt2=!|G{?r;LoV`Aiu7DUJ;8e3|OYIy?^OMxbFW0u0T=0 zK=Q&TY*a=_UL9;EH+rSVVQ`-`VT$m|era=~Fz6+~M^lFkgAu590V_A{Mp3B)agk<> z8rBSd3P9T*sl;N$`4&!sHbZX@Cy~EMBz{WmR6pMA&dGlcphHAN1oUPr)@<2_g7QkZ+}w;L2G*{gV?hWmr1mt$yzwI^W2YVV$>7TR-(Dx2FMoJIGiCG$z0%&-xp0 zydgN%Z@&3v@uO@={-oxJskT>3VqX0^ed-oz(3vUYGInD(O7KnRzKMUvBzJ=PW2X37aCa+&x+fz`C zx96?Fs={hmBNGvAw?a{>p*SmG(|Zsh`GmG5DH5D658R3Y#g!hEJG`iLcwyArU{VZ- zi;Y2aydB3KRWRvIaCmA^P*eer><1&eB?4Bf4ke}Ku*b&1u6R&VUV}218~rnqF>}HI zC?38+)IhK35M6W-5g)${IjuJ;XWj&>&5YPMJ8U)!)@J;BaJrlV;B9M` z!Lnu%YDP>#Mb2m#C7@eU0+N!Gv1nZ$4wum8%@8jhL>j?(0Y&G5PSzvBY{by4RHSsb zWB0cGC@-#r&+CA}L^B9AR0%$h0-fv?XB3&4eGwIB!=|kVk(!o-glH>PE?Eb+rv{SI z0-H4oid+uGt3#Dn55?(4gjJ6r*#lvTvEoQU1u~N2q4Skv$Bw;lIH}<){)1DY5i9UjwqmyvpZ~@BPUif4k%sfNoeFncx-UPjP zi_n{OD6c4hyZk8PBp2+86IMPKH2+HyTuv9fE(au^mlA?6(vC`VEDEa3&{>mUk4c2x zU_z9^fH4CTFrjZEjFJpluRy1m1;BSy(Ez?3Buy=spiT;b_3PIQpnmt=cLk`?R55kx zR16z7On^IcmGW}}-!<1Dr{1Vq^s z=)EO~QXGg;e2DTmVe>ga-Ob^3puDCMZWv&WOhJ)HhkeCv9IK!QM+71xB9M|E2a8RD zNwUG|sYYR8DQsq-U$1mT7$c!bJgD`d+Tnt$x*GW<$B{L#7pCQAV*9$SSg|n=r5+&8 zWU5#bf=JBiMhi!hh)L<5965I@trOK|$YMiOA0Gfkn&KqxhHu z(H1j$r$wV%LL^KE6RKTK95_;f!^f)N^Z=1o8^(<2jc(oIaokyh)hqK*a-(Oof~%}E=ob)%rr=nL70Sie!}+# zz1}2DIxJgu@4=!~TQH!{5cC_=6JO2WjN`HwanTW&kd=mHdjxhItHFvbyTpdAM28{;)UH}hAlEu{Fp3eIGs+E6&J%%Qw6u98XkumUZV|$ z^j_Fm5N}C<$*M3#zJows1Nb&a76{F{F^yFPJ9Zmr zj-l3n>#euq4}bUrUV7=JI^bu$!1k#1Q;XlYaid74-PW3La~eDW`u5vz$Ft8qThGkW z7{GI0p&rz>^-|FE;M2*duJPd2uNGnMzG^7ZY3Pw)gH*X4eIjZQPm8X6(z;EaB41c`Xr;W z%0+_(%w`ju4mVb9-jBTf`MCDNaoD_i3l=Qf2D3d1L;5G-WJc8_+$@g7eQAfmJ_l!hyX-h>wWHWiy5&+E{_g!rgFt zT!@NGhGg%CHCv0ZXhj~px@aVIGvU&6Mqt+G-(zT2Zwwuh0ZDP8rmPUf`8y$dT}Vvr z4O@IVB$FK*cOS&p^VcFdu{S17&c*x{JA^E9bNazqU5%rAj$q*6o+x+uuwmOl94)L8 zrXX7Ic<>uxFuDxrW5=e= z0_fcqBXr%)d_!-MHDOK3ZoMY3!i0EhgC#|-hGCN)36drsF5rf zHnbnoQxmat{(M|8Z5;Zf#-MQZd~AF51Nf>>kkOgrV$lD$zrhc?c41#>9L7%`Ds1oH zFFgn+=#uGzPl<%j;Dc51;3wyd!LDrwap2%SoHuPW2BZMT_b$WkO{?Lobix*CL%&gz zVeX!b*(>s}X;%T_qT_My*(0!e?PeUwKa6XCat;!$9voOZ8;7^A5rAokh{oWvro)~( z4DWsR19lfkh>o@6rBI-v2;ZqM&|Z|$!x%vi+%)rCZyRt7(F@{$I2a;yJ!m>vH?Ct2a}{A z!X&}vDT7pX1gR!B#$*k^;OwC=+U&vw)35LQ-D-6T-6;7!B;#md0hTWQ9=z+r~mT_k`trxryI}3p@07qC7ZT4IOU@gr(&xd zhm2kWalzCqeDL8c#6(%~tIH>2-NS!E#rAy--nVHi5 zN{kLmZoj7;wbE`Ovk7(gApHP!R*C*P_1)A=XJyDivWxsSbSbwasD{$ z%{z=ed)MKHt1pDbbqHG*eS<281CnHg0WvI6G02{D5e}3&@%|SJ5Eqw;v(Fxh)hoB5 zy0Q>A{A@Z(4{XGi#j_Ei_d+jO1;MFgF=O<_S7Y0*qxj#PU5HIg!7pZx!B^ib!szTY z49e_*&8z01G=B?>9vv+D2)K1F*wa!mXv_t0x^4Jk{wh=|7EC%T8w;0i!UdCu!&BqN zj$%@2=wa2lk&=`MuTH{;vsdD{hi452SPeQD^j`R?^AW3eV#@F=}dq(@re)BA)w zX?-fTwtMP>ThdH4Z7kb{4p?c6r@cAQ)Dq}1Q&UqT%owy$-*eAB!ZxpJ$bo>$4MVlN z(m&lJ001BWNkl+FThPYTWRxewKOU@nx-}+_P_3o#QKJDd02VrZ%c#IyAh13`; zK3}*E)r{2j_~4W2Pm4p>f0N68y2Cm{4h-5;j9IUz6KV%2?KK{!G{>kUH&5q zt9+O;c?1@%*osM`hrs0XVP8=ReHtN~ZRj2yDcmIApS2WKvI&yT1gk-UUhhPdd<=uq zyJ6b+aWK;jQv^lP7YERbID^`tGkWS1xvQ~s;e6CU!mRB_VUFpK_{aoA zTRpfaCmmTSiSQT{FkGvHOz;}nSR3Pey+g#$KKra52nTzRP>X%=!3V*EOa3G!B?-V& zwRGCq)xaVZ+*MEvH1{;-a(Jo$A1W6OC)u1Id|S)8`S$!F^qck;;{Nv+!j>@v-J*dE zqNj>a0AEt^}>dX>6kcnIAZl4e6wN)s%Vz*(0ASlz2bph=fb5I zj=;ek$FOhva{TI=E8wj4xRff`vBJ}A$62+BHy!Fx7h)NuSb1oc< ztsAzW{Ln#Mf7RJ2KXwFe_i;qW+Mx4VQBhWm!h$0hI&nHSZQO(p=j}seY7bm}*;st@ z*MqZ+wXn{rljmu|2Tr-o}%3m~(UStu+m)y$9pG z$vOD=!>`e!dkoGW-U}=5Y+Qq{NX@{;o)a;2)IfAkio??H=Hs#pCc(066Y^euwb946 zG-nXDCQiVZ;n|3{xG{UhPE_m6Fi`6i^Z*_h^*&s7@mTENdKCNeR^!66&qD8X3k>c` z=wN{?OYrJkaQmDvTDxJ@>g`y#YBOSzGjaBXqp)W67L@MYhpR4{jFj&5@+pT-azW?O z!{>2BHUieD7`*%DN7!2)3w>f7uDRkYeEs!ejP4bWVY!1L>AmpOlt7aGTtQBc8IQ?KK690rMoM2eTT=11?x6o*7`kg zntLK9HWmqbAI=`s9V7ZB`Wbuz64JLfj%Wbi-V#2I?Vr&A?`ImvN8fG1tIM~eSFb@x zN^)bUr4l(klhCI}9~i`8R}-aHjrTCbo-TQc8(v2Z{x@eKUZ1lOCEhp;8{7-gW*gj< zMY!gwX*hJG5FdWA5Tyn13vw3D{6d^(4k5MFfpn# z%BaWHGbdxk@=eIkKL|;##+4ULLUNoLMx);Yi7YXU2iUW(1Ru{@55<~-$OIdvP8*3m zTlZn@vc(wCGYQxH^kSIAJs$Cf#K0p#Yv8KJ8}H7?v1%I<5+X5k<~X6j=Vn-tJ0uGR zhRP}q;SQ>oEYL|7Ku4|@1umZ#Yd7t}!Td6en=~A2*YC%W>~#FNbq_XeEr(Cf04Ete zlM^v^M1Oqw&0M%0Xim|!<1q}i1M&j+QPI33!;MEKQfeRqa^8nnk z4@Q&%&JMsCf1$h1I)hJTpF|cnh z#M&ZIS$r5b{^EQ@M(FY5hJA1=Mi?wcjL1nt-liScxobBrzhpZ8^}_o&Tv(24ub7S* z*}ZV^g=bN|z5YRKkDpzOA5Cf4eXJD8J-TD+@PT;ugRih=-FjU2vx_ltNDu7ieR(_T zJwgeWUxp<$R#exRku$U}GE$N-=d0P6d{#EH2Bo8B*G_DC{*`(lZ;p#azhB>gkJfBN zjjlJQOdbuls}$ca-wmfiDhhhiP?lE!UB>ufJrQX& z;n3j{Y}&pb1rG5GDwe6jysC4R((>osLP8o&`n|5RE>J^AFdk|q!An6s17%>vb-7{bmF$aFKF}Kfy z?Yj=5xWbG6S$*;C;%zWk3@9oqMOlRjip~q8q`+#BVYix5QeFwCVuT`@{2IK~fTRc~ zE}bzBQD%lcsX3bXoCx-s0Mh0Ybi;l&QNK4%jmL}GD>mTUb-NLh)CVS$4G|_iMrPP? zPHqbHtW0m34k{YJcaWe@M>nU+Mbp`B@bsej`#ay^tKC&d=++bcG9odxM+7DgOhJ@E z65cXRg%$cKY-)LH$xQ+URW%O0^WInZ;QI|IF~%daM{jhGi$h7l0SxY&gi*Nz#FyA& zGN7{RI5uuC!1@h4kdR=LD7j46&A-!fd&5;$F6bWi?yA7Tm1~60yvZQLOzH%;13l7`5p6d^mYpJyD>1nzV!Eed z#iqU3b)b}F6_5-%I9(PIuVA9VN%lY@MSEbKW4U&vVlOAz48B@pRpl7mO^dX6d z#2@UXmSCMgwQ|!fx3I#2SHD?`{7M}nqT*pAFOgA?esMZnepY|cih7XW5tyI>d`C#R z6ZO&B!_wB?*Pf!GS>e$)zs0OQRWRFPF>G)u#-&AKdUgupB|oihQ$Z&}UsGtB;kVKQ zS#jdV;;zD3 z!}{TZ8RIc;@doVJe+WjS9x1U_B-@RGdD7w3q1tPL*JMCKf(;`E^@LpIM#0ge$Qe2i z&%N~(b{;*BfqnZR$?AjN=YeFlL$DJwWXEWS(EyAb)(1xp=fmT!L{`>7vhN;G!U}OgAd;O62nJjW9;Z5IPUUb ze{q$tnHyypR+9w|7yZM1u$UuYH29Fz-Hv^`^Raj5cG%6ph0`YEaIqU@)ip31O@7k} zJg9QG5FH-{vsFTr)d-_3VZn+#94b2wm)GpqmUXn0+r%cIxV$jy0gu}$+F+anDT&FQ zLynwyn}kHW0q0E_iYTid6pue?hd($;kSd>0-u;iS$OE7Vx7fvNHsjNEhhRy_5R9N! zGx>EC^oiBs$|+fXGPd@7=!4qU0KQfrr%Lq2`{}w!FBp2by!hga!sW58!|?+nVby5a zwtQY%3)HQ>uPw)3uPthx03P|zJj~it36G*jcHd-VB}d|-(Y=rvZ4i{ZJQ!5@!g+t7 zcE$TW3dwpUNU~FyE`C_D0ndD}9J|US=q(oXPD+41Itn`v9K>;#7bdF>)(ER$k)&r% zYnYU+qJg9NM8!{!a!#l2+HRAje^?(~tmmxGjKk)2NGQN+E;-D5F!Tox=g z10+d?g^8tI+!Q21nn;HeCg9kYe+)}kZpX$Q2hl%!2>Qm^FltZ|tWkPYdt~T!7D(i2 z*SW~b3y+)T78yGZ9KnH7Krt8~`6>}*FrjaT9aggrvPXu+U=%dJPL~Vi$E(GLYKgL= zu-uLPM@!*QAiQcA4CSXA2kdGXwgx_#xb+mtZxU5Eo@ca;yQ9M-N7n z%^C|z-$NW&^yOy(4kihaP{ek-ZR^vXY9R)(Oeds^4F=tOD96lNG zHUq|FWukvKD=rw`6Ny%X2yCiL!Vv`Ub)4a3OZ2+1cGU{J`^{1;+Fp(tT{LVq8&Z=J zP~|8`ad`#wCOh;d6S{Yc722%3#*Ngt1lVjw5iE1Ks2Y)G1ta<e24+DGt80?HUk8Ou}jv&>664p=BaR?(&d52poh`t zg(Na0Q9gu7f|K*C}4vJI=u^#(b0&Bi$hIiC92D7;C0fVC8I`mqqy3G zyaR<8G<-NLdKnhk0~2Z1Njzx;A|s3#kdcZgvlSci4&iuZwXkP<^j4VkIz+&Uin1!P z$p|_#g;|zNNJxx@7Yg>}AHl)Hg@}!dM|4~abS4YDBF(Os*ip}v@r5E$oY{$~A z`OsNn5FHUCi0bt4!D=yygW(>L3a&dR8z$jJqb4S7x2InNcvS*{psD(ktN!V%qmqR2 zclxn2X#=%$`l$2TWtUx6#|WwVtOwE%G{g!?tzISFYK~Qgwz@ErSHem9QG$ck^{id4QQr|u*L-xAi zayhVc)sOgi&PuG?TZS@^9(scn(UGxmOF99{W}6kV&xq)#DD+5A5TWnRN*7|Hqd+2Y zouWr+g$%oe5tt5fh?mkW3InryL2uAw-~KY}-F*=58V4$hN)QtrCv3+a#SNXuh%Ni` zaipRG-IBYbe`a4~rl%lhP%L6C!0OG1aFFC)ZWG+@3g~?`kleLz1&SMGj%w^Vauhu? zGX>RfT0$hoyYGd0LM znDqVx9320caf1A&)$20*>zXv-oMlP znck~LnxdIeueM}Ma*+$zm}W`>gd`Y92qYvo`4aBE`EG7PNPy4+A%yS|YH(;VwsCK2 zRvER?sE%edy_eI=KIMDX+H;KJn*<(lB_1M;A3fIS%sG3Xz306D^?%p9-dA=rd8Zqv z-HO)+UZ;g3pOcCbFHJQ;>MDzHinXxp4zgKh7a|OfPIL6!B}V3x;48!F3E-5)5=pPJ zYKun#Vj8?z-h1Ch+|m`W+^{ORnxFfB^V+YbW(vU+Vi{1FxRk#a+#lu1V)r{dJp793 zmi$}6JyO8?avJ6Gk^IYFy8!&JcA1n3(aYTZPC6Q@X)Uv|s?x^#_6F*z%GCx}_|`)3w(!nsC^a>~@sr2+ z;d4hgJdz=j4`8$Au}bn!-b2RgrKB>TDNK=tIQ7+4RF(O3qB9lGXoQ=^DalG163IMH zo5bPC0^z2$u9)f~CuPMxN^6Vxmq(ssbSO;FTY=l@B$ZENV5B*YAIu{5b{aw%Iht9*4fBlAC!Dkb!ac?_GyNke&% z>IxTIwyj}we1QXd&yq3nI^nvQGB`anLg%_}JT`}!awYb=RtG+dlYqlQiQmTNb*=Oc zPjmXhILS;Ni$~IutauEFL}EgisSHziY$q9R-L{rkGC|Mrev&CW>712`nMqt8hgu)Y zb+$-&OWsOG0A9?#)Q3X;-Atd#B*jopFPu_Qb~{RQN&i5;cQ{-)oHFDT$79PXe=odR zD48Ra%9F}V9)JnhvhX;BnzLEeiB#jZWzNECrPh<>cOKY?OD@8v6a#OC$t#V&I<$Ae6nOGMT?07E+_{;rk zeinfLdA(?U*;O=|T#k=^`$e8QGp#g1(vb0TD0W&XcG)TO*))uyHfW=(v7EY69}b5Z z6ulUUa{l5deHW&CrmX{e#Hv{)nE z#>S^8D=t<}K9e(uh9dZ#ZtTK)OZI6#NljIN-8(mGgx&WZeiXYcfXxxW5GPFXoF5!u zES8{Uc`H7lS1eHC_uzNg=vq-jTT>0s@9$+Mk|vRpnmCVBl9hy3GQ_et#bPAF@Z=23 zR&;99ud>L(J-4ml!2aV5&!jOdJ}lOZhHgl(wW%z!5sAc!C!?Brly^EL;|hx*<_&rB zQk^<&O5+5aPMXVn6gx9)THnRQWQc=@PLq`(seF#vc$&V^3A)#=*1m^?bqJCQ^DUH3 zW2uMRZ|-7#ASLkMc$BeF=P1x)+BdsUxzrmJiGrC(Rc=j z(~ZsUV0wBIi`_z1Lmf7UM`HlhIX;^|-B$ zCAi~q+kt{5!Q~$8g}{$beBu-8B`;O}zeg>-dRe^Qb?_3Q_orWdf*1PdnUAMcwPDF* zlmoU2P}m)~BtSVG!I4eiaahgF)m)ZDJVq*=A(a#Tv{M0BKgt?FoyF#G>YtKefSTGG z<#ZF#h;s4)pGQNx=jP@$#Kq%w5ebLXPB&*{RevwLfZF;hsw@3e6nklJZROD)J&V=m zLmce0RvQ;CUSw=~imH}2YOAWTTe1p}Zij`I#wzaF)z0Kdhy%y^nO;bc5{E-oY2@(O ztXMM{lJOV|ktm}xb2PWE)Fxt0nVWldt>WCdQF=}dk(Px^fXX6yrc%vHmaGJQ2yW$c zagwwuyJV*d4KEzUk{m=J&}Fl-eZvY(Jt_-&IDX<1r%w;+dzFfNA(`Wh0Q`n^I3*TO zDqE{$+gfp2GHmEv#+tSY7Gqh?^pA6@e+0QoLY+yY*DSV$@`{qRxYQr0+-v2Q4Q;qQ z9-iHQn)y&%RV$JxCB1^lsYz0q3^nzQczu41OxkRe+8nx&2@fy)l6npauddm!R_t~s zmTVfQsE8yQP_t#lLe0!@mFL<;A!U zzHS{}$!EQWGMeie;4iO^rDA?Hz+Vo$lFW3uYNb%^3+T!sP^i=kuOWdPmpe(y?^a>4 zc=c}J)h?5lCngoFbw!bLIp_YfTzTBNKmsueQ_nVwY93qSeT!u zx}scjO5@Qe=~PM^k?CX#r_Dyd=U1(`kxi>|q^`1zEo+*wW#H1#4E=+n7y>X4ASOu{&Iv>Lh_1 zvWVF1lA4t#7LDluQEhnuufxXdT$p4chb@~`zCN7J(l<0l=Z5tt! z@Hm9mHUqjNi6nVhOr#nXwT}jfOLNsqIw$dZR-72xES6ZstVI@KD-Myny=hsq26@Pi&SGC$%*D0$)YYpOiPQqUD6FD zrqC`KuyT3qSaU+}*~rR`bf~6O<)zttMh(iWP75Vg3m>>|6@HgY$X=r{R+V&K$6hqA z2KZNlrU3HT*qCze0_26i%kO3(jY+^-f;tL0qXkN*(0sid_zNjbujcGu9S~9g_{&`v zU%e>&ES~DuJHV$i@F!pT5iebsC2C}eB@J?-0Li3P$0wYrJ#XN$i{eInM8M?_QXKH% z&dVZ@qOPHdY%D@}Zh?vEIl@^RmOy}v%^ZShC@xn}ciC;s%+63&RzWJ2(n>p%PLj(c z@k!9OuZT!A#=zJx8L7l=7F@#d+R%wt(Q_m-Inv4$*mOY0ViP@lB^7~y4$G)C&jPKj z%b6G-C1=F3WK$$_68dQ;t4T+B>^5WO%YL@I@m&5<=y`g27@w4jHBPR=`+l$v% zZ0>T>8FIE9MV36jbN^}r(v!L2MRRR9_Zzs1<<9@dbxr|c=iGpE*f|NU3t7f zqgpKl9zw~>gVjjS!DTnVMT5p0nc$ zlwxr>aXK7SmlRV~8pLVM5{ZOyd4&$hWr`k`hqwfpc>JdIEoqEIM4OK;r%&k& zp-Qq6SRPwoWOx{FAV6tZ1zwL&E77s>al(->sbmbV11if)DK4*7YXg!=EJi}JVf%*0 zsavr^>9B@UuU^}D)~Y@*atr}%n>9<3$3{a{3A2k)=3|hMsy<~v$`Dq>001BWNklm-e>#HmM|BKiEieBnx4X(cK0Y07KkH7E(o;yEBI3s&&8JaP0rlZQm z8x|W`;hIGrmo>0ulBy4vv2_zV9A-6Y$q|n(;P*PT>6gt&Gt!OI6QrovONq}$J~2;d zeim<_jHQp{ z8*YyuPoN6BH$a9op_wt_i!%zoR)?4B`sFxW0W!HfQzK{bdn|Zdc4p>6l-D-n@t0uD zSrp(ykr>0%Gt@QL6JDIfZo~;XZK@kj+dSC)CAy zhjf&iwr(OEOOwWf#o^(^$>S`}Pf%MPq%7dk-Am(&ZoGkVa)}h#cvJ!Yc>f^Pjg462 zGi+$9W6i2A<|0WB^3w*_D zFYwZ_^MsQYthqD+Yl_y!YD&wBSx6f6o*ltz^JAoQ+83FfpU03vD36n1YKrx%mQz(- z#d8NwGM{u)Twcf6rL)wQI=FTHa_XB}_}J&ZN_q2YT>cW0p&3eTG49&hMM-r9-+1&z z&X2?imQ*u*?htF12YJiu?j{(h3pG=Cnd{n%M$D&D8Gip$|IFS?Vd8m<^50&PEGu$QSL)Z@ z*XUe~2tF2~3A`j|Dzej1S;EX>gplDRV)2tmCdeiixP41E4kN20i#-FZCZ7j)ZtB2cbz;P#EQCW0jEz%USIgAs06R8zaMzB_LV@!S-+Y3y zhIaj#nUV9{vc8?|o7Zx2V1yq%y`Q4`HufAos@4d*Hg&Lj*Ug;1FvM5C_Z+^8CPqdE z@!8@$c+XC)VqZRdlw)UyXAN&aRb3^%%mR09UB#-Et%OopKK8d? zrJ-#dp=gX!%Pe=?w2GTIu4Qm)fq!}GAQ_vF*^xmutY~0Gb0r(rc60pn1^(sf!+0y2 zG2$WWe0er?x3FeSCr5hw`OYKH($v0=Ova*di_)w{&ptt(%F=P4c;~e1}mZ zz<4M{O_7t=Zf)l^JGL-5G{(0ddx3ngfs?0BQB&gKzFXFC=hkjcpX=xEzxO z3BLPWFU1X=9PK$kYmJxJ?cB_kb*p&l`91Uv&d}1inOHbMIu_F`*>j`gG&I*?jf`^F zrj>NJw{U4{j=%fHBP{C{hsr6cZBcI9+{N1Nc1~X!=X=i{#ucn!cDSF7t+gy`uB5B8 zjRQTW*mri4>6n$s>^LiHyzJV#iq5uH4j(_wkM|y^@kj23^A zdv4oAacO`biVZ}}MOjrNr;fbHmR0p^+t5vMSry;;;nOUnEDG?K`p?kaT*2;}SL642 zcp9K7qy6l>>$M~;b~0%TNf{!`X85hwuBN<5 zB&j!=tXJ)Gf8&M!^DA(rKz*gpyL$H{Pa>A&gMalc_Kl>-*z#0*4VIU<+1}a6?OVGz zcls3He_{{L>Q;{Qou|I4m|g2y*|Bl8PAWhC;vtr=+r{yoV^kM;*wWd+s*Wc1A3nkh zM+aHG{ceVbE>Pozwx%*xtY~8I-lL4or>I)C5+j)-8Ho|m3ce4E#h|UWm|bgI+0d~} z>5XR&oT7c>UG(;zAm~P`>&_Jo96NcM??1htTkd**1N-+;RpMgj=2f&cRnv3y82gU& zvU%6t^bd{^%!k>ys-3E;O0D3Br(?8rZy{w^NW>E?L}OeS8l{ zaD=Zu{5ZSreIqX(Jfucj_uYPza^QV^XL;nQJ#=l|#lFMGX)dvI|Lt3-D-Ce?#A%+~ z*URP|ceCfE7ig<5WA`oVsHrMt?}5V{KR3#To9-eMF-XOe#G?_;Ub;k}vK+s$$Zx*k zPAba+%td1S`KSJ#miF}w4UJLh&GC*mzlMsEAeSa)_~%ET!|p3)`1~2xtf=FjyS7tN zQBMEJ3@;ox!^B*Kneh=;)Ryqp2kxe_qKtvj3BL9HAJe_*7A!U|p+!**50&>-s8uqtt{q! z?|v&TYo6ZTULO9zqpaSvjfv?6T)8Ok{*^alcQ|?M$>-?1Fv_~kJBh?IB$Ebnp$G%R zgOn9JX)O2frh9i$8aPM^ELm%si!+E=aTbYCy^6(v0M?za*Qdf0#P2+!^9p=6sBR;o<`Dl#qKlTi6ZyAZ0D34OS?(UuVy)Nd%F`n7iL*C{h zx;RgHz{MRqHmmM^F`i-H;gdw;X`L-7@j1Bnj#~)?{mh19ymas=D^{+<7p!D%AxbzB zCt;+BEKZV}K0`}=wMx;YUojnuVX=wDLxN(ThuVrDR-2vKg(!=Wq{>4r`7A!SjjFOD zRXB-7K`0bg^^GWgd>%X1mE~A+R-_-CusG@3d=vSy<>o|gF0Xz%zjoJZ>M8=Jisl*> z@izee>LJW84aPA6UMO;{~y#wVsZe`$)+swQIb2o-KS z%a+yXd)PLCZ=M5w4NX7WNG?p#cV zwM6ePE}s^QNE7W?EIEDe9+yP%iDiOYCsl1ZF*g&70#iS4i0h^ZHN{*eD^;{SCQ5a% zI$b*RP*K;yn)TZVN99_@h{VE7j9efwbAeLvA5zBwyB=R;km?(g%cy~vWb?|fm-&jO zF|it!StPbmRF&At2oS_3dvey;~oQ@31-wQhNytL{}t$EHOZYVNtZ`H}zY&Ky|z~miRd?mE5 zznRL)29k+1kywP|Ck~N}%;2*ac*V;Gi|V%?50f!s*z<9$sTe-HXxC+ENhF=3O&9Y3@nsiZe91yJk0IAr^q*=Q zAk)Y4HbwfWz-pR)$u*E6H5pox0W3KK8E7l7X=3xX+lVG|EQZ5OO^$Nm+;M`|1f?Ys zs12D+Ru@*QRkZy&(xhN7@7FGXFV`U>_eSoMyg$HjMy8?;9Qz_-?f&8>f#%LA3w)u`o>c)y8_p@7Y$nF{Qx-4o^u+mEDTkFv!%b3|9$I zOZA!-87d+%%`-VQLrceMn%mbhI6BFNfqtT)864RNPK&vS+3j+Ci~7NsQ5t#dE}xpV zrBexggI2pk-+wM+K*qq~lH?{CFtg}6$$Pfh9D2WGH)I%c?<}O!2Gxzr*>KZsL=ri* zj2Id`!*Ks8O1*Z9i-XFSXR}h3YpRRxencFb5|4V>71_-}xWcrnO@^+rIWve`jw|P{ z-^;bPnBGFU94@DWbSBM)TW%+?d;{?;B;!dP@OtNNNs21@H}0iZ8?bIrG*|ly{{mnC zy4Jx1p>T}f|LFfmPyaM7ON64#G`WQZMKp<~P}?k-M0DEmdEJ^Znn)$ow94W1kj>=C zCWQ*IVRyQ;I+Q`FOj^K3rXWo!RXkD*0e_2_d|656?X+*cg}TNz60roa&>W|Z?IRVL zB`8#i8f}>&(@G~!N+$GlbT1mwgDRjE|8ViVwSx`-!|=4ibX`We$=AuArdIw+La z>C@p221sg&AT6paZw!m?)SqLvMGd_&f2$|Ld zZga5`3uUR2buVDE;B=eT&6!L_8bEww#5(4|%hnnqTKN&6NxfJ-OSIP*z<<&IUfHdZVx3fBf0 zZUFqXxz4|kqg?j@ABytfzxc8OyqhS&%oO=>L_t&lS!+&<1a8=MDpdeKmPjdpN`>jN zIWWXI>u%Kpa6&^Cue1Xsn7zV-B+r>Vo_TG`4XB* zN>ZoTBjmD#6B#;IZ>F|+g#uPI65{CLmxwQn<9Awd3B6zu!vZ-*7MmqYkvD+D;Ut+h zv;wxOH;q^+*p>4aw#1>J@6>aU_bmX{KqX8$t>);- zQ%cP+siAA1GCNOo=D~YipjIpt{Ye zRu=O5^4<%UF}jOVs!C2rz+BAca-k3wi$k6MgwK`wQKH~*cEV+$qdPC5~oYNV63DQX|3X<$`;j(7?K%@G#QIb#O82h@@h+5-M)(D z?d!CHpPw1!Z0{kE2~xjbsSl|Z)eu;#KnGr@O)GM#LajEZ^55#UBDt#$p+amL0Vvg> z0G=p4)cZu-Ewd(nE{#|tBLHu(qH{e>tzBj#HM+=&!+VG?Oz2p@+vO!IRsv$2YmvYU z0dzYq*+obYMpi0nyV4Nyy;SH@@1%Ko z7d=OhYtu9xUu1Ub5;mIvya%UMC=Oj=l_C;LU5WjZdr;_oDCUaOV=hlhz5Fe@tH{a# zk@)c=yDx_tiz#KJeE`{EBvtyjddn^|4J)4DTZtj^dB59 zvQ~4_*$_W{2?mkf#1h9Y-ZT<*n90f_DhrZS{^Ck0i=^~HY+^I7g+MB0(7tXnWt}$@ z&j`De!Iq8jtGl}BSYE3>H`nUxMg@PZuJkY9IM+46lV@Rmf!`H?zc_`@7Na=3NIJZz zp&v>sNVO&{HO<}@RfZX`oX=;}R7yV3LYoMgBUPRNjZ~^;l`ZW?(@jFoRzCLYqdW;G0eGBN5~s-ii?5@l;-9^piHttMF}G>mD2{Ex|geKmKozG#iM|_ z__Y}6lxYkm04eW5DttNDd>)rW=#3nUu_W~^9a=?81371;2+a(0?&M+enK)jLUroal z;6ZoEL4PPnJj=MO-S=Sh=sCA)5szu{KmxeEX}Q* zbgtS;IGkX9ev)irfwR3mSZ!JLwHJ`f=VXB~y>4s{E5#nMY%nz|lAI1xG8cq0b z@p6}{UaEO>wdLgNv_)|lD9Dn&aih>@z{$i2a zm|3j(jHWbseLjq=g?z?P>t|Wq#0OrEB@2m|iMgCk?KOzP$mz6dzraXK%9T{|=6euo z%P=zB^X3O})ORsD6~+*Y=xl_y?d+hlrB3hPwfedN@Ym`}{{oJ4y#xIG>^vX(^DlGc z!U#TVh|*kwbTlR%Mr@)25k$9I@cX^m924*m`v9r@-5#$3pj6C7MMc`&ldni5q8zb& zkcB!?)rD5tqNWh@zzlIC$IiR%!{Q7Oi6)qz9%p)VfXMtL#X-NxT?>G#^=w{a?o59Y zX%I?CN5-tCmsA=~vCSo~KqBC4Qb@8$iIOI#U@ZU1q9cGGjiQ z`3X+<9wMKP;Zd$zdI%QN$R=}ybC1eoUQ%QcbX%kiXNB9F^?X}0Z>ce^YG@pz1`H5=Hn<8BTeKSM5)VRGm! z180v?9P|+I7wP*q?`c+dXYyVophOlp*&%4yh|Q*dH+NYD@HX`RYwtkZByF}=uABVb z>+xb_4DNgIjW`>+xiGYdA;y@wFmK)2PFHiojY-yD02cn2JmhulMMIw1=^5VtKmLxB zBUAYD3zS<79i7h!@12*5T~suAg28}t@B-Ar*9z_7@p!eO7X^fbb`(C;0zAUcn<|hz z$#hDqH}Q9u3Ru7~kp1PoC%Su@j`?VY0CWTz1J4H341-c&Q9Utq~0PmVg8j z$)q;yWC0Q6OBpG3UXt%2sNO7OS19BNR7g=j2_TNEvBp=@MRl2YzlC4n}Za`Fm@ z*{m5!C(=bdFS98+IXlJ8J8xt4`W>7(J4_-OVQy-GlZW?egVpbGsiZKMH7ON|*^*<6 z!=nJUylyxg)?*dEmw%IMF0U_t7l7A$AW}=Iv<<^dZW0URWP+CVPVRWkn>l}JlB|(t z;LI`gn<*{!z5?(nft8p&r@2tbjzR!lzU0`2_f~LJm*dEB<$Jk5g)Cof3QIziMT!N# z{>3BplNwrK!RPhjayiLJWoVdHtl0I+AWJ%FXyvFL?+%An zuadhfAmb7MR4Qmuo1sD%Xp=LZ;$07YfSLIiM|)3cRGbl;XMS>&;v&C-kbseRlS|bv zpr;f}-UN72W(aUOovtP6p8%jmD|i7HIS&C9t=NT{P*5`IB1y4|#uL2b-S5R)T*<(t zQPQa-<3r~;*|T4#W!(;G3OZi_c&VOUB7szJ%`3o5L)WCD%yV(MM2=`GT;z{{om_)L z1)WSvcB}LTtW3|(aLes?D!^YHm?Uk)S(v%R;XTiqO;)cP~j6~)6efpjX z0K2%jsDD>#Xz6{+lfE;lsKUZpIJW$|T!TVLyW9ggN3U0Qe(;C? z??>pH$#8KvtQEY~Sm15DI#|=zas%M6-iQ9iEB~}BaHT+frO*3m=X2$c=b4_I=Ar-R zv-Hn~wSq6nCP<4jq*RQ;w+gRox8U^(Wnt>dMM0thIi){@do`;_`9Mo$CLeIA-UMjm z11a~N#`7#AG|~+86zE;V`BIsP8pzC;+3U(lwwXQ=)#u( ziB#?dKr=zc)NJcePhM0vW+hvoM+zV(Y89c3B7#mxx88gy$wW-`As| z-;yjPjb`QfWqMO5G);;}8lR%uDJVyj0@7nzUjcKoVwD|>NmCSlM!;G?w*c_oU>$vZ zgJkk4;-Lv92G1%*Be8*|uF$UMpahesd8{S{RG>%-psMG!M3HHwE!TZ%_i#ClVh&_k zNv4u)-*pGhKotji`bZ{XWMgwIOkJWR=)u24(dZn6$RVwAA7uCO6TmLKw?frkI48OH z1&T_JUD!pKQpwyBz~^|!dw+v;aU;EFXGx?DEXE>l-_^mo_7y5Oy;fg0D)?)4rGH6| zbEQCirO&&1m&FA5_x#ak7?_I^V3DG1Tr*0|;$1jk;f>7+Q4?IuMyWXfW7WvGtZ=(a zUxjK-szv!=%ZEK>Bo*8XRdiYgUaU4Adf$gQ+Ixnfkx8ui458@}Vxbv|{JvKjx&;ln zsA&q-q6wU4)m&IulwVfbz~qMubWEX|)$w_i@<~rXIP^4cd*^QuPG&iMreAj^@z69A z!xxk$@_WRxR+5ZFi!Kp;Sp~QP?V`ckOVg_+_b&8M{1wjq@`bKI&zLlZRexq?VV2#m zy`Q?KZcd*WBAZJQSs3Nyp}jgWD~p_I0w7>5!%kBDngCyT&xHlGz`e`$mg`=SuoggG z{$0N0G1=h=m6S>+x%t-HXkE3Lqka9dIx;rU$JvtyDGIm<_=~YxWJ*`An<>%Mm|2Hm0q|Gv zLx1Cyf7%teQlP%l=l!(vx$?*JOpQA5jz46)HJo`qEwL& zZZHtgYEr6r(ZAcBb{+D$oEDG|z5tw5stPjsjC#drfoXwEKCk}gfAlB+L#=~{$0o@n z07*naR0#S5sHhaH$XeCfK&o!@UdjShxUWL<=mNg9s1$lI z1zOC^ur)0T%;WxqgU@8reDII{fYG#9o2+S}e&VydaoY;EtZKgj@K^q!zVXbT_X=Do zP+#fue%|x_kDo69KgDl-tt3WbYmt=MVECMiYmq-Og`h zi>p*lrdA7}TA&96bbLM^@kHFTJkTwHS@DZxF%nPmfe(F{!$*7RJ##@T*7)KS$;doG zzt_}E3nd`XAQDHLRMJ1;Z>3t6s@nuJQ@$yHR#H-=>Jp_)945#rrD2Gc-vk_y4@&mz z`#$ht)#e{L)~gj|d~uqyrw(hlb&+4Bnx;xetQY(~FU3VANOD;L;0wTJ?j-CaljgAs z+CGY>t+PKRa0^)f*UJq#_tsJl4>(y#MlM#1E z`GCvgK72(%M#rak{|A1TgGY|D|IktFwmi0Mf=n_(QP6C%nl6Rlal3JQTqH!ksSA!M zHBwq#+GVgv!NqI>%1~8-hxe*(-PDU4GF~qWg#dgmPb`_{*B|>^CVt%9u3 zoCqG99OKT{+)rg)D<@7~!0CWkc$%IAFY3@!Ns%-hsEjEQ74Vj- zSzcT10c0piri(?MTDV7P8AvkajOI?l)YVI)dehC@*?jA6j-5KM{z4-c`Z#f9FU5Wr z#U*9fZK4noT1ZN78Saw*+jU?}uDz-MH>I(e3q%{84a2U%}(f$k#Mx;ppzJrS+HsPw=^x~bxfLJ2~AWQsZu^M z@+wR}E)5l_gimH+WmroZh3ZcuQ=v8@3h?hInapzTY(GXSPIz&OzLP!pJx<+y$fT_L z@R(`cN^O{SVTxAzn4C}nOyw8?u%>cEGHlJC{z=nW{B>ly6Q-tTxq0UuR5vW=N00uP zBEN@Xznh*T2MPF`8jK>!mRK~Yo;)eB>vhW1a8&Ps&}EslP*2jEQ0O#4R=IN1JyNcB zp|X~1Ba3FhAJ8E2kl(>eoHVUy$K!G_eDNG7jvS!KXTujL!s>AA>)6TQ5SwG6 z*(?sVQPv=H8KBa8BG+KaDN^N)(z}tx#%vB}rMW5#uxR$JDE%b6xDS8i&loX0oE;t~ z5;t(?EWCDIE!#J&FdO6rAB3y+>0ery@&%FSRX)&-m%sK`;JOF+p-~?C$Y&Uvk5Q6e z#FdSy3^K2c%FNQ#q|hU#Ltvp&E7WaLRSL&$6TNm$>}#{+Y&oSAY~p2-7dI0nUzKL5 zD6eFEdR7>9-t*oMGCDcK%lr3n;mk>_*|>&wi%z-#@aE{OXz|S>io2pIw-ai{9N{+~ zkVT*%7c|!Z6M+j~Izy{mx-43$3|hhG@^-%c&F?TiK1^w`hw%I~9;c~vv8ffX6{n8d z%P^CS`kVH}W|LLq=}U{9+7ip|;wL)_p_ELek*PzMACT%=D5#0aX>Pyw0j#b7U-`;c z@wpvr-LQt9!}}>M4UjRCDnpeiP#KO&8fm?LIkiHTMS{3%%UnpL_;LQUJ7dcB zR3@$#04j3H2^5GzCZ}L0)wf73rB^E-aoN@f0zu_l10~hG`=Q@vcx;M&FFZ&8nG;yE z2^{uP^ zn3jCi72q}Q!@NH~X=s|wOgXO7B(IQNg>Qs*^Hblv5*&W&8kgaAS~&2+Q$$0Pkd3ST zL|(mcGFa8qM&7%)doI~c$fCQnc*t3pzc1!)@0AVKE8hId)hz9>OxMZA#%1ij|E*Bj zLdqtznGH+QU`JaqcW&=|#bWqc0KpA_zZO^d7j%s49pFc`g8ww5Ga*V?B(X5A{HScP ze^McuArdCI6%gM1SPOUvz^nheR_g-p>eOzkCUQ2d=JUCX(j)Sp)#0J2qL$ac<(>2# zKds*9v*UwIjb0=gnKd0Cb!2o2$P3#BRbniGiHdtnUAlRm=J^&XN5xlNgqHkZ)HmML z)LZQ?yv0@AanBox#8O0~F~W;;7|9T$gXhSkVye40D^jcS)2e7ucTICL^(Rt66HL|i zvM_zAfGo6-xk#E+k=ES`T&BF#N9VemX>MPwad{FHl8Y~}_xVRi8%fLzx- z_CZ|rZDbun;|aj0*|s9Uo!h(B=g9o+y82%?0RHM<<6qbjZUFoU@B7owb7^9p62iph zM~FtkX2mTH%d9vzY8aboRHe;N?HZaAMs32GjYQ?gHL++34D#YCX!^1XxJt#R4N9vE zhrf)@_1o|lR}u{`;<6Zw4V`0n;56B+spVGYML1@yPR&7{!f;Ii)J4-Rl#&$sIuNxq z+*DAmNTqF_mtDDh_4;zSvARlF(YcBCuC+SVnKNQUX2&>jcpurcSoR8);LvxHh=~$t zX^~s@ZMX)IDyv0oM+A8iF-(f)uON6uSZ9d%(-OJ$*8+~(wKF1uvuU@k2}P07x| zYPaa1mw|_}npU>&dJT4`hfFfe!54o_d~u9)GE7rrgI>3p**WIs7j(f=HI3UvT|<*r z;Zu{7EG#aX_b8ty7zk2VSF6*$v-9&z&&_K?*pf8}dR;U$H{iFQPzAYhSgn)v#6SmHJcHmFrOpO(1nwnKYa|p&q-5by;l4~0|P89EUH16xGVbo zJ~~#mD{!7WcaCT{ra&aYAY#PT(blSuotMW%JtNiy7CYq?RkXJ?lg}Gm7#JpJE5_!n zV$;n#aErz}6`}vs5zhA=r6k~F#~F6DzC_${3t-oNhv|N6s!ePwsz^LqI3hd->&jt37O;?YMRRXL=1!~6U` zKKR?eO;K?%hmRcP$)}%IDXV~QO?4%2d&`3q7Z=fY_B>BMcYwUJlw0q-AGbF^CKX}N zQ$Hj$Jw$nti+}v`mnbeN;p^Z0XFmVMFPXN{xeWC+6@2Y$U&HD0@Q+{p8ejX?w{<2$ z7W~e(6@2P%KCZ|A=6Al!m%sW=4H>cKQZ!bT^O;Y75|`J{bNi0)!>12$$L{;d_$$au zJfhG+@ibeP2e|W=t{VXVUkYV^$==MB>e;XKc~|Z72*3{y^Zq~k2QJLS$S;oLA<5SD zYk0$JZo{5U@TpIKj)9?33~3_T?d-a37x&$BH>p^RzyHGL7#bQ;C5D7z@49^#58QVz z)@+8)e&$mQTpH1-Q32mOZ`;KiUw@xgd;j>=Z_+=qKs4{Bd;K;Af4?)w$s>Ci892?Z zTW;cy|L703rT3|ie}ZS8d5(0>tU^0GSMu4{4_=kV|inb4hUtiwR zz?Z)CMZ8`g-~RT)eBtl@PAhQXrrX-u_~fTPrb$cZFAVa@&wiO0K9wmJm6VWA#W{WK z06qJjp`oUXKm70qX>VK3f&DM@mmmAM?ocwh48?%}|NSF>LRVK82M)f>$N&11uM8Rm zf&u>KlYdRi@)myl#MAuk7yeEcXxTN?*H-fvfBt9cnp=z z)!1+eie*ECi+gTg_sUM}s{QU?_QE$Pnrm^De~FH9r9ge9&%0`uCZA_)beP}y%dc^2 zJdCk0fjt%GZEtujZ+~DnMtGJ_edcrQKYW~MDy@yh*FW$&-t%kkWN~(i&wcuDIDF(7 zX{%dA=-mInef-u#zd<6rz+ZjzFF1Vk1V&zRRr9>@b@%h&o8G{}{5%%Bhd=&bpTKYw z)6}t+#@Z?Z&K#$D_AzkwI4j$ldHw6|!|!pk=lSP({K=;=#FHhTqpfWP?|j#tp zmCf6C5iIe85#>zJ%bYl}kEXhEe)Vl{(Ol9aN00IF!w-{ANuI2O+UhFa_uk)7+vJ|3 zNBG_k9#IQjpmQW|t~*PVCb_Xk*9 z4Dr|#PpJKXROv;o9p#YOU(qo%r?o3?Jo=k_u+8>a8#2o`TS z+wQoRKuM{vB%C>ZkOR;Cm{ONP*UC0^%3O>Y>^*$Kw2jWBs4DTZWo;LBhnx9Sj{V0@ z=}dt{tJIbHS=-Tq!|h@^lHu67VWNpFE^C%DH>~Sij>Bcg>MvtD6JXPpon+j_>VGdI zZI+b5>S{ap-L>fkz+bfw{f!s?saN1if%;0H_ft>kN`D}qXMA*&4}JVwT%3s!nVTXT zon!ZwE-L*_P4ekGbDEPEhL}&L$yu^&?p(>X?v>;-DGr_N;pnML7+EV0mxJ!^HnwhD zLq45U`k?nrKk2NgQ{S{x0%;Uv5m=D^_|(s}Wo$;@#9A^k}=kHwIhkF z;(hM&h=lJ3mzR2Xrd7A6W@VFgX0rw9~kh7S9 z*0y|@uGSWcynf~*3C@j-kry}1WCE`(Puq%Rc)VU_=0a)#Az|nu?{qsXv^Le^_j`yM z7GgOcp5i)IbgrVIsg}(fRlTq61D+!hcnTi|CM6FnzL6VEJq~}NJYO5z$T13X_r>uD$ z%}rgzW!6AlJ}uaC8P-<0c->v=HKpoCll4kJ*f*Z{b6tTe1?nq(-p_Ti|JjrCk^_2? z&p!MDt2b?Bd}x3t9({yzcMe-7sa4t7^c1tPJfT#UY%WcS%Rzg6H7+|0j*l|Em{-6` zr(={Bd05e0qs`2b(FtZ2lH@F6F`T5dD8RC&TC6f&Z&;a$=9$mAsan30^($MrW7`JC zhA!}(uYXzdS!*iG)zNWkYKEz~5N=5r%I8T$LR#U=IRC`d9JApRzF;|1lf$?zIa(TP z@ddnG92y}UH}Lragyt4-IIXlVZ_p{x$(b-4Zn=;Ci3p9$+Z6n_tzStxy1+kw`x_j2 zc`wzaMGDIEiy?-m<|wbNXFjw*e14kF(U_O$fva+7($tl9&305>U5b$^z zo18|jU}<$NwmgKVC#kC~Bj9(FNahHq?IfKgw5;AhQ$sB~H+JH-=6UMr7x}@%|HR6c z8mcNwh$Uqqo290ql|&-R$zw0ErlW=SmS%=0XBnMOP`|95{KHBHOuALwW3TrY2b(`#AXy^{Thj&X5#miopHE?l_8)aV%=c+KssThq<= zA9;+D>J`|WK^7L~nH)aP{rBypp}vYEM^18PaE67fhw{c&s;erfE%xGfIeGZI-zPRZ z%$x7Oo!xit;Ki5rv-jl_R93erP1D!6pV#i*rtkBa=MS*2=RAS3M&i*B1E-Jj&bQyo z&KL)e2DnsIB&Y|COSJ;^SvLv$aDw-r8QhQ-$!hI zfM0vdJ*;21ipQTj!0DkyDyo+=HZ(|hqMvuX^*+|EU&Uk3zsR|XD0Q`M#O-3aAaR3W z%NndH_wc6IY}5(mYxQ-5gTGc+`WJAV>)VS41}}~AnQuSIwr!i493A1A=bxwC@8XUf z+vr^0$k)I1O{|V`%F1ea_JwCiCnLQ5t*>WQR~tWm{4vg7n5U|_ont)*aNCmn<~tu` zRp(0n;x9i*^|CGv)Y$XvQ`quJ-u;d@vZA?;uYc>iEM~kMyA-0NxtsE02OC#5laGfv z{NmH(;vw$6>kd|}UBxpmzQD|4ik7yuoIi7lfwRZ>wYNRM%GMU1d}bdPhC)=-ws7>s z9`flh?|t{%=xkfg=l||Y*jxdv)Hu zxNYFGX0->9iA{0qmNnGXRuhhi2aoaQ*Wb>{l`Z_}@uzWm8;HhjMB*XlrU&`J`+kMy`Wp7^>*4X|4id_FDXD9r zqN*BaK7-c=Gh;*apE|@{x2|W+stzWm=lQ{pp4ay;;ozrF9prWQ+{EVf9gI)T@!d!E zQdPfFX9pH%F0pBCJ!@C5=6LS_NBf2-DQ_T=h%q~Hk*(`mS-)l_14ENMy|md)x!A2bIc8$qN}BxiV`=;oRhPoaVi_yiHGM&E{srFoTk0Kld;JpLz4;0 zDw~Kz=9ry0LshYb6)Rep4rdu#%u-spj956#{P;!c$~}}6dx+;CWC>7Ry_}fEt_m%w z;7KLvE^+eK`?tK3XL~Im;Re88i>v$#I>z;`gC7_e;eY(Yj~JVa5?YwW`D zbgy2?*yIF*V++(ZttGrL&FG~*x?5|htt!J}_j2U;CCaLsxOB0PSY(E_6?N3rR53g} z!F(u+i3vz?t0Jbs4$xR^P0DL?;DeH?>#rhxFoigpZ&-hX_dXU_Wyg=`~HiPCF-3b8=XU)k5XRd z!r`ps@bSwuw=9#DW;{HLRu#i;(NSOD#H+_HP~W;-S|3C`Y@r&h2CuX_J1iNGxCY=|;f5k0Hc^2n3> zscu|?qUeZtW>9io8ta^F*}9#tfBPvKn!8a{dA#m1GO;;HJKeJV7G61gj*^N7$v$$= zj*yLeu$Z*;tm)hGP0$mV7KsXl9g%dxT|6>R7*VJKulmWonw2 zK|W2yJArSmpRTS>ZrpVnkN@Ol9Ih&I`3w=?4BojBHf~r$Ygae>UO0iXyiwX-i0gLG z4pUcM%7z^~Ie2c8Qdb>my+MlNWHe+pO}h>5xqTzLYZd%Egoy95)4sO>USVc@l0W|T zb6lB?5RJ#s=aXz|FC*@mWNCXNYQ2R?cbc5u#OT-%#YU}UM3fepShsN<-+Syi8roKJ zb#xH5lEkRV;&M7DE3aW_e1X!cdKM-p$z@`s5`H>b8(7-2oWrMwxH#^owsRGFtCf-> z3szO0gnNpGu>n-MIICALW991QJo@BwRMvKrPA5nw0z?ASl$O}|#3z2AFa6~=D6eWD z6%8{!If&k%(9zmTV?#5q9=SkibtBUY9-`h6tY!^&?758sI$n77G}FE$4P7hI2y0*z zblDWzOpK8GD(XTEvqi_f_kDyfe(~$Hw=I{VrdZsEqC{{OS-9te_wbj0^)+gmmXJeD zCK4i@^57`ev+KrN`RPv&;&4=x1Mk;D*IMX-8LMTIVbpwW?Vo>tLy(He_U@YqGv|khWlR_hMZ|>-v}Tb4s>-EkwG{a9U0bg4;NN99`;NVx z_d38&U7g_b-*|?hg($IP3MCbzsYpX@iJ3jSwlnVyO26)`+Q{X>D;U%TT58H@tSzIZ zwV5aP9-y+Wh57ke+zXR*wA8V4TQ6hdGmK3vV6r-i1pR~pUP?;r+;shRrf23D9Gm0# zg<IlWe@Yy zKBlJJsD*W}2rbR#Bn`8(vzh6s8Po+MYL!V^9ApX!%1SM4SigejUpPW0r^O#l5R50$ zTdcyG3w6FgU1+4Fpgepl2T!zCSC9@uzq7NlQY6*S0<*SlID>) z<~=iP+^`<+!UFMFQfdICl2^&&_srAU)`(88A>a$kVef?7Pe!AaRept|h*G;vE(kMI zqpVrgMIj@i1miM*T=>xBR0?jtU-Iyi>72~gP3IS*{IaPOLC>5#hmZnC<0%;$E^HhM z`7{gjGpt&(Q{S*ae~zI_YfP>5Ju_{^)BnVLms z(clTrv-`&D@y&_wkfgNlO=Obf^EnpWZZ>V%N;H}v8i|ui=kWUdWQ6YyU^f|XS#4+w zIsAb+n%nE7Rc=My9 zN=|t1s7Yl~_#-}+cK47;DMTU(nL8VOO>Hae3-rRPC6h!;ipi^2xb2o3FzIy!1qD$^ z{tJ0x`5YRv4UN%`Kb#<^2nJIgJ$ef1JbiL9(sgG>Xi;~Ne)|+VT?4qK+k-b0rB?he( zoyJHY6eW|(5f0803VC_xp^wpj`4R({u1ISFVIv@__=c8dHgDU(j~{u0OfpSta~rb@ z0Zeumg@W+C&!J>vj16C;qQuJo@z8zL*Hm!mh5h7W5ea%}vxV+;y;4B*w}1By)~)Yl zXm}cnsTjYUSB%owRKx9iZsCc?e)O7)rSQSgN>yuRbv3(p-^`;w_%TIAPOL?xWHF)@ zY?e#}B@^Ug-zjdt>kfAA+=4b8r|;lPXbX8FnLMq_SJSw(i)WrYz@`2XZoX{~FT8w8 z`u1c}K_*8pvwhPB3_2Z0j~u4GrIneP8EWflId`s)T{qv1&TQsH-$hogTEn@?pd7>} zg6l2JqL+#@-1`d{>?Gz3oK`PIi%TZ-B;VsLznt^=)wCqdi*Hi zNQ7J_O?jz{kUz-0+sh|E{aJqg^s{JndRkgLxI8e9!CXuxs}K(^P^66#j`+CsuDe;* zwS>uwrR=9em~QzmCP~q_=lHKl$lPc)US6nqBz)bKG;!2PCMS zI&qqgjt=PrdFj%5mUeZsaqD$F|H6yROpeppzLd)&^VrLqWdKGx?x(w>h7(5)P-M~b zp%2_aTWb@q{_77BTzIVVXFqc#zY`^mAl@znIC`md#vl- z!0MGfQam+q@+j(joi@_(Uoyiq>;8{O|MyEO{*UmoW3-}*VD-UQdLY2*6!%NQTHM0YFmoEvW|y;_&Bc8Qg-dSfp2{CQT)CTJ9n&OdSZaa+8T=N1|I$K_xZ?g ze~f|t^RmBxWnh$#KJWm+K!}0C5jwk9^6Jr3I4T>6M?&1ReKjWzzf4m@9V>g5VaO$z zxZEdIss*hHS8XGeO>Iofy4m;4^X#~OH$%hY_=5?2o>`W6w%}Ws9?|e<4%s9JjKHFBo?C$cQ}vEQAIcwBNg$my>}U&*{gWwCfT@d6;1WE z3|#0#l}X9ajjYjzqoxXjrI=S=I>_!lw{hsy0Mm0pW+(dDxV(*GyOs9#4jy^zQBs*S z4GoPrY<6a6XJy*f@BRMo@xqHQ6N{*8u)4`|e*m@c;e}yiuTj zqx-#OpM?UKE)Mdi-+G2IcbGf2b@5v_Z{XC?18DPk>MQFQJAaaVG(b*-RhaD5bS%SA zT*h+;4zR3yDJ>mcJhAs>MutXkSQUDfHdEnpkx9q-+0UM0$F|+f&WzF6+{VE}M|kkT zj}Zt286F;^uA!B)7y2^oB!wZ6z2r7dKmB~WGlBGlv z875~I*s^tpG!BczQq0d!uyOrL9A+Jrm1PVJ3~=_`IV!8FUQ@s(n4X^IV-G&a=;(+H z)Yh6ETpXI_>Oz=6BtcWPlX?eCj`UOPEWu{f5}X-Bn~N>xm}WGXi%Tf0Yr+!_v$l5= z6}2@y{?zk~jZd+vt%|1lN>;8}A*{jbq1;Nnd)ST17e=fKl<8UW&$h#u3JxGmKA6^UVGuq|$ln>;^8LKPmlQ63Ha7cxurlKgO;NO9{E>_};_cA{q(F8A3Xlke=#V5pbe5 zkkf0Zu4`e(w(Z>e(U0)8e|i*+&Ou$3onuE{WN2_u=Guzja}nVuSS-R{UeG+vMm;9I z0lnVD9e3Y_FBD{OcowU<6rH9(X^Ea^pM4g$*G(c3qqe$A+F1xLJ6bJ9iv^ug%eL(| zaO2Ip(CAJ4;+Z2@tqu&@G$)R{OjcMc>-5rELA*qN-e}a56Eskxp03ym&GNEiF$JALq&kUKKta;qtX4DIwr=O9n|JfKU;Srnu4>}( z2tA!m3|>0T(L)F1W4>@Rj3pA}k|~)Qr8Zhn8_m?z*Ry@+_3YktBj5S{6VmQB>hn`p zY~$#`7bIWaRa%C}=O>X!QCC~d^uoOKa~B@#D_1OMN#|1B!36t{_EF!l5}UXZZ>&W~=0;N8%ZbMmuAd`w05y7Qx(N zA|4lh`bny)Ye=OMq!MwudR9r|&J&GCWCi`J^e9mri>%nJ z5HjU+tX;d7(vnJM=I2P{(l|?MFdLl|GAYKdUXl@skw{3MSLDK`6DgV4C5Odo!8j^# z>#cX9XjIJ1yD?cSWoStv>XyMF;@^s3_Xrzhk!dT9#55vmFh?NZW8=nNnQ9dbMNv5_ z$fU;_vSp+lN9}LK$W-gl}lS#=C5R1)D zRZYE2BT5Q?d!31)i8-no+Hg6F$c4S+69UxI=qwh}$r$NK2({KIEs@1F39#4b^>lW& z6AAErUkXpLMW*) zA5PM_tP7($OETak84k+9uuvRb9vDP#G?7Zh7v=l;Jg&M*T3VM74~8kPaB=i>KPAp8 zNpT$PKSyO*DYxBn3;TZlbEYOIWFWa{j|hNmUDC#`TW;g$d!Lt!V{Kyt!EhXlNl;z` zm<)NwNBjBW7ygK^{LNRf+KaK-on+HFOa{T#hs|4daOm(EN=l2UZ*Jh!>0!AD#A9wo z1}<{fo||ZGspj#=pCsT9$u?Oi9HOJWm5)96QH~rt#l`*^ZrQVoeTS}Kw7CexBB%>0 z8jK2m@X(FY`0Uz{^*6`2_xusw(>!KYA~J^VM%t>@20K*eXrewr%N^Or9_QkH2Kek}hVZ zr{(voytIT3TedJTdX@8i7wB2Oj>G3i2;?;^?dd^@1zB3-x-nZvA#>Xc)b?PE!yOW%)0+q>0D47yMU@CPPKJz=fv1$dtzdhSEn&jJa zpWl(QyypS_#0CE3JHKQ$mglyO?QCqV#xpZPRc$>_zxWEBJC`% z?&4eDdYG!JDpsuS<@-O}M=F-!zK`r?^6D68PMoH7F0*snYNp19Skb*4yWPo&(|vUIEFl$-a{0m_t;<$Z zY}azb#ua?=3;&a4y{l1c%}k8>S(v>_MVW&{)XN=r-pZjvhtR6^IE#xpcJvrMD^@c( zJR#w8S6^<=zLtmwpPCLy@xTGE%dJI#pCuc zK6aJ6-hVd}QxhCLbR3n|L0DzNn<=oYYZ>#yLpY6jTuviPyPD`;+Rdjw{iodX;g8|= z`v`^t6k8oAg%o$*aT9;{xBq}zXQ4#+(R+iOKYxZDn|kEaS9Ns_hYlZJY_kZ3Xmc~k zWP)fc!Y#MlBG2#hhe+hr=q(il{BeT5aW?mM(AZed@)bS&k1zi%D_5_V{qlS+FEek4 z2CnegPkx*ypW2JgZj*!R>6rkrP!uu|n(B+Fsji~5w34Gok4nZ&ZA}de3k%X-`nFqd zWp-|kk)bg(COZXtHCcTTiL^pUwEMIP{^ECUlWm@BJ@|J765m}XeXj%j(G!>X?+^bH zcQVhOO>NwuI4x~0JihliLg5(AP0i@FTG`7E_&wZr-v@c|g#*mY&aracCZ0KP z3is>`fBHusCFJvPzV9N=VjIU#9;39ZhM}Q8Hf-2}&lkewbh3WkDt@tVA0A%MOFL3$KF*-KF_U)TVr=ncAaD}qUdM*!66G~)Q z(qyBpshZj885*1F`NwbkBNmI5ii%3vZb-%x?7VR&UayC-p-Iv?0}BZVDH=LEmg2cO zLXkE}_tFL`${q4&fA|NVlYIYTmy4np;|kMk44<25!9RCXO9CioK|Wi3J~OV=2jmf_HwH9b1+W z^|`64s^OVu_Y;l9CD4kwgcy2T&1P0C?_u8OVb}ZKM_SQx{KQ4Vfe=Pbo>Xjs*2Wr| znwoj$nP+9XmO*bsrBY!q=-GACO^jU~XWkp2qP~gQ7!+5v5l<9I=M~IKm_NPm2H6gh zrZ{iIcCCVc8*cL3c?w}5B}5+3$&oAnn@9KXV!fA3iqk{Rx~eg#`PtMJZD)85v`&z^Y^ zpFb?=g<@Lf_X@)>C+~m%om{+dk&@C9CT6^xAD&}&e4M}j@+YY-E#Vtq|0dNn6`VM8 z5`Q2;A`zyf#3ci;yO%D-RZ>KM{~#KJUB>6>&1GDzkk z=JS}e8pNb^EnGjZR7lz!zfCcq0v#iau}#b zuhl^&i``*o)20n*bz-)VXXlN#^7mi+4y9FfbTv6SdF+s+blUAU&YV6Y`R6LNhHN&A zL9e5tx?DO(cC{~~wY`U@o2SYy1s@78a&K_oJYLv>d3J$$`9IeJkUg|;f zXjKIqMK*aIR(lZ-KJ+_$>)|ITEw3ROPm=IWFgH0OgRfI5F?)!~s6(|zBL}`(gBrbF zhXy?leEcDz8HH2lN6{H=#KZG!-_*tb`kTK;uM<>C1Ic8PL?VH+sF+whidv(>WU)|M zRmms*@Du1wCLVkIIrJI>OWGQF;_>gwVXRi8Ary%cizhG{&8XEHN%s`}crmxAYiZ^W zKl>>je)2`i>pMuL6cVW%rhJe;|L87E#%looW_`!s6URAt@E}h;^^|;hz25(n?^%HT zrcImp{O3PUV`Jl6e~k*9IdO?EeD`VQ;t3wQV+*C)1Xud{$fon0Jl#hyk&-fcA=VLu zx6)FVl%1O`W5}e{Cyt+xy>Bu9u-YBO69QmGyG@JPV8vu}P*zh%EUzORO0c4*9lI&d zGrxFNwq-0vBe8fKqrpH?Q8AHdM9yK9c7u&V@h(`+$O>@31rT1wvNz+iWgN#%$q(^!=-fBv!E7!B8Gl5af# zybI27<;oTAzyE$tpFaIB??w!-ii(QlE2~MMGi#`@*J9Kya<~7Z?ai#3U(w=Yq3 ziR};m;1BrfSHJonUCM9v=L(!WdXX>v;5q!+0-cox)Cn)?Sdzy2296&;i7yw+9I2I-zPovj^QE$d%bVwWF zWWhjLLldrIE18gw>G5F_ks!^@Ekt55{QjU+!fFJoLuHVzhvL7RciqIq)iJ`MC`NNJ z29uSLZ;GpvW3+a5NLnU-NW%aCAOJ~3K~!SIAH*cg)I@trrN}j`)~kQFK{Eo!ZS ziMdHR%&e)dBpe7xs-(Df1;O-D$mg@@G-6huM`+iA$vCtA2rbPWgnjdr3$uR(bXwh_ zf>;fOyvW@ZKUSltGz^cA(6OYQB6|@@VM#3h5H+c6nwi;Ys%xvT*{mdDQ8}O&ttpLK zgUMn=qtT<)>m`L$uzG}fonZ3_x5;EWi%k{gk3W2!)GJ);!T)Ao?|1#)0^C3Ffe#>l zUA}xdd-m+%gCG2$Y>E6P+Zz=u{YU#h=kaVV{(wWEPdB1j>t7Cr`Klr;HlhN0mBnp#>hTOATmHH92nB~PJ{Mx!yJ zsIsUO4H}g}(l&>u7bvZ(r_5<5?(>jIB^ezZrF}^kCC*Z!p@8Iei-l>%y+Amg#ALOw zazzi>RFXtAA%Q=S@Ki5wzW*{yS1p$nf7Ba5l@%5ND!C}+l`MsHRw_vsQCmeWrw~qL zm&~B+}u!4BovTy6Y-fzOL*bSuH@t*lZy(ox^qE(KX7RwFiJj(j>wCYi)+ zG+;0oB!%1hnwCQpb6AOhX)is zMpp4{OS;G^8fHBa3>GJ9jY2_hAg3tAV-dNa+qE%1``bIP34j-?%iFMB>%qSbH~FnN zg%HCCPmqs){NsG(D_@Zn`Q{ zZVi3Fn)6OzhV zS6zX7Y8YKUiB_w^WG=Oe$GdtX{*4Roxss@G6N|78C>7f*O@pPv4cx^sHNh*<>Q+52MXzMeR&h z$znFEFsc=4vs_f_M59wn@ZR^#tIQ{IEM2_@Qz3`P8(?H~9A`->2AzsbDuJuG7>C75 zPJywxIb0Q$RFpc2`@N7(qo}kba|(l#)3mm=U^VJd7jlr#F4_#d2Jks0FV($6S4OF+ zt|nDTNXC@I=0KZE(^Tsu>Yu`5Hd5jgE}MCJRxaavKYE&i&PFU>F{~XMdhf~1#%i;6s;l> z3QB(CeK{HeECg1*Xsr9|K~}6o&7Fe zyhu+^k359O?&1NWi-}RQ%I-j zzj&Fct23B|FN@8Dxmb^A{Ztf}Qspecpk%RIG*~QJN?a}!m5z?~W{w|!g_9R%2~$K< zYb}~&7@ZJmiqfy3lB!EZBLY4$3=a2m%T3!zhv#T0FJfwTj^dIkmap#SiKq6X(pYeZ zL-=B8DjJ$FiG^os29Ga5MNJ+4aD=9&I!er1a*+j^Yf6Ymf)tgONiUhT>zA|tg`;>q zQ3|gCypZk>jE_;>)IhPL2$E?unGA(OmaLMacYOz%T%3F=hrPI%vPu`8IWJG{eF=9G zI+pif*Qf{tqSBqRzM+wk(P1V=N9kR=hNYdt!zCbtQi{sUsVFZaAQ%=YVcP+L_iBLk~lW@-C7KR3_j z&6}B=p5fHl%Ovs!Lh%CAo&fFL?Zl%I%8H7}OUs3T>d^vwH$(k3Dm_R-T?g+rUC zxu%lp+G-ZU5q|X3mq-@$*osQAS_~NNHgeelv1puVvVb-f;?wu+pt#8Vc9CeV0sLEn zEN}5aAA9UES@}Njzymz|@WXHF*?t|M{LZJ3oX@qvz&58+qZG z$C#h@a?7nB#Ab2eFv4%&xs78-kKigVr>NK^14oXWInUX_8OrP0q!CzUiJg2hF4dh% zK~%$Hff4SF1;XI~<)tR>xMedhKD$pih0)cshF?5;fOK9@Dz71tNz>8QiQDg?#O7dp zcmku*Mj{z!YWgZ`SFNI~s6_g-KY0Ib?A!ZOcHFQ7httKC!7*NW^(7~bv@RErp(#+4exo$@ub{oxbztl7-y%mU?AwQOA5f>{F=vxR5&pOE1#+cx%)OQp#dGQ4>BB4cA? zbhT7bYBNw|Hqy{g&o5s(#ML=B&hi=@C6#n{Hc?h)!Kl@sF%|LD3w;z45kCEatrQno zt^xd;^o@U49_CA5`VwFK;uq!X3t#xcoBAGqU7-He$$#Db1dUVBCq-Dp;Nak!^d9~d z;KktW@Uecr|H>5tiHrVwVklI>pe{Nz8UTwsJeMnIIEmSNXk9zMp-M|1*AX zi1+{Y?=U;(Mz19Jo%?QQu>UgtP=xmOC0w{Ph_R@gqkWfU4(OeG-iIJsq+(%)2ZyPs zD5uEgK(AGp7@wi9?<`i6mIv>-ppE-iVX5yg-@8sO+lPq{d?B8ad`spv3obpjxQIFYTW6Snc z7{vhBY#|U%%OT^!yc?}1$CdtR#>S`FxVn|Lx)P2aK1@S>Jrh%NoV_?mL2DtC*KzYL zyC^F*Ng82Qjgvq6)2~rh)hOE}(O`(m%5o+>9;#}pNvG1-48mup!1&BG)eUvTqEYN7 zJ$92#T0f}rab~7RNW@Z9l-E#MRVMx5lNm9vPI1fb?VLFNB9r4|RFnxrv8?wfDr?3FQ+nF8&Nl{~ZeabmFq-f)sw zB97Cl$7wgxSX+(H6X2?dRWzAFr^8^h%WPeXMNel(E5CK$NBGv>6J!%{K7H3FT+V9% z|0aFm-<^kfy#W88-HWEBrA1alkw`>Z!2agjzX$kZCkJ@^_&AFhG?sgMqH?>&3)y5}V@>a_;WpFhvi zm1}waz^l|ZHp}ZVTa0usT}C#Srlz`#Z++vNEX)c9idshSiP$)kRz)EvtPT>WG{WUZ zEtx2JQPrw7a-LA+aPYB@-_Pij7qiJOg;fV%*^iRVQBhijR+Z;NAG)1%B0=BzKAbKW zuO2#1ES|^iD3QE(tzL@|U$(Zl)48liS_b^tfBy>^<}Da5xq=G235qOQX#ggeEs11S z4sB5zBwNU!*Q3!W6c;=B+~+^Vqk9ia8v>QiNQtY2**Wp_QbRNv#bz+e1$Sz0fvVEI~Bveo$rGm}I3Jw7ZZ8*Ob3tXjW zMUt@`YgVnLs-}i;(8JlmOKe`g4pIrOziv6tKJk49uMA4LzhHalwFQh?LCS-CK`UvB zg3q0if*s*&o|ml{z1~QBS2w*IH!wRn#xH*U6I6--Pc3SVK~gHkfYGGYk;w_ckznN% z7J2=P989Uv6s@M~cHc~Cb%XdFp`eGoPyHC3a5T(=$sjoB1?ed-`0QdY0d!(95}bN* zOto5g&MUH--*e}kTs(h{%NNf}N~oX~iikk+Y00z^bj4g=kw7RwR8T?%<43F0NE)Wi z>fn=~`W&avkKl=B2qe3u61$7i5-U$W@g3}<7p^wRr#1o1!q!(T62g&EFmJ?S zloo6tov<7hY#@bvIz>xc2OTSVr6F2>-%0d}U@B>3>qyiAf|4l~zr3JXW)*Z=@wpV_ zIYh{KPB5xeDoV>M_{gwv` zuOdq8-MGD50RG;4@8yR-{2`A%`lzIM{^r}i0eA(Dp1i{2$0zV6GkE<08DgD@$0+1; zWYQ@LS>nYx5nOte zMih|(*@eBWpbVWELeTHSVX}x-j|HEXs-}8E!3afq6W;j+qR9lE-CbBs zCV~r77*r8@S9Q=_Uq>OECm8Z^^4uj7ISYD?k!aAvnbWV}Dz>2$J$gY!RV%VumzxwO ziE3PhM!P6>6N{5rgbJAqiBy(tH|=43dWM1XrzkS1BBeB zM#disHc&Q`k_uZ}Q8AzYi~p17`X)(+{rt|&tEj0em-qJV*xpfq7d_;+a&x&{66i&g zmf(yFCFQ$ed$$1m>wO=u|1s?4tTm zgg{r7SW)ManDvVwD;}@seIeo*EtSq1l6nnoOX`>&yud=pi?gnciHlQIxm?5wDpsvo zjuP>6=+Z?tuj$2}g8WQ8XJB80Vo5G#qwSX6=n3f-G_cxqxJHi%%Iv&Jt#) zr=)L;R;@@|1M%J#@BHGzB^Cl9h7vSM`J|FdOPZ(P<{M0Q9{Roi#+m*J4xYF`U3&+S zNLU7b81rgo{T@o|s)z)`nALjx3m&;xlvh^BI6bpo&(z3e?8YQoC5Aem!=N{jOvUNw zS&c8EBAZf}pSjA|&{>>CHZ&^1;}=gQ85H%R@>DF~DltSCEf$qnuY@Be6lWmO!IuX{xDZ$P-}AnjQ#wdG$&^ zo7eVY%7)3MyqrFAfI=#TR;@!LYzag-hiDfFFch5>0W!i1U8qSF(RRsFDCDFEdpMD% zXXP3$UATZo$;rX1uo+Nm1mj**jso2UsAxn%DuG9Yjx5%O5>jQXT~k{(9ZT0TIX=PE zL_f)dM=lI%l|fddxk3uHT8E;DCkz32;+Ts-FWMMlIIE}?Vu=)blbL|ew+QeW@zk&= z36<9)uR(zP;@L%zwk(z<{4WB$-el+A2S35Z(HV}Oxx(u88%f5aq~dWrf(ltzMOgIV zbw(n-5c3{49ZNbmcjhd4CC84fn@NSeOb(x-y}4Xg^e$&P1H*%46g95OHuP!}tGRR625IsoSScDrFZ(r+ltZ|J?6120Ax@vVME~#tp@NxsTrD~+ zs7x9Rikg#SQ}p((L>=(*>c9{i)~v&r2|zl;k%Q04p`cb#FRCqN-&%mH7?%p95TGD_ zppkzrel9rNqOUE&s#mRD&*jVK33=Vw=q6!sYz6dm;y&!-~RHVNGAWFmZATNaeDoMgeC8iXL=(dZ+ErZcw zV}5Q9lQ2jVtAtpmWJRo!i^k$gBlZ)(F91*gtLWtmwXYVv*~Yfrw@aV&V`neRctSB3 zxzN`~ZRZla^KKkwE5UF``nQOlx3J_reex8Ubb<}**2pZ`b0_w*W9usMz(R?$oaxya zCg9+D7iaQ{}K+0;{ z2}WWpObwyQMbYZiViX|3TcEfIPgy*OSZo(R53NRpUMJMaD)K5V6}1hl*nA_7=2fT* zX+C;=Cymvm@BSYAJAjLvIB|l#d-w9SuYFDWNSBwF^Wz`?nCq^)?wz=tH+;_5JDe0O zno!bDPtEIhll*n*j=y>nZ)CqWzk>gj^?~SOE4=XPC7wQgm4RtLo=}uTCW#>(rQW9D z{txbA=Z1D17PVxch{2|s45BeFzQB2bjsghsqL-?dZHmE>aen^%F`{u7in^GLDj^e_ zP7O`ayRjF73mm*Kz~=SqFyx{nd@~$;@n_PfMn*g+Vt|^L>CaUUMNT;JLOpeIjy&?v9!c{>=)@2r19U8UlpNk=%0C>ID_*!OYLH2_y zYTH@9dNW$`Tsn7{$*Y6X7)^juUJ+uY#eu9!(aQFMc!Chs?qaC7c(Tw)z|ZB?)HXEZ z@ywHq2W3Q^V5cNANhuH$Egrc*2(S}T|o`Vom4ho;x1 zkXJZ!`Z#TC*P==1qz%GcC_sIChqOzOS^)Cs)f%ZT)#jrNUpmV2WlfY6JIG}6Qk$UG zo2hH=A{vaz_jvmFOIVCr%to7xRP=}3i*ts8xMzz)Z#MpsQ*$w*hnb3>D?+qju*XqGbr6Rcag z978?@P+ zBbf+s=Fs!(x^ah8n$FD4bNcvk$;Z#Cbf^TILnIh!(rC4L%8M(xZpRJ86JZV?J4Q)W z2TPW%hg_V&3x`>lnZRtcO7EIL#7`-U zn4TRa8S}Gs^A_3vK7XN)nb{ecU8<;!6jWN_ECWg!qgF*tWfjYNR#H$jcs(I>u1acK zmT{(kjCEVKV94Y-bLIqH>(*jaRE!Uept9R>R#v0r1g||tI2w|Sod27>^MI4Itg`;U z!dtn!I_KOyohIiz!w`p@gMuq6B4%Cn)7910b#+avu4(yj1r(4dabSiF15BQt)IHNV z=Uh3xRrUSuQ`3IR;-Zoic%gpN(^K)Ss`K3E+;h*#v{{IGN9b)mKvh{T7PCP~FGoiw zh$f6wH!j8J2{1b`gmdk1^Cs(C4W{A)EzXN`PK@9G{`dL(=Rf~e zKdo1N{5NJm=xqw{Paou-oyR%WGfPnNP?OVq>go%)`pmUBtRe{%bFQcgv-XViGTPsz z45q|1%HnjBTU%WyD0 zF@?ciKzYp)CP#ai8f_!!onq1aB}C(4cJJN8^lXSkQV4$82}sqgqnV^hYGm1xB^2Zp zs9~yO$9t)+nNMGT8!o4j>aq%|t7t)rZ%~+!`_U+%z;x((WW1#I=3$~mb((?;cpF>1P!eJXe0ws@^f6AbH*tQ_VqC_KEdks z8`$|`6X}_G=(>+jf9iT3d+1>{Z#spj9^nW7c_X2?9bI#gomW60FoW(N=Z0&q#9=lu zIx@tPWsBIi`zTNEYo@w>CHqhGs9+OIEXtk(dsw`31x|yB&J(Rz1>p1YAz{R-n$t=2 zWQ~J(rxRLQxLy-_5z_oJ}-g;2Yoj zB^lYp7!nEAEUU*5o#pXuzvDyKe~6N*I&S*SLv#-N2^)3V1&MwgZ$#h|IBkw zKSNH2gVWF0!sC07vwin*(u?LPXUwZsm$0C&^6f8^d}HA6ue;Yds^D)Ov+rO#89AkDv|i+mkwAdc)-2$(Q`WM5$96Tgzi|En zesbfl=^UJ*zNV5dedaoTchBAU!eQQf&DGp|^KEnt&C)#RW!Z*Jggrhc`0wTK3t+zcuMg1~tR-2lP z4f-b8w0;SvZ&}BUKl_DJ>iolXAL4iSKS6ij5Z7FNDVc7KTYh;nOP4NV%W0=@^KX8~ z(e@GI)^s)PIy~5o?j7TEAHSAkO$XEz>*}?um>Bi&{a@TlLFs%Bw)L@M{d&x?82g*{ z(6DqFZp}*fNs1;dFCP;rZrflssQyBR)r@zblku+OOpSCiJlw0Aq$Q=Ll+UZjWG`TJ zz{79$uG>}J@5Yj&+chq`_5y;EE-o_c|OlP z`aI!@K|Xc;WqkRI-yk>B$`5|aXZ7mU+;GDUY~H+CHDKOO$7etL+24myyb&HRuk~ELSvI?GCcw)%nX^3>dQ51t z*LwURz~BGqE`GM{Aj7@{#kOf~{?13J$Z@E~VZsn6GSkCd|M%y7@Skpd)rZ~n+`X(> ze=2d&t0#R#f>HkE>;Fy2S;gMt{jA@-g_viE0|Hu$7veJNSfVq0`ufY*wR0y24jg95 zvLzVIHeTF)43jmJs=8`sJs$en+xf?jT}de5=jS*6m-1Wx==C4w(Z_ePzqx~XRpnfA z&M8U_mXlw=rI%ks^RW{=^weIC_Ivo)r$556y@%;Pv7dkY%E!3t_Inr}8RpAh`J8&5 zKfCb`jAl2vIWEpSXEk@<`CG!Ib?K`uOR6Y*$- zpZ@5FSWFr>eDY)T4^4BdrHc=J=yD!=^dVk+b|*HQgD-sX^Srq02u;WPh-pqXY~I4& zm!2cfW#WnpPUSbh{x!~Y7gt<)8HKrdeCZoMCa+)~huV7;Eo0Gj4jny6{jwFLnKas4 z+c3J)$S5kpm^7o5m;&%g18JH`rBh{?bq*caNptf7HT<<^?Hbms-^>fUPEe3njm08z zST8R}E%+?aI7!D0u4(}%!52INOoORCGc%vG7jt=0{qbyjo0Ky5p!+nHi`{?f*B@&wA zr$703;!ZcW-~S>uccIePU%j!M#=7#i7T^Ws7c5xtM<4pBsVN?Q_+f^Jhn2~dr1Hq< z?%V13;0Hg*Ew|jFUXt+hmtA(5vgDNy{_EqF@|T~j*AkTRx9&wFXJhZ)yeCqSx0j&u&OZq;%OArDSNm`$r2 zx$o|K6;CXRnfJW!J=}TM6FAdzvAOI@2{YK+$I3-jG&SvJaCDr;y7{bLwv1pn%8~Xy zGSlpg4fQeW^I*0+R6}s%`c*vm#2z}v!mM1i5Z&Wryr-4ZPgzADo7GaF*riluz|GuQF8um6PN@>&cAGl_VNxE{jkFp{5>K}YKe z+FIKvE-hij%2Q}<@5Smg(sb}8BGR}{7?ekQN$EVg2d4-a%rq=msGJjZ-xPK&$<)j= z;e^gduDga4M?2W|#Iux^)pERNkR@x@VvfXUI&zS@WlKpjTj=iS#Nc$1mS3P2W6fw# z;v8ebfF?dN;Q)cjVU8W%gVkoHx~57Eb&X9yTh);ZNU`Y|YpB0{_yR-*wkreCu1^ z`X4^)l9VKaQckB+rT)zQ`9_3Ezg|&yf9pEy&MpcH zs!2=FQ7K3wrig_?j19LjG&abRKnt43_ z*uxMFQ&zW_)?q(&b>-NkXB_s^+0mjr-+iGFD^@OGu)CXpKS4%TA(3!^k>L))!4S!~ ziTR5fsB5U^P}6Z7_B7QEkP&(ra_ZR2nH@x>x1c2n#ga@-d04n)F?u9Q+lgih3i8Ox&QT_E;%~1f#GA*!_-M+K zLF7tOFvu{PNlPt)a{k0*&Fa+1FUn_jCPKs?AfbCHC@935?!as{G3^PG>r5vW)d_}t zT(Y5(mGi5VEc4Ac{vv>vCnS1p-)WH3rDO-)U2*~@$_Vby;x z052z3b}COj_0;b#e>j2smYw{UJ#a$rC1DhWw;6OZH-7y;=rmTbt96JKYt|9>OmMV& zgk_5sVl_lChW$h$0Xo`SsjaEO<*?%O&k_jgfK_>{3s}U0K`JW>7@im-VYX9TP>voF zjk`%XM2g8+EEb`AaD-(mSCh~~4E1&~?gTfRtKR# zgph7yXu^vl!-3H#QGYV+s$te_1Ofs2hK9*4DyFt}9udEvkZ)F58KmdtVYFy!P%9$N zp>8{&SwBs!?JQff26HGv)8RujEL%*P$wE(8H*vd#oU)3Pd{ZWT)xc6Bl^?6eaG5oH zo>{tj`>3m{$6>b9+0{W(?2#=F!l4lPc_Q%?m5l>kym71sV$xoZ%4(QYRt3^TRnrr) z!!nAsg3Kj|qo@Ic%mavKUd=`&NQjI_bp6JZ=07#L8&O_1NrOYlR?S)x38WQs2DL+r zCU8oep&la|3v=;?Dwfxk{p|w$D^>a8AH_akz`E3UXg(Mgh9`nk`2PF*C2@h?3@QYk<$f68-^%iPcM z=j(k4sLPH){L){`4&m2!B;)z=A6`seUj$Reh#&c;tR(p$+d9C zx&_!Z(P&Hc6u~<^!7p#QPx*Ym+L4!=#n^C*(yqq|6W2Aq`i1Wk%3R8>6TK{3xq{fl zG_Cz3tY5Q&MBJww5JR(*ET}7_<E?J7v6ldG^?WDPLRie}Mf~3`Nen=;04GfU_yB6 zM;>`Zantg<|M-vpP_%{sx8!YxLLrqjBtZ^8{NWF|_~MHZ4*z}cdmjxA4SeT2-%*M1 zf4Cz!_uO;2?Y7&<%*<53mjy$7V`Td-W?|wpBa+6apMF{`9P&F+mB@~wzP?`lDU+#k z2*BTc_uUE{Kk$JMkS(DOIXQ|~e@FxA&ih9ydQflPn~*}QQxU-|04u;G+5nDNf4 zYE(d23g*xK<0ts?m;Y69+vi;R9(pE%coTN8S}__@q2DG+qm7vu8XO=I32|`uUZr_o zzi}h>jC6FF^i(DQDN6(S!7k^1(!;^_E(P$GP=Kbx&D1PfNQTwMKwmGuWP-xVY9*5t z3xuRuxyTR~+a5!bT(cGLZLjx;Tub{KH zTY;)oczm-=)+%EeV&aN%2yPK|MaIn zB|SY|0j>bJ{9Y<#X=unXJ3Fi5*ktQ1oW8g^e)X$g<(oNMNKem@Hj~}Z(#?QWd4eJ_;RMmw+d{>ejK6I3&tIl}UkHC?m zFHyf>A*N)2WPFA@Z+Vzwoen~FH~ZSVX;`udgD*hG&=|`XFHrfUhLDbDvWt&==wb%C z+OP_+Xz=2$-RKF8ii#@2kpO-DLo8gdKw12@wYPHS*7ML!cAnpNoKVb!F%lzT(rE7P z#*v;z-MkuQU>5cUX>aMkoSC7j%KDlbcD?X|dR?-kaAss+amZw;3@^peq9HXTS_GbSH8x%7hS5Xa%GCuVm2||}w+=p+YEbg^RN zDr}(;`@pt(bQ zoMqwIy?giXpM%`y-h1y=gG*A~zf+IDbuXIN{e5{^1^>H8_i@M0BOD%{#T*NAYJ;0^ ze&z~tGvo^?g@`!+>D+ev{k;DJAODk2=eNJTnX9h4NL8YS_$=cieSGJKkKoGM#B|8Z z{?1MotXxWDVw&#J305y%ia8#{Anuc%em;8rrEGuX0ToOk9QXR*O|p zaz2E*WtW1@O?PK2c7v6&f>OE%`-nTt)YQ!*DTeWWou-!K%4;Pz zH%ARfNmVNHOS8>_X0zcCfYZacOi+|zXF*K?vA`5Nwm(9BT|F4rfEO8o653G^NgqXofe(iE_ zDw^6rNks+MUUxkYJoY^OlK~u=xwu>w%+VzIY1wFYjT3zxgwUz2ZNQ91c*cWgdRpa{ zdOcp{S)Q4ljl=0s7R3=g6{DAv=ERZ=>Y(DYj6MqsQARo8L&5)y{BVKcOV#S5zt+V+q#Q4GEQ} zE3?01V5T~0(Wuh<_YMxQaM4229Zo|20G-`EboUKVSKmN+X(?HmE@B}+C)(R^=9Mzo zc9=XZ$d^8OErkVn{L{bwn39F-n2l*1eCaugtua1*!}};KE94tr{{dwUs|aXL_V3+8 zt~tyN*PKWFyh?7rZyRl6A<_%yvFpWWm|tY$lkdNTlClbZ{;Rv#-!Z_lbz5v-|S7Zo=z057+ZU4_s)?;d~t8F;$@yaYGg zvwaUcTL(GZJHy1NA9KV@K}MA8uHMRdn^%%ALGM_Vn5>=dtujPJZ{~u3A z(EWbyy5k8BcSo^j6{DLh4D=7uIX=zm4XX){PSQ3!#;WCFV;fTIMIrgtSALrdxeyyHwykD!a^g3&}c z8prDkQBYEh$LGOrvnzXos>*8S)z_=Q>WSfT0+9qb(#S6X?Y*OGZ8b{S*RZ)bgw5T*=oY43bO&vWfT(tyyB+Q|sQo%1K+vZf#&RH=DtF2ey zF0U&tX;vpa?`7v@P9`wux|#x>kzui+0U8<`)%ShY<7H%Il%b(PRxDdiB;+UE<)FK# zkFqYnwlM3L)KFel!V@p-rFS|`NzEc!j_#+>8Rg7%izzOt;(Q7)q!PQQfwq7niz z9dk6!x+)u|u3hx^0q}om1urlo3&CTLJ;two^()1xOZ6}Oy#T#%_`ce)`dVH*aq98)~7fMJ$9 z9h=2UZ||T|b`19Q;t7g>$}&px@(_YjCM-vNK1TgM3Q9{;_nAON@2U7X`AZ_9QiyUg zGcZdWT_A*6fIlHV=1~Q@k{_BhY7C5yF)=%%xOXrgPDUJJuFzc znDj)PgGY~3-q=8ehyiJmTU3X7HPu}m%`R9J_+##9BLh()nsq&PQMwLE>%Fl{|O z)YR5dP*6Z95MXkAjK1z3acpi%=OBa`N18}GZS}$J)6P7 zZWiQgoO}8@5*9npJoOU6q>Ds)F1@Wssm-@>-WeN|-SFe^%+Ag*Iy235RA=?tl~@8{b{#%SPJSMFML8;X zLacbr=A=@#n9Zr|QfW9^G^dJr6J@r@BPG|=pknmQWH@aY<1r$Bp9;7(N=wsZ#+B)& zvaAHV@Z}O0hY3$0#FTeB<-sn^Nac4fgG4BMT|F8_QeG=->v7oZ#DhVMdQ?RgsuUs> zR$(HN)EOKZA}u?Iy81c>`vy7D-pPtJYn3;?aPDGbFS19uouoC%WT{9D<03Om==i3l z7#|u^nWiEkR68T7^yf0BMEGws;&xcbOLKF$t5;DpLTNW0I!5ul8nPWuf-^JB2K_3e zMQ$w=mISe+LQxV*=_Bt`y3L8pVpY^n)R4pziP6^6t9o|@dATZRMfCV7GQ`O6=qSz% z8zX(K6lPkuc&n)D3_P;^X$HnUI5YC;>+hw~mEfB9UV?5k^W@{tF+3F_>B?eiu$Q{R zbk5m&8Ya!ck=8C=+TViRk-^NwFfNPE2i|wN>O1rgP4Uu^7Ungsq@b*dK*EF}8fR6x zozpk|omB90+FngX)85|xM^mqJU@d&TNFRkp5#XL{tO`vd6^JNcM20Dc{QZ01`<|k0 zL^Ln(MKgGV5eCOR_`?>Zlt_2yW3gxoxDp1*F_ntd zN8jKSK2wqvtCnGp#_*0$F)}$pKqeqhW_3F3F2YfrxMYGR1YAv+4Hir?FC{T=621|S zqnS*^5=k_>lj@pEG~z^j9=wy&YJ$?~a$=PvC3$@@3FR;&Gdp@rEC?(ZELOaMAfc$x zPDyNJ~0kGXaz1qiRPb(Rr3+f{53z93?et%9AE5HEOj{{pUabxdPxhK%T4m zr4pA$s&MXZw_8ag#nn+RfB5@3sFKA%D*6{*c;SEO;ANCu_F%D%HtpNd;X8Vo3#TdN|05jse0p6U$dG#~O*F&w7c)bxc;PnpQN4 z9f7g{FcJz)qepyL3>q2fnG}}f5{pOa>=?#wcdE(Nm{FsDe1cFct}1EqLQe`{%9N>q zzcG%5xB}2fEJAL6J|=@sZ9@Y)p4mfd&k!{Y3l!ZW{I&cS4~LnY8fS23g4zX*xHKyU zUl3y~rY1z?bxM^xIX+3)k;cM?TBdr3Xgc1`%FSzt8s)X5s1`{)QoM^HuIzSYJvEy& zEJkpez&|m9%bdVvHBePqu9~)bRL7QPW7`w^v0KxXT|k!vgcy^`CLq(9PN(?Y)K!t; zPRBPng(g$0$ryQ=E}{{?vTqi-p{Qt`TP?g(fiOvj zowDKr3^UVe7ZZ*rm>8L0)-y_f=K)+=ob0qrOeQN{|7=Q1ir5fHP)SlzTXN3To3_IO?UOJck9f(o8#~s`gXYFQ@5H3*)mPBGCj%J<5@`4uU2l zYd5XO6p5kF`Y|MR>^4z1%?7%mM^Vhu=_YU?o8b28I)I-;BY#*<>m))y7Pz` zEX0H>PsW*;on_h=roM3@HbabPID#=QAxSIiaRNO;MqH{CERC+6VioUof8xDTloQh1Ck+6G>*Kr|?_tEU2%+Gcd~j zW34P+vlOE(L$xJjTND)w1u^{6jA)t>n?-gXy7KsOm<)Kw2U)YM4)4r_qP&WWi&Vq& znVoyFSF&nV5QtDvMx&BsOA#x2dHJ18>8Dgd(rS?13+i`r zghD};1}4R-)9z5ciTt8UmY#bhvq3Yagr8-_F3#Sv6z#20(Y#*O)Vufdw{ZsE=>UJ{ z!%ZBT@G%wfWAerE1mld&jPuP;U&vz*KhN>5X-bPTxah1+?A_BsVOb`N8cTR``vF2R zGYb}%vSDcrcRlnhQ?ni}KKB%MzHpeqaUU_=L^K?twW}LXEJ|T{IpwA07^6}2ppSHi zBoW1xwmKS3;+-Djw9Si2w?ygd>LV|=0C!G029t#ykMGBxQGijiV%21TD59$Ku^GR* ztXjETEfS+cqj)FBDb00qrT;EyIas5jjl^ zuP2BeOc3{n709;^^ioq-ORhVUcp!uxjVX|xnVux%bg{6p2H)Tq`;N8{P3kOKz7B`e zrtEH;4y1gUWaqJQ(|Rh3Gs$#VRKqyn_0iXHf;GzWXLxi3w=0W7`&-q-YC(w$cXqZ~tlB%eIC5}5wH3L%_u|vpcK_YPlV)lg z7xCQA-Aqge$;mCHu&9jr3+jnP14=Q}($Yb5*8qNlk;>8%j2!U(DfLhP*~lcP`(26GL$LD98D)+FTgMVrrauxMrC25 zOFzY^DF8Rw#E7hlrRQCNFKoq>2vDD8@$xcLv_E059Y5 zdXn28X<~QZ7@kCw%%q)x(HZ;^FaP$*^V#{#KAzp*L4AE0S6pxgPdvGg^c*Y87FY4q zj{Pd^VeQ&F48C#l%Bp$l>77bh@z5jBG2s>CC=>o!FGC}vq-AC?;q#N8lg+%!3j9+e zeBkPHiH4($P5G32;qy;F#rbEhp)B9U3(xFQhFG3}4_`1$G+`&Jpq%omN|rAw#BCL^ zyoujE@;GZYrNA|=M`>>#r}@ZHa?`DR^!m%W@80_fg#(0xF?#!^2;*R2!q5AzyNa@k zY)pnY>2?b{b{=EK8%Gmr$sZyVjk3S>81t7cCCimgc*ct<9%piLjF>w^d8haXhm;Fv z??4xr?YPsNlob`I?AK^K!Lj4VS+i~x=bpBNm!5c*>Dg(fr)Tj@j!{~aOLbKl{R0DP z?7yqCi>WCuY1xHnHVvoCj@#|TUdbJI zZD;km^*s8(Z)rKvrb4R|dYqDi9L_)Y48qX}F+Jr}_~1j^ai!r&hQJ9;7MFU?Tq(Ij1 zmke3yYgkh%Ad%aflPp}cnCjX^>~HSIZ_=nPufX8(5Q_$tQfXpjjAMu8zQ;(no3I$| z%CaJEh^Z#A?2^R&QmXS$(DY0r)vyUY^SwPcIz2{N3qvDf?-Q*@$Mh z;B;lP;)3@QO1ji+L|vwl%gKhPw7Hey@&Xn%RPe;3y9q^2EM3(|U}k{M!7(nrXe(v; zPHz0a_b@Q#!>GCNdwrNpW~>GiHiv_lW+0{qa3o@M96d-R>cuFk8BByD5zJ=Mphqz! zGz>`r7JW80r+{hF2h;`{%~v}aaHC4~x+2s@iqBN0zx zlK8=RL^VGX3GsXpD=f9{s1f;d&$)o6W8F+fVBV5O<@sca>O}oP{Lu(|jviw5+BFn7 z9dxvH5YQYfuB}8L9b&M*n`O%?l~;RuMmm$DW5mKbXP$Q{`&-({FD#&C--}H3o=`q7 z(q=Rp1Pr5?H1SJMD!W{fI?BZ;>EbfwFY^UzlFY=CmFux(77|IAShc*4yKnn7BmI3i zH4THvJw>*vCT7LCQtm}wXI#DRgjo3sK*x1u=PTjkW%K5fu(%0o4r*)W5gr>;w!e{B zm}D%@{yonzJK2T9V!*DY5l@KEjZCD8MS}%{%tV|tdYo&V3ZM(X&++o|)CK&7j*({U z94DWu_)Wy(N$lbzshP+tEN9VKm!$wc8KOSR%*AJ{dKci|JQ#fYKGHkMi{^hcS>s7= zeP|CawR@Nj`7vr~j12WEkzQtogR3vxj62=Ik;C1L_79St;bQZa6=b=sJonT-28YI3 zwQe2l&CSe)Vpuf;S6#FvRl(0jRK=<0My(pAh_0L>V>z{ zKIH?u$M=)$r5fqO;eP+%j&^NO$LvFlG{pTUfSX4Q97p?JDe;@K4P!JUT{t zZWg75Idryl;5Ry0R9iu8ppVJ1Uaq)oGf_QEc3wU%o1Ko1UMBrIy%Rn{kr+pJKSyF_ zSn1M5%P)V%;t?h5l;8{rx-c6|SWM=W&45S=b!q;lhO*o_B~&&pBM?hamYu=2hwnv? zdeMwJnn~n}X7pH6HA6+Nm{RV<)sU9BKPu6S%ycE=$}%B6w}hhVg^WiN)Ya4xo17#b z3#E2C(I_(${WKqW5vw_g&Fne}@VfHVaXHdd{GR}MBoa|xTXP(|{9S-v&a=g0B@&6M zpXGOQ9pUH&=tVv$Anz0^D$Pk=VHu}ga~;i{(~t~PlLl9wyZ&8(fBVAj-}Wo}dzxfD zDcDoCuPUTTom!DGi0?^)TOQiU_jMhRAFL_~N=G5G4r5b?mM@N~>3pu%;0qPF`sVCYuc{ z9>W|AF)%oS(e0wNFqhtr4nk(B;HwDqbu%+P#De-9^k|S!D2hWQk4cy}e+Ao~*o)0! zrS0f0qO;T3hTA$SQ6M|=uF*C7C?iNe2NO)pe9;n>e!^tr+U3Hv1dpss>YRFLT*JP)6qEf^>uj1 zCYT%Z|3UiGJ3{*t42s*S$McFJ>VsmQMTvv2xJw|l*UOa9c8 zcqM>W+hjvhZJ%$t=Q$qO-OYqw0xu#YkZIBwOKM74wPZf&PBW7uV;pa3r=qe3i^a_T z!^bh2O>9`bSlP{PSi6FBmxN9jh$Ry|y5l8AMngmsAuMJqQg@4SlyX-TOWJq@|MUps zgI#C_8QE8}L~1Zeo?FroNB)y_$Ses$3Z>#0#izz-CZQ@wBcJ@-zwpqbkKvo_Vq$1O zSr>>cqnfKxU?~%*qRAEzHDDCLH^^heA)cC;jl?757S`gcyl?I5;`K)bAq(&5(=spGZ_f8Xz@Zd zS$k;D0dg|aICy9$X>uB)Au`e&suGulH|0|a4vV;NniQDFbzKd1$&N`4c1h)KO-;=T zMKed)%+WTo(~v4(ey@bFCRFC@;uWho?Xvf=t7TXw(kOKqxaPujScPYM7vTSFe0j%S zQ7jt7+Ce6N#kTox^_Ytul=Q8+3FX)NTwf0GDuzM$Q8B@aCHV1gp5?)pTA2z7(;X+G z2dFM|@r}>ChpvtR{Glj|8!Oni_ZU@`rPNmCbJHyk;17oR@U@rn@MBMK^?NU*qkWkE zu>fV2+2}q$_dc)--Re+WcqAIeVYjQ%eQ}!%&WscGjM3lGjMbF#w-NXk-xlE|-}=xo`|)JPw8t1WeHnHoJARw1`lOtwr}s!pTq z3?zomq8>#gj;_pdY8GuKndZjgvMC9lMAKc*hxiUriv1D*(G4bsr+_? zGgkmE#%QwMo=l%oi|0uiW=>HffIi2$3q2!;8bUi+<){8lq?4#B{=&Apd#*{VP`RDeVT)sLsFs z*EY8AX~h#a5|AlSi;1&VR`andwyyZ_(oif$g>|QR@g&Jekgns0nI7t7sH+)sJan?k z28;5c5q}#YN)#4hR9-Mi)!5U-xl$^6u_SP~C@5P%Tn2t7I++;kQq9KyAM!T0y-$tI zrvjX%YSh*J8WL7j=^HdNc6TYZoEjFcTaV3YQ;k;{yO-%#bI4Cm-w?)(EGi3f=xc8$ zY_?HfSwduNm?MYxVUAC5!P#dqFff44;i9#pm8C0BVQ55XDjx^-KE`-|KZOMaXqt(M z$th-LJ;ZdeK@i{*FiyQEHmgO^T1CZ$sR%P|{G9>R-Y&)Re9`OsexDsZ|CHW(&0oR#VZioN;fEMT_U-o0?|di@R`G zg@#KipZ@ma&A99uHk(~3mm)DyUBxg8I4he18Fo6kQ#fgVF$e6aUWY+lM{(|oleeg! zQ%W0A3rQS`t|o7{oOKRswqD3H2m4ghI7bWf;mfzYbpS6#KF&j5- zRNn2cG@1HVgXvr{lsu1DvMqkApWhqt_+r>525)i*Sjyz^)~#DfOG|rA5BElK@RF@6 zp8xW>nj0Ds(2xv(zxMc(05AR}(KuiE(LFqKq>E{Z;IugvUwXyHg}mp?r5rvoKvjJi zxo!)s&3)KKHfJ&uNf;GRKCiNfXJ6XGDH~St@I$-loYpBUwQ$LXrQCJjex}V1G%bX# ziyeWg(a}SGlEGP`Gef-ilx zlJ3f2+3GWiCS@|Ti>AHLDkDFe#lqCoG-Klv=z3E5poqbkaPo@&(BfD$6E>4eSt-QL zMheRpgQJ9)%}!Za5&5}=*j;H@EJ=)^06pCUB-1jeE-j#^wUv-&XJKsxfuVky4(uY! z8D;aj)ygZ%Y_W3ecnk9vty2|zEb67Ndq0C+oisMoDw~00N1N&D8zdArk~B$6TQ(~( zG-6nZQCd{avSmw%q0`knf+M4xnug^H;HL*Wm>B72VziI>bu|RTehwZ!rY2YA+=%K% z1#b)0M(VXzS67jjU%<%7IK$)9%wMve{EGRE&U%@@ppJ;ghj(&@*0vUArU%K9KFVMp zX?8oBMWXp^m@PInPav=yPb3uYK3B2NHCI($tC+1xo-3*8RapdtzL`_m2*{^EUjn|( zSTz${&f3b_b1vn%raqFoPN7}rLzixPYXDxJ@J%<}#23H#MU~DZE|21`EWYnzBOpd$ z@&%PZkh$&2U;E{JJ#Y6;19%Cf&dtqLmJs5dzjp1~S3I44Q|-v5JiAt1{+#2D0{FSd zmf}HdDCBv6@Pi*zw$Xp>@h3TWl0>39U;e?pJax2(pk~LGk)gg+TbEUG<>^a!@|gp8 zLkUjV&`7}VS5Ev!St!`?noZ6}-hP z@;j+e6=9&lv5i3w!KpqL*A#GY*E85$X+&Z%_Uzq@o-p7KCx|7CDuzyg&uEC@a%h~f zc?%|+gRY)#7B5;#TlWkFCFKlu9b%-vmD18;<&QMPPsB+X*t*SFkEW=5K#kPaSg zC27wjuBEBPWNK;*P4`pkHgmyw7qVl=cFsBfY_{!q7Dsv+RrO1VCu79C!}zDi(Ib9* zvr~xqWOHjLo{%VHG&Gw%<;P>t$#9t|%*i6doq@$_VQhQ~Pe7+}>3Xd0LdIsjEL>Pm z*yBMD#s~yG^z1R^mq^72@=d>Kza`7C2I333Zd={UBVYpyz<=bw8H zug9ajS{``lF;yMwQWq=!LU`#Ib=8Fw1GCzu+U zV9llt)HPJ2#iR8043l(aP?YOtsJD-h#YRJQDY3B;P8>f(V^t=n(x z{+ci8>v5ZR8o-O==GVXeb#)Q5w!b%km**>?E)w9fZrwU%Q1{myf4YKC5Q)V2+V}5Z z+p$p+?mQ|>@+ini$8CnvTnDA)MJHu*BeZpnlC(OpST!bR!>W?2DRMD9K1^wO1%>&U z%GZ5*c9!nGae^U@Xgs9!-EpPNu@H;snBp-qZ3d3)dV*j7;@{{wag1Nxay!@G@DWPN zO8M!Hzrq*RusU-T1)#?QSWIC)@!|J!WdA`DCKFpu+sxsnqug=NlVs)=a_;HNX{agV z+u!;&?zD8i^p!93!~eXA$=LuVha1i6AQJT9_e}D&FMpERi4ktT@xQs`@=KV%dmP32@lAE2UvQp^}Fup%*2Q&MY_JZ z=1Q*2nRDLvopbKze*X8r)N!z9kpKSi?UYqFsW9@Di>o>9gyYp>vEji7xa>WbbD(dK zg9AQBCKH^0@kRJ1rx+jV=Hpji!ua4IcmMA9oOse|)!qN*u1E1yHj%`}M8HpHXS>R2 zm2h$i$xf#H^dH>KaQ_hn^LRWia(T(2mBF^;?Ft1`c2)v^39VIZfJInUaFHwwPz$*K zEVE{I2rKX3!uMsYY{00YI{5V$UBc2+&f)PL1EiBliivRTdrrr!*ivs$ftSRkv(G;J zPd;;#lang^dhz1Ls<>Dz7WLtjIK3BI6rS(uI2++7?vEl4kRhS?xr@KMEE)m{&2D*K z&SRfn;AOZc7RBeBbB=PRJQhxxwJVk`Qs9B2qM}z)Ti(#3lMM&}03ZNKL_t)ac{>z% zxq*`ACBM5sAn=Or=L_@T<&!2n<}6?S?k(KCYly77oYtm#N-P%4x||XZ37#4WhL|3k zVAAg=o=IVM*i`tnRc|CXJjn3q5IN08Sw#)5k}@>AhTc*T*MRu37YxS~A4a;sTn2|O z#qhx$T=$Jnao4YJXMD^@YkQl5ByPFmPI~&MDXC~=(W0en-@X--F2cLdKaHRN{AM*I zJoo%_X=5FXI@+{9hcM!9)gtaHFW6Q?P z312&@>eKuP@Px7Lvw_cAfmOJj|V2kyI1iHpih%lOdM*YblKZ=tHbgG@TYKU}$< z+i&?5VTt@JFXzKo{{#0wyoG1?_hT)ornP-Ok3V!T?Tuwz@vgJ^&u@R9n(7Mv^>hDB zJelPSU;F`ORm~VQ9cDv_x~d9(cl)hOPmD2t;R3F@`XBkx&+lPuD#`NI$1&J9KxAr| z4_0x%3il{^jqP4ChE=V%+Cv;lg&65t|CfR5DjK6XDRl9Srs! zLemMaT^K!@(jN%dU52*>&b~}Eq+2g|-Ty&fQBcv!Av9GPkQZzVgl$uxtcvVb-WMj5 zz%)88zVu4k*Ph14-9t+2P@;=-^`$aoeFF;oEJPzKkpyF}U%#G;ii$t6?LGF>_(}@A z3^9bCE$K}Q7A#OOg9Ld9EcB^QeM;T5*#iGk9{cr`If}5sM5U7KlFAf@G?7);Prj`_Ng%UmwWtCftTJ&=}jaCFGnJg=Cj|p zg~z)`Nqb7Et*fQPqTw{@l|TB}z#!RZjH(jJE6ouOO`tcVnKP$~>hf~Zk+=%7PG@!W zP2}mD3Q*QiNo92%X0u(n59W1ga*4e1iWd)fDex{`65rq<&OU7oH{EzWr6tv@J$@}K z*DPW4mTmO*`>@)}RBmc6pCq3OQtB}9@MD{>JBz5BQ_mHbU%*d(ayz9}l{nl^o_O?L zii$lfU%5gVnAOzO@Z6q$Gldn_xIDbcmPZ_Nw9IQI6Y-Oa`RVQ6gW0U% zaM-x^+7EEYuODD^ET|k84MsEL-XnNN`k3+#DU90Tc2m_bm#opj@I;WsOP1krI0#IP z(zWv$JT5DVc!bsKR$+JB+4|HjDyrs^%H{A*O{pMmiSEnB668}!^64a92X@fk(?vQF z6kV*Mm&)%#3cO<33Y&FCET>|5Ww5ITyjf*uP@t~MVo+c;sp2k8zZCtv1fK|_N8p_V z#l;T(@uUBb=HpJ{;q8afWwI3K6MXpc6EO)5^!4uGWd*wZ_S;o3wqWjZELpNdF=#Hl z@IqFsSn)@=ynO$a6nN>_Zoc_uPCW5M^%_Di5~$(MJMTpBW%;nr7WkL)*cXCmgc~l{ zuFMQhKmGKhwL|`2*g*H(bI+^B$9}nm>92kK+oizELVMe7w{gcEcc|IV%RT;5fse-$ zeCC@sv#DnqU0Ds~6-AU;Or-o#f)ifKi;d{h0W7*Cmz;MhOBOWXatW(K1Uo``gK#9y zrj5_Bd-s?M*giBg#&pa^bLS%LZnIL3X5vXSla+KXhcTO_#B3xsG0OHQA0rr=W`5^! zbaZxdq_>-q(J@-*c3{$+YCE6HC-C`3*t6$Znp@kbsI0{|G0oKYBz1G4r>19_WHpw{>u`pJPQCT_|giLO<5>4efGC0c8z-SW4 zEJG+1A(PA!OT-!Wj<3IB4(X_+vz9_TdkAae-~R32xaOK`j#_5Ek^=ui(1~>0lH~N^ z4}Vy7*0Tlvr9Ae93cS!eFTeb9wTR5ZG%_%e&R$fW*I$4ApDb1{x4^tnkAJBJUKljO zYZpc8n}tPl>^*y_*YW4>^Pd!W`LIbRmdy}Pr1;|ZZsF0caWbBAYHLfe#FNCmLFU$! zkO&{*nh%}Jyyj}G!hIG#wKBm{A7AA%s7$krIug+=TOQla6HgyvIGp3TJ|D|YI6-QU zav>DetaN!clbL)ZN-i40A<0n52+!==NA;Xq+S{5*#^a=uS>>)Me&M1#^#%MK>KmY? zt)0;^FLgBy*i0gi7cZAA>1>**=}A?<7A)!{7znDZzPL7O2Az6L-XJyxdXkB_;-X6t zl-aB7EQHQIFzh9q$zv<>;3+Fp-MGb|$C=L2f20pXk%Q*CDh}`3Pt926e1gs;SUArAME4Iv(6+E45)0|Tslckg1NhP(A~8QT{ecnkX7~q zLOE5~xtN<7W@x7>N>SNVDq5@j5w?<23X74B;(v+`K`?w#EK4q}Xd()>1~OBy**%=T z{xaq)I)Sjkq?FB`Y=o;XJy8Xuyx~e#=`y@tFWa|oS8Rv-?z>NQ_QyggucW{W{38sI zV-I0e$p1ArH}l=^epm7D1xJ4=kCmN=EDCbW^5Eqrf8h&XVB5BBM`4;-c;-VN`jCQ$ z-m1rJ=PTW>+@n|Xcs*D&v*-I-6nJ@VDby0<_ND*&4Vw;miQAo2l@){Ehb|Cc<-%G% z@!<<_y99eJe2KS-__wI!A}Lx3-&u^i#J1K*E@NYCaFUyT{#(Xk2KJ34=vci5qdu*= zaVbE;qZi4(OEcp44v>ll2!_U$S=R?Ya3wpoZ)fkWy~?6MJXEC8FI~QzB`a3)$cD!- zS)ADI#S9F1(KM?P;0WyG_lN23>*K`JPE*3BcsPtfQkBSHkTfRYysM1X0wY95CYSBX=N<<&|+l(cI!R+lr@-AfPy^E;YJj!%}7nhx(kA4xQ7np+DhRh?wi8r4ukY>TCvS4vO?edr4|4q3TJ88SMf+8t>|lZrl6 z^-~HWX@z|2a|Tjk=^)**S^#I>DT0N|B49Kk9_;a8n9=@zx(^WZAlFBtx&R^D6u|SZ;DVj`y!Op2?T}s2EbwrIO z^w|W?beNA^acV)S`+7q(FIFf7EB)XHKd3Nr5!s0N;*}J55xksm!U-=};2RnmRFR$? zl)jY5$`d`mz{~&527-%>Utk)+%>+WQ0zn7_023Xo0NH$glC(K5{L~Blb%$-%bKO_SoC51Q)4vG zZQ{WPA5xKXixw>*5{;_nY5n?hsHv`2@5!OjN!k~#~@NC=w=5no_5S ziExCl3*9)N_cm!AxbtTqWyQqeg{M zOM#b!qZ!vXwG)!Ax1eGbZ=9T7_3EmyshnDcVavVGsm@oaL8TiOXl6$KFUnO}z@*<5 zs{)Dmn;su06^qifcQ4h|6|7vf0;}CZ$RDDwyN}7KNhT&Hh{q$Ge(FiI%xxqTm?ja6 zuxtBP`n&hAW_br+{QPII+8uoD8{cNzQ%|Y)fSAZtRg`e!4galF#sBrgAMwzJjmi~M z)9Yz&tm9w)&d$1k{z0Sss(zSNvr{l;Mi?@ph-_?ZsVIRaiwZH4D4EP**OmFObT@g$vc|OSk>!I{4>5R$l9c3jEmE7*}3- zrJ5c5>%ac1+6@SMM|L3c_gnQ4_KDx`SL(u7`#Rpz1%4Ky$z_Sgl6?CokMh{QBY2}R zEZG!wwhZ6>>PKj*b)o4~po=U1cq%x}_Qy8Rf4G}?DvQzP##LHH`@*HP%x?p;bg3SU zxh%PipT{45ihCdT@@$`v>b6A`6}wdkwc3Ubn5}m1x%WQo zPM0cjMa89<&5~^7WckugZoTD~$`_`gbt&V%3?^Ht>c*wZSAOq$172T%(TNE{gsDq!B$xEMpL;g9-9l7$x1lrC!L6)W%2})Ns@L8jg{3* z9O)&hH?XjyiOA>}`K*zQF2|m}Ar>rIg58i~WU!BL2CC-HE4XJ0tc5@>LMfchDiusy zin}T>1=vhr4YB#1HCzz3iP|pdmHVO^a_S2_^SsI{EzAmJVN$uW>gSB46KN*K#?W-& zcGwk!<}Pxo1v!(-vg7HUWHUMT?B1mYqwCK(6V0e277h`OhS<038K%ejdFT13bJ07_ zQFhID-hB_hz4LBmZy}JI2*SSll`mj-Il1q_N4WL&-w}yK6)e*@r;5+~%O|L;u3-1x zF24JN8wp2KDjeNyGw}J(ep3BzCn9kk*|eR;mSs4r=917GfmF1?S{K~Z1*ssR1OD0zVfk4Ipw%EEShZ01wW1w9PelM=Er$<+tb{;WgokH#_)&Z z6uImyp5M&nm#*hMANog(Rt=-hOg>%cmcRP-@6j`2Wz0}aLt}%oIuHm!mp5P*e0h3= zQgengPg=sWPi>{RxQsn}_cAmztl$Kv%cIn`Yu2n{&Dv%BAt4?l&~ zS$-7v&1Le+rZ*#SO(@KycT(*x^d_w^6r8b`6dYJ(V~h8BE~^HGa!81GT5lwoNU^ZJ zjq-|8#huUiBKT!y;IdO+Ud}|%5i&MA^$iuId;!u~jWORe-gt((+BsPADFQwp3C&DJ z!(3(8YZPx7>Cpw2p7BE$N{M2k$hirPP#h)|GbJ-)v!-m}6qj5uC_$@KAc$BFE2o}< zx4nFSmRml%fT%1~!OasX%$kPXZo_1esJ()sxNG-bcJ0`yc10GGkwhX&ZEZCZ6JA>9 zHPN+qCwq5nWl4LZO3o6I+SvFMo1b_}rB0DcQ(aNQ8E2fL;3V&)k4;ZLMLeEV{x>Bq zJExwsMnw<$!cjIoxsym#5}|Uqt#Ib4#}`;tnw6F&GlRy_AhFTIqnfBox94nKQHu@o%+qaXdK;=#{i-Lr*Ry82^j zhnqHS;(hOXpIQW-U*KhX^Yfqooc8v1_4G3Q6g*b=_p|WHY`6bX9{ZPsP9n|{N~A0l zJ9g~&6WZi!bYEYSr#)5yD$teuE?({9^(^o&RgwGWuJQRp)|?nysp66&9EtJ8AKuEA zz0<^!Q0tEJ^XooErN>rqam-0L_6W~Cejm5~<{`fSi%0(Kt^Cigf0~c~%SX`}9q4mr zve_`dyYu%v_E-;3PiwR;=)~y|W{3S8!iYXDH(c)pl=3O{Ee<<)G&zC|j{^|nP2(~WbDhce)2$4_Cl?DIK5efPg zhddGvs{5ek15#ddIpX4RP7br(f=-u1A5SR;PE;@97aE2{inzgu(X7Li)1xSpD-WGA5pu5z8TR%3<5rr-l#aMqkH z@G`g5>je^%M-&`5WzZ@@Be7hN{$0K=9ll)u#E2KG(L~TUjoDXG}o5kvb)Jx9k{ET zXj`<7yxC1gc2=1*)=Zp#y8J{{;3XJDZNiQY8(!^C^Dz*OJhj|BDcr(3ks*QzkffLk z1hRGOR@JQw{woZWmX;QEHnYW5F!@h>;uDHeDX@&--m(i27~%N^Ub=cQnUW5_w6s)x zU%W|fxZwuHQI`vzE$}bpv45$+%j?VBK!(IJbQL=0o5@G#rT$8f^>Df9qKnl1eX--s z=tXnvIUnn(BRjyCV3bU9H)W*F$7;QQaXiH)O18rm1*a=S4a zH8i~rs{~#|{G`J^4j<0)3q&55U+#uHCILwRK# zHk-S^-Vie@;cJUqr4&$M?99|oWi%%EwxTG;(a6x>y^o>ZLzwgc)j%r0G9Z;AT3Ad9 zy!%3DTqwG-7)sZxFXW^O)G|{{C4Nuh@S+(5OV*vrm_JTUc{NkM09m7nruKIAGxGd0 z1CZxaHpJ46%fM02S#{?He7z8efr=bV<%LTY$SH!&QD>yxt`( zN(RE|REqJT5t6|GUAuNtT2jo~lTXH7UZql-Bviv62rxA{t(2oiqmIfF7mf8*oPX|G zV(}DT`PVO!4^41fXDh`;E*{ymm4wd5oaPR;ZP`FBKEWxgmeA7D#D*=;&^PL5^}18p zwc|O0(}OJSY@wsQox}aT?Cu$0%}E#Hn+&sS>w~PAU&(PRmN6QLGZ@Iw)VYS7$wgiU z(b)`!OpK3Tb_x#jY+)Dp>UHYi)e4)>bMW9ne)`j&^7!MAD;Pi=3fHb(tGZz6?vM4T zk)IJ}jTC1wDwBVUtD!(4BAoigFMjbS1^!qiYgbp7T1aGZkiqNhYW6}()<5^y7qcpm zxq-kl4?OUIx{kNf@j@<)hYufS?%cUAdKqt4FPdXdT;5NzYm-Bo3!%k|n)JnvKVRSr zC~r6z=Zio3Et~gxNhP9O_ivYR;-Yd4(g`Y}%rrY6y_>II_bcvueEW;N92dRgOn&{l z+tKSJ@L5uXjNE_MqulYV56xA9!E9AAbwan4;_CAbsUVD;1dRyeMM5J~trIgU;lPWX zLJEH{sO0>b#jLvWDen|6vrTo>q*E9*JqDA3a41N?A0(BK{M9UGlNp=Sp%w^9p^8Vt zm<@T7(SU-4bON0SV+(K`VG3l%$y>P_^c9BJ>a4QAdR)uS3*s9p8g2hNZlLcWmflDnig#|{Z z;0nXh`y}VBV4s z`9dV0C}=gKp1Xg2D^6pQ%P&5Y+Nx6S_|07mj)s*;YUhsUuo=@_aq*dSbhL2uZNH(b z&r3~XE2E=hWFr$?c=m~$bo}vb+WG{)d2jBB!#O7};i3yKW^d0Bzq)4w zt;^PtSKdRC#Fa+NCHUwi$1A+PFq?R7lbv4IM5n(rWPSc8?BzW6#Xg-ux;x$lBuNXs-??U-YGMMRjzW@TjkiIFD#cromI3J#SBSg zjjTTPTnzSN_8mCH{Kd=BX;wwu6#Aub@ui50Oh2m^oMjd?E6DYQ?pRpVW_AtAh--Gt zDzr!8jL!^YCC+a~9V!J{m_P;ojnu}1@4e*K#$#~~?CYYovI=89r!0A+@wgIkS=>$q zLCHDEP*ynWvXc-8NLhT02BVr+^z7R~Iyl5BYdZ1RH4gXmvH#!*&GVLUxTgnFK~^uB zOKFLNeTRDShEkN*wkWJVJ~d27Lk08ZHsT9~*xNgTt+)}VqlDp}eaxHVrlqllNXEdn zy*;!pTT4!p?AJmN4XG&qbn$9RoRYvb!=8B!>5^~z0xwiFfoMdD`*OJNGH-a~kw?^* z>}1}^LkhYS_Lr;ne5(|AxwkUdm;3?wk_GO~c;vGar1OFyOD6`qpF6@W8z%^*W#DN= zZxa9WLSYeBg_v(CoOz~87H)S|uo4j=&HTSkux|9Ea~Tz?ZJc4@q=RFW+A@6n>dQ&S zVm$rSv-qc{866%b==Uj_UTJ9wie?ysB7Nfp_vkW6Y>)8yg-` zaEw(mQc+onySNygCIemRlqJ2jkj*Q@Sy>=NFeST#WHiEP_kQxeVY0yyI$9e!^{lhG z?uK8`v2-o*c!>T(yRqpL6uB%cTd{^6`}-)VnoB$h-rg<@scB^-w&uj+d1lWMJQdAY zEP~%3Au`!Z(0hoFeCo5@cJD@7mmN>u>YB-u6=*QQ)#ojy++E0eE$pxgyUN$%c-t2E z2OoS;%>p)W-mJtCqRJJH{fiv}PsxD!`8K?Db#-cBEbx@W;W+xY{QK2DWIiGOIhB=_ z%8*O`ekI3SslXq5eYMxd#`lr8(0J9wR9Jv{oyQ5Bk> zKnudwkgV5?IF(6(pLxZ+xEZQ~TVR|BJH}?zGkjFq!fb1G(`{mhKxmhY>q1YaC7Zu&HFcei? zIR>Ih9Vef25m?-8du}(&j$5k&!37If1Rc2-!e5`EFba=+HfdA|o>ZWTbl`+;_vhMmB38SKN#>6k4v_&KwElJsjS+;B;zqGqCGGg zDX*-ep}DC5J1Il3LMJ~Pj;O?{(%EO@1V;xUJc%wk&GKanmFLfcn|I(UuUEf^sj(pp znJ~w%S*}9Dx9>VgQCS_SjFGT^6tg}|dAXbBmKN@R^l9eIU7#2^@lb$tRBRcBxaOnR z^1rvs#P!g zAr@we6n7cy3OpcP|H_psIpvg7UJ@?+qA&0|Kj5ue;9tsZdLay6eVi4htHVDX;`2ZJ zHCwvJiKmmi>-hP6?gM9GwWP>OIJPR(X0E>GpZVF(Zhq01yy|`L=4U_quR_7lrO;(H ze(tT2%^}luqg16$GL}vU8;4af1E;{(xTF>v-Hl1;e}*Kh7u0gUe&Ng*vj00k`mXziY<;RPGq*+U=~9+w_6001BWNklgzUGhFK&iKn@Gs==+XkdVZ-%ndh17zdm(_zj(?+hM)Y%?a4SO=R(W+0VJ zFgDW5s#QxF9v;MImm#S}Hm{LMB^mejv20m~VrqqBpjn(M&|T73dV3DDX61)?eSt7$N=^mxPk*4IM^%y#yV&u%^jw+v(nOs*f(^B2OULz9E zar|lLVzd=AF+R=kh!>qfQ;(HAR3$<(2~|^=K3VjtbCzsWDTaE|IvooZFT-H9s^^qI zlxWbesD@(K8;^tt_@ieqES)sn#kuR%T|W7Xr$m2q@7&v@*FDDYGTJ1g9#o}d4RbH;xCnSOiK^7pncVBv;QaQ>nQsA8}Pafitok2o4NTss{40)zg)oU_P z6*wl1Vb&*HAPZfNXeh*y?!%N7mk{;`h(zN!J;hX)6=BhIBvUyK9_&Ulq`B&n(|PCm zbxMRax4DV$fB(PeJ=~*U4~dJ5#p8sc;-Hu!9*wD@Z?ictTddgZ_M>!Q1&_~Q?#HT4 zkG)nkl$0l)X(nYro6hQ4wBiKJjv}=H3Ctwi8Sz#xaybfxQ(cz6LYDO+`6_W8i3_kW(Wtn4)F7z{tx{}jwq^NG!|0tSRk!!Ev+u!;Rrlx#URaGn4Lgj{PMg_wh zr9%oPeGDvfEM0P@)TkYZJYK%yi3GKC>T$U}WKszhFImjVC!eOwwqnr)!H{3&&C0?i zyM?yacIEfpH$1`hKe>&GP@eL-25c_3vW|#_1I%%2*pox7T)a$i_Y+|se&0B5lZ%?> zxs=tGQQO+aBijzLVapzRj||eWq?3$EM@z8@L)@pj_+pO-gJxiGY!XXJBhv{@t=GP> z3AT6bLuYf)xp=Xno65p$wP{2nK4Rm2oVji}8}7Z2WlP#vyY4v3i%Zz_(A_xDlN76h z_62CJa(V_wc&GMPDk?P`KSKe1?p zhPpYlFIdJ+|MLr~YwM_LY-K2z!X(4iWQeQIT1;(4QDLW~P_);JtnVt^u&)@wePY(u(8*D6|*GR^D7;D zMoA@;YN)F&V}`3Z3l+_>TU2S8G4(2_NDDJRDe?mG6cxES{~hPDX7wsn@NG7mvSIG+ z>sPNY^iB~M6&Dv_wOOdIYf!8e@1&pWuKy*WgoU1gVT=~D^02Qfa?t2V(q{AGFvtW;2n`B$+t0lMh{bE_dI08?Ezd>0G*q z>WUhk-FQF7c#@oEq^zNt;@T#9`i6Mykqw-5!pZDCG|2E|1h*y2;bd>) zUlWTbIq%$adHCT6IO&9Sct^dQa^|_*d;k6T{C*ndFTtO8V6>Kyi3WM!*^8*JDV>4E zUfcTcH;ci`K=tDv|G2ul65BT$aPr#T?l=Flzm*Go0Us|o0eHRBeE2Ij(Vw)Du@|wV zV;;rCne5q%KIP}kQq7#i`hsHuhIgim>;$5SCP>45TGkr}NNY9;*1<%mV&*lcz+ z6cyhYzi*1N5*HS;f&L@iq|>Pxh-QY0_q-+g9kAtGvsAJYqn83rxAl@rLVV-bJw5GLmRf@^(P?{WJ$*y zY&H{ax0_9yo?u{TMA@9j6ERBMF0?FM@UC}r&wamVd}^Gs##XY&L*-G;_S>V6%jc+KkGdV;aFP!(kAB8*cRxa>=i0p&mp>aO&x$E)Ss)=Y$>TAkr zEViSM28m6N5)X`0?$WVt)gsocT87guYz>*qWt0jsnaC?9#J&RudH8{?3=Ky~n~E8W z<>*+s2BXmJfMBVC94 zuvb>IaK%!34nD`o@QC7?&u^YbU9pGY_@oMgP9@`HlY+6QRq%(fLIl@W3=w7LB6QF= zHj51GvRF(KD;H<)uI(y(LoHg0mtUYj&YD`OpFf5Jue$gdvoLuN$UMPfv(Vhq%=_N| zKAM^v)Z%Bi*;KempX8#(;>@2fF^hT?R{s0D@8qNtPC_%7@CU^BxZN^kCGC zl$KT!3wmibc{!^&N{LDb$&%OSNSQRWyd8`&<)#KL6yUaA(v8o<@nSXk?AokmMnF39{%xzmr>-lsMxok{q&a{J~Bo$Ye#2vGZoHY zFDa+AwhGN=RxAyjPE!`b*}w=cU4YtBCl0$Cr>9JLiHo6^6%!3}D%so9&xUP#h=wzC zb@fp-ualaVxeQMXFgi6!W8FMTtY%8Iyc+tYq*f=BXd-|T1*mlJf}=>(T_miil*)Kf zser_HMx_2R47vo{pLs&1JsCwnlNTSFLJHBW2h*{FqXI7T$0)Gs;7ul)<~DN0`>$kf zOOwLZg`ty4rRnYMBOH#haM5A~=STs6^pS^IwQ?2NY@S3a! z>m!twSy{JsEwM-fv)M@Rzz7ysJyS6l4M*u*xf++#hDp@6`J6H&8yD;286~Mc8^%P4 zuIF|Vi%qK`yX5AM3>-w4$tjBki`_vwuVc;HbZP2T7;m zBoi@gb|>+8TE!1~irmVQSayN#k}8^;=2B5sio1Fa!@(>jM+v%knD?K(l&0E0WL^Kg zz`ue@Ak-`Ilo!#As3h;Y>#n2EBHlXJUVE+boqszYZ)YC-OkMheRly&HZi5u~Pk!rv z**%pe=Pp;CB~sw6I=u>Rwp$Fu0@DP2Q)Dv zs+t>cINeH4FSY@q+|-*4Xz3*RzzC-uH;+_kQgwZ%+7<3C23`aG{e;62THEHU0x9g8XP$kUmgad_tu`X@1Yh~u^$d;0 z7#JL+s=AUnl~oKM-oc_;`273V5Di9@ILu-*qdAP&@@Bjf6O)paRUY6wPB=rvjB?WAHM z;^7JMxsP`u;o;#wdHR!1I!T$Oi66WuMBnbm-(rEE9kQwd{~tHA zdoo4NSxQq~HN~19t3gwdYJyc~a|v>ptjbA^gr)n{;jmkkAyq+1X;75Iyfu$zHImQj z(51xJJEwe9WH^`;#!J-8KV9_>0%JoI6_t?2fYakvvUjuHM2X$Oop(OUz(khrfeCgW zI*g;doX&;w=-$4Of!-cYzW99{?(?#8{sJ}Z6P|cB7h>(24h%XotspWMsO zZoY?oUHkEP95hweD<7BkiX@-=z$#^KA4#NeI<1%`>^!YkzXO-cN-$^U{~kQV&Ld!V z*Q?!&&YWfM(+|_!P|BRTIxJ>~@_G+N5@hsl^g@$NrWu_GG8XbPw{sy?Rh4)w7OXl5 zOpGh`Q8t~&W=@JnId-d#Oj?9z7Lw_(x({l^o=+3-Pg7Z0L1{$|iHwfP=_n?PgIp?3 zI_|?}Hc;$w5(!7}`GU$8Lh@yGh79vso3YqR@s3Sm)=b3m22xg!vMX>J(_DIT3kzBs zluypl1@<*6MsH|=|MHi={2EaRaYqktG}h=Z?3=}O?1jLGBU|O z|K~02nn;nex@m2y!>!Mw3A7?Sb+Zgr(~7&T6XOA~7*P0jRuw&E43^iC$)*Zcy)y&I ztb|JEa+pOxlTHx{PC|5?Wv$hO#z&OC(qOczp{T)-Qz0A8^>yq&GKA)-qkm+YU0nw$ zuC3#wQ%_*S{ddrP=m3jWosLoOpvvV|A>byn0guPXN3OXH-%m%obzot>Di79|=IGqefsDAQ9@)HT#Am8QvR<;f>DGrw&i2E7SaaS=~Gy_eg5 zy^+0L`$&k*KqgDfH_F;pGynO?(~0?Gpf@Yb+g0gedT^3xD2l^r#8uzSkAAzIDVm9= z>`E0Zi}9YP9^~DZoK0nQH8zX*yJXn8YcIYK=&eP>Q%TYpnDm7h8lPt2iWOAU)?hIk z(PvVGr=|#vkFun*fsGG8$T?@6Oe7R#-@aZ-D~ePAOC%mcGvrk?-*Lw+=U2D=mh~5$ z&;1WRiOpVw*_g#UcnFgr$GPX6!Qq453=fY`Qc}j@BZsN0pF?r6gXY$SJoeZ|wR@^* z>0mNr!Qv<*ACGe3>N+~x8Wm*rwl46mcCnRWE??psBYz96>u>q^TP*PM`<8*>(6ELxaKbVS0L6F-K&1G+QieeDqOT=FO*~s#f9Z_dl?i zAKmyHg0V2u(-Vlq*W%aS@02Z0C$K&cI@|^6NY9W96!q6qi*h3=9{0lEoyBdEegyt^CSv#Mc zshCVM$%QLwSlIT54qoNhzD8X5H>`vITQ0n>*R{Xh3;eP7adzOUIwExR^$+t;U%Q#U zsENFzh}PzM9FpLZ%PJ9&SrZ%ClwySlj$tww3*iz-dXnI(BHj^LM!dzP{DDb%n`F>s z1=dNBibXiIV=HC01P#R&BI8rI-5v$!7)?gZnpFjXG|g+_o`*K0l{8^3spLriD2GP< z80>Z`JRaqCSXxGua!uJWEe`*>>GQ>uek#d-z?C^$UM_>a%HMjkEjLi-oFs|ryqSPPpC8jVej zy!-OYSh%DUyWOJxU#@#Z4a)sAFc;6Ckc*}E@cr91GhymrAPP+lHDm)J z4n6e{`plGqi8O-+PgyDU;wr)^JEgTPWW_%|ohKbnsOyg9vviM)vf}s?(HUewoZ{fl zEp%3zFlU1tx9WJTE;n6Whw0jXkTcd_Kr))ZY1iZP4|C?}r}Dskk19X@$zXy>Uk+V1 z#)-$ZP+BA@TyaLmCU|n|4&0s+rK}Yn{@x?KTzv5b9O^!RKO7@xa*{R|p}A|xXMRWn`ZfnMJ!)&9CzJy4;_m-*>|WPv{J0PJT{^X5B9Kb-Er*O ze}HYGm3w9uhr`P0r=Eg$ass=v2wQO#lMx;6iYAijEaypqpWmo_`V0B9e=qQF zo~rpaKa;l-5B@KA@FRTe>%XEml*d|9N=tJM`b<>$en@9-5*nd`CG-k^7Sk>%M8dMr zWd&o`D>Y|&M${^Jsgm$ZaC9n3CK)Fk3zG_r6CB-7OSzNa=r~T78=KpPQ8TDPpu_E< zeZc}AdF&~4?rPGSjZv?UeM93o%gQjPQ}p-rv1s{mY8Y8$H>&}uV9xc`c0O_SyBHlB zBOZ?NU)OyPlO~RbX+oh8!C;8dks-p7fJ#e}Zcy-QtHp}PBU1Q6q@Rd_R4JKNt188B z!4_B!`MwMZW#^*8JoI3ZXui2ks)KJ^*pAI?!yq}Th)Q@`am<^Vo7JpB7&i~xcMl6X z7gJPK&A`AYKm5VXq;(FaVj<>KSF2q~EbPS|?c!q>x04JdsV(8$Yic_qp zC?laWu<>Asjok)%0%=-W>dA-VB>fW{IPk2x*3(WogQ1ZjrhI-po?1%FtCV?KE^j1- zo`H!;N*n5MloYGkM1S{TLK731(-AH^=Xh@W-yf?vjMd>{V$w?@nF51`NC`BP9>MY) zb{CC}&0O*R_wlP=-;2>wf8mHG^qu2{qjndED&qs!s4sEGF~G`$-j5-Z}Wovaxd?d7Wl5Q9sG93 zPgp!>4d*R--^+d3zxwg2RLvADX^8p;NBHkRkAqZP zJnR$HRap4^C$ADhJWoHlja&Zr|LE@SR;f|(WCEk)x<+FxTXQ0hJ-(4-B1v&k5!q}; zWfrKYKIPqB=+#vhKU3%nF?j_nzCfom%=qPqGh!Z1XP~X4jf*b1SjqVkqnJtiR|a!u3C;c zufuF|5S6Gwmzk-dNem_nCe47Ow46;{0X7~s(mkD`p{WL2&PXyEWq7nlSuD@*SVTM# zRk4RIXE|1jUFi-|sT}k|i%A;Ns z$uf!&il^*|WY8*&z|v()mECw>Z$Ht5z;;&Ru^`^z9?B|8Xl!m`$1~4jw_5SIJvf{$ z{DGkQlJ}L#Y^J2VO3`Ms1}l1_4VTNwMXTnpYFWF2XbQ*Q3;bVQ0RH|2FYOMz(gHso z8s;aP|DDFtcHX<{6EE$>Ud2Zp3(*McWpLQbKY#aT_D$uFe*uVY6}k zx^-M|$wh2=;#t1+&2QkcSxJflRtApBMp7V`0=He+8mKUjLZO$kFNY{%1xuIeR)DB< zn2j298tQn@74M~E=|W6;g9`bO=NcIqQZP+xTbp7HS#37%{rz36JLxnmP7gx^BYg9l zKPHYHYgw@>bh>1oly3xk;vk=W&tmkcv=RsjCDmSJC*bu{R8fiB?I2|^@!-=#Y#Xq0 za3aOr)&}(P47y~5$;m;cd{Zo4ejJflnBtOBdXJ1zT2hJ5q;X_;gwonNEFKTZRF6tb{~? zU{FCL1v7#y)6-Lg{Zmv|lrb_qKsuc)C|76T7%Apb!;dZS%I;vsra*0e)Ot|p=p~V= zd0q<_z3ZJUTeVUtQ7xLL@cDs(K1POzXm4*VU5sI9N%_!CZ{ysDfBAKlEhr@QbJRp5)K2;>Y@)z_2CO|*2`g`Wy-5UJR*FiBuo~dJ#pQo5 z@UMG?`1=d0JMc;iy!`BsH-4EwY>I16`Z7hf(%1ElJ|Cj#=^x@#-?^3Pc!rOCo3wR%o1%T}%8 z-1E;@l;dKzjdVIgU(XSyeN)ue)nRu!aXKB`_1oK3SM4Y%V|v2RH^2EK64)^nxs-rN zCz6B66!!Q*{@<0$sIRIanJ$EIr*vtI8ABlzE0>XMByNB706RyW^o4SiR21PdSTOl} zs43M^URln{RqGh?j*-k;xbwcPxJu>_NM`u|?41XkU1hcQ|NHcQruUvql1WcU2u*qu z0-<+Mlq!e(ddd{5Q_G#a5y?X+D`g!3) ztar}uH{@_;pIzQPd%f#@*0Y``mN!%1+@vPLiQy5-98Pt=WJMzjnshRW$?aFHAd5bM z%T}bkszwQ>m3!?p%$~sm53XX@?mp@os?pO4OgWQM0TuB#1=Tsc^o|VE+S<&lmO3@b zXH&*%qGiS`%yu77KldV@(h3q8Ve5n4VOQP7E}O>rN3?O|vZ)OIZyF%}6%Y2e)S{8` zdt%!!*wnY0*|mpo?jhIwO^5W4Su~ydd${e}53z8;OfEm~c<#CTAzod-i@e!{-=Q(L z#YRPKjx0JuLoxR4DKZo=Q`g+Wp@+`ovh$B)cyNrL{_aJU#iJPxP2_~Yox@bfkO~LU zQW2uVd+2B?BQ_SmUs8tC<5D74R*M~fMFk5ME#&dXpU2{FB#n*zy+e$r3)D|UhVGRCb@?;X|Pw6`*FD( zczr(R&Yh?Hjs>3R>DtBOrAu&mONm9|eC=!BCz`ckD=oq5uu;t9$w$YqC-!p7C5O;b zS4Yt#&QArhWU%H$Ge=WK+Sx*$$6wvgmQf%30y=HeTQKW7wdN4>XO$wPdd=j*Q&t6z zQttWLA1JGtPB4}xU9{5B+^GCo)8PoIV97!z## zm?M@j5>4>gFMS`Ew?>V#)C9y@&}Ow`wM$=|n3G!xhQsvtb#d(n&&R4qsVMOR- zZ8I;vwv~d(K}l5u@k|cQYA2V=;IVTyo(_ESXl#*T4S&NCzTTEXvDOxby`~`80{( zFzHB;_;?SEWe#%5Fg}kLtKE&+D(n(Fn!`bBb2Gbl?Z;C!jj^b(;=U9O&b7SW;KoljIw>mUBu!GWXas9FLnIO>l`Rm8Byii@N~7Lx%`1++ z-Q!2NoYFw#v{+bi&gqj0>|Xx+ z{zoY(Z)PHvC6w2wYHAW!Z_J4VPI45q92T>t_Fc3X458l6PCj+>RczY0ie-l_rJ-58 zZj=1?FPw9MBZ&`QXd3CAR9{mNXeD!~$%YHM!%OkU|yPr?q`5?DmcOHFx{XG8MPRcwP z&N!!>jf1QH>^bdUmu1h6dal0uVh)>I$2~uLf{ewZXoQ*`MJr}i;5CyaH8DzXa0FX1 z%~|h12Ca~xy1EuDc7=Ip<{}jp)l`&~@#N#r&_AIwoP_RyVJ2b;rgtpB;q;&t^XNrz znZcTkqsJ3qvS70m=$KZgsEHD+6R`wc`}U#hX|;cW9V)6SnKg4Jf$>qg_jRJDqHN!~ zMP-^IK_HNVngJAB$O!OnRWE$wvq@KO1;v|+s+cNpO)QZmme472Svl#r!}N5?Eo zHV32Q6Drf6J9{=W=gg+6u1;C{_4E$&?_d8m@th5tw;Y$(r=)?MWXOzkF}m*+yw)sE zyO$zjb63P%w2+rVE*j+(Wt@M_Ej;)_7YTDI#e9-nG{m_lE@4(%DWgM!l$X^pI3D0< zzk8HK)`z#Gg>W)WAd{q|u9{Rlh9_UZl1s8=$$aL`ZN*|Ls$l!v(`(qiVI5!k{7tM~ zvx+6l7UM6e=H*v5@$lnM(%jmH!{O%SlaHaK)UApWQY(-?0Abf;Qdzcd-a~ii9%i-I zaq1~Y@$@s#FniVE7o>@)t3?A6f=&O0i2MC^&5v zX3U;LGL>L_pqI5Tt)`~J$A_*spS^qc;Pm)$xV_k24wVH9e9_+8%;S$eO>aP_b0|#D z;IL}(pFV4@D&7iyZnnGd3ezJvLO2jmk_ksHna$pUwHNf+-^7P*RCZLo=`#F z>9n(O!F-l2J3`4Vq>@RtZr;SBzkifyEUqRAX~0oVM~e0?mVJg6ywPN1h>fY26c07w z?g($bsHA~C-cp>NGQ1@fWU~oAb?Xh3c$`XzOu~{Z)qE_WEm>ci1s}@0Y6? zOBmU2VtjD+7~>Oim}APGNJH z6z(rDNHU!zF8V#L63S~DaCD#@P8 zK6KRwIr8{Zx#P!A(mNJME2harCb)RT;k49SNKA}lv%o|wN+eUpYnw+Hjl>B=<7!e7 zo&97aidQRO&cvBMy^$B6eVTYEWZ+M#fGrfwA~s7Am&Z*~FA$GQC0O7bD<-pzoQTd@ z&CHuWm$S}2hm|Xz=cQ+#M!+Qbo0ejmnS4mI+;9vyOqFbkhL3k(9=6WM|&Huz48))(SFkL ziAkJR0V3*=#{|drHf{LX8Ed7gKNL zIU;foMP)QDSiY)W^E5OzD*1szRwosSvEkJhvE>6?ap4)f@a%Jpj0~uWp}e$~ zwwcp7|LpUW$+@q*iqHMWeZ26>2K024n(|U^`N(;+)SGab%p{^A2F6F()1770jxbq^ zjbI{4O0!bg+(=$eQ*Nf}@y&ogiS zLKdBRIo{kj%TGE&eP1RALl1c>!2i<(h<}t5{ab3$yxleHxirDVD8cwB!Nl0xZT>EP zKbgU+Z)yZX5jO4}VbT0Hdb$rVFdSj_93P|cy>GkktuNVGJo_B3zT#LCi8S~A<{4}j z8>gT2K86Q|2t-2c?>azJZ6&Lodx@d`{frHCDOkX)3DaJhf;3g2%M=UB^~YUWjjMJR zzJ?i!7AY|ypF`=;sHM8qrl1c=Fjasg&+$uIIc{MSk3RYoO-+sL+Pg(G%KTTm0DE;{kD0@5Iz&2Z60m-77cFEKXUhu3AnVzwy%T0yuDHk1h? zNQOh)wM=TFJD9;s058zmHjSmrucShYvHavC)I=)Km@2YP1^BmpE~hql4@TfG;laNL zhyM$9@g@c@L2S>yK7R7-c5e9KN!m^L%pdYVr~c6=%_KT$0!;c6_3>F5GsDP4N37ryV|vqh?p}^ZS3!^3#`d-@W(J z+}K1WlTq}<{oP$eqEUhqK@v&f^^4P!m~t0MCK4)`%VCs8rp$kn8N7k}8c4vw&xJ{I zFv!T{B*jF#yOeoL-$!-*bawCWrlh8UlG-Lr;sL9Pw!VaS5h@c=Gg0;dyBMKlv!qiQ zBGH&SfXimVx^;8JTKWqQR%^3JT@%uTAo^LRxQuJhr1MInNL-qtu^6YFb_VO#Z6XvL z#p|{iH4HU=CI#2XOYK{Uhe;|ge*;o7E{L~@Dx`~e+i@3Mhcgr8^pg(%Ga0-r>x`oK zd-0lrXx@ua{1@8CKYM^TZiU9)t^vOD=z2c(;Zu0#@fUe&^?uAY3-cC^;H>%cD~R12 z90bRwam@$Mq|s~PfyY-9(QV|4X52P2dNQFpGZ9QVGLAKuBNG{+w%p3**H<$U3X#(D znCx~eb}Js2lcSG3in)sq=e0efL`^gL7|D?|nW>%DN->wmp{FpV!gO_RVPdo&ztf>uG^#aKnUG5cEkW402ciWe6PFB< zz-K}ymFBN_JV8s#H1_Q~Kq?i(X_sp@Ow48FB9@A(aBToqDy+*YpddyvW`nt7wU`y# zY2iudQ)$;(aoW*}W3N&HSth(uU_H2onhNm$LSgkE=TiQ80{mpqdLuB&Gb`DTks0sX zKfs+2t>>)ehf`uobLY2z!$1t&o&qyFf>h6l{mGzrZ}ZUG)5Hl!FX6P~=JNdWt9fn5 z2t}KdjHnE1Cd}dhmCvh(JRS;ADmZjvgiFsop6~tF*9ebK5Q-+zO<;97sHv&tTX)<+ z|4@kU-}ewBF=2k&l+vI)+y&8>m%uQo7bBrYer%=!ryRSCTW`FCd?wB#zxV~~*Q~+e zD{@OkdN{};Ua>T1RH@7lYUR6MTWlbn*UHLIZ!TAq@$#V|WD zU>lL_6=+2v^J+|lOJj97F}usCYhS{WqfR0bjWF0dKu0m8$BM1tc~lviVSx(JL8DN95tNY9zo!kX7!R_dK|=Fg|8d7A1Ree(Bz zAeBfFNoDCC3!ypOI2v^GaW+STL}6DJqCCg~VGK3#(|gtNUUmna*Lc zIFzYMA(zBvm3w5sG1&(0~hXNfXuem8>}BNDlN4^ZVyk zlg!%5N-VUBAqXnKTMBt)7$V(}9?1svAPr?^wyt}bXdt43+(bNv)9Y3N{sSNQAcG?l zyu4;Rv7D8RaK6P3Fq>8xulT-7yp>=gfyH69kV{3GHLZ!WSDeaFaGb^pF9*5~5C}#o zEia?Dr&GxWG&Z;6FYz&S-~gM}u3^r++5F+D$4JCt96vDr-wjgB(2V~%Pp^7x$e z@9!2#b&?`RrfCGCQEIAcNdzXSa1|No-K!*#)2S3k9(9C*g9Zl2D6gz1l+=k7iZr#g z8Pd;@5ROce@dLZrykQk~n^8c{=5%%5$xN24E`LWB3PmA^=2hdC)hvZ?Lmyw@GGA#G zvu4d^>z1vAgCiV%=mN@1{A}O3i@u>z^nw{(W#K|UwP3PZ@DwxDSJg3h-ZWB~EL(Q; z(zf_e<{WhjEv^C=pLGllDc2N)K_far#`GvFim3qq&ZEH8mj9n4@b^}QeCMb8rvY9) zAd*%UG`8k(f$8ZVP zSRGdEqJyJW7aEyDj!a%B8Hr&N-hDboGMP|5uw`YXDpO8`BTApgYPFLnnix-Kl!lJ@ z*ydwlZ0Q)W;cn8g5vH}&QCD5ds#jj7v#VPLLz7HI z6@5_(yCSIO_V}r;sb~A{J^0EhnLmFa`}cN}%@l~|^URz#ho;(EdJpt55SpO0u3kwj zJ46K%$S5JS9Pwm=XecQDewa0*=qxj-WY1Cnb_wR*+DK`cm$YtBP^BQLqyYr42HY+u znnfd?h~Y4sDRFxhoF&X0$-Hy993HC$Q#M0jWJGb-1JVmnRjnYSR3waB%VJK4$c2YF zd-<_E_Rz0znrx~*vbV3F{;{Cs>=X)8Niab{$4-LUic*>y8>yKSM7 z${IK8k1la#*q>~R-IfvqXNc6(Sqjl(binatsg!Q zzXlIJw2FN}oo#2h+W-I{07*naR76%+CfBKqI5}n1^55t47_delLMj<18Xs2~xnL~< za|n?_Vbd0?DtekMHo}QCHg72PE}+RMc<;SKvoyELvevJBy4>)8xtcVbnovb zAsl(Xh3blO>`CyLM9VVH&~QKItQot@$3QGZbxQ-5be72QsA^ksm3T?Ve?ve%u)_j%8}OG2%ot5 zMt=Og?{V&V7cgVaT%LaRSyrujiPKLziCHr{=!vv zk<;_^b#CL|KXwtr(E$CsIyvLaGuSiG%fr8WhGNA$X4lxc`~o9`*QOwvcmBvvZTWwX zz`G6be@|7&cYY85XAFMBhCTe`rCnTb_R;w5W`6n5^Na-}poeI!H_Iy6Kq8pb4| zR8Bi)i_jev?HQ}ZX3!MHd;{@)1&hmr-Q!b5!eTL}%p@dt6EQ1cWw`8imBCI750Z(- z2nPeqUNDzuUw($^GiOq2E5)r;7*k}jX>wVOfw2I!Go~>%5hN3gU@L;Zu99dnMkW}d zp{j;>I;G69CDRqVy%MiS8b^smL#pLoc1WV=w^$`)+M0kMZ4W%L02-$S;B*ZI3}4#u2Mhl@=CI~0z(J- zh>ed@TkgY@jZ)#W@{KQlil6@Yhl~yPaNB1;huP)kL)U$Z(#jU;`94>{*}%A@MjN^w|cnb z1DEp3tDETBwV8XqaWnTn@Jp(kZa#SB<>VYTzH!Gr?2Fhqy1kO?t~edL6l;qT<)^_r#JA=2Y3o5wr%g?+fTg8r*68C=bv7~`knnaib>8qxrNTe zO5%F_PY#q#!pjd?(frf6@%nSA_d59APo7X2qXc;Acyu}4Mstq{c?onQ?n{$eEKx}Lzs(sTy_ceCPQVhC<~7QG4Xkg$Izuq)8nVUp%I%Df%7@ysT_KRiz+dv4kqZ0 zN3qt_;4nMzIi!I|$`d*CtgfUHq{bkDTi10%2i;*;5KS_bQO-xw%p@xqRpZF!a63J? z>{ilxMz#G*Baze$B)H4UNy#pVX-8I9KSe!*7LVhxSjdPOiZExa76QY=goj4)h=GeH z#qd0JResJp^CTX)|6XRyYT>*KE~KWRmdmfa6|b)bm%D_j>MHi{-OY;kAIZo-7Xy9W zN_ygq6)TwDK7+4*`Kw%V;durZJ`$m!u8uQSEN3Vf;`Zgx)%{zVYr?xvd0`E4! z%lH3&s*vyW{{0UDzG!0ohTYut=vw~cGna7xJr8qWD9rocH;cIUWrpKJfA%1ekpeG1 zS;h@FUdHUY3ch>ygSh;DrHdX>Z%%c@9R=nZa5l8x;}+-F4?F^=_+oISvb%F zS?ClCy5fvW5l;wqs--=jH@NVVQUV^YN7#%8w>+1n+~a1b`vChocX8_JC$eSdMiSXP z?K2mV3MZHt=)>vrqT3uQ6Aujz;rI9%jfALgY9KKl#FWhnw-d9^k7ltkJ~)KOYQkYc z*%ivMT`src^^0M(G+K$ad`dGh9#1oUMhEFgh+-m6RxeVh_EF|=UV#EN$WoKY7u3Wl zEEyTkoEVBrc5gP3(bG6g8lGa2cyNM1G)C>LS!4@2LIZtdLNO!2n*`>`k=2uE*(9l0 zm=jJpo>Nadg%@6Wg_l;X!|w3o@s^;e`gxjMI)TS!<>CuZ=id8%K{A!1rly|2$Qb5= zMmQW+Y#YDVjkm;)(_caN@C4yhk@k+c1cCu_;c?ui97S2hPh&0b!^$!M_(Yp zf?6w|xZz?Wz)xcEvgDhhNxsu(e`>qG2!lU3e19KR$p4?4_oh*T;pp@x4}Rm8z1;WA zCO-YKv$_2nKT%?1w|@LYp5Axg+aBQ6CoQa4{$Wm--@=QpY~k>umZ0Zz{NRUovv|pI z%x!PwwlDk_8M}>4PMTFj&`T5>g@Tt+`&VWi0xuNAuv@Zuab3!*PE(;HYU)S0@CEF4 z2i}TmY!ziVd=9*3J9Y_>d zpSOrmAV4lD{O=u<>y z=-$0Yd6SyVIjSps_}vanvZ8T1(Zx_j7D6HypzDfW8j~TlxtTV1Hbt>z$`-KZvJ{gs z@|iT@WQy{pHl_KJkB7*HLyGMrob-G?jh@SsjK|1CLpc3jI_Auxt#uk(H*Z(k?xkhr zXj+j>Hc2Qrp%_zTCBmi}C70EezJE<^gDL}Sro38Z$h_?Kc*zzu;(CtZu^=6D=8;b8 z6p~4@>7>!y;54KhO8vF;^bcV+*;rI><+hJqh|6X|D~j2R48Qy>$eTAiir@AR^&M<5 z#e;tbgY?h3$-B{_`QvMSJ5@;GP|J@j@l{9W!S`Yy@s`ik@6}Jy*j9cwx&2$e^Tu}4 zjPurg95jqp$C*6dTlY1&?ZJIzb2%jwAcaqb;R;V>(z5RD?&r>RX3je8-#Bhgy<&M3 zgi3A}X3j<)e`XUmTy`#3f9xwntafGRCfTV_4kcKMM!T3y3r|}LgcfOI7s$b4CX>~1 z*d1tcErP*|frJPf7KB>b2@3O^D#C&N;;3mqB*Z6BUn`iuaOg5 z#)3(8)fQ6`G3HX(|K*oo!j7#w=<6N8EM2>**Qr1v6{E7Qk?GSr7#rv(5SYO1DJ7Ul z)7I9E%`U1saz((L25 zo6pBBjaP-K0RMK+@5E6i$6qn*C_L5#po#H4HImOfv-!zS1cM~yre}_vZye7nZTrYDE}|8h{@)p z%wNh__ipwL3}EtBNFIr8XZX>Mub z_@fr{zyrTw-Nr4PcmDZQRaQ`4QNq7}>8qT!{7kGiD~Bwa%VWQPiq1WqTygm&_)FaQ zOFdkF-7Q>x*%f%bE*37F$2~v!DSP+r=hDkAqqe3Ruh+q~SKq`{*Ih$i%X928NARsX z|C^q%1iG&hduatik~9~sqzgq-IbE$xRDY;kr;LZLGchzwG9uJT9k<0qh2KHPv_>jR z9C#dX)RBiO$pWv}OR$Lnj>(mJg}Y4{I@Qp}juL0MTDcDu`921#%)NO0FFh#r2yqLP77 zAgHwYE6d6hTow!miAKX@Q)#Tl0`28yKK79_@koG|3|?6&PG#`#_IaK9-g`I#f2<0r z?A}BdTUy=^zLy8UjwTRuOyA7fv}KGplTerNI+f3hz*`lN!EPz?n# zdHIzs{A$%czV^xU_|jMJrZ17;V;??-O@qIB+tGOK88?@me+>(pODNc^eDvl!nK^AX z=bUvYTRXd0aq1C#{tG{1JnO~kcBp`q(KCihp@>|G8cU&pDNYPx&u3Y2^07D^8i{m-7hZaiqmMe4 zXfURrgLo>=s@1P>_SxqX4@XpB+p>8RhaPq~qk*u&Ldj+6?&@Os^5yK%~ zCGBDo(Q}K1f-2e?YKj6)rIHDP!^0#3LCU-~yd@qyZaev8gmX?ljy+pn$70s`!k0cn zB%DwpYQll71_Q403r3W5eV0?At{o9KqxD zF=ycd^*1sR4y#q0)DGsAoA~st7vi*t?vF671mKzq@NfHIPHphNdjymzwj$)2cyaYc z?s;YlcYWqE?zrO@Y#5AFU+(3w69<_{4*c1HiUrK9U){*9H(ZK29$@{xVIKO!Y8t8< zC@U#4cm8ZT+8g=xZ=U6~Ej^0aA?y(~At}sP3aO$fC_z3?u9#IC=`w9uHM7dT-3|vO zejg5pop>@vJey(Wym^#*-30b`v2*8MlBE??PivvZW+R`Nz?qBl!E@iwqD3=!`SsU% zZNp}Kb|;sfdlq(w##g?62eDY14_|c!9qp|=^1Daay=yNOH5Gj5%FBs_VtoGx_mI(Z zeE36`(c0R;?;m}HU?@Q{ndO$7KcXOtFMZ{!1jZuVdh0E;&uHVvKfaq#AgT(SH+}qi z!qFJt{N~+k=?ai9ugByq$D&y=7xEN}Idmx`i@CMctjt03iMXPBI?ZOqKx$}fB$u&4(=r$PvR>p$5B#>#p}UWR-pp9Ih$o^jg!yZDj2+`Xp-Us+d=O@AA_+3jni9cudQas+O_mXBY5jts41zY zm>k2AiEz~gXHZt^WW$av3K+(Rat<7H>gt!62#2t{ zyqtXUNeYjD;rZuqxjighwhXu5$M)^pl%aQje=nDP@N$yz6u5s zzkdv;!@~H;5Eor~A@M|pAK(2;g1Uozd7}#Oa(($!3aiCn%2@1ng{NmCVNw%8oEF0y zwz9g8zTtkxM}@MQ;*$3tkCqZnzQzqVUX9gWs%ng(P>{jFAs+tyldRp+NxbMGn6}V1 z{}430WWxcXfidj)B9-1!)n8EA)I{E5qL_{`yuXW3Fu{0mLflkoY;95|DIEs?JxwNd5y80RlW)tI~2zxqv815TjMr|40-3MrEpUL3(7JlPi-(K1Q=Tix(|I3yss&wFgiAG%BiE@#F#&Bf}iIXa;S~wQSn4nYHWI<8`?? z=ZqDqf#`P+J*-Sl&N+Jp4K>y5*|nS1uf9e_O&!M{|30M<`Q*yy2u0!?f84ROHaBpf zyPKz1K2KSBIhR~~KG{r$pWSyqu}GZDulN9sjg4&Ewv8vAc#7uft(+&@X)_q0!tW+F+K{@ z3k8#vcsxQfFi2#0kkYamw(Zz~shDNy;me3eLmWA8I=S=&E1!9aTt17-Pkiz-ELuFDuYc_eDxh3(`IYqa5Ac(F zend-C1KYN2 zV6i(%B;u-BDw;@f*Y|!z*KiCx_1Mds2!;%Z zOjMQoi3g3U&ZX1}3HZ@jL5Y4}Obowh?U+2gce!Jm^%&b|!1xr5iS2)5y z(k=~JrgBKa#52#o&M(*WFqpJpN(Q*+OIKjCNGE9)t03Zn1(-E-5yFy=8__)xM;}e& z*_E&G&=apRJW(X3$FWyc;7zh*P`BZXcqM@4BF z8R_J-Ss4#UsA^~+I1$BZcjLC$80_w5+Vob2Mn*`)6Igsss;bJc6|D3RkBLm9qBL4l zF$$S5pS$g&9JY7{Pd@Q1_ul_Aygnb_`qu5z%fvO;-b5^x;HDdIxLzv<(|V{wi< z_887P?>ruR{0UaBT&a9zKk><1@RyYF>Cb*u>DpUsnlXFJ6g?1|0mEq7f-1}w3t3zy zjYKd=G!dn&rd%mCPV^7q6!)Zj3b)6E-KulMlDXV;-PMW~sT`sx(%aw9x4-*C(wdui z(NEWCjKFx15{HxO@-p;7fs&>M;zbx2)=DI*R#>)NmUJwlq!LuqmB@*?+_bmPq{3sz zOkUK1)dVaeYs&9RWT1;V-go#yX3w38x7354H{r7x9a~vZwp3EeQv4U~_aZyCceC=T zXZhHTSE{10#avKADU9q)}M{1gxVA1Ow?$LBHBqeQ;gyS*%9y_5xjJ)Q=SMJ4P$@8I0mQ&*?a{o_%%dXCG zM&deU)isLsp(hep?OuEiGkSE4WHv`diCb~V#kVt>bd%G}N}t_Qj6*s_ES)5oPB6P; zCS{d1Y~6E!uKsZ#OT@3Yf6B-{zw-m8@U9`7OqnODN7!4@HZqZDycjgI?jgU#j zaXXcWxax$JVx-{u%HmrZs8l9u#%eJn5~PtyCOy%25qr91(ts7jhg6^>*&=mp#rbrhT>ILaFcC9_Ix(`2^daJndD(x4}B zi7ro}z<4N1T|+&VTuKFEYhK51FW|D}uoM&2Rh258mx`Kt%w{{OOqzj#KJL8pE>1Z0 z40h}fvg-BiSga0p3@k2crnM8&b;g6^!~>&b$H#C;7*(0Lu$D4vMJ4BM^Lkly*paHx zDW>KHWwc>cN}WYhmVD8S*Hq-pW9G1JZy&3+_ah4tuidN^I5n%2bTY=^-~iD`RM`a`Ok+w0aGDxA!YitgEj)g~9z>G21GY4vH`|JSy}x>#-#@hqJqwz2l8V5X%}Gj3KI}Fc8XM80Q6@$P z)P&=(YuM9Ca=KvoR#nI}j82pymk|U6`cNj%(%x?vI4cv6$>5-TS0@{YB;ZVbbuzff zzN86ECXP4l{bYX!1B{Y0mX(pFVH1%s%|a}m#^oy`mM)SMy>~GVu{yAO%M|Zij7%)W z0wO>rM&0FAmDsEW;u9g9<{}PK)Kxk8&=u$L$b-M)x@)gi0bcxFlgT8}NQk@cx(h5G z_8gcXRdnI>`Y_pSxXUUTi^R#~3Zz9*aw3RBi0QekVL)OsslvB3l!@#?Q5w?RB}%)e ztiB4n+eJ2!$E4>}uK{K&#blI=&s@sJeM79-Gp2IGF$^DX*f$ z>Cn=gbJ~$y^MMukTpGDto^)QC)I^`sxKk!mk$60%WS_gc4zOk2>s)%t#kf6AwUUr7 zTEjor2;>LHU3EiGI(@y12g10|#W(KayWPdq_x_Pb;IS?Dv2|b#N6%Q!F*DBiM?TfR z@Z6-sRk*~`OazZVvxW!P9pI}UJBtS&eT6mayU66tG?a!p>{tt-`~Znu0(;R;X}*Rv z&y2EmzfRIo&5ZUszWkAM*uU;IIu2QYx2gn}X5xYSpXAvWR&(c_w~z?+fmTW)9L3>s zlD9c|;`v>K(i!@D_jBB`=~UQF${Vz;t(D5k3N~!(>iLacqI4G$~{kS-SL4&N%BV zoNh0VJ@yoL}R2=3BL8MZ&5V6*}iuatEUEC)0i=TF3Eg>fx#i7 zfeFQK617XKCPHv_wHi^$a9-3YCylV}ZUXTPv4Tc>Z4X)Zha zFxIT!%btNac2iNAW0!e7NB_Ug78qJ6gHm-1jR+lmzRT7>~dbN@@{qxBD&Xn(q#>nF{cK zVOaS`|GE@fzx%>x@H@-7>4dNSqo3|yaDGMxUo4uH+T#NcuH>m5qkQ|e3;FEr_s}1a zCYKZ~3x}0N@E^aNCMSDW7I<}A7JMaq^1Aa_&{#rcL!D~i$tLqWxAH|E`0Zod{e!RJ zbrwnJNwO*7K^NHDKf-SwTaRXUGSs`5xs6W6^KPiBMo(w3+MVp&Kgh1$AR}R2nRr)~ zm9k`Z8-7QQ{^4F0Ea<>g%qv~;bIv`NtOn0M{{p|g@8>FL8~Qee(eq?#s9+cg2u5I# zfNW&<^4UQd3E5r(^ueHRG@%&*LxQ-#HwQDvH}_*m7$21Hm4c+vyp>bO5qGPz&pnrm zF1<*}8tmM@n{X&-c$sE1D)_awcksYtFYwBa0c@U1)$C+07KsJM$!9{Uz?uvXaoC~r zRYqIe*e2+ip&OG*aQp55MaP^aJn+zSG)-GX-$aV=fJ z%KwEg*T~>0T2+X9;CCx|u{Xgtu0NfRfA%io*f{CT*#Fq%{zWnJ=(lM=so}o_mcMW56m#}ix>#TffpW)w{i880g zOh=Uuw@t%lx8e4c(K8a`^_~4BiXwvxRplkzaNWfOgZo*0$U@S|1a;LlJp9OGw9lMP zDx>r8Babt@e~&8UN)~RmTGeu1VYHKh+|aKy0{y`tu5#B&n8sN8zlrNgz>tFI!3^HW z=>KoLS0;snxV~z-H5rhNV!{+PtTrcJZ;6r=?wCD;XgtoLhb>W%iCEgr>6oT8TQ=|S z=PTcSknwQRu+TG`mDF!0F^=7wqQtGSbkQ6xzW4&_o2M(GufX`2n&`gq&2KV18YPi+ zQ`s<=uHkW}&*{MCw9r&rMS6S~b2`SH_9nXf_R&6Lx-wUZMxzQInLceAEiEmo^Yw$* z-$p1^K=W0SlO`;a1Bca)%VSfr2KH2(>n}Nxb^C%mzitOMJ8Nx|ub#N|MRhFpM`K7^99N@8#U3 zP%aab-|sV4V{ggu-_652mBGK8QJebCKi~))EV3E_{=Q#5$zyvG{P?yNeD;gq#abSv zZr;e-o_F`td3uBO+zDkc?o3mW;Soo zG7OCOO?bxG#t1UT3gFG6>cI?Og3&=NUfS{x1|^wVL`PmQ?yR07E9TysnUcyntWFoT zwRIf2bP)~p%{=ntOKjZPOHwbQ3HwMy)GT5u9>P?NF|DzZj`k+bJNIl#s~hl_l+fGT zquigqb=O@);&~?GR&3sSx(7!U2CwTW=5@3)Te@O{LtK63*(Bm&Hf-3;OE11=h}jkL zv^BTz(T{(GeLX>L`{I8RO&Ya^cs@h6XvX1o&@`hNr@tIqR_DZJ)7jY*WbKYF?AaJs zo^~jgopUNqp*kvCMHzCrZbS4@U5v`irAR8Di4d9eQ5%@LQ6n)XPh%c1?$^Pu8QA+| zJ!SIuQGut@NlHpelz5$SKMjeGck`MG@b6~S{zbkcnY~acg=O>B0_>mT&2R00P2u@} z{94d(I13t&_><57+S?!0yZ_?@zps5cyI<9LvNOUDKYuBo{o?J^cj!24M&I_%jcqEj zb7ut~zvUX7$pHo@()cSXlrQM_zw<)|$HH8E&I&$y?F9@4hH0s-A}|r*+K=AC&b@IJ z;LZ6sGpb=xOD%4P4U5x>-CMzy{UdDc2@xwe6n5@+Sy?c%nZUq))c_=RfSFVbn+Y0f zDkyQ;35PN*hwqzC14vFqXY$`0n5nd4ZQxXn6DB1 z4R~uZL45-jFjzF&n=1n~kx0Q+8nvLhvV{3_X5w+%RA8NmWvHxeR7J}~EI~Ayz-03i z&)QUgmy?#2gVkihYRXby?ZxMW>M{>kefUb!c@x!jbp(Us6!Tf`|HaSP)!B#HS;t@? zOI|A~W0P1YLQ7*4^XAONVoG!3F^d`P>!z=#hpq$t3MLU3EeW3U7cR!`sbF9tNhoTt zfux=+%9_FPFn0aj6+{u>CK0I26t5+Pw=_eeiM9}^Zd+z~fS6$}+ zzt6en+}@`5WHK{pq!2;~gdjyaNJl^f1OY)nq&EQt*0Kr~bg}CKE367CA|N$DD1juT z_aT!^CezF9{oeC?J>N4I0;}tatMcFfTwc7A%-lBLJLma6-_P?Y>bx{Q1Xb`$d4Q@` zU)Ii29loqk`IIA2i#-sq3w$(^V6cCXpkFq@TE)Y+KR3IBmy?z_pGG24Mn^|zZf;g$ ztUV#MzxWIMzB^15_`i0={tw;%f!FUrEQQ~H`*Q=?KUYvcZ12 z#Z6yl^2{u?Q%3&cr`Nlp#F|ZYTzTdBxKn*3@UY?SK@M9qmuLR)dtQ3^4L)(|DO~ia z6G-Rc_#6@hlI4nPZeq>mG17$sS}{g@jmF-sbySK%QtWd>wXE4b#M8YHGRYvzJp@Q^zB}{w=@z)gyLs(HuAoQ&A5U>@v=p5xZd( zVLDEylTKbbcsc&t%o=;3Diq3cH~;QJ*m%56F)eqKHtuWV_?p^8q=S`BLvU!hmps?m z=bX(+CmfB-Wh!RK@;6?`C3d;lteP3r)HU5BEZtpqn;aymyJx*uMjo05dK7!LbmP%9;lpt?%QvNuuL`0ViXR3^u3 zuP;|{i&Sr?(@^2$+uz>7(ifK!^yu7v`xmIJs!;G{PZapS zc-2na;ZLrB@Z_`kH1cOg^6JKKtyR$;A3Q(MuK$4fXf}L7sW;B@R9ESfzly|NdXF^qD`{ z-M2$1fTrsHWm+diTpir^IKB%EQ2ythRL64hmp`RTEFb&rjX_gbuMP2(AsxH(m)8|< zc@;2T6l*O_b*d5?K5zcM9QM(VFlkb=8hTEi)Tko(JWdAzpNl}ak~Ld<`0fKw61O~L zv=UCI8>b8vM|X4dg6S-K_AyLHiIGS|dA&<<&WNHnr^8~`_D#&2GmRY)SigQfo??{iFFTjR4mp78no3OJ&T9hk$cos8cICgl`+F$l zoe~>2baLG_S5cHCDa}&!&bGGcOrNnAPyGIIDtrbv+;{`ct&<5?RjZ+`eH%X)SYo;s zRiB9z_=zFwU%YH5?(lzg1@5*ngi6X0=Tw5b&wo)|Tc;ytQFF>vl!i9WM~9sKjp;x%$#G z*}Z)evu8}>@!vh6>~+_#U8nrZlc|IQ~eJ(M7c2bpyi54GrIJ)Upfgz`ybOaSu zVSfAM8~p5-PmwM-l)6++9Sa$Z{3zF7awbpy`sd7^F_o?zJJj=tb%fykHPuxdb@Z_` zPnpg|pT7-%T{{EA30$UA4K~{*HQ*>^>D{@FY>}jUQB<}EnY>2P z2#_h7=%ydt5V%X|oKDiI1YT3)!2Rc``@glhldjHT9lL&b|xK4JW!f zS=lE8dsvRLO_t9@sFEKPe^<{r!Gr(5TKfL~@pHYmgO^dGV6_hJ{_dl!9CmWgb;okY zE#G8SUzSiqj)M*v!{r|5cki)8`Lu&gFICgsZ4s^ta?PcuGdj4F_F2>L1^w*YxRocK zeUptFw(<2FFQ&1{&yMb4s_QC=CF6YY&U=U^T@*DpxoiZdmBer8czoi~A_+eZJQWRu znrE_eB*XR{J8|oI&N}%B+*+EYOP-~F_YR7g6q@SHOXw2Z?Jy~ciqz>+kbpoYGH8`z zs5DJwvC|$u%bya;ygN*_*)ip!zbC%Cr*hJUXWnJjC=+CXeWZgG`k!GS(}0lAr=X%} zCXF*tf#D7jiA9xhm)IKgkH+a4&5Z&SeZK-F=`c>po5v3^hdQA2HtdiXk3sqD6 z+EZCb77XGU>Fiy&-CiZeayq>#V^yq;TP8Kp*jUTk+cy#!>cL~>IN`XXIQX!SqMI&a zkuj#VPiF5qGi_Mq&s<)zZW}jj;i}6o!C^_tmkXaiM5v;go}S%`G8+h(eCCo%S$ybW zczi*$@i~fuek=)#DKM;Po<0?TQr=`g$Q3S{xrbKVKK zJsJ-__#5gb%~nx+LCs+8#%=WM+QOYzp3dmd+qAXr4f!}5w{GUQ&%DlP%1@?XpqJvb z);LKH_E4aN&o6=%lcv_0^u>z2y?cygGL7G@Grc*$Snqn$$)sXvh@eTl#?L$NTxCW3 z>t8?0E3YoMbLNC%r;vsf7p$4^%Ua_RHW^W@`?qglE-b%+nU>2b4rv_N0VNzyWue@r1M z0xyXz%!4CIM{5PMI+{q04Jr1Jbh#x-z&4yTG)-bx|1itm+DtO1;qrJ?V%F&JFm=_H zXr&yf$RLK5p)%wp==az(M8U?@&y-j0lc^lUvpNOctKt-8Euv!)>gww0@9V?qcHs^9 zC>HZr$v()%RUqHO{r6|DIrABfC0VudEov(Q{Oi}hOnqbhJB$AQLN9w*I+@~yr~g27 zWJtkixqOMCp%J!j-iqJvqo%Qv13z*wd(YpOimKXo2IuNYElbTX;_Bmg{^P*@%?}QPlnZ1aShKsv4op$ zx{`P%$u+lrjlsB66?m-_;R{!t&tt#%8BVvGIrHX`7ZWba;Eyl7K|C$gLi)^`s+dWvPs_#0jS!$D&2^DCP5NC|OY< zoq7S?G%1yIcJAEG55E6H5`j@+C~~`Yk2%Oj}Y{EnB3B=Tr`KrMzO2{Ms_z{x>*|{^ykW8h zU1hDh92VE#bSTy{ zXFkJlJWWPshL$bISIDRMv{>MAIq|zp?)mypS@za;3a$W2%_7v)giqq(A_KTxE@rmX zvU&3|^lX9Z+79+RU?ERE`vUQ_K|GZsSBSD#M}vy0lP*(=Za7@2jL*8d2gny~n}Lwe z!>u=7K{D3Og8B1^MiYv2{p6ERs=)BU!2#BY3JRXnovXKs6SU*Y|Aga);#+-$R zQ8L2}#nZHiH~r4-tX}>G4l9S)`}q7`JZ_WPK!HonKa;9(kbCdFj~zWjWJ?Y@+B>KU z1-S0UYiMX`QiExA(ix9ow5zktkC#)MoU>$;kekS$-!75to`Wd zsOsRQz)xWCAD)sk@lO7sD^Lb21XGvRQp3`V zve%y@6!5Zo#hYYP2@KsLIyRFqPG{)K*tAfBwEa z_wt*p-#$!651;_#KpVdY{Y;zQ%A|%W-gx0zim@2;rcP6ZuOQi`xd^qjHB4!n&M$uX zTMFXVqgkAB@^Nh2u##Q72WV++XZD=E6+7nVKmQ3j55%-i)<=JQ)3;WppVXtE4cCVm*LV&Jp3QOVCk|| z;Bc|eKJ)Q=U7Y{v^O!PqilV*>oTAqJo%VaY3m>0T*bth{xKZW>s<;;w)l{7_#(jax zHkjdjT?D>EQjHLLKGh3y= zdtD||C)d#5y@5j>H zdhT*(XXBA5$lv zKRo_8>o#nruD(gRUgk3?w(s0U!3?oGrjx~QD{`ws%-nkp^_7+MtXs{jmMRP@hGiuv z<~4%BFo|@DU4tt^pMKuNfu2)4b$=0Od=SrQUhYESWug6DBx3@L|@-7I@%_YNk`b#xdAI3rK!G- zY~Et?wl3=H8z|nmT1He{&fZ=jIMP%30;Xlmhi z&%DfHtrZ;XQaevvP5iT zfXOu;rZiPCbxN~>hBj~8rd&M(;d-LcD4knY<24PHmZZsvNq4F65|62oO2$Z+TxgYT zxU1Xn`NMQ=+d?K5Rji=qNs~BW;X;X zN1_CL2DjdJJslk#wql^Xf$s6EZz~DLyZJrjW8?Mzzad%LCnWh_Xp(Z9fN1_1HD%&8 z|LH4G)?C`hUY(Lw0O2-^A(n1&%h!IvpyuZb7krefZu>6jbcyp%I*?=Lh3H)OI@>mN zlFJuyI2|-kX(L?I!H*wa%3Hk|!ZmeVcg5K_Gb6OmnyH`yw~^=GyMM&1t2T4!g1y$9Hh0aje3b3^f+m%uTr+b>$`Sy*S8+RS6xpj9b^5nw@BuT zTN`0W0*#YfYXIvlBFEt`e>;83X?}p5{bNnxTA{EoC}BPr<97|$R){&%cnocXCi96;oW}IMW~kQtJ$i!w#j8RJ zycGKKkoAK;^#o1wgRb1fHswRLOVle;%WRMV@x^y+OXHMdcB`@;F zB`>mgPCMB|f<=oCWX-0H^!1IAw>)gxG00dlgVVIQ_R@1G#QF#ZeJa~@`SQ2u>>Xn$ z@1}b+!|-T?x(Yv6oO3FPU0Z2suH&)C9#b~CeSQ6mjYY`j3W`VV(8@s;wi}^xc~o7z z?fGsfUb*dqUdG+aidDPAw1>$y3}f#O?!NpM>k+UtDiR+@eGS%Bg6(Al+x?w$d5 z_eLm|a=08RYJx%Bo)9I6oHuNU#E|K!ZV*WoNfuoUMsis0AYqrTo;RL|s}h`X!@vBT-9>}1TyYwoyW#8XGq;s%&-n=b z%b%pTX8=7=ql}!Sh-NZ*s_SaORl%)ae~@BeGI!l|owAAD+S$Vc5B#^n;RXNzAOJ~3 zK~$E57R{p&9p$lSpJneUbxdoWf+5|cBhTi|+bKChytPq$P2x&bIe%Ic`_G=Df;@a4 z53$i0tG0C0pVZm7wU=TlM}^PHAqVZl*zitzd%74M=)uaTaXC|J-lcR!qRkuM9Q#> zR7{X}aQ`CWxLaA_XXdmHrS4q0YAx|(p6c30+)fXXv8ckxleifvm_!N=f;BZNx-jUl zc zIJF{&E!>MUPCSB*t5@OFi`3MFsi~==wx$M`(?htj3V$f1P7?MS*|Uld=JojJFQ17H z{-0J_CSLf%umXP$q7lA!PAhWrR~{hZ@Nm<4NAdZazQv&j&*h3wEM~(qj}WeGBs^&b zmSK`FW{D3CsJzpx;o(d7JVerL;S1MZMlRdOj$IKdDl1f1{?wz7(=$9qG15oJloomi zdNA}N;fe-&2GjJ7X33Ov3@yjB1|OAXj*^~-YysUeNa{W|52T1DbQ}fY!5b`?Kbig= zZ!s1bBH;7j^SGGOI)!u3J(qB}g8LtQm}j1SS@FB2z$-?Ez)*tKO8$}f$c#fYd-B=K z#i#5iW7`AUgV#NktYxaCAYJyhA-A%M)qX7`L`4-c`>_%b?KCw$an|Xab=Il4T~1zn zehEuoewA=#wc2b#;-TVj@|!1LVCP7dc;2l7wEYdWv`%g&-QUfw^{+Ff*3JIyO*Hwv zbg>(`vm&fhW z(M^x?gem6Js&Jd`AcnV=;gm)(*hIc$Ln~t3CYk}$Vc|DRq{arQ3A=GSEVA)2rIbDC zloOdde;=ABwc>Vp)n+PijtHsB@XX&rV|@R$R2G&=Y@w{R2%X;9NIt-YH_^d=fJK{l z$UlDt{$znK$srom!C!ml&&h_XxcubBTz=i%%$_}kFJFBoshz6{`omZ*KUo2ktpbUG zUdF}-*d5pS>QA0Q3r^;qFMXD-&P^1Zl|bUOmvl!g= z1~s+SOrJ3mUns=OufEAX`yIgWNSxn3_B&pG?rCMSYXcAC0o&@Tx1AzwYlE^auua|D z6RNSJ;Ox|<^6<4B24W{T$zWDk+vC3GiUw&rN!pAWhr+gHQ&B!InnSrl?lW&5AN$y` z>@#mR>(^~05DL)HT#wi7RBRv#r@rIM-{Hw6Z&I+_6pAKMr%7Ey6MB4%ME_=5s&o#T z-A1F&OByF0ubb6dcCcnggpp(kEuX}#r)Y0$V&?SOG&i---LsQ*8#d9~7bTyIbI9Vo z*t}*X>1djR5B(_hlc$r&WLWa_V+5QQha7Pnk3O}G!K{;_!>vM7@&)_!BdxcgX^I1% zNkpi0WeA!jl95pw8>%?t6KAsj!3R^_(1KGHc(FPjXU@oi+Q#qWN1ng^x+oWT2|pLX z(?o&)+t+mB8U8=G0)HBVcL>c`75LBH`U4`NI==YnqqyR_uahg3_}a~%X2H}7vSWkF z;ZY2|(uowAR9p=XzxyB0@Z6dR?#ddz`_(IX>6s<`?uB*C+h-1+KJTM^=Zs*Yy9J)a^lTp4f z(!qUCujKR- zjwIxEks?jfvFmRoNA3{zX0 zxc^7@vvyM_1>LRQPo>|%F^3<-nde`^>E~X}uF(ReLY|7sFm<&xDz|oUpr3d$ZHuZb zSTw7S+pqa7Z@%&pom)4u?*R)~c+g@hMb+x^sccr8dt@nViTB+87jT+#ffu_1iA*e8 z6@1W3bfSa*per}=xPR&j{C6yxf>z>+TYo?z+`w(;9m;2~{Tjn5lcu^5SAXhA7S5iG zPb*^O^Q6;hHtpESqmRA7%1t8-W<9vPCf~U8N>;r5BENg~O^!PD1dcj%Hs87PZgvj! z6V|eve8RDGZr`G)iBf2~`jYg=isYmW7ov1jJD6VUhFlKIVNf*O^hS#eWZWd&Vf0{_|PCVi}R)e$t6i1rLZ7ZYmbT&^0_hA0>xViLjI!QmhKbhpZ}Eh!SqoQ1X2# z@QU>^9^Cw{S(p^+a;U_3SFUK0HYLwivWi`>ox%F9OXWBiFH-xmlkK=?xy#VWXA=ax zCWTy@(Rd2Y^x_LuDK)Fa;nmhQu%maF9epF@EQhig&YK>>RaH!>uOzyAD`B_AQHOt2 z*%VY)S5X!8vc0>P$Dd!$?twAPe1eu*A6Hy)A=770#p!aB&E>f3U+!kr+AcLn{ld+c za^@)~vSs}iuDt3hhK2_4xHPW2_H!J6(n+LpI%iyP4cm4`@Hl<=D?*A5G^K3{?X4|5 z`S@eX2S+;b*2y(oaq;=QzT|1#Mu}-NJ6L$&BI+l#ssXRt5D0Eu+wgZR@bY^p9sC4M z@}F8}CSLrXxdQ5NJWi7oagkufWfska*WZiPFojz_bqF_J`(<{FxJl_6mA*9f6$W$K z8*%9xTROMXH4r0{@sLhiqzf53+FH2%mdjZF+Ury|Ph!XRog91kV!r+5Z_(Mal}b;Z znNz3ZbBFMIovLfxx;w_81X~n}Xt^;C+kXZp9dRJlm0<#*AX_`PvugcLHua>~oz@wP zr_hs8rqwtZ?OR7W6~{pyr*5gB=nF2sP;tDUdwL0Lw`^BRR)N3m0xwXCZB-y$sIzQ0 zJ8mkb2CrfzFz!oZGiJu^$<&}!Ii%R}ams$t&RG@M#(tbV$dv*kLD6z6khk+kg^eSb ztPVK#=#O&Fd1on1`ib8^$x}~0Logh`xqsGDlw35YE=1bTV%^q&rmdjo=@O6^0c=%<8+5?rK*)zw!&TA{mO&w&RehI zs6#%&Bft40e|X|)%wiU&qsS3QAI3T7okt{@;*4{zrh71sZUjl^#kSZ%CX;0G!g*@5 zU;XB*WK(gRJ~z2!grK1j^f)-WEX5CZy8J58B04(6_FerX zEI%tZbrX+7sPSlAcJ?uh_N-$p9^vGZPE>*#Dd@+Yb_SZ$%>zIA4}Sm1f2y2O8(OhD zY@tO;$(DcW2;#$Ew5ffD3enB z#V6&cqmSm|i$A56>}#08grfi;~wC|X`TUN3oZnM}l} z2n9Lfqlb`8#7QNhc(n)t!y?kxtA6&G^Y>=<{s&Uq(vCk6ChRo{`Ap@eseEV@3rTK! zI(wD_JU-a3w|ov0O4bjyb`y{KzqSH<6nHfNR4fslb8otrw?=dVE{pG6a}Kou`0-DF zMPJtdrr(cMbdVg2Q&Z_Bn~mWOh46+$oc)QDSiWKt|Ms(A5iJ-v{RT~wTd9&T=*??r z2pAl=&kU6W)Y{sL&$L**ej^*V52{3`g0lQgQ5Q0mTDDZop*c#pd|nz_XVO1n(cKfn zQ7Tazc5vU6S&0{bmo$n=h>3dWc{yOq3d(ls#3jbHvTgV7AxjCk~Dj13Lp zDHSl&5jvVH&`U9P^>nIW@x7^ zRIBeK9{!D3ynJ3_7hLY(Cla0huNAF{pXYzR0`KYI?P@2={ZHL;AItj0p1`6#Wbxg9 zy# zM6Zf@OJ=gPPHI$x$IczY48|ZWzA$EzqYjwE_EoFs8?xz-v!_i(GySaG*3VGJBxh;V z*MvCt6Q{Aes}nB;US0YUc`J)YI>_Du3Iz)@AVWnR!xSF89r&S&y%b=}_GUMwn?zGX zxiao<7yEH&Ms?wKhpBww?W7Quu_`y&IAkhWF7S5eZWpgy*0#Krp{i**$QQC`S`n91 zlB?3{vH466({M3;=4_n)Fg*hU?7d)Lrp=tqZ+`zAYc_N%PnTjbrL3B@l0`9-#;sfU zJuaM1je=IBWH`9++%tJ)$x94Ha_FX)*ys@LE!Aw@ypHy%lQ{gyBYAo03c7XcR#~rR@d-nkGSXK?;BM#1%ASd=6_xa zChqxvaRuI2;N_yt=SrM=SUM^-zI5le>5Uu2^Cnp>qY9$C=%6K7qNOrJ&$jiX5-@q%Os=`%8g9P* zUm1uL)j+gZ80BZ*xs&gF<;!f_xmy*(D=)o7`Oy64>DP!^ZdKp|UW59uNii{mmM@Uc zMX;iZY%bmZtT`C)1HFULKCzE@3!w|Pe({QRHCoq>GaLn{p4nOoj<)iU5$9Lma&LKwO#(u6q;} z)9KLY+P0DY-fo-~^(@$bKelXG#o+E9N;!EBw>o_kB?q8Xpdi-FO%3>6ZbrIxU}}(& zoL=F+7c~mwVlFvZc~l^}rZ#J*FhON5QOuBwjbP?8v`uNHpqY#$vZTcs)Z=3Eq#CZi z=CjP&Yp?Nvw7n7TDKGmQ8+f$=m4!~BP{=+d?2)_s*IdRE82n$eS`+vE@U6g}1zvf9 zLq1#LQ#apBchbSPZu=ygHt*smkG{azz$o5KmRYR<=Fe2y%l;Go&T6`GAe)_w%;?odD`U;U4lnP=6 zoMrBeW_E7hth#F5G?>3|A^n3F8)v9i}%>$#JKh ziqq}ok%xZ6AD?>q9gJPN>vtgf746@)L(~!yP|i`%s!{eUwX1J(QLj2a(t?>0AQS0-ssO@1I}Kl1)QIO+PcI zws6N~XYt^Vf5so*+)AlnP%P;b!f;iq8|mW9lqlxtjVZQyCkH^6x+T zAv?OZ+N>Al`Y1)WpdgxZ2VbtzQW&IYtImB~X=#gj?4GhLa*|=G-ALPCx0xIAerHfpLXncm(?z+>QZ8wj}b z_3!?aU;h3j3cA=Vin!sYoGLWUzmjye^i+l{B_YV#lUUloAQ0 z^i@(YQS&P5sh^s<22v^Uqe-X@M@}U=;wx|PrJFBj)f+FPmGV@EYgxMVby}O6FiIIt z`S{7q*n75etF-Oh-)lJb-~H;B;j=wE@;_DVWzA!;nED(iAew(h(?~Z7*Tkcx@?zRmvz~P|s>RW~*E6e=DzeWqDwmj!AKs>Z?q} zlw-M$AvO-`{o5iZp+?Gm1Rl~ImWr^GE?W){@-rH`gXT$-30K$P4tV+anWs=&U(1hv z`YV3>_=}V*6J6Xd#Vkt8t2cM~vh>SAS+oK>Pze}tN`Z?z4BiU!cBA!|D3N>|A zl!{3{an@D}3lBkM#fS`=Jf zvLzSIjg9y!YWcyhUm)hLI}zi_Pz9w)TvYQr_)4HNh&S`b-vbR5aF8a=OSBATb;vKGaXpt+8l+2ff=? zkr){vo*YxQ$0iO;6^kd#cn1<%C%!4FTa<$0&=gHi3cP?PlJ_a4Tk+ZjjwzeDm-AZ3 zp&R+Wc*2*1yY1p`%k5<&QBij)m_(zZvXWFPtIXJhZ6m?j3eV4E6f@q?O3H7&zBY{8 zsnfNqn^-1KRc#9%f0(@B`8XI$73mwvkt&M%RjiHe(D0nDVfwsyOq29z1h=jcuC8Qj z{}}FIC0@5!C=|(JQgj%E{Z1CnY-O;okF^^*l{K`4f2d4er%tf8nyGD*apW?*^4c<7 zfdG@+TA5N)&8ts5MJAtB7R9yoE%Z;vr-n>eM zV$a=oF@Jpe6>6%g$)}>6cfr}rm^I^F?Lj&4qa4069_vxwTKA-*7VAGjq@JYixhZ)Xhh8_9lU&QAJolk0)ziY6{3mP`8%zElsMsp3!ZGVXe3nP{9C?5 z%gm`re%~?73nahRMeuu#p|= zQIO%IKtIZDOil{A`nucgB^(Zu&F06U9ZRuha+##fIx!vWzyE$*arveAye6-_^diqa z{~R^d)p&F#hVnA^v2t@48+x+D@hf_zk%yAQU|3)k!-Y?GQsWIkAxms*n1MtJBV0jA zW)0(crJ68r#9`CzWbbKHv669iZr-2_#$>aIWOC}c0=0Ftwzm>A4c=J#2F{?Ly5<^2 zyLw5Dj*&L<_-mV0$BwMGZW4`UF&w5clbhDofSDfT&f7o7+VyK#yLuId=Av^;7n53A z$mUaAbjhb_ZJUB&*uF>a*cE8wEG1#)6pM84>Sts$N+Od}-ZvtQ+O%dpD_(mIk8W|* z)t{qn`V=fNFB_*@+R=XY=OS^9Vg(Th?vcrAYtq#1e{e{!?`Q3Kj{7@Zf)h_Wu>ya; z6|nJDhg|BG4Lc-~S=KExWhH$DMx9B z`nHoyM5$<+%1?j0hD`$+U;g4}apT~Lr(fhho?go5FS!71Y&!=nK9H|{`#;#Sc^6Jc zftzmm4Bzc&wH)2&kb!AI zJ+C^$NLOpiUe%CQ0;tuXbX?797kE1ft01_MVAJHsY4Udds=Sb}Q^W&DHi~SnNIsvH zDY6>AW{XAIr%&aoD=$}3cNLvna>l6~e8i!I!a;SiQRX@0aer3H?%?y;yc$HmL!g-`@PEHDGV#nG z))m;Zz)SVh7>gu1=cap@cj$ah*k=Y;eDQ}IweJjW`OLATdb@FWf><&@EJ}Gu5gp#5 z>gF38hPeOn^%Q+|-2LS%7~Iv%y7is>_IFS5h1+jnckkOQTyOxt`sLH~bPv$o^ETi9 z-tBz;vsV)z&0y&P5=93^hfW~m=IyN;&^0eDlP8lA;YwD5F?5PvC;low^JcU%qoEo- z6XCSePGo1-E((P-Pd@bwp!VeyJjM139R~LTcJs8fTcmGJreiXNIw#Be(c z7^N7eo_I8;o^T=+p-S97AHIMG@gH`&JeUrFtjhkLdqnhEFfT7DK3Hv$m1cL#kmfiEVhkxZ?yeKC+ z_`kSB6L6D-X zB;v!Ejtre$V|@2NUSi9TMPvIU?z!V4e*K@n;h5t;My#iYti$Bd7hmJLt1sr|C!eQd z>J+x`>S0pH6kdP+1@fawni^ZV?}0~2pwrUY$nNR})=2;WAOJ~3K~(N-n0f%eFHCG? zR8cK0mm57CKp^!>L#M6MM`UO_Vka{;GD;zrQQez#!(yp0Ff?EXd*mg++fdMeC0;SA zxZAjRQOd$N|GgXpU8YE?;j1d>iY#d3_-YVq7ypv#`6bdrL{IX(;|v@5&=n43?-mAG z1%pZ7DjSRlnleRsZCx>hq{}v45|!t`Z3YQf)Zq&SmFG@(PejEYYKC~rSZF0(ZGt7I zf#LDe(AYw*2$5`#q;#$VI~B!4Ul1!fPe_3)DcDE0CBfv2x~VodqnIaXSQKMpDl@g@ z_7beG#vzbTBucQZfovv$kxG(@=g_KZsHyO?yK@6xO{XFdCX+3YE#wtLD4h}3O%kIp z#zp6z&P5k~noy`x8Kp_Qqxw@faLAu>#wep+JM$=U^8tTx7JlKBF`fDO@1@Zdk(RcPYf{oPjJy&b%C zwWDKkK6%64eB|&$IeJbDmw)N!3~4&8^)4>ozknb9+b>x6_6Vn+`*GTuyvinb^_HFZ@&#t^)uB?M zURk=D*Is>7K`VyGRK``(!DZqJ#UC#?4O|r!SOPD|U@@D+=O|JlPClQrv2E$cb2;_= zg0YKd3WXdl%~B~(ZnuMYJgPc8!I1qvKbE6JEFQ%wmhgFf%4;Q=NRmhju5VHimLg#> z8jUN}t>5b-6!5FUGa8Ml`?OS7Dk!GEzn@$_Pi0jVRaI4tjzt(58Bv4Xw${n2xW$qg zhT~b%mVrA^fo=+2)S;BYE{V+3Jrp!IMRBPVL$thxH&}sD>BS|vtFoPxN{H1=8i=Rz z!8lB5e(#UnkAwm5r!gZ1`-Z3dJtdG z%~1!=;q>E=;49z!1sfwNW{8tvGQ*}7>nZ3ut_nXTj~Cq)VE-9YNXACkxNZ%Ju`x2K zj6Li%P5c#=cwHtbiLVpBcS9{{O_GBmXwf9Df(VBsBwFB+aXz}RTx2j>%uy^#!OKA@ ziA#suZ@iXi9g}$Q!JqT|^UpDB#w{2BC9?Dyo#vOu@$BM8`iBQo6E3e>sB_u-Gj$piDBiGve-q6Po8-SmtJutu3(s)FqOom zQ{n)}GjOHI%Pd2UILbljD*6ztT%MxXI+Su)LN6^9=-a)U^{dxXU0uUI3l`!I1aUZ= z;|6l}yhH?Ov9VD`hKH!FtHmD(+Ex<({ueyl>|BtCc6R+}jTY>+I!4D2a_|$FR zBjyQn#}#Lx@9yHkhaO=~w?!gv;nwq*T2jFx#k_E`4J?lvm*2;6M;*lB2hQcOKd$DP z*H$o+E8#Pp%$VGSGo4`bTdPRmpb)CX>8YTqHcU&skNDtrwyau?mKU7crEGCS_0`nZ z)GADMC=wx=%aV-8C`IGA3Ps7WRvh=DQdgGqQl(&&(5yUGF-x%^y!$j>!@&=~_e~~G zs$<^<`p&4S%MdydY)`D&R%n7^4c43 zaNq%p2n9mici;E;vC;+V>guR! zsN%t&KguhwF5|kpZb3{I3KCqdd6cH1p(e+0f-6>q7Czy0@HL^?Ufi!Z;-=*SpHA9WPV(%bK5qSz3~R&ib@tA zus?>w38s%fys(VCr;?H+28k>?ckDn9hq1&w z&E+B{f&@+DqX!+paYroT_FL|tq9RN#wu|%5IFYHXEv#C%p0?ThP}9%@|xHkIOP67c5uw{QF#Z|=x4?C>d=MCA3F zC`dg{W=s*dCdrCr%OPArG2q2jFsYR1>F**hII7{LrJ;^k-&QhmVhC1|7Cw18kDkjb zoV}=^8Nrxk%qeyNGN`l%pbm$oSQpY0s$pp{PfN86pAp03cF{9DN@Md3dUkeE9}cME z+8s%f&XuTkIj9Tz*cFZAuBc|TuZPJsVYPY0bEy01`4p3CLX3=#5Ne#lhOJwf+7QCf zy>#~tW4IicT8`;0E$rGoNKxVj`+I1vug2r{k~czh4i^|B0RFI$T~wFZHmQmEbN6EB z_HMSk-9sW@qEsH#il2`RNG$`eBgX-=TKW8CXLJ4aUn3qFgygV_CX}=!;r5IASKVK* zcoi5fRt@8^v|0 zzRlu;7jeevC-MAqFX8og>F-|4$4@?vnsA6EFTSYkghQ28HkVzK=M|40Q_VC)+3a?? zmFs6AFP|3}rlCyPoK6#;&xh0PR1k|p7xl3VM>%9gHVKEWBKaf}R*JmGWvEk(@|YJ) zUuhL=_fIus{Q!<;69xW5RIVo8%3rqvw!}%892ySkg4M%ycI_VG(_j2CgDE%rO$%|s zr%$A}bAYEF`y;VLikwwcG`(ClhtpxAONGi8afbt(_nC93a+kRKzK7X5m}5*>BBJD% z&dt>E7&?t!KV4flWBS}=eZqop6LgeF_q~lK6vBdgJi{|b{{OM}9^i45=ic{kW_M=$ zu2x;LEL-llVq;^#^Z)^ZLo*=(0)gNYAhb|I2_XqJbVBa|QZNCMP(uLIvBACfCfkzL z%l0<2-*rE;BAlFj-+-Z3gpFPp(kw{zx+vuLQTW95c*{ORq5RF;QTR9$^l zIXB<`5S{%=&OYe`#x~aT(ef3%w`d7vJ}>8<{td#BFpvK7xAgYMIOKqt%$hNUojY52 z>bc*O%H_EIXIBw00^EB0J+$_AaP(1!a?BwIvu4c(e*ODD5-?4EeD&puB6!IaKcgk% zCuUSq6uP3yh86X$TMZwD$1Q_Paj=w4%OT?A9ZIL|!tYAaRO#o3mtMfnetZ}CR2zD} z1Gj=NG;HfH)(grdQx$5*5Us=}RIewDpU+2+C9?PcMbuIB%75ovOPP%oWjN|a_ZGPO zzDK$E(w{JP{Ai{hFq6-gtY^ruQMmHm?Ao?bWy1>I9`t+hcqOk^-2iq8i&s#LQuunw zq;d*+F-?cnB(Z|>CER&=|MZf#zT@XF`U01V8Wd||!)4&s4HZ)E((@d4*epejR8&>P zsBx68|5>|&!2EMEM zzRRo``|#?Uukp&8Z&48~=kiN0!Rv8x_dWN~+}zB!zI7@`9(gFAEL_I3znQ0ot2bYN z9d(f)*Zt^cY~0<<@u!@`NnbmbH7i$g-vjp%Evw?{D}F#-O%-R&y_D@eMKZn`3cj#9 zwI~L?lE*rKs&uFU!nS-*P9}0Dv2}cUf?;8kD=$8e>#zGcn%$3K^(rVwI&C#9k?$C>$tJ8k?d9inU0FD&vqeb(thoIGi+L>`c;E@Hz3whT6=4ql z>XF=e&%^Ay-~P9B1d~56jDV>)im6Oj^Af0j=$eyDt&-o{OL8DbI&`6np$x>m7o91*C0*uU#Rd5 z-pYT^3jBuxubyV7gFoZyUvT27$8zM9QC#z*JNdymM^kRZNXL3G+(FXGICj3kj@@l! z?IP2rPGt3#HXeL_3BxB$;i@Z7=f)c!WofIN4}`a^k#iSu6$?Z)jh>cW1VRCFKA-Bu zLxz{cu2y{VfO}lzEID!qXlfXO&ug+_<2py&qfQzE(nyEq!XGI|^ZMxN>A{vfS7n|i zq!%ZlN$Q;C$}_H}l4(s9q`Nyf?!>R~&|^<=_>qV4$%hL#VfJi=7jNISn=wrz>FsLg z;6o4M#XtO!$y27Xd)H28OqIiesJcVnoy@84{Vd03Yqmvh_LP@0Y7n8M8 zahFAr{X?J+Ddu9sJdmg)1zoyh2hy=A$U16be>|{JIGcccHe?fUdtLnOrn|ZM_Q!Df z3{IXihwHEZ36Y48@18xE_uqd{72f7;Tj}rXQBav0k4SM=x&pbDtu|rNDoCLgg{sGp zI-f_=O+}zo=EwtyS+eK5A>j8C2nGrGOd9GcsR)OZRf3qV3B||b^K!tfg9wMql&DRK z&`K82{|SU<(5m3SrxXpo%74WQ{Ko>XOm%7A)y|pM-p9#je2odURory*!`%0i^Jxh6 z6YJQ@l0{2M##00hH)(WIo-o6Q4I`DxbLXRPQ$A`M*IaiFcir_Q%XSGL-A$%wla*iy zT_aM|>D;wbQP}KYrJ^|ov;vvdc3e3d+i;ra&g| z#O|f~x=E)}stc4tSn3rW9=L)fY=%|_IPUPttXaN-A76h3mtS!m=bUvKPdxfCS6y)h zA1z+RhOIkjsE*Rnx|0hpy@Y!oc#OR#Poj`bQde6`-iCMHeUF0=JP@zP&4h^)dE%*O z7(Zb=o7b#l`m}u%%<}y6FL1&sC-cFF@AL5e4{-XoPUEm6k7nEEjm$auB-U=&#-qP^ z1v@;1q!C8!$0QO^F9~*vGG9;%+ERg6HZ8KT6)*))?{B5vqjBt4_T|MFU&eIh@F_z1 zUrsHK!=>=f-T3`J_3@EYm%_7M@_Lr~dnS`rry?0}3dK{)$vGPC@htC4GV|MP8D$lr($k>>4Nl|h@&Be|~@x`M4B81m8G-Ko0whQ=l$AwOrGaVlj& zKW@{fI(AX%rn5O#u2@MZ6lTVZ8R|7;V^JrSFLv~Q=L0ne(fpkYHTYxydMog^AR2jy zx9w=N;6nXHPssJ`aucBlz8G z>qv!0arx!n;K6$zV_i!RK2MOYSe#_h#_KZh<}CU0m5i5^n~q}BQJ+? z)&XPa?&#uzi_YVUORnRT6OLj2o3C;9*=MqF#TJ&X-oWukAB1kDnKA1?Zod5?#xxBj zVA#w);dmA7^lCy`FGt9cXKHf|QTmXf~KfjXpXmQBLrG1ZXOwhDN>9<>2x zb2$ZTNeY!>9*IAXO0II&&*Slu66Z$cd0*Nx#oj^wou1>^uN=)GhaSed?c2HI{-=p0 zEp(%xc<&EA{3wZdLP2V31|X~_Ta>;+UlrDi@&v0 z=EW;0SUzeS>J$VJPo|0Wcauz|sjeN(yf@deEfwIVpPr*E3C2&GLeLjwOY?S~`{QdI zamc~^>7`d_98%BlQH|`i&lIZ4E79_4p8w4}UY-9baaS3YbwdanqTO@ z4DmTQt%OW2m5n+8V>m-KhZQ2ujt&N2T^(lT0ejKXvWK#YD9aYDWzvK(9CPFmD%$Vq z=U!${XNN`v|AxOT%)|FT#6>h(GqwbHpufp>iF9VbVH{g(!-;%6^vUnf-D8MsPPi6~M7 z9-aO7-JdZNCNOf+B+i=qLsE$X9y7~TS6$67e(|6(3Uj*tQYx0ZFQ?!;1zzkS92iPM z#>Y0*bH=w$lbIy++V(#2i2^I|QfBYG4zUp`; z4>#DbXblaGQ*irDYzfoIxJY#GV%^5&jGAx&zx=~zY)ot1a>GS=K&pXa$=h8XctbE=8Or6-xotOvqKiP(Pc#}L(bG>)XCIpBB2p1mP(pj_ZnBxIN=&M)Yfxrg-FtSat}MIa2C-D1lJWc9VQjZtXCOw<=~D-~RVj4Jho{6W8Aw7J zD0~A&URr7iG#S9>2Yya5YE+Pk2e+M7K_8xwkD3vqdFz99Bw{vhSCXr*y^4n)d5k@K zIvmH&(&pj}yw%}Ly@$e}QH&TgLQ$sfvoC$IEU|c!G2@02OT@VPnrrZi zL#VKBJ|}z*e2$&RKmkmDof!4So$vqfvbwTg>PqD)o)y891$&w|QAoE_R$0w^OLy|{ybl<**EDXt z;VL|u&6{t&&9?SV&OYlDmVCUP;bSXVv3?h)9DfjN7p|dc!dPzj$!*kD)G=qyk<7i| z8u~H?Y*z@6uZ+D$45gvAf~89qlS(F3N2mY=>4v4*^#{=c5%OvAT6e@xwo9^GiTaMYBofntm(%AsJ=!spMSSp`Btai}y%r_XMXtK+0_Oetm-q}X zZF^eKbjd}PPFh4khAQwfOjVnnTf$CC-7GHh;wx|23a2(q7kTl0Q64dl&9Sn>ce%-A z#nVSvFp_2KI9VDVgApT!QBhIL?BkB)(krhaoe$xQ__*@wOL_RAC$VxSiDZ(N)@F)i z35G*zPUA9t%KIiK16&&dKA-aTAJGuufT^P>X5-46v$bWna*~wOOnrSLk@9l9;WAqH zv@>@67`AWU#uZmyu7<(lxvv~0OAY*g(st%=KAeLE{$H_X4c^l~umWEw@QUYLVC}kX z%>Bu;Tz%!g5$|u|@h4y4duPsMOnHd%K!EaK5Rb=4Jd?)dve8BOl+$_Z!}Z+v)T=a( zo5Hm}yM)Cn)-h?yc!~*&9j$x#aKUO0Ib<9UJv5K=FFuoP8+Wk(!Lz6iO0_F+=YxOX z!w(m$uZqE?OQ@13KwIrP<9CEc)Xq5{Vdzo-T4p@l|w+Q$cg6g3jpD z@hlXGK=fEj^rAXD!MSyntmG2aWF)MZIQc|c{fw_7qP)g4{c+OqxEe+p!qgDwM~RBl zY-%f`Oc^(hciw)7xTWJM^AoM9VZRCES^M#Pc8Rm3$5C1qWSTe-BqF+il6Q{tM#&vX zkrMxvl(H5UFUY(nLPc#o)5kZlb@`_<0v>w+03ZNKL_t(+-?mfz9&S5N)W}mCF~}u) z6x+q)4=5uyG4Jvijt)S$?+%uoci1x$`XTnn;t5mabE>4z=OvfVC`GHNMWyh|u+{B0 z$tn$kFmfbt#93dT8%ETW(Nx=@HpR8uTWL>MkkDORbon_v`tW14?}?F&B^9+*-p{5H zBkAhwCzH!6W=l3L@0X^OtYr~DjkOWZ`sQo`LV+*l>FeziBLkulp*tGrriY?#s7>{z5g9g$zXy1I~Hm1NB)&p;4cMU6-dou&AKgo_ovTt z(zlLg`iL6tz3E|wk11DaL;LsjWqGds)6{DeKm*qnOu8#PjTG?cumNb2#v* zSzLAdBXp#F)OaHF_IA@}xv45Q(fS~sXvYkP@c4s-q5+0ghgkB#d-U}r6@#L>EI?O# zD^{R_g5gtGwdBspG2aQsmQJ@oA(=o+r&M?COzm_maVS*SgM(|!_oUE^ic-AS1-}>E zTMD(PCXIl=Hx}u*IMHjk16~Zjk9;OWAtu+(D^Gd3iqGrA=ku|rZ4VXY5%!)iiDiqI zkP!<5`L81(jG8c0_a0Bn`b`8~zLG~u!pVA7uPZb~2j>=#b7`>+@roa?bnv=KXA^AN zv<2N8!Ch9%xV=WxzHTX<%{$PtNy>s6Pd)Vu{_uwv*lWxf?!WIL3eu@7ycxWPaKl~X za|KnTl}c7}T*bmbBJJ`5%ZSofS1cPj!YNj!oE}Q%UMh(yn^mU(#etWSEU=sxF1hp~ zrcT|TV40hxYqs*^TYpQukmmYpF67o5Zza~9QnXJoJuBJ;h7B7|U!UXc?(@k2H%%s; zR_>N^vKiUbz}aVflbWh1rawq;UoXi-oM6DOpdOdoM01;L+_;gBu2$0VZsiUdkplm@ z2SaJT{EyIN1|gb%<>EAWZ~ylz@RtIw7!+EmgTLW9B8{W@`43NE)m!iI)*Elr+O1JA zH9}Fxk6auYg~ig|*`@Ggfj;)%{{T)p?PTtH;twp{yc1jVQb zUqUeu0bi7?ty5iQGIewfi$3^>Sa*(Sc@_SOpz1(lz5S$TXqpCi%?x%!;WoRDCANUa~^Ezn!`SfXbr)lj<;AKZJ6kVe5t?} z$;(MZ3cK=acbGo5Cf2y}eer>JGkSO(;cO49KV3w|TZLX(%f1tav3$XMq`LOtbJ?7B z>dCzN>dP1^??TqaQbSs&i+754CY@CVUdoHcE%>)c#GDOgAZ=8_$sGojri#9Ni64vu z@kki^0FLd53^YUL5&;5{I%e*-4{J88VabZESbCl(9=eCSZ@+`S&OZDeFR|WkH3YA! zswSPuD`+SZiO|uxM-57Ykurjzh zKEYi#UPEP>zr=BO-g9L=JXqlW@5{pA75=xZz`rl>XcjA1Z{mA5{f=0%l39l~ao(JR zvD-U%`S-8Wn&_iwYSenG$n+-&MT6u-YOh%|G}Lj>!LxYrPYZcz{!;og8hSxu9(0Os zONC6BhQ|0I4aAx^)85)iDpH|_q6N1}MR_^Xhc~c%{=39d1u_Z?E+`(gDu#lLC}OoE zV|SipDNN1~&niJUG6+>_O`+qJjJ%Y+R#9+x7e&*+8wueL1WCn{6p|?gPxvB1HT1O8 z8S?!Jv_iqb?WOUSs6cgnjZh?_I?q%#i#yu&tMAhCE{Z3ZsgRI?E|X^H)W41;A*Y~^jdK7(|o zNLcS-Qe!v+fz_W7APegdoCeV5Ke2D>am&J)7)gs2R7nLf6jPu_lmY%+^&IYU(`1mbQeU7Wx! zVm&L&A2~V5fK4LrG%2KVBbEeQ=M@wp#%Kz67o#jGUSeGw@?!=96ta2Mxl1AQRfNzy zZi>k?#aIGE85CM-gRyK)4RoalTQVusgqdR~-nqZLg6i5z#tf-o$-DDOrV3aXDxOb` za_u4>cY%T>g-Z&$Y*^x)=wuo>hK}N|o>jktWgE&LKJRi9ZD^pPA`0;yI@?;%Lbc>% zpxfU;NKZ2FnR|Kp_s_G}_z5apTzT`@7H(a`=k==1Na72{v`gTYWHRZ{No`xj`pG;& ztP7+|7bwP2unM!rX@O;9E664%e^GwysAMeJ^v=KNGIVztV<(NEy|<4muYFRT?(l}3 zO{I`kzVn%EMmb4(LO~3#heSqBGO|HC8@F39f6c8T6s1JF6~$GCz6AwmDPJ77Kv}v9 zPWO8~q+=Zn4cR<-+f~#>Wp<%a6qb(@nmE9n`BI+f!2nRb)3_P@XXTXU_+@%H2 zQ_yV6%gUJ6)X0{P-k~*~M-P@M?s!H5p#vuSjv30@1q(>_r4#iA$| z-HK{w7&?KnFp+2(e$zwij$Nb@338&KRNU}VIW0oYaN)0r;xIZT^{AV*WXe@ zO!=)<sl$Zg;a21({@div7pB#^>IHW(yWU5SxN zlkD#Y$u{lpfW9`$JUSD{j#X?Efsm|R5*wKlNP*Y!O2;d+0})7->ReDy5+%bc$8g5Tg**D><|>Z zBO6&>Z4Q+Z_F?$wO{U4n`yu)nI}D5*Bgr691$XQ0=4BX?{+V zB+sHHt2yuH-_fnR$!Y-%%O#2;>|ze1U@1sOjGc6{%6nYwTBR$KhqNF;8&ZgsG~IdN zZOe_RI%vpAx2ETm|A=7N`;Td4>HK$;?LZ+EA?pueyS!BT{LC2Hz>W>86c<~0lPd$Q zfgo$?D23_=S<51oNn@BE>Z)oO+tj2?zq)$6NsIVNx#T)ssdVsx>MFcGA3eKT@D&ZL zXt^rvS~A73;lqhUf&@LL!nuuNiq4kJ6zwcC_nXP;TPfxW>UYV>hB9g-GY(*82*YdsjhBZiC)UxDK0+u6t-?yp+ZQuH@6a3 zb7qG{<1lDs1J*D+UbUep`Mv~h+m_DFNN1_Y-;P{+1J+)^9mixR62rOI;~1=Uw@iZ&LU&UXQPN#$Y7@vSh<`S z4=drB1aT_}PR<~v8`~RjJmY1?Bk!HeOaQ-OC|tjA^E-n;4@iLJ?stogr z1+nJMQWP6sWmD^1K(J*+T#=);_;?#0iY`-0?xm18GQ)yHcrgrWYATsf6J^t9AJg3* zBjc|i>y4`1&!|rVM09e}^=XD0Cb|R`vNUo+HMH|+xh#o}9+lszk~eJ^BZf6%x{It@ zwM@NEK?Q^;vt5e1i$L8FJRUc_J9pwPdeN(D30WzuRF16MLn!Dc$UVC#s8#ZjGtfH2e-u#f5E(N}p zVkSi<8N**$L#DfnVt*$=SC$9vxrt?q7t+(!#llY(lD9G?zjR^ycoj^gI&q%}or)AP zlB4VR)kxRw_xqjit3k4+pb)V-Q1b!7@QaWYzPy?r2o$EP;%R6)M;>t)O~Xe}-!zKW zM3$Q$`Yrvsm!iwT?q!cx;T+23EJq=grkKk)QHtvSjxC1JFJ-pj40)XmT;6Lr847a- zzXw;qPrhgo@OlWC9{RfasPP#*f5&-@Y=|lg2Z3m0TT-b}1E%+1!Xq+R;J<`L9K6Io zX$AhOz^k;KVu8;Vt>N4|o~K_As-v>tp@wu((#hpASUC|DS!ktzYsUx1v9)!IffJ|W z2&XhjZb0*R6>CNQU0xl%rIR;Q$5!QaGqJvsO{$>dU)z6gffOMlmHG%Kl6kn)0yi?GOT;HzuEaIbsf1j7L)jjm(U<{eZt4Cl~&8aR2@WHztgLgkPlyz$y=l!;w!IE0*0M4|i1 z2Oo0E+5bkmw~tTezeBXP2|E(tqmR~c^~Glq)ce`6b`zr~O=9=Cc?`6^I&BR<`Le)c*Pme$}{%9TPSUb7CR-$g3(L-uU#CphE zX{BG#L@ZSbIr)6YmI1i(cNf@249lEuSpF`!yyC@Mj>7dX*n0^+5@L=j>`t1K6k!3K z1mmx*h$@j%SyeqNcC@jsJxw80P0{05lv9sH?#V`yNn&NQ!pjt`mvWSpvAfe@I~3Ld zA9_`n)jhc+Y}a8t8E$N!2T#z4UsS8MMkk!Zf027b_N z?4MMc24D8eSOHbw3lvL~JyqbbSg>$8|900)^bkN3{(6CkaEijFZ+i}8G{_-;D6dcG?)Ch{7cs8kqipfNlY)%G;8T4X-f^_OK z_;hOo>W5+)9(s1}K-Uc1|yC=8@b@@*|^+kc5mIr z@TMkOHm#t)d7~;+3Nd!;j62{En#PT1%eI}YT(N;qweW0+sdX`3$KoLd2qZ&hf`_*dd1ysi@-epWexbYjK1tewdm$NP$LawEAcT4e5n6uM;Nkc456QM{tW>Ny(NM|qbgA3^u)nh06cZK0w&M{h4mxiCb zV%B6S=w8r$R0ji099quq4J+Bx+DgU}Wu}}eqyp#^G;x%a4Z(x0d$D~ccs=SqTy_T2 zE?}p!4h$glMBCxZ3yy9VL#l(fjU4{^Mm+8yy}Ng+cF!oUz|5vecJ~u0kMh;Sr?Gs| zd`#2FR}Mau?v|Z2Z{JRJRTW+ByXfj{RsJWM%S%St?&^%2xHr8W-Ao=^N7Ja`-1fk4 z=f*otaQq+B6&u9c|8wrQo@$wfO z-Z5m8PT!DezB&n3dfYsI%^arf)%foUyoklr*Iu10IG%Lljam5{WqEv&t(+90hafUi!M)$w>B}FN)?j)yCnn zbj(~Ig?JyXqM?SLdBOPwS5^*&BK`L|VkJYvTibwX81%O6QobkNigL7Ej(AtElHLbH z29YBIa|7M67`mS{;P*4YlOJci-Huyo3!jZ8maKjyvk zJn3AKgJ&JYs>Sb+5jR{>Pt^kq*A9 z9?i;;>F*;LsUjEe#_DfV82p5hL+I~nBcD&I(@owsOAed55;{rQl=U`cAg&9)UFe-s zyq%yA5s?W4Mbx|!dM#c1fG3TLKrD#bRlYAnbb;zD3b^pPprNvi5ku=JE3f9m<(pZ& zt%tn78n@T47&6&pQt|N%YGWy7x=N8(HV*>x$Y(_C5JX>4#1cxa!vRu%m$QZxcp0{; zELKr4t3!`V*%nlqI*(s9hiMarse!%hYy%zqV1fTKD#YM5{ztFCUm6`D^ogIgV>Tw- z@((^)!i5jKMsMDw9&pu_3*;h1JmDv+WM&)P$|=lVMY0KIq6VNAMN7=SN)dGGTrZ3p z;ix+U+JbcQE;nYljEvz`ZiW*2EzPH)n|MT)t`${blJMq&3~{w0W9!PyB%y4!72Q5MAGchlF^iOU_PqG>ecl_pzOE+dt2 zSeYo`qmE~T_jJz^LYi{eq(EHUOR1&Bv0wzH>n1P6Lv=rCGJ-rDszH+J>MiTV+ z>E6>yB9kLyga}pD}S6*=VL@Gr= zHc-oE&dGE5%Hf9*t&DK}Ef4el;}NT#7=Vh6Yn4?@a1lJ?8=kacVd$|F-XU* zUT3g_{~ukK25p0F!4Tr%{tEpl@1_xRAusgyyE_;%YCL`YaU!OR`|p30O}%-% z(K?Em9I2iT$283wCRkC6Ap_vPZafv$5bGu1-KN|mk3RZHwrt)=yr*07>op{S$tm#C zjSE(-`0ieh+P(!{6If<|3qRliFK&#VWAHM3RoSgF5O;J3!atYdpG>C6i{XvSgD)7R zx~_q#Gxp|_&(^Yd<$49F$q-wh7-7e#5LIQPP{3U!{BB9 zcdWqQD)7=^OE>=hf@NI%@So_+IJUcr`6$o2oyF@a5HJeVM154477>rw@7mb;EOwzl zcTc~fMby9>h`Z5%XQZP#LcY$-H;Ak#f!3eszHcICx5o@+ECwQDYh*pXR}PpX9YSKV{nf z`*F#o-{I9)U&Ss4l&pULSyOo8SFeyRhG-gA$GDMET6VSZhc_0JHN;db&$LkuTyxp! z+;#hd)QVs#9OanVN8oo^Jo3adoO#BX%37c;mgSevJi`yp|1R@>^E_`ZT92o!1~M74 zJ?&WH&+d;BsHnze=ZN?A;Eh&eCu3xKTJh=`%KQfX{T)gfTUl9wp+dO_)Ul<5R!L>7 z6roBW=BQE?Ge$9YKVEFRc5IusxZ@S^d;}4M#O9x9M5UpWn zdoQUx6a**N3^iYnfD;*_hl6e^{2IfmLe%)cS4I;xkh?jBm(yXomqDa!>t z5XGo!U{hC`=B^y+ycY|P(q3rN!5ePMG^fBHFlEGG2mimLBn|!+U-k+Nup%TB+fu_! zr|iGKUrczJx0B zX0V)I%b=|%O>0k)jOADUFlcFq?NBh4($rHHCMEy5E_S)HnUuUy)Um-Iy@Wa;WnJo5OX{PagZ;F-sN!-q?^;I6F4PWO}RYIWrP-Y~xES~WXJ zb+_RwtEHHTk?Cv0t*4lK<~Mlhw@;HyCx}#*V-}QAgTl1cFtn6k>u3`+48;+bA}rPp zF69>^Z<`vBi<@MLxnil4l*~=s%8y4NI^8r>_=cqyFx(!FKj}pB*&Kg(`AvR&+dbTH z>w~nmbdVMEHe16Z&Yvy~f5@b!(!=mDj1244Mg2^fwl~8@j>Z=*!{rhqG+X7c_H}ph z!MpFWY5hiebq~Rz!`RlIXTwg59?MW+>~7tQFoHrZizhBWfmu^VD6C%wzXO3zU)F$C z&1wfTS-B-v4JWJYXDPEPn0+WaM7~)A2 zCap}T#*7@ns1d^n2LvmHY$iu%R}b5^?_$x?m9)oG<=?{46 z_ir)hTVLhon;zoe!wz7|-s5@nt|ygvYU17_$!j(zopK`8HDwg6JkQVj1G{&3vhVci zj2zX-wyj%u^_6$XyZr1)78p`r%Y(OG!u_}ZoLPq*#Q4e6@R%mQnfE&TOxv6BV;d=C za_rgF&b$|%qcjLV;Lc8(Kv*Mj}qJtDQ2h z#?NlJmfLT;nMACgkl$Y#kV+Ts2+za`Q^G%-LiM>do3bdj3brbka*`54q(g#q(z1#I zw+YN6W6*5g8K{eGgykZcY`i(R2Mk~4R*{6B$cRW_qTIV2|ffSLO-cI;RJexLFfcaHq>kQP*DC$zint}a%u zTEYBJ7Gn8pS+cRdyIgGm03ZNKL_t)K)_$9UiVafHOOEN3X<|eoWK>~y91W$b6s*{T zTY0AJxA#acJ@ZIfH*Dtdr(fc%^Uh#+T@*8~vAZM2+Kt;e>d2|I@7}5GXD|EV{q&}i zeEXbJIArEH?5svEm1gbw^&Io{Bgor1dOET^_Rz06eeUu6{71L3-=Rn08#$EKYqnq} zQ_PutD78Z?DT{>Jw00|zP>6=wN+8GPE!&l4?&xuibawaApUQH@t?=X6Z zmq@sb&em=!d}TcH$P>5?jqja*76HH5AZIA*d75{pxc-I*XzuR8sIG)`oP5_FrE011#UX2fLtQ8y=-ks0@1;Q{`jgkPx$v+Mmgj$KwkG&~#DL z3Uzb99@NQcRWXKcVTESs>yPo9Uq7Q9NqamEys~UFeHj-%txW9+A&qL4`u>uh7?`ZavEZYyh>vn<~lQ)~-?2!z-sypEhO zJ0cO%w!@KjW&uT|P!!su&n!?GEOO&z-z88?vU2%y>YK(gaq4tjt^%#iTUfht8#4}? zNl#}hPe1fKmT&GSNtVV+7vKKwNgR9RQLJCJUPbQJ4Q;^Vb%Hvg*Est8RFUY78;mdYG<^hO4T9Vmd{xtKFf5 z`22XPYB38oX@O{}>L_I6WV>3a@@PEr$i3Wh$Bk^+xPh-8bg-h4_V@KDN5-Aa+c^6> z-)8>XZ?bD=Ggn@I8F$?N3o0wBIN^k^Gw-=yE9w8O6#2OqM}zWXv^@98}Fz#|+t z`&dSd7|LCD+{vlmI)kmdT6y`+`AnZVlltm%CAd2HxZ_#9b{+4&_9t$+?QSl+;chl= z+k+uYDzT<84Te_wIbdWt$IKkdA&1Sv8w@+@WyOhi@^S}U1spMzh^56L)UmVZ>uKkO z-@QbaE6O{Y+gZ0;L{k+?cMvoRJpO~Pf1!gPEb#yBrDN~~|0k@#e}rh>|70Z>KKeHO zmiV;0sHrqLd`yU;#SV_zZy&~tn~Y&fntf>?S5i4To`cTASD;ras%)Y&o*`pp zv20PpT6p|mCbMMYY2rnV=@YAX_t!7*hd16M;F6 z^cH8xOd^fXA7IRoN@|TX&pr1t?=4@+@X@2V^n2gI>kaVQ{7*4_WyBL=y{jX3D=m9E z2}f!PMS@J3IE*@Pl3RZ&mc2Hoo^>LP!<+d1E1%L4PZDj6l27Fj(nzc~P1?#3t*B&3 zbp^*AG=g6}_z>@Xwt-A&2!(W(wD`>wb@HYgUu``e3(`Fucq?nL5;3y9ZA3iq^D>K^d%U@V`zi|CKsH4E-ROR%9c&*IqHbRdFiEo!^;1r!qHZX+-Fg>ifBSUGD^UeJHj=R~gbthL|bv?dtl&Y$F zDr)Ko`29q~ehxkMYjk8xZoKV&(y1hFakkVwN=-bbA;RnfMsoVs52CWN99*H2Cy*0T zsK&u+$m_s>0}My`i=`FNtPDFgZRV{{m$AIt;`JphWVK2>E{%}8z~h(B=733q5Y7LD zDl>SG|FjkOs}5eX_;BHBzW?YublV(+NIWwvi`Z{D_UaM0h0FYZe{161XUJtI+ji9pqGy%@Z`- zG?W$j>1C&rZ13ZR7w5C9yB9IH^!v)OHJh@ii*#2XnRr2Eb`BdejLR=QjZI6JvU2r0 zzINIfJoVh0eDLmP=miLPG-_*t1VceqZ`eUP?@>d?Xjz!^&-n%iPN`wxhwn3P>OQP) zju+BEbNL+om_sODw0+pYs!_9ZIA!$PGU{lVC2X5{qJn$wN>5o{h^l z;40TLCZL zni|YPkyvLt!Rn!yGGy&(#UF%cpT3XB?z)@Jt5!Sn537jVFiE9SOrA1D4IaOB+8kbd z={5Rd{Ty@bk!;zpfvV~%THE(9al#~O>#BJ7gO4Z+moat9Bwl&#RW5xcI)f2zL`)had^t{)Ib@yT0Sv29#Y9>LCj|ojt z=6>@~j+ixG@$!pBpSq`ku3bJOj`~8q>81ZWHNT)NEDG4!46nTLI&1q~JUf3QJ$4xZ zT~`JE=^viN^sz%k`!tBb|I_Nn;0ynYufX3Z@SjS7pHElOgUh3_-`FUJHo7?VuvwIq z)l!h~X-&$q<5A)a$-ekUDc`ebkL|qK1IiM^9HjSV`Vk zu!+W*U+4619Y(po$fHla&0BBIN6+*zd1Mun#@5m_s-8qL$M&rqY}(MmnzmkI_|XI9 zoO|hJYsEZX{39)aYt*IIbsycKbnu`vAFa8TZu;8*r_;P!PRpa z<*nY=7vsSPpJdmr7OHD%=eaHamqaYCyzC8+pYi)lW7z0XEcp0i#jqJYdL)aN zFQc!ki}JDvsceq2igLdB&2Mt|ZTE5V$tN*+zZsMTJft<7wz$SUcRoeO?iSo`OTke^ zx2d!Y;Rb;#h^t4?OZ&~k;_4-Q%X#mmg#?ftV>z$x&GCaF%#79V}Oh6^8?Pe;)} z_vp-;P{Y^9g*o}48F)Pr3JMz+!Ba`l^2M|D=b>q03?{a*Ir9BU(urQSb#`#;W6!g2 zT_0I1;P?~DV73URKY;D^l2+a&MLfkKL(9u~;?D2$^nFj0?{8uDSH@EAv+3{cp|z!x zp6)o&iYOIBhGM&H>{LI$d3hCU;&oi~!*i+jCb{w22ha;?jy!M-`;V_8(bG&ilOdiI z+XRF1Xf=!1?BSy=UGx&Bz9!0pcV5nYzj%_Ri#IZUbR`GwT}x1lVWoO-Nmxc!r>u53 zuCjXWdHnZuW`lUDhw{Tq&R|SqB^RH6H32)vxhEe$eWgV*)yKB&o3Jwm6DRCLYkz|I zE4Hy{Ll0TYWN3X2x8Hshk3atkoqOVJUcH`VI!oT`B2-^TeW-%%>(}D0u4eSGp$x06 z;?s}br@Xq7%K922p|Cog7oLcPfX-NF+>eXBP#TFG%EJ(I#3`O&}PeZTl_^mx(W2iSCili><5d8?=%a`Ls<9PL}Db7Hx7fTD7R}>{6+-5_| zR$f}ThNoX$Pueb1jIQdi$un1;#9l+A=q@3I4zg(eSrugPb^nD|Kv_KrdquEsr8Koz zuyj4=J@Pg^wg>zsGso5N{UgS4(8yZcF25R$>RMh6%hXf-R|S4RRj3|2Dd5Qz=~yS* zx;nV&p?Q3|K2F+_0j(I52^F)584Oc2y~tI?KgFjPsR;*p^3IER^yYhs7%Aq=*`Kly zbnVZ|2Nz?a$bHH;J}g$}G+8 z_LI$6boTY&uN=b0)&kGJz8WGUIsJ^UaKu4lIq$SfIAZ1~W*;>kpC`eVbvuX{8aX>l zOIw1XJ4m3qi6>rINLyT|VQ4jX-1bB6eDZg6#9UMagREG%fOO8nS3QJLBbzYo6w6ku zz$gn--#DD8KTIl?P-`#dV3K;2lc=pycCF|als}L-NNVCPsjJ`<@fl0!^7O|gbi*PQ zkCQLt@CCdCyl#@+-DG1a)#c|UyS6+`I1-_K$1XMOm2#ZZMaHDz7Lz$q%Szab+f=p$ z9#OEmeV9HsdylQ=f^Qwo;rmR$l>Ai{)-r&$|0O+DzV}6nqulqvAXaFcJ7ax3^76<0 zZvJ|bB0AIE3^DRNeeG$CZ;U8oG#Sq8;$R~QQD0Knhq|vp9{j&>^%}gj|HBH%NKp9b zVr}RmC&p8Df#n;van60O(PjB?1$;~%5#^eb_h&|Z2siQ|%W+#`^qk?C^Kd#<-tmC{ z0}zh~K2;kSt2Oil$&3*KyoBUrkrjK_3QOIlfm52@mjo91%& zk8URD&a?lFp-diIO{TL2-Exsr*0BW=y$N>p=Se4Y-e0njwLRs0`|R&9b*#?yKfHz0 zkK3EC9y*dvCp%+irglJJHIqvxYNc zuc35zw4(VVXs)0#Kug8j*xu4gzg5dif8I#19pt-nzsdglHgMT@uVL;f2XNG^@oZ~e zA;%L;&5v&6>1^9Wx;IHI1MjZtW5tdFwL@yS<;IKn`2$b0sx?c^kVfhPCaV@MBx{?P z6%`C?s-s*hvT)H-%up1!Kj;iB-HxZcGT;?o2*pMbr%$_-DJ#|m0}5B^Cu=$L$!{NgnURaaTH zUNpna3rnQHAU;L1FSM4Tk zxfIQEFJFPDesmVY>!eW-E|&E0qRbN|Z3*uA5}yCT0{F-+UrIe$D)j>?PeSeM zjVJii$18a7*Kg9?WnoDH5i0^2sEH9(q)d%mm9WaPF^hS|HVxsvADzL^ufK(`-_7j9 zM=`v@O(A0wj5Z+7ReB*svcH?1Ej!q_v6GKhce1gsf^+76n{h*n+;YvG{P^OpGJ04! z?R$1mBViw*D)l2n@41%y?|y*Bkj808PeYAf{C?Oh3wU1ga)cYFKN-LJQFHj)rXSPTi6#7saCCMu{DI3Nt7 zQZ6{9f-Gv`3OYCg2th%rbVR}6C@x`~QA{ZYBOr?`fh@)(P1f$DlivI7_rCk4&iDWK zb%)WxlCBt2x2sa=_xioNeDB@!fA{;&cTS=$hj=Cnw^TuSWJEOQMYK_~Uc@?)15K0> z)iPwX(sTDlwm8njM*~n?ACld z^vou#`rQ`1)I9)y#1)F`;%PD5{fW!al2QtqVmc$GA1+^$H}Vt${ND(h!re|n1eEcT zuoYMzWqBmxmoYF@z{l@+5bO3;Fm2WhocqR;F(Yc=Z3}0inJfv>kzwXe$OzzE{U3n3 zGIUT30SC--gG=@g~1#G{kr@lm6O_G|+8{rkV* z&YQoERLsXk=beDrZCO}m67^U{Y1wceZUMc!w_xY4K0NTN4S2cOg{wdM0dyvZ@#W8d z6*qqJU0A+&9`b zo`8}4`v5U6G2vHDBuooEyVt`teSGUDPvUo*N0DsJ;da*GzrG5;ed3QOC9*JE)0olK zikVF*Jo`8mG$V+$WYN*p1(OoVlCjcUr3Q=c)gsNSEfa-^q_cRDpPlMbvRKAjuXR~%a`KpHyn=@i)W)Xs-zU^GCQHNY*mBT|Kw1$uK*lc(O~=jVch$x zr|_F?gV?cW7)ck%+GSjF*73OZ(l;Z{Av@Opc?49;lp6o!{e%ENd9e()bhsm+0iNX+ zu}7m^uU~~an4Coa8fRTIF|yxmm1v@rV)d~SIshJ zR5WL+i5c~OJ@Pc}U;QMy_l==irx2_G(^cu56_24FjiSO^bApBj_+vV9xaX!1V&zSD zp)F(J@{5;X?wr{u4;RIwQ)VQkH2KVj3-d)}J?%Ege!ayso{qXzox|uevy6($( z`&*Xc(zh+gG3`l|Mn+JsMMV+O@Qc{7<$2^f+wtj@KgE{)KBjec;?{q?3O9afB?`q+ zy!*m4@TMiFfTn-0pNCQBU4w;z!Cnj$2C;2V8TZ`(Tjc9WeBk2q@y64S$CV%X0?s>c zF+Tk6706k2j1J|+XdE<9sk%5gvKNKAgPU*v3HI~@ZPVIu+s#+w&O5$|=bqn#GWkVu z8+LOJ?X6QWud5yFA76)|d;yVM8(b$2-?wC;5siCWNiZ8kU{$@A%w1V01`bXNl-b{) z90e0_v+j$TOJ!_SEcI+BD)R_dItkboN~3vr!y~A>RVi)PZ4}A3qKcX>R2on65y#Bui$;MKt2Tc!wpK|{w6U3%&=7^ zr82NOET4@k18bk$gwHcUi%$)FxD zOkprVDbD` zTzTznNHklx_}rzq=pRqRl$In4qeZxW9i?I(V`GDO?D_4u_h;L%f7HjE&K$mS^T%-e z*Y3j$o4YY@Rtv7Y_^mj5`6ARR{TLe>Mx|IoER)7l8@J%@Rco+yuO}0lpStoA%$kzK z^*7vuSW6u5`lls$--RoXHh{uNpD;{(yN>lcwqex|*J1sOV<;62WU@Byy5o9$<3Cnm z-BT~a=h@fGa3gUznJ!G}%HhO0t$69lCr~O@g$n62BR6Q`Q4=*qF*d1Fbze0vsX?RG zSv93V*$2LkJu#{#EN#`_kp-e!YG7;$})XG&`w4T0UeEy!*cyf0EBZ(H|I$N<~*?i1M)bPgn zQ!%$Wjwr!FTf~V0w=`Ip#nE@uz+kD0Uq7=6KmO@jY~3}0p(0HkC_n6qx2x1kX~rFk zh*F`vmy)+E0{B%->&)SsUw9Ah{Nk<1q)l9O{&GxdYeO>Eic~hMdIxS9u3N>(=nzH* z264;E)!5!==FV>AkM<{~(M#bT^D{WL^PARbR(G+)NIS3Q7dH}#-r ztQn@~V^(V#ci!@Gti1EvShs!~qM116bf$38+s?wW#S388U2NURcm%P_a+9aD-Sg%4yUaRk)|dzrLu?#g|vpMR~9Ovs6x`- zx>kor9U8(h>+moTk8-$3)wBul4o%C+dZ8u_-$z3Z4ph-hy(bfB|2fmAF4o8_fC3wd;;GB8?pvEk)GJiVtETle+j#pkx7f0&v%Q6!8!PVR8< zzBiqMbI&{#@u-8k5s@;ZC0?`;rjBa;PtH#W@RJkAa4UyB0?M3Ok=FDLEw6Su@c1>M z&i&_)*Wi1P@5CR=8F)?K?gN$0?!HD9GH0LF{FTDMRcp=(kGpT6lTv@|Di;|;gr$&Ed5Ed$AH z46(R@xZxvW+o;qG92hPlUt}#iinKq5%PzeD?|t_Qtoy}U+ppiaj+vgr4Oe{*+qw^8%#OfzQfN*2s5>6)nkgR6iies2hpZBD)xv}uEB+k zWftA#V9Xgymd03LC%CiO%1L7d@QS@+nq=9iJ1@(iOs}rl%jq8b*p`^ykayAFbd(-oVy<2eD&UFRFRQo7^oAbDKPzf9h1c z6PP(;3QnCj6>W9}8M}s-bR6kqOd64W1H;(5XCJoj>O=RQeJGbb6bcs1x()b6F%6-m zpG>bZb9W+=fs-*o?lsE{1Rme4A)avXiOVm*n-{j@;nl10(9a)5z7~^`fk+!0F_e8@ zN)M7*#uG@`z`xz_5tM8T2S!G*bnX;<=~G|B#_rvyI`nI;%M`ANqSbAbT>}vVNXMeM z@cc8d;+-q-^h;au564Z%+Mhp)@2~z1@~#WRCLNF|DFM=hSFIz07;LMKQ%;(J>#uu1 zHts73;4L|}4G*q*2tWM!qj2jPnDr7o+eC~d1g|Jci*!bcStWe&#_Q42HXSR!@guyr z`DK*yMOovjwTke)P5P|X*#2e#%RrsyK*qNK8p~oz;+M*2G&+~&s;<8`=-?s;&*zmK zfMmFmjjQaQtXFEcOPS5rnlJ_#EUuJaXmqaJwzP9nPy}JKlnXVtB|Lj&j4eENi~ETx zF=9@d+BTe67Irj&OeTRDQ(7=*db?=muu$mMO$-$)*t~rw`iAoG$~6W-?wIHSdt7@O z%V#BV&cZ2Jv}hr0E>I?QZ!D2NRzrGKsokqS#N_;h8T{nLG2F@#7Xcr|u^~LX_8I(s zX916G*@xb;fsz?RB$h-vmB#e;3_5ZNF#@ryIy|q6J$rhwx90%LW%8^&_~nuSHZONh zQ!<03wI3fR(z!gsQ`<*x6bcd&>nulQ%II6j3(A6X}Mb)3?q{O^GS z{YbegM&T&Xm9HjtHXnR2Qh7Wm!K=P z)v1l&A6ILb000W#Nklqq(GZ-V`|JQhO*^Q#vN)JR2zDT zTm%K$IIyPZkP5iRm4Ot{D>-NRJz$#X=Y zw#0B;R|=;b+m1J!b^?;AX2sv);->FD$7eAntG%i&$PnO@!ZoIcJ`R!pJaU9PN+B#H>0NjiTzQo&(W$XmkwUfAGJtW8bheTVsxa z^Uhj~`Ln0Ntya<0n#170Fp{w(h6jg{h}rOb7oJzgGtY0uOB;8hP#l9%SBBTpv=+ou z74HU^Q$k;Q7|M6Gp#!964=k2Q7#}IG=y*%!u4#ydG6IoD!bu+&iW^r3RdHw8gcG7_ zX;JU7ZDkN5kF@O{%QO58SQug*p69Pu3$^gDyrUbiQYF`S0@TJyq?2--oMv`d<}-XG zxTrVBg_@d)Imjg)q*wx**?}dC<|C7e!?5TvJ6SpU|9`cF06!^c5^m&3i~uik-z#JA zU>|mM??&%H1y673!IpzX^p;!5>|43U>G%Obq(H+(c_)5tdGV2BG)REDA0h$Z|~#3aNQ1Mac>h-l5w zY?>fxISw*SEr>WaDy0fyk%(GQG=ZOhX*o8$Y6S(lPnB5?5fdXgF$eKv0=`#=BW$67 zd7^-di;V1taVi$!njSpEmxgCoZkjkZd4`87MaqPh$xNG*r0kwj1-~w(o>I{jp)S!> z(M{1npM|w^=I%UZDZ|*d0I$l>m9MH~!2G@DO0AuLW36ABq8i8v+Wb3T$%U0o*Whn9 zjj}ngRQJVqmB8#c5jAy60M`qOY1#4`eums$G#ZoGkz`99ca~*LSwz$#VA-5BRt;IT zC~?x&mW7=13N!;x#-m8Zqew(dL^-r&0WsSXz;|o|S(XH+cj35WXCs-U?=6o>m0=FY zPYCdbBg)}E{w5KSiYj{VrM_W-&N4x>=4qFg0IhE{K+=P`3r z1m_yH+X*)6b{Dm3Rb}X^4F}t+N!dg)NILomz}P&HYx?02XP7d`u5g zPf-KO_TXZ`eu2DS11~dSQakAtTDPh~Z}fRbVQ0kDf)l5%jL>r!mL}9>o4BY}ONhlH zqOw>mm!(v}<8~YcqMqxivK0Z6Kuygak6AS-h!$MR2FSt*(O#!CL0z8a|$aBcILMU!E|QZxsWbY+B@ zvrN;grX^pm#{X5lU1C6X5kZV`@jU@b9y%8*zvin&NgsgI}5&*M^kR<%3_WgUJVl2O|-4JDr&!Cu`7 zsn_xIWJb?zaiI%-Ctsh(&F2_@lK^h11yuO$QUg@qLE8N3IoiXNzlSyWzfg9AjwRfS*MFisVtJU%yg@+2g~N|v?>)4j0AuhkJ(sdX+j%q z>q$ld1U@I3wDV?zcNGu|HBtk;^gi?*m0Cpgxkzzd zf2Q1z)XH^PM=L+7ML?Bv0)n~PlrHgzCJp1NfSe%AEL)AvsYb9Y2#toWihl#4_2+g7 zUAJ+<4Vlt$TgVCD!oTD@{90cVX7H~yg5mp**a)cHkeRjOPDASL8U)CfA5S_3Xho4k z139yE#hp?0VFh3Mw;+`k(9q8+`bXo!H#o#2gHx(z9}wTq<(kK;RQZHS= zO;48!Gl&+25+m-1;Lb%#xQTl7e|+*()yFm1>Qffobq($cs8!i0Kz~w9MO;iTWWk~k z)Y?@X)Q_Ckgt7j{ECea1df&{b^=a!(1r1g$7upE=1V)XXoNb8Csau}$PoMn~;dhRI z?IoTQgZe7v^}|zr*QXxJ1s}2a6du@XjDWhF2~v7P@{0mJ0agw6@*3fmt1OlvM;uc4 zq2DadO*;QS z<%O$vDAm+-9Fz+_VFcSIOh#aFq9=%8eP&Y-1 zbjcvmMB~E-AdUm0oQDQ{1-g3CBt7!~oP*}Q>&#u6;C!>t5rfrY{KE*&P`0ZxcUdTc zeN6lw>BVxwTG5a$P=_6`bM$B3&^rn?(zvhE%~(z8)YMM~SH4Sfvg64?uq>%BPYo}ain{pnnC;xQ_y=QG+ErD0chsF&^d zqX5)jJ$SE#o>ykZvW1D+^Pfw78;Sj)nf0GOf{CBiA;{m@-Je)*{>;fJ8tC{ICob{< zz`yeA^yl{f>hbz(UJ(NPUlXk+H0000< KMNUMnLSTYY#(up3 diff --git a/extras/Images/pinout.jpg b/extras/Images/pinout.jpg deleted file mode 100644 index 3b4fc366bbddacb8a9a9ffb40d6eebffef0912cb..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 211009 zcmeFZbwE{3*EqTlhwko9r8}jiL`1qlIP?JyodPB*AxcV12-4Dmq#`ZdAt*?v5_+h+ z4;at$zVCOx-~H~rf85`F2KMYVYu3zOvu3TC*)!|x)A7?efcT24hAIGoKmc{{4>#HG z_zWfj;a&*oPa3d72*pnrEDfOrFu;5e3w(so{e~AI7yeSG&{;il}tW0f2{se|UW;{F~P&U=|k05xStTh~N|GuePC`JVE~jLrI@P&S@ZM zP#^{Z;DYq1ZsCkU`}JHXe+>F>ym$=8Z@gR#*3ajHvW~&|2@``b?r$2^m@riR5Nxo{ zYcWsGo(mO`0BN571&;XxKmWzEkf7l6pE`l!=sDW2c0re)L;nI}{DRR9vj~4Z7u`3D z=r%@IDUAJhx< z${f)%8dVS;&JjC<@j*SI1&gBsO8>5d7bpV&^6xz^{vWhJ9Mtj~=Ot0vj;i52prBtm z4NCDZIX?;he|tj%Wq}$U&~>FG0T4RZd{B#iN`xy41fY)qT1)VbruP&3U)}_TLSkYBcd5r+2LUWogDJ_#I!&suPHKOH}v z0+a!4OiV0H3~VecEF2tcTzql@d^|jS8d5SMat2x^Mh04XdS-ThE@oCQz-!NOI2#AZ_}YoX8`*k%{8@w|hBOG!mdL(9R*b>SknsF=8fq?EMsWffI5 zb&V@}`UZwZ#wMmPTRVFPM<-`5Zy#Sj|A4@|_wI*1c=#whCN?fUA@NyKa#nWEi`=}I z`32<_l~vU>uWRexzH5Eo*51+CH8?apGCDRsG5P89{KA*TrR9~?ov+_^_x2CI|3ISJ z1&%=H&HCN4e`yy9*e*15bSOF&s$CE?Kk$N*pkuHIVUjB9U|D;Ru?pYDCRcizS=NHX zCZfAdVdFV~OUW+!iDL)Vw6m7|uQlw>|EOiZ8}_GNlK?&xG(Zw42_O#~ATIz}w{ZVs z1c~XUC%IIiUeyaFPM{sYVNc!3M85gR0g>267eN`zK}i1K%p!W zZyvSU6XN#F7T-uF`s&3tzv_gcqsIZg*Q@qcgH&D&Q;oXMOsTWq@g`NBBdJyIxHLS{ z=9B0Cr?~~Dj|=TyC@)&{kg;(;r?g)X0K6j0BX{W@6hpk)5tsb@5O}6e$f#3b9G2#~ zBz>1mnuwQ^)_&~R-$cGBsMzElq%t&ISO^<8lHzg} zH;R|V&EO4~?LInjTwGep5ZGH5C&HbYJ`UfpjdvYkBg?7&0(06f{zB!Tm3bGE_Ktn0 z8MAm*aB5}pB$c^FBG9{udn)2Zx*82GTRS^(qv`!lrVA~XMwB+M@lA9JX@9ylroPt5 z=>L^R%YN-zn%&*Y$%^|H?|7VB=P;Rpf|)~TpC^2hhr9APeD=AjN|Ps-7aHLya2 zo56MBYr#_hcIz5BWAwX0m0%I4K&_GHrw5f9UaW0{kZ-O|Bk z4{qYHZg804%eJhmU3YA_U0BFSwS%X(1BLt6Vb+R=$}j%Cpq!$JGR9BrJnhpinVCf7v9wKG%$3tW@FwkcE@&k zN!`JQC1drl>(TXSUg_{yAG-i=;i#jX>4==yei+bn_ zs!{AciCy1Rcbq1gmecMCV2{MV6Zln%dDuG7$+I!{*+WYS3)~m!T1oca2CdGXO8Bw2 zS30?B^wun{J^f4`TS{1_OWxp70cD>-kq?!0iWP6y<2N*UzfYH>vjyZ zaS`#QHw$_}oR*1|Taya*~2JyhJvrrIwiWp`alQNWUvqEBCl zBoxFlk2MI3@M^kD{fL9kkKe>URIj!?sH(cv5ys`$rS5B>7u!atDl&#e)6%w?xzERR z&BPU7$A0o6E93QV>?zDtE)`o*aZ>XO=<$+lSXZisocIzy!>+}S?Ab-*JC7oRKQxwN z#HTes!n0K5>qf-C`+{wVg<-7PeAHZq#q!$9ZF|ka>VtS?-BIGC!77ib$um|R*W)=0 zDX(g;1k1dR$&heDEC9hLR*(F6lvWF2QECvUZA0Pkgw3_!fQ?RNTSVm zbNo=f<7BJL*fuc3R8y6!tld9+US(vru+Y`!^J>@V#hcj@iLbi3V{n^vzn!?g7F*wOi)bct zp#pLT_;PK&vcTkZG5(0m3r?fPF(Z+8xulQh3a5oPed)Sk0dy(oXhlj-1hIc8QYW-6 z?k~EeTPh5yeyewKz+pSW@vNO!aa5iI zA6{#fil4}ndi&NyJ9D7GyTi3o3~kxmmx-DPX};E{n+Q|k#JYX+>cE~XmvM}fTTX37 z19iBD=Lg!m83G=?SVN^t=D8^dzFpQXt4k}NeSD`bUXJRx6nh6#pY)o@eJ*CGWjwb> zJOPpP3k{{R$(2!QjWN>EA@Y_wI{=eeD|lX_>GrM z@LbgUhJj9S3V0VhCX}L<7fYEcObL3pA=(`P74FEKH{dj0&`u*KBoVfg!NRo&gV4iO zlNakB7D~7oC%rH6h8LMXTh#E?;Psg12?(c?oUU!@xU|QhrlXO+W@I|DFlZqMOV;CV zee@-h{ppj!7TAzSr{qGie~Rb}#>@vpGY(}p*>?=ytrTXhMzaODek2OAN zBy~|@;N75_#6(-V^_uS4CRBAywR&iMp>~L^g5;6GCgYK-HF2k7TFMuB;r4i)7Ms`H ziedsj-*BZ%bQ?1fq*lr$X44-h-q-)2s-fm|909Q4uz(wiEzI%w;$QnJz1CZtlIwSIr~_ zwJ`5Ay*AUhL1S}8JI3^u;(1=9ZbJue^XKTd#@n?T6xM_L-uaD5Oe#=K(SDs&t$yv_ z!Tpt`#kzTJuMJb$(D=cYrdxT_dSMa0R1d{??5z=aGE^ruElu63CN%Hs;4f zHrTS*Y~c_$Wxu>h%c+NM#aXYT0(m>=z1bRrNae}QjarFt(@Y0tuk}JXU)U(OWrqJK zAiT0b9NdO2m*%|E7vrqz!}0-(tQ(!o%9KG>^i8sLIR-YA*G#Fxl?(2sJHezY+(jMt zddD`w(9(TQ@sy-cO5SAPa;YeJx!}N z_Vc_MO=wkVY$MU!Uw5v>xMS&Ryp4}nx%!&{2B)>4yHIjDH z-FHj~zpHSzpnhq8HT)`(@Xq6>{Ba*VoGuxfny=e*5sjNx&&#td|lpPf#rr=7cFrj$g zGSvU2!dh8$*Z9Su&h>;h&%Pb1<+e_S-l@VnHkI0K7&TmZW~oX*wt*|CZhmt@a^3U! zt6t4Oi;R1Qqcb*TuMf$R>N~lj&|?Ir?$-FT7(c1Cp?)H@ut`7STsygD=8RCy;G4bn zz<`{j)i{g0BCSW^upO{PZUaZ$S3c1FdJ)nkd8$BOT9oysItFK+i2N@6;wI1gJu7^8 z-{-qo*_1UxiI4R|d3qi&lMCE^btCn@u1Mq^p(w{ILav>bli9QbaWNWOwS6D`;RgLT zRnWzK5$s2}H7?d8$b8FX9i8|sgN-n&D<7>ZL&fdbTk0#ZlcfOGm3j4b z%J3U!Zw6-(3r*3n@)gbR&EFVlVmYO<+ZNbw%!}d_K6OG;G=wc$4E8PwYq3mk`qO7T zhi)^*=a$`nPWlS@FYkhX-U`VfrxT|eLPdXeSw;8-0ZAndE!4IE7Cq$rY}8JiAh^jxk9G;b6A}}V5)tP??ZBLs<2WlvT#ad5f9n~#7TWWJYmZ`E z-Ouu*&+^8=7~JbT+fe}kJa)9X>E@#^p8gAZpc5Xhd zs0w~ECosjba*F6ykdp$dE zA9rmVXBe1?;mG1B5z!dxhAIr;y8q4xQ)dO0T)f?W@_=vS-n<=+WVa(}8;g25erHvQ)gk*=DOGRO_M9Ss1ww#>}7 z2p<~-#2hMl7Suf5{tc((^6zv?p0@f1Zr-YFx-O{R{2i2BY?=QPUf0XT`wV~G-$g<9 zH#x4a9n2fydD+_A8r6a`Ca*hO_xhy=C>TWy-cf7=SM9*JoB!}weem4iKjHOYF6a2` zo-hRyR1If=80Lv^H*&NCI~UYRCpU**;v+<5=z=^cA-ug2t}X~Sho438f90T9_zRxk z7hc!N!SSydc)v10-hR`gtOL4n&I9Vq2h=*WU-vW1;XKPD{P|GuCVvY!*EfPQ9Lic5 z&nRjBo`!xqOXHlyU<5fU1)j2?0`5<<02TI(gS|7XIv`+g59YXlF}QyU2FOoLW>WHR zjPM!W6pVk-h@D|jn*S4XR_Avx4FK-oIo5v+&}CHif6O}lzms<+3slvpVGDYeLhW&% zpCz0DXE?z#5FNFvc$P+SkCF?D7G(_RXIN|$@|QiMDS%ai*H8JQ&c8r9RCGprc6I?( z0h8xaKxF{vSI;l-Btrwx0@MI2Ko}4OuXCB5(flp?X_kL0`(F|K#{U^`05=~O)JTYG z2Bri_mupB%QKJI@*VIn-89GrfSwkmq4+O^McU>yY3KHdm5 zJ2yK|Yi~PS5CP~1xc{0SaLDcZ`;o!`~+&Oluc! zeQSrmQ4zxITwL_+{Jk~2)b+Kl{u=nOf1&?IjN^##3{-S+a`+`FqVvY9|3ZTTzykN; zt$of0VjN#PPw)RgZukrRcXB)%2W5l{!t*b}B{{EON$qzAO2*d^ZYWvfcq81wDcsBM zuOl6<3pgbH8y4T@YzX}~JRaD^j{i!2W>FVV4+8MP3r&9e3_iCs@U$5WC>1`pQWOPn z0W~nAtmpap1(^dNydZc%6QBkl;MvV*d}9q|WvlDD+Nv5?RZyqr0KWQFCpQEdXg;ps zED279%-}%=GgdEXJ~*HigN9-a^K#eHQ$;N#01XvoW-pKk1^)^AqvvDk5TE*WX68Tm z|0Re7=I#kjmyqiqwTP{q7Yu~&fv}68w>t`tYBjkH90jAH+Dq;UG6=%dDA?f~Mm3V$ z<{VZ)!M3h$pn;&Fcy_mSwMD_LApFqR2W2?Ws~{Za>tyE#!owiU?&9O>1j4BCn%vdS z8Z>5fltkIR?O=`|EC|B*p8C4re2abw97gdS{sP)*f0Z;+10NQ{)U;O3CqO)q3}gT~;GtXzP!7}p^*{^I z26O}czz8q}%mH73HDDXq2M)o73KoO_LI$CMFhMvVJP=`sBt#CP0=Wv&g_uBYKpY@$ z5Ff}*$X!STBnFZU$%N!X${@9n7Dy*#05Spj1X+Q6g&@(OX!vO4XbfnaXaZ=GXo_f> zX!>XtXbxx|Xn|<=&>o{bL(4)dLaRn=LF+~vL7PKcL)!xn)$yQ|P!=d3R1&HT)rOiv z?V+B~5NJ3w0h$FZf!0CWp+nF)=sNTVIwm?9Ix{*Sx(vEHx&b;2-2*)YJrX?`{Uv%e zdMo-6`X}^l^b-sM40;S63~3Av3}Xxj3_px8j0B8aj4F)x7$X>8F!nJqF)1;*FeNb6 zF-9IFVh>_3VISfU<8a_e<7ng9;soGC8r!8ybw!R5l0 z#ns1k#=VXE47UXLJ?=E_H#|H%Ry-*@9XuzzTX@g#Ug34%eZu>JPm0ftuZ(Yw?}Pss zKM%hde**s-0RaIgfdYXkfj7Zpf_#E^1Rn{$6Os|~6KW9J5{43{5LOco5^fUV5OEMG z5?K-j5+x8-5cLtQ6XOtb5-Ss16NeC|5Z4lq5$}oBh4m#M>N3B3@M;%UGNPA5YLqYI}ir<uV zBRC~QDs)BYj!>P@S7B~pm~e{lun2*Osz|8FYmpsM9#K2dbkT7!GBGW&2V!rRR! zJ;h7JS0vaaZb+m`j7gG9UYCrN?2y8cQj!Xls+am9EiUaXT`s*P!zTlmDUeyd#C6H; zQqHA$SyowV*-Y6vIcB*Va?j=FR&Krwy{vXQ{Bo}fsfvM0vdTwQR#gYpLe*_GF|{DIW_1j8P4%bhV;T$^FpYeT z?JE*jg0Hk{;%n+@CTo7a%6--IYMmCE))lQ-t?6qV*W9kvXam|B+OgU**SW5HTz{j3 zsdHT?MQ2f0NcX00yB?XIm0p3~zP^%vwEmRA1p^<0w}wQ9=7#x(2S%5TVvOdD1&o7@ zyG>|KoJ?MuVwoD6=9=!AshGu^eK8j^4>KRN;Iin!U%8x5OOn{AjfED^S5t6&>vyJ9D67h|_%FKZuTzw99E5bLnwDDRlyxbCFv zl5aApW3#3tlzC|l^g&@Z>tZoRyXdmDcH!yUmpF?V+F8r`kC$8hh~z4`lU z_Y1=a!#u;r9>_e%c!>Vc>0$39kw;07PQq=&yCMW55+aTwVUb-?LQ&76P9NJp?u{0Y zPJe>=#O=xGQ~9SaV@P5GW9DPEVyokrefBzuJ?Tl( zQLt_D@rOkDpRY-s=})w)dAJpHI6lNuT5SL)LyB5TPIUj^@blje`l#r zX`pC`Zp3Z8*Ld0#*tFN|-n`!8&@%tl>h07!<9EZYI<39$HQ#r%skXgqS8Q+UknO1N zl2nPonR2zf^zSz@>r4LHWU!q02*U!y3cgBiBX- zMh!;C$IQp(#%;%!CtN0WCVeLlr*2JSOoz`9&m?@L|Clv4AOju%C%3l^0dQl{j%o1cDNq4L9&s$d1141OJS>L+j#rS zj_1zl*T`=)-|}`vci-+^-}|`lx_@{O{+;Ig%O8?I+L1=cr9;0XtfObg7mw>sG*6~a zUBMlU4FLblXVpqs3w+bq1PISkfbA`CWdH%)z3u_{*x1-O*!ZB+7YQCN9ti~zK0Xlz zH5nNN85uPR{#p2WJ5T&;3?ab7BOoLoCL|;#CnO{!M@59>=S4{VS1LF?^A~##JcmM9 zfBB2efNK}r(^iN)$mQR?#-O10)Gx0w(AD$rncxo9Z<;*FURWJ zs=Uqi7N;6C_-yyJ;@-OG}n_xq*&(VrML{2$7Ik@eg4hDf6W2c9~Msk=Ek+BAEUu>kv&G^iUxa( zZj1(dT+V-m&_3<|7wW6(K+FvS4W0<($lfWi&bwR3WAemYlPUGuYN0>mB+aL0#-}m% z*!dJ_HaWrDV9MQ{0bSSVvUEu(Eel`zSY`|vw=aI23^u}DbwX-;uw=%M%5EX8#*L+z zOaqH)L>FznyLSR#nygH_ zS%>@!|6@i2rizPByV7nvR<%u^N>75AcI9Fk5M!r65rY}cGqi#k*T;?tkIm`(`wX+h zPXU>Vm6`p}-IEtg+1g=3tms-#zggvJua@=N;z@^W_?=X&xdidTEZeclnkj2@6|o+O z-sfluR#{E(F34X=)8?#Dwf1^t@me|}e=s=)M>Y)>pA=ixeAm|PD?iAu zWocoRU?B3@P9$!s1ciOo{I5dRJ018b*Mv~xwFZH#dE~Lur|aHGpJ<7UG1k1=?PBbj+)^hqqh>Pe^d{ZR zPpYl4Gyl-EA3X&2XijiRhQaq$X>PEZQ_`TU^UUOF=gUOPkW-h@u==9HE0v! zF;i1@4`lX?f=VhFlH{7McOHui{NNd>i{myK6b{rfvP%*6oUN^z*H;n!9QFoYP*7Jb z{-zpfv^9Y!UOffcO>f_g(k!jvl1pJqj0!k(O(OCk7mcmikfIces!o~lYS26dv{nOW zKj_5nzkwHZTqbK)V-#79YwFwyS)%$OuXLLo%Ixp(DtcvXE7YR+=|Dke`}^bM14&{t zukvec(9IyXy}PpbfmUvdW1GiJ$N8tgmCBbZhP#o_SW1&LvsAAg>Th;L6e5#r>uqpq zr0fqX$9H>t$7Z`pl*6}&k?)^r7gSf(*dL}L^7T|8_hjQIEM;ZPab}75j1uq&+q2?>IgMK;4q-(|#yRSz2zTQssFjYZPN-^Y|;!K+yAl4oiBcgJ%XJ*#OJ;QC%_`ly>zQc^Yqt ztnkDi?I&7eOd~k3wNSA<1=K=^s!O+-9Lr1a)?ouLy-29fNPl16!@TB^LXrwGjC0O~T4?bCVkNLEp?Ay`GR}U%= zQ)1dq9`tt}eaQF_@_00el1KR4h2rl$)m`vCGrLMC!5&;b+o$MgjXOwxJA)ohLd=Z3 z&6H*Az=&h1`AmjnX8e#s(jmp61Q#-B8}vDVx9 zhK;+9XJwr-nK4-QgNHA2c^~NynlPekw{&;w4b!ggmVt0!Lp;@u8@lfBqO^AV_QV<= z#4)u``u&ecyNg@O}@~*L@@a{hToi;lif!rnHetWDp zq07|WvPGR!`-trT`QqcmekGa)g&x8&jdTHxPh1V)WU@p^kS1QdTf#CNl3_4wTV(O1f4^)oL8`aXWK}2DQ2C&|z&XF@ z*s=(*v{t%4oBf8vdc2#)E59l%g@>aQb{qaoZL4g`ygjrnbjs;&5SjeiSG`Cb^e0-3 zi7Pjx2msaWji8XU;fgwysI>qp@m0KiTk%BPW&GE|E&GAiW44FE1W8m=YX%WUFQT<4 zb`rDa7Yt&R1zt=QzS2}b1#EU0<9%5=vYCX#7OHE=BFsKg53b22@T|*?8U<(MwEHw= z7fPH!xj1~8^pJ~ISIg@}c4i_5k$3ynk9!FzdY2>^dXbiG5))0|Xh5C0Rr11!7n`%A zX+ZATj@r?*8WnjSWt&tuI)S`qG1JGBA}eJL3F&*Qly;z@Uj)}5S3*yR&MckR-yHG1 z8CfKq%d#q2lsawyJ`!r?%#?Cec=4!jAtcJz(T$<~LYpePy7%QQ_6v;?gUBcvGog@I zdw37DvtGKoxI`$62TG2a>DX=UOAKY70`ja2!KSOb^R_dCNbscFkYYnBeyFNt!eJyRedx6Xe0H~Z=Eo|+mpS&a*!yoDLhhtMQk}G6^ivx< zTN&=&=aaLsD<6`2r<&k=GOj_>1loC{2NGlL)e$r&8BBq1Mg(OeyIZGMQ`?fK)%k-3 z7e~NZuOT|Cu0cR69_ec{gp6mhUNMo?A z;!4qE_c6Cm^GDxyk#gfcOnmG!?ndrgdL9`(=c+@xwLoy7)GahKTGKZ|HvAx;Kd#s? zW=xlDzU8kVuH7Aq)Ka=^A`SUwbSyy-KjCvbzOrGHm3H8>GBkQoC?&NGSsfDb1Fi>s zL8-UDwn@E5N!(N1XLqAMNSQ%9FEMu25SfN#(jIOL@yp(i2n;TuPMVRYBCh)WxTDk2 zgQca(!TmtGJ~FqQzj15GBEnVvfQhrT!s3xHA9k7%T|VW!{i5Y`c8W1L`n15!U}-g8 z@F@e!7n^T}_l=Ojgs}TO5|1k<0a9c{Zk;j@DxzxlgsE|E0pW8%xSksQr7I{;TXBqw&_=FFTOOf zGPzpVM8`C{GO-$%k-a<8jeH^bdZg*4m7$)Wk)5%DA%=ubIk%fg*|Ao7#w35NPp@7J8H@JI&DY;d3m#+4w;MaYAI88RgBK6CSYm!FmDz_Mm(Ez{g4^uw+!z%f&XaAEtrp>NxA-x*%obS z6vssZX5m`mwLWE(J2{1T*?tP#Ic8d+@Q`6w@9+qDl2{@?lejG6ejVK~Bik}bu6U1a zjZ#&GU?t6Memqk{>py0j$~pmsY7?0DH{!a@2IMeL8%;7FKD|5WeDUJG3fzJG)8rM+ssLQ`3Dp ze{%4nthdhetszuQL7q1NM%)7%GT zrMt_p^;6)UaS!$PXWvVEgDU7^+D)!8%04lxc50^y88fNbpiA0!ZdgAS$jzU!h@XME z5mG*2GP=1nEnD)@V)J8VARk&G_lM3GO|~VYR+d^(@MGC(!){OK_VP)q5Vqquds~BJ zvRxx&W3gpgO>j1TNQ^+!@!EA;(u|k18>hg{CN0Ug)q3&aYaY@mexFBbM`B~Eiu0J5 zM}svT{f=|&nsScCrQZo$KB0%SOn};Af(Xf?r?*FqiT*L_w40UVTF7-Oiw*EN}&57dYEj-lN@bni&`Q z@X1DL2y+hxl&PY#r?;o-SaRr&=?;?TAxm!!;o??Sy>kWA^7xdj{A}ru*`bh>jU*Gi zbYEp(6JO;oeI7ogAtgbNxPtG`YMlaIffE6%Gl7Rf(i}wDFJy~5vLbu~y&^lx`;3Jf zelTXwS{zy-HG`$U37j}_dq}%+y!q;i#VbkGk9WUD$N!Mikl}IW{&7+bY^!M^+TJe1 zF}H8vBzDjm(+qFIomHmxdjlJ5Pg)X1W3Cb6MXV0z8#uafn_M@OR;7-`hd057Cr?j- ztj0dIp*@48H$*wZ+|$Bdj$RC|`k`v}s%#CkUiofIL$0;{8^?A(^aD?U7bi9iV2P0D zN0W6vYV;yh7$b)5)fuk$qa-9qCK{ucgIybo2 zxr_{X5&9{AZ{6W#ZGm*jHF0rOs+V++o{d&-e4xanq>@X4yWT#e9+N! zt`MlUy&j&McWG*s`9d>^95P>)^3$pPT#@Lj|kU z*Jcc|4Z+1i6mRb6iEF&ft9mXo8sJgwT7)Cj)oIL$?aT9LFk}bAZRk}xKbewPBHz)*??rAIxHrNf^ z*{m52nn}6gyK=)lL@a*1&uHC5-wMesE59tCA390rYWV_AJ7+paKZZs>$WH9-Wlr^M zZ}Z{Fqv0@us}Aew;Lki@Gq08zs!J=!H=Z5b*qnJ(;{XoS&a$S%<9+m(arWMgJna60 zb+Qr$yQ6v|&@NYj)`Vul_?doswANj@2=lgu8oRCBWYJJ8MdV^fzH+!Xa3bMm~`Aawb{TnV_ z!K{2GqnS4u6Tarulbb5ur?rQX*(*NSHQrYdoItzUH=sJ5G=gM00{$jWyx084@_W(qzQnRoq*%`>YClQ7Eri9i0@o z0TVV^maC8WDr6PxcM`ozX=L>sp~hPIj*VjuJ9_d9?S^P@W|Tl1{Da#oBDXEKeX&!Z zbB}xWBzmOqn00V@bEVj>xVviD)^K$8c0$Y6tOjSKgYoRpfaSsQC5I9FzW&f@yEj_Y zdkf;RW?n_z1$nk|)e*%V1u495o4E3hQ{75;@k=*mgsYDW*FWZc^Ba8lF?w*L-A^-* zp|s1fly%bMD@SER_RyXzoTt32addXT4jDgzc(D%;>0TRhQ_2WuV_Ng2-4W9Hd~9VI zMa$o{Cgr*^!&oS|?J)&g%e}?m?%H=FgkJ{i%9WwujXinej@_NYJ-70$E2WCQq52{s zfd=ux7OT%{sdJl`cE5S8)#iu>CSLD}w5U3iPjwBFS2+b-_yw}3Mx+JIN={-m%a7fW z6PjVwhV(Qce1{U^MX8z->L%@#+$B*3ijAi?h*BO&Rt?Wmi-!89-HXvMatJ*g{XK-Bc0Ki|#Fe_& z(wOK9cMsi#z2SSsM+wIADOF7eTMK-)GIT6_s@d)Z4Mavgb=p@~NAQsF+a;?wd4rkn zO9Vr&tgQ#R?0S^11^bTeiwB-$%MBs(COuthxaZu3J(gDj)Yy0^N{-WRQa)%2oeC6q z`JuRJ1z8!$zi;I;9{Oo#EMTwcxy(!JiP(tRT9=n&h+K7_xMMDniQVt&}%6w^gnC z)l8H(ZD*wC8EH33@9U2y&v+fDWZrr2V5wIYd?*=@aNZKbk7!5tvZX43S8{d;#f*UlXGW#Py1}hH449zd}QD1Y_>yj;>h~yMu@8H z_&yAFqiMab-ToBNNI#f~jyz1;2oB9X)`|vyDQE|O-Yix(b#bL6w>Qt?T6x#xL3ygf z`0DJFuJX0e{1Ev`?nA3g@I5y66xh_dU~#Fb@DnJ8$3%%nUVYyThu*l3e-{)#GMGOsA?IZ93f)asOS4%VQc z`|pBXTbr_~r`MGoS0>cXjd+u7ltUfOEi-8u=3*3B>*$!lOWaH+o{ z{IY_Ip^RD89IaOLDo|{AGh1xeEYz~>UPy} zBG<&)aDy6c&*rl>?{|;vwc<2A1WKnYikLnG?qfC$HhmM8-*``$vZqG+W+E-a!p~k* z25u^^ViKJ2Wnu;Vo$xzblbRp6&5P=vNrCoV7-enCO-^xkIU93cL?L1=$zTt^E1wq* zb#~A1$-BYtWwmd9cWq%IsPX=xU|G|%-LKEy@G>T;vZ=o$Jx~ZP6+Tc+UpiUZH0&EN zED?Sl4&YWTvsJ=!Y~+lq0U);i@mHI!W<5~UIX@3&{{0LFbz;+>#vWIR{v4G4MerT! zZznnOrxWKsh%DgQ9sn4C*V(rghyX>v7C-fO(?f$v`k-uT)k0O;8Oe6gnU~KL<})8_)W3O z@xA;~pL1E%qW~&*tb@cKMw2W@tt(cM^4LxGrT3XgE_pbVg!E=m zlvXm4I~DQI_19~%7&$4f(C4Kd-W);ZABrAnjma_lV~)yGI*B;S@sukvX2ZFr;~y}( zsMRBe1HFqy)-f4Vk4s1nOS9|XU&c$QK6p^%AJUuECkz@^SS<$nkf+?|yZK{ZQ3dq{ zrvKe97D)oB3jr{ml&_tqp1(Tu`@yRTxB$iFklU{k}?SpqCRXa7|**yqv_EX@IYs9yM)X*a9 z<@%tpuBL6Rt*DR-pz~Z<$T)3j^vOlIg!E|acHh-R3r*O)s+u^anTPZAfS`6M#k#ey z^q%0?_xcCc42aoI{=B}=-&XZki)5JswY9`8i;mHb--No+S>0*`@W-A^!A;{dI5TqR zy#%>pf}w2(vEW*x&1TdF?J`@Yf8*k+&iScIs6z2Xa+p9hbSH#D&Dl;;o8tS z)Ny8-Fq94}E_9xZ2z8h;vsYb1`+z&bY?sb92-CeD?Iu^XtcIr~{We?s zgVT4JL_NH|oVjFqw#sEHOGkw0k5iz0FT!h48*a@zn?U~lA>)wn#?=Fd9y=zg7f3E3W6j!qxBBg$mFG&^LKLrwTwsrW4N?D+XOwPyngL~>eDcEks z_K)EK{Tg&_emwchilr&-H@-Y5m>bjED4)J5BpO#YrEi%P&J(x$_J8LIIh%o&~c%5h<= z1pH-^Myhv@&?$g@aB0jCOQ6*zuTxbbbW9IC{`bGh8&J^IzAUi;Iss#Fe}^3seh)}# zoow|BVUCwDb@X*%Z+tELNav(jc9!D%heJ!@T8+TZ{82f4VZ7A7I*v?g2iTk^* znys{zr-1OpM6+#Z{yNq4*h-QBR)6NI7lcd{3;prs?4ciNAWU-(0{1fOI{H-=1w_y8Th?J4p#=;=BO< znjFnAqrCWqt>UhLRq42pNV)i3wIhpb~fG6Md^ndrh zb3X+k=EuN4(6>1dOf$B~HElG5N8Ns9TYduTbK<_;e&%+KDeJ81b|8BN)UQ7U^umgGNo^vw$AbrI|mlaM1(tdg8gyI;} zKf85QjbjenP1zqBG9Hj<<*)KC3Fo9R8cciBcizg=ju z*Vy_(#^-kJu10Y6aA)A=6|he-CNe%D)>}SxKeUg1=b=&rA8J2HR(Q;+ywWhUAg^cz zxhb=go;i0MGNv=+W?$9#>i^*GJ^z|ogSJuJ7DSq;h|;10q9Cx9-VzZ35g{U5kQ${I z0cjE-Bq}0Ei-3ZH5S1o1BE1F(5RfLllaNrP1QJRJqRo_P{@;`{S zxm#3WvU(1v`Zt%e&Kyj!G!lI~a>mk#=l?&KX{{2EMD*2#|J+&$>f1KdLSS+3Fzs2V z?97FliZn{eXAKuU>-{d*KPMd8Z+DsfUSMIB@>+EIdTDIIU7&Sv@{TWut>adbI%6(* zvOO=`R8rx>t}IOv`1%aM4ZYfD@{$D7?Lhd^7=n{*VlPw&Jgd`JFIoGS#};j{Kfbg{ z9Rwbk$joASIXJAOz*Jtd&n`QAhPx(Zhc8D3$lD5AXhFUAk1^=^^T$SaMEB0C92+ee zp(EELLiQP8c{TC^rlL)S6-M3Ck7s=6laHFpnv3*f^5)SvLLRiRtNsPqLl7 z+t^7JrhEZggue|^;ZWVIzoWgF}{LJQ^xiY>xR7NZ(69AWK)eWU?_YFXg`(80qt(1r>7{H{9d zDC=KtJ46uT4EjgCEUI8~r2#0qGapfwyf&^S`AJR>GgOC}w&$Kmrlm7Z&=T?92YsJ2 zasx0GE6-o+4JA)pSU#|shp^8;x%~EYGX{H9Sn0@HqY5W|FJcGw5uY5B@KY5H&*sb3ZtRqGk5% zFOMRsDG6s_7kXA6zh3i0&1(VBHg}yU(ZBvXQfF*m2xZS_X;rN3sXu-@*u73rVPs~d z7>WzpB{GBnMxf7$t9vo+THeYEvZl~*e>DVXCZ$B-|-9DtpBUCF;iRAH@Cs90C6LJRSrgC)F zK@mmRNV0Ub*l#@yd0Ph5lR87(iT`-{2uI`GBBgSxZz?T}IL&+jFS}$n?{3rQ>*j_N zxTeU^8d5}61wk|iP1%1m!^wv{g-ywD`FRUfUL&QLsVS*~Tqbij+Nd#i#!e#XezGwBuOj>ddra?M8fylP>6wB{znh1CpEVB&QB6-V30z;; z?e|&Rnt5|KH9u$l%ih>ldhs802Ejcp$O@;HKGP(GClfjneJJDYSsop8mzyFD?Z=hv zHa0@J8sO{~0zA4W2r+giyS}N`jpw;c5(1FL=pFb3{pD2EHQ!6a6gP(okwTOpZ2(EfIVkWGBY+?!yX8i=r@`{YcMBNs{(}dRXly& zie5cswif@XQKt09^lDl}jq(s`?B(jGF18T@eb!a+wAtF34+WqOX`J9Pn%{o%Kc*ZL zyu1T@cQq)ZgJzPjLyVO^J-l0bc~zIH^5088--3iix5PIFrA6!{(*k#71z(}!7l4Jo za^)K^7U2K(E4P2NXzERlP`aC3NBiJ(>xuLfQ^`vgq)g?%eBq0t4Ap@WFyf7>G>MkI zW?8y*p>%4l*Wf4lPa}0a;R>&y^A3ySR8a1kxc)99J;cX9XJVnJgjoBk_xobT4dxs# z_AXPEkqWquC4>@9B{63Zq3R;sVXp2sHry`W2ow*0%QeTxKO?U3JU~9v2$-w?SIh2W zdXK5&zOL+3@AigqK~Hs zc|Ha^{|UOI89RaAcV0+APruhMCiD3Tc%)V}R~>8$xxp3wdwBN*bz^Riy0`_o-hcgL z(JlnZIW_TP_`K{>(WzM>pHZCiz?*tdCul0F1u01fe-*-fS+kot8ya|*Wo@MGA|2tu zg zE5E-_i{*YP@duyf;+v0G4et1A;7x0iR2LpSY8N+d*(B1{_kq?CM*#uxt1dXJWhye} z4g0jO5V{B+_bZ~uB-!kSJwZOr;klO(TuQMQMFP-tO(ycU4Igcre5^uz&1R7BB+o}I z!ExqLbdm)-{J`cjsM>0P2L`Ve84y- zTA25z`asXgvE)u>ZJ@=T3$fr@WI9i%df?iB==;CzA3U%;d8RHAwHOsnVa5EW35F5h zf-gEaB9{hpYobk$5)KH`%Qe8D9$wIFtF3g0R&J$EX;A0b)HzGPLb>)Z3Ep0!jXux7 z69+<^%edSd-M(9j@1vVZSF6sTFnQKhgLC@wP+YaCvQ#b@&iYj%bQ5AnRhP3L0Kwmg zrAB7;9<$kodE2KPQ{A~-Jo_@YN*nbL^ZTDYLCHKjZQ+a1Uj<_gd@9yk>LpHmeIC(Ki_E5l!2jBH1Ba~*&$`bPWmX?pE!>xV0EM!{ zakn7O80JOgV!F%x`rHjBuB?YP-bSA3J7PgM3O4bQyCHd-R}bVp#T)>Fi3>yi&4R0Q z8cZ>|HGv$%Q1~P}^t)Bn@d&G1vK)N)Wf#!nKhBnMOtdLJ1G?;Uug6dd3?fFdjknql1rLkkJDW*4agALegqd-wDDH~TV)~Q%s zLlY+Oqxn};Oc(75%K5S}z0|FHhqNKo&@wca&tpCUCx&Xh*!(XX)nYF2m*Yx9!8xE;)8N~ej8Xcpret9>7>&f}WNo+JDW0`Wx9erZ+!tJnAhGgs;r+-0oQ|1?g zg}kg~>&o}8uV+VsqFSXokO}xp^>1LG?33fz5u6ubb$BTEgbPcoj|S?@NVR3M+8Arf z(cc@mj74Wq{Rhe23~-WeLd5tO!08E3jkojKj&P5#?Y6IRufnD7RA)b_QfD1PE0bl| zCSJTVL6haQ$zlZr$W>zi!6u>+t9lcv3Ww0udY&m0>_luhRaQyd3PLe{%A4 zpGgS++pqln_dKN9{Ip{~^$aNd!UC5#MNgJY+XGbkWMd{y&^D*=j7b`5eQ^G~x{9<< zIn#U04dVJE?&d*S-g>OgiJ`3X=97}O32r(HTOQ>;*^sKAO)SBpD#q8(VV0aOG|PVw zm4!gFLI9{`)hvbVVVw3n=;#G&(c5#*&Yc;`?4N3v49j&DUZ%pb0pIDt7SrtjNmVIA z4zqQ)n@=&qrTTcXlsI)($%}G>oQjRCF*3VL+AZugkNlA2?b!j<|CdnJ#to&hwC%+mHXS~ zWwun-e}AYNRa!WAL)Ig9Mp{xx$biQN@5T;@Yom<9SIqrIEB^9mE=6j{Txc7`>p*SQ z8;IOPWEAb5%5 zI?rF8@7i7G*D2=+`GS!w+WCvX`S^=VIKbjD=bRqdvz?jt;@$JU&bPqB5#CluT{mTY zf5>nw58}9Qe^n^>eGU>(ZPLly2VnIQ((sepR)N*(=);WZfi8B-jA*j)@&f}I^_NAk z$c9dv1niP5q@Gv*1;LK0=S4Dy&O_1aN@DFAR$ldGQ30}I)my?D8t5|ppd?|$c;WQN{ z;3k~~N;On|f!K0Gibo-t&0-qU^5x5CQDQSXi)q`_YO<36aKzfs zd0*M+cU4Utl{r3|TJV`jlNARP8gXVypgYoId!>eOU7OVv@%6x_2>F|M?jo~^KHNS& zRP%|Ghf?or>W=E(9y9!Wrh73csxPQMazw&)*x%Yqt%36Ph)a-xyq8HW*A^RJ`lira z&e9fRA5+S=Cib<3Y10vklo-uPn_KmCnbRATj1E-}6P>V~$kh~|`y!j|V@Yvu;DvoTtKU%%n6P#cFO8bCE!jjtGLIw3%VJ*?e}$pz z;^Kh^IC;Kfss8y+)4dEu*;o7@U-~PU5M+gBkX5~Fc2Aq7NAqjm`=*>faq8Ib_E6Dj zxMS(AuwdV@tU`wgrONE51-!lQMUwu>{(vSA9Kq+WK>UG-Q04l*Ov;T4v(2c!|J*z# zKEa$l5%)u=V$hnyOEvEs>mU(Y=h?;I%YA3AIyU{~X>jt-<&Pf8feXzREX!|<{{fg! zABGjJhH6gld6?Rvu~z8WEL~||?k|7v$!!4qm`mcx;2f6ee(x7dlghMcNv=ks8$JxXQU7LXm*S| zzUfw{&#Qn?xpwEV3)#}3x4PLO`HudYLvD8aho5Ne+2~M>dHG=UE zCr=GG6+bU|e-$T)c=`@=(tbkQ$7_$Wmn+2cE>PIxVEli!&SMUmeU)W}5Cjs(^ZKKe zW82dN&9_vMSGu%A$uV9O=fg?lhJk4y-Z2B5Q6#EW&V>mIAooEY&>2Oi`t3aziSj91 zVJRn@EO|)oIMrs+HR72@bCRP=tJA3wy<5#KSdAit3c*_V%`Z_+SWZbi_W;=I5;Hd!`HB%7F=`NC-w4jFbhJTA95!_X<5s z1$s<`=i;gf?aGU_~UbvWU1w*G1sc3p-NrZkwFYLqyA z-Y}rSzviExdX_8&=2}a6+F=GY*{3NC;vmWo`s(b#ZoE=+)syOJo1X)HMwVB%-^kFurdjxCQq{Gl^rSC+0{y3lDV zsT;3#F>Xi?bnRO5nWJsreo?+@Wcj&OSpIZWo=Pt=_bH2a%C`_SAXKC^c%}sG)FZ=l z4yv3m>PNi0^%B%O4!ya|haCG|t>UCwIf0b^JFSs9sQ`3^$g(pO*FZ@PJBlzs2se@a(xUJ27>3iEI_9uVT`nm#0Gy?PhISirM z@uQC8QQz3Y6=QlqWS01e zU2~9Zx_JIyp6eAWwU33LbRggM(LC&F=r_UEL%}`#{8Gk~e$-3bw;_KB8+UFVNu(sd zyP^Fj$POZgbFXCw(VERIOfQZrm0kb@5@lH-Jod%MnH)Csvzd?u-?^)u29o2^@0qF5 zZO+<`{AJWNf2C_pLJ6p2qgZJ6!>UN7f_?VDFWt?ZF57b(egtL(%n8|ws;pXWrz#NV zlggjJCF{$HQ}8ya-P;Zdf}5@m*|kS0dq;I&!t{~9Vf-#kC|!Kb?2So;10S`5ZCU#V z8mJA54$v`qTR@BHD3!lIJo|uUlqS(dWLp2H+lf-(_{ZLuQ90>$y%6f;25%;g5!x4O zf9+dq4;KyxF`)Cr4wYlfhI?;RPWgysOEgv)B_0tEsI%hB>pE|F6j}D(|TkH3>f>xJq^F5^K zjz<*a33jrE%cnZ83ll^BmX@uc6VQ6)N|>0^9HHd9yfZb`{cg*k#>{`3gE-$Hq+AFH zLdwrpMjc|S4ypU|GjDioJ^rmGJFAMHm~{~FJ=aQ@IkySJF7D7K?y0u81uVU4T3|TN z9#m|zL+;l8!r6BIn*COzfNDiHUtsIf2~<%Z$cx=lNV~LrriF&IEO+4O*SJUhBKR%- zPr2RR$v?|>Bwv6X#%BTA*`5}|I8i->~*Qi?rC05KJ`gsIw@%IEE6utUI?nRVz*-XN!LmNK^mbrRx}Wj0XpifBrsR(@69%`!^R(8$qy!Q5XU z+?LE>ZIjUJ{ldlgc(Zc5BVKxpi=&l9`bT|pK1d5ETl1f#|&uK z(zV_~ayw+^Z?wiMt8bvt{C1K&LLplb2)Fq37A^bg~rWp=R0n$`=;SwTZk31&Li( zj8(hzeaI?PK@7JhPB!h)N|Bn5mCM>S9`kjc%Z&F6A6;{P0lCFB^j0vw)}}!9jJ;(j{+hS3`3rt&X(g| zW(Eb&?Mavpv!e~Pra2~eI7ee^%g!_vt)usTm5)c9VFqF<%C9f7uECAT+YA&_H}VOY zdS65>qfunq(2F2+-pTL+FB5D4^SAoJY+%D^tHs^anE>C`tvOoQ687y-h_!P&6SZH4+FAej6Qv{ZUdCy%Q z2~lLh@1);vs{Py@5Oz`TGGiHFo$?|vB;v6S7ayN*p5lQ;E^bYEl@T=o**sVoPV|mi z3`yMKQb`cd?@boXzGroK2V0GM@|Q<=(!rB^ZSG zWwH(WSII$FNh{5d3~#4R`K==d+det!oI6g=Xj~{G!WwChsQzhO&!zG@pg*`h%oZ!V^-WxgZ#t%I*RC) zxV{o9b=E0dCRo2=9O`nR;*^o1ES*rVsr8q~sR`m#wLebw5C^sU2L3u`W2SEm{{n6^ zL=VStw(*FzGXK}bY0g!arUg^Wiw;ksxdZL^8~9?)`VEw=wGDmsEUk~9AbaC`aPZUO z!t+PO%cB)xX(*bZ3iB$vS+%-?3854(r{1qYd&H=CK-9{={N+J=fWJfz_~|R|UWGj? zq3=gJNQD~buWjj<)cl*5@U3VVMdOP(bN@=2>hJ&kEbRZw5??p691m%L2zdoL5gqUz z9)1mr88*k0(GSdd>^e8!%ikz4-!huT1R-Z&HMkg*hYBwt zf)253qD3ZsK{G&tE4FoGRnK@$Wzh>U+yl1HRty6R*ij>#$VeD=rD5@lu$X3E#}=<} z1j}E=U|>KE7x{LB7i%{`^Iwm}iI!pY9O?Ft=)y^jMu8-!9;NB7Si-wclCP zn@l-$RHG#+Gs^~FAHsN__C>6*qER(6U0lqyF7TcJy<|{^d z9z>}{sdheCjd7_f*wq=Lr50h*G<(YtYO|A>F7BXQpmP&D^2! z`H|r1!cy!-R?1f@$7lE6v{Fv{dBwbF?;#s#ekKAP(=vihT~Y`c$K$@Tl;*P@Y*Ru$ zhw4ODX5<&k2AC+7zCSv5=!}=Z;|qUYo_t;iR`D?*ZNAzFran-lsmiU2Y-3)*PgUDIOU)6Jm~f9!zqC`vBfCo zzdTGiPzQS2-u}&jpz<;vEYe_-LTNuJvG*M{4s^L?SP?-I+TA%@Mc-t20fu2o2>Z&G z{OyZWKv>r#n8?S4@S2r^e?8+#?eXIX^Znk#61Vp6|N8O%=K-v-P}D~W$?alKpSD^{ zDUL7RxT;U|>#2h=LV-K|>jmOP2nx4jrh+=GrFm(yKTahcrXKPukjYBX(!PdT{`@%O zD+>lJ*>f9{;dDTnS2)k|KLPjC5D)j!m_p7PK74xQ*p#HJM}?O1D4hsIcQ%04{-CGA z;|UqN{Z)}evO(2TeL*d8klH9>A=V9eXdt&8b*}L`9oGgqr{*sRM~<5hm2pS&rs2(t zPa*SikA)upOoC>c#`fcrgcJfMbgE=_OMaPs@IA7Qo!nFXMGtndntVduT?0fnFG4^S zSoW#S4v1(~7dsT-_?j;cZ&bM~C7vQ%1(1EMe&0Q}GjDrz`>z@{bB+; zAZO)YX3-KzXtl;>%CUsCLp3LFxxN=lajEv{>)Ou6jLOMQjZQY0EQL?7^LLtZt^crs z7|)o4WR(dJC2tS-8_MpE$9!+k{F%yXH)Vh{{`*HaA^6|!&(aocs!oNp0>=B%^^nbz zh%2LuRaKeLvCAWB#WB%(U3sY-*F!*i@JtSUb2yF(V*F&z(p3pC0i?vrUmg+PF|w5O zkbNS*{Y`N)cgl)ex(JHsxdPXV+a(Hde@}@~MOY9ZgEJ`?(}|9GCZXMH=nOB0CM;=7 zCJDA*IX>_}af*B|zfAGO+7NPkZWb|+{VO2(tNp~Nb=*G4fNeq3lhz#GED13Ssef~z zkpy34^<~!$AbHhkF;uNNIc8|y1RFf|1Z_REvp=wBy19$0WhPd74> zBKKoh$xm7Q&+C&W(y$Ra(bt9^6BFWpWX8cuEUhLj$l&TWRsI(GO!l8}Nt+RnAf$$? z#DqYZ-6SS;fj*8mi!G~)@PQw08WG|2RDg^LCcB3-I48$YE-KL&nj`uR_#88H{;TFo zq^wtX_{!XcA!=zG9#z998I$C4a|sT zhe3`0bMzw2lP&U>C*F}1sj#$gcW>D1S3ZQ?s=YjY4%?`XW@>8UaYwo5h~7G7g^W@! z7oz_^#v4Oj!h7_DfVCATdlneTNxrEfC#;5Bv$|kiFUt(3PemoXTub^uaSr=0k`R#< z_V(-^*lHB108<|GiYt$h zX{;WpthFXOq^{2sx~i>`S#`gY40xx!O8LkYL-sa{){Uxh^!qvhzQ>=U@nhoTiT$5XvNudz8oQgC0`o+eSl{7Q!Rtd^3ny$MBkp$D|rJAUK)# zW9k!`!U>^$h*o+9skw#)W?PTzi2;en>M=Emw3_s&pKfcC^z1jr(SvN~UHre(qm=R^0E^LoRLz>F7v^>v?zg#6c}tM-9G(|1TZy zu?=nmmJP|aej7afm*>Q6Z*o_XANA0Fs7K7=6IQ!+P3{e%9b#aUb3kTVUOL zTQdmkJg#u`!&77AaJCA zU3w@s%Q1geZTED$yMCTgEJ&o zw>H`5nbAV!UuU}ggYvsiPdOO955E3-f-;=%a{z#(SNDNa|29yiF&#nb)u_*Ee+C4m z^lNsdAwQwihh+arGs>}4ii+T@nr7N5 zUc;=S_~`ct zHU|3AxQWWVdZ6~@EQ`aD)`iM!rHxVII#>OW!8 zfpBA4s09{vhxj~EoifRq{v^Yju=~_QbZM$OGr$My@Ta~rdkPX;`nLDBuUSF};c?{k z))JxsGxZTOk|L$q?gVPCEgud3G!)@Qf$03J&HI}pi2U%;jfrrw($S7Am2>llm=DCZ z*c86*Jwval_X%RC&NG@b(p#x#J6k^lbB>*584HcoHl>+_x%)?EJGg}2MjtLLL$_#J z@0|_wrp->354NU3KkGOc4%r7Kef^yr$CQ~*XN&q64~87y^~qAE;E@+1u@U}9zcdb& z$w|42Xv*k6KY3G@M6L#_0o%-XL(kXwoxPV&v4i3HlO|H{?IIg*vy5*L(aW%&kXm_7 zMp^3D%N(`cI+mm48m|I!d`dB#8@s`2=Kx`41F7|dxey5!PVt|pO9M!f*j}~n8b+jgxeS8n( z8XzDt;DO7B;BLY7JNwNs1mZsc1jUJShvqcUhBVC>brlgq974^a}{hjCy(8iMdz;1UF~6vT8`*f~eq8+miLXp3glK=(?VlQNL}(=zn>*C+IFD z=rMEJCc}ePifcn1S>Gxcb%{kiUBz7HKdXHm!8y@})95mI4?i>eskE*e5YWi|0%QNUdit8#&IbrHsVSq3+vRkR&sJom# z4-&chmh@S6jPH8@Bh2q`P=)p_gL8Ab*8C@as1?`+%(Q$6DMd62 zlj2lkr2Fc>y#w`5w?0HK84}g^L%){wnX$mW#-2~nmTj2L$(eh70 zd%8%827TrE^_0WO%_h6DyV~r!(t%hm7&oE^%4bH{jVM>C2(4JI|M+}Ky+8G0%OTMD z>-0U z-hMWHWpe8&uNLLyT%#sg@<58%F6ayuAcP3V@Ye4kZ0(pR?~ca zgEz+03ZC4!JfN;?npDN8S+Aj>qi}#qZGFJEbgep&8AXnXm-`UBcIAja<6&Y~Z^KK4 z&yl9;^YdHv!PiffR(Ow@(YHN*|3|2^ygLqlM8|fT2R&fQ3%`0b?Jcg9^d*EJE_-X! z=ju7swWtrXBT1jIxd=y=KGTN6yN;j7C4zV=+XoRwG)Dg!IyUBZzK4tW6-|0nisil# zZ}HL(wk-)72cq4_qBAU_=ZR7EsF(%MuhjsnYdT!;=Df?Fy_CDAM+cm=c0`Nw5$eoO z0K*C6{3ubMn61L`IYBRHUCo{;#l|X~F!p=8nAp7D3Q9=&BGM7rf4^7b4pxBqZAl68@OS&-212#;%=yX-yGc*eWA_$9L^p^( zA?ts6=20==D~;t$YJkT#rUk{KzH;O!WM6&i+kVqal+cZA~->57yZs*Gl* z@Ec7_G}DN!?h_=}i3`DG>qdM!eJ+8=5O;*0qTOG0qn2f)lsd-nJy3yIWoy3LuV)-)WgH2f{l0Q*JxFOL`W zA5^O*j`StG^CfM-p$e#kj<6HdTk*M&GGIKCD?>eN`tSVLpzQyohY2^@WWt~2ah9 zjwf+c?=zF>hW9UPshLX)>&&|83nblu>c6vjIR{rX{@pAM_;g;jJw1{wJg*;sjs=6* zmal%B0;M%ZC?<1w^X8H+Q~Ugb*QCSQii0>;&dt<;11>?4 zgs$@uJ81Acczi)h`*MA`ZNgQPlr&;Ykt2I9cd)H`Q;rh`j0x34IiVRB>Ej*tFy2{& z7_*f|FdJ5ykP19oR~>zEO%i+l#;F+nfR?qP#v1O4JYa|R#W1vKp)ttI2$fMkL>LX# z{_kau(UNJI+N1;eT0Om$N%uYL1+t%+dw1aCxg>!E>kQ=79>QB4Q8*d zv730Xf=oG;je$m}1TZkLo|&))qX4J zbUJqYiZ!Eh^se6uCd>J&v1&kySB^2o>}|T>iO7IGoOmHn^xltoR=dTh5O75aDJY5k z=PSKm$(ocZ%|BO@)x2ZQJyw}tlcGH-vFJwOOsy82Go#pj{>d20npXl@DZ_XP{O;!$ zEQ0!OXP<9$%%SQghjM-Pa*{ufI2bKN_5E=vCQbRsXA z;of|W(}*Hffdo;mZ}Z%5%x}dhY3(y}A`3aQ({0BRVV{R`ZvKEvcXPhX#Yg zNZw_6!IN>QGc$zhDQUubdCkGtPH0=WJ5C!I>49ZlRcTk5cIi~LXZGA5$sMLH5Pb`# z-KCVT?MOd@Xj~uNcH#|F&Fh5zDhjumaYe`$+vQ)Kd=4w5pC^c_vr2TlIkpGeECJ-W zlRT#!P~u3!hQ6dMhS=8$Pc<6ye!}%84$OXd<3fqn(icR!!BMxyn$?iQ z;?QV>(dE3$RY66S;`OV5nBQxAaNuK#-!lC0*AmbxkffdoOCND>sL^pgV&$58-`N1Y zQ;O?0tw(^u&!Qe?8xv+nF{4H4@6Q6X5m2 zUtNiN!$Od$9o1_%miEA;XMP5>qI&$#r|vXznu2ABy`S!W@#bnMLslAR zTt8Cg9`}ns?8NlSSoQSbE)%+55{W0^#p}H?d@E9{W@yK!I4EagE!-Qiy|Uez?PA1s zzZ$S)a^d`is1bn#ak|PRhEYPpC8^n$THS7{ZXOP~l)q=PJ*aLjQTLDb@okw6sT;>T zpTW!afMnlW8j*y11F39;l&-xab_uzSyS$PJKDXR+r>6mAp|~F^l}2fRi=9W8gw1)%H&$ESV%~AKV{L)RvAQd?yGW!{DM}cII-=sj@K*dE&jobn_ zNMllVxuB;nJcb&{vJsvVWX`}0KF(5*o?@_%l$2vp9vQhK`KD&C^|o* zfnMwh5k{zll{s`y`^obVT!4JJW4??l>Q)eJm@Dz5T7$axjoZxTv^< znvUn5(4-7Z$MM6e&4uDgEC(qF-YyLO^xB9^%wcISQpmaGmrffpT7|KgiXIBUWT+SP z;1=M)v>*5mv$IrW{BERh9wLb4f)ECLk;C*19Lk8GjbZ5gWVzbwFedBK?b>@txnyC%5Oa8EiyW{FC*PzBP>Tqm-MtC zeGXu&gVDJ&%qZ)s;q`0SDy6#z2BK9TJ`3x2;HBS6dh?eb*gWUGQeeb-YPggMOis2S zWW^FjidjW=Cf{IVxEopwz0bT7#t;RJ*>82D)Okewb)qm^%UP*oonXs{(;LId>4bYI*&iTT3>nUUTL}g^PxMS zP*6YaNh2T22c8ZPmZECVH$W~38`TV2lLpb-1C9L2?ZeL2H6LiFdl8RcnBFozu^|0| zvc1hc;mbPjfNUdHGD_#~81=yY??b7=!gF`|l}0l$b-1rr;A<-AK)GAQ(@nIX>fe`&soFV_aP>bYE zX$5b540i-au#~M{B=o3r~pu~-8KO1#(WM^&KGEc6#K){G% z>XsBKwq>=JD+hQb}7ao_Ux-cGNPH2zmL_2U1-+_%Rw^~e7! zm83{=zf2L8P~?7Dl3PMZ%59Z$o4YW~R^)yQv0Rss5X*J$bH605+~$6nTkf07j9vPj z&-ee|}-<#F5U_Y7}54cLqKC-uOd}cIwZrFK7F^lZzLiE1vsE%NP*e3@~A(5V6SP^XO-LO;5#!Qa4q%BBv0D^zT8Y zg&YRNGR!Q1>m$&F#Ag;YbAyC$6?N>gp1n}bp-X9Y>E<9_A<{U`39qXRa6H!9 zCcclkO9hU%6BsHR88v@@%7z;ED5_KJ#vpUHU`^#9#X&mJm z%n>LL=O<$#n0)YSN(G_e`C*>v_T>?7q7M@1X>7 z)3y_QLCLtxl(I&%9eFxooY9{l$gidbPSSzsBin8wfyqB=qkrL?uI>oNDHX_T$J^RZ z{xF_wlQJ~8HdN2HZfB*aKJskdqEEwNngBst4l?nN7*uTDkrmAfHrWO~12}hQxghXc zWU;tVzz8!ldT`HJE5Yk(!r(oA_L0EksJmKjNnKo28F0AvWtei09f|N(vVQbqiGADG zW1LxE>^C~z-9jte!(YA0RtE2)>B0g`94W}5y(HGv34cmTW+`@WYVas(~f+dwf8jwX}Z62*d_D>t$D>M_z+TA zEMsK@GKae`@&WNt=Rp!t^s(#4d7`ZL#4Qg;mW>m}ZxBUFJ;44pY^b9_ve%_)kDIre zke%%f2`U{}p;L*azI{sH{-TsoEJ<=ZqdFf8bpIOcUal!1^Jc3X>+X7(=W>}t*aUxk zU=$h@Q}+H2y*?CAO9Hq>S2H2FK3SEuZ=`A#H({L6=zr7>VnnO50HgNgzKF=vTPPl*Zbc+*QT*1y}Tna`)(l z<4blS*I>qN4Yerp{f-W0iVDBVMAx3Wh3m@c9Xn(3L~(Z2rRkf&et2F6dn?^a{IbGi-Rds_S@p^5n$a(a&|{^xIaXy#ha{UN`LkGEdM$Sz(z z)gR(=)N(7HHLQu)xLdAV7=@A*9o-3$*BjndKnQ0SBWRB(220>g9hy8fi(*1;D}l*( z1vJWk1O2RRj7H|Wr57;QmL*a@_~0Elbr!924z-_5Xs?G5R<+8biV%~zY^ifx2{or6 zVlWec-IkA6I%&8(x?wOiv}I4SoQ&p|?-TY1mVH_#9`KzmX&bM^+FKIqk(l(o- zma&-%x<$+9LcyHmlbSzbQ(RkW#}D&YcE6Q;Ia8Ji$2e+>R?3agMkKvAnUoRDL496> z-r4K1KxW@L>76g!japdrcPUpxG{G-KoO#+3Lo{Lug%W=H41a$u9aF*>E5+Rls(Wyo ztmJqF;^YZz~d0nHx2jx9SH`2L?g1 zVN?3Z;25>!XC7}p_L+yRW@{@PJMogR%ZDV6x<;2XKObHzt2Uu;A*NGFV#gCC$;O!u zAs}%#9LY3jp(e#1)Vc1xnvy&_{&58Vh1x&I(3k1cd`_C}f}Hj@w0tt;^xYphWv@@0 z|B$HP17bEXq)4-E)6mY*Vvj<+vrnmaTdnhA3{D zQ7;1lrW&LhIMSQS(}nsmqe_}?C{XB=S{~WF(+WRGz7@Vc+CsB9PS}~A2hb-qiE@jP zpZburRjgEAI^Q^}{A-DGG+psP z&K!h?&Z!@IjhM|(w9KmZ6U!3Yp{BtYnOswYkA1UjF@xSi!$*9vUKyqs){jTeKF41F z|0HJ@|NEGs?Zrq_nM`UP*{cJ2s!7zJ$i)lI^orWEy*R5iy+;%nnv^c4i2P}JGhv$} zT*tcru0d_Cknj|F(!?xmp_7k-vg88lSEgbxTS+u-P9Nr3gGwr^l-(#tXxoibJuH`(Ed{czVwLV@dzscNwIu+C98`Z1L@w7|sG(i|7X# zj2pT9^4Evi~2bd~DGU+`#I0nw0E^Md0T+q%Q0;lgVL6WYuq$z&CW88Ynb}Zj3*b$T zg`^2ZizuMlD+X>v3^kH?_-e$H-em+%`Vs#^wN2~8nYrZ@TNSH#+nzJo;7pouQ4u0- z$Uvqn9x()xRo8QG4x#^2TYmU1=f-8iVYLUUNvF(&7*|v`V*Rte-s{$k5l3&&$aGAA zroU9_8o#kuk$+u;M9NLgg0tUnU4$aHdT9CV_}C;P(bi?;-lux3L2~+|V{OvX0<2;= zrP<`};s%Y-%M&Jvt%CT2w|^BUc{f8;&12v3=Pj9sm)gz{N?Y33a}{b5Y&YBpDz=>Z zs+MEcTiA^Z63;w-gJbU8HH6q-WrQ-du-MhytOQoM&0{msyNcpAig)KUJf`6&g*(qY zKJ5bGLdd}ko{Vhr(e4lK_X|(!U*kdMc=2|6U3YAGD8!6$r~A*_`*m8}#g10Otb3yU z6F8pKN&q?7N=j$aLxu1)nFVSOPfXGM^A-VtICQFZRn*t{LJLzFtJ%E`A0}^B7rMqP z!Qa?crVgWo;cR-b#SA=@{h7SYeuk6RaQld$A{CIqbeAm^nk40?XZ5tm}TbkGaMu zV`@Ut)ok7NmbN3TldCFH8VNEFV)wV)Z_K|2X{s$iYY#NN?UHQh)(StbL|Vr-hT;bm zrdT^eDv*i*ZVGz~4|7~?Qvst}5A%Puik!~h$Pi!L@!7UJXvHVa z@H1+VPL10D^!?TB2t2`nCY4j@)?C>Z?-t$57i0^Pscolu&@G(mZyoe}BusetCU?X- zmdg2wgtkdsOgiOqyTIgQSH7$73NG7S^Lb;m5V>k_hOB2u969@_Oi;;r9GG6Q+}___ zMN;a#5$aXoiS^qm_*!@~x(8L{YPjiS&|m^3?s;A$tvx#~GL3 zCjwOfb#+_kuahPrWk`JkE(5`++5|=N6Qazsb#xts9qc8{;Gk%e3kfkwCj1uI8q!F4 z(L6@Lp*#L)26el|nC-o<^SkA1FV+&-1biSY^t-@+bO;U%My{Mmq_i5dP1mwtsG=zw z+r}w7&g6~gmlZm#y@z^1@*A?nbm=;BZP`31aUyiIkc79b&f36oXGo@Y1fzuIWm~~A z--X#ly%pcf%t$h-TP`qL8&3X;0I;VeO}CR^9u$bYKsWb938j#060!}Vle9Y+sSqB^ zsOM*mYPbiQwkS&^$mm*s@DZoMc+&Pr@0KFY8^T2t8Uz7IMGP zcS+=@fwc%AS`X5t7a$Yz-RhC`uO}k0#gHlC#_7lOt)L}MR3K2sd~}9!o{<5d`Wze= zfZ4O2zzWq~iciCu;W!Uab@3BAna3p>3qShlfvCuQRB{!K}i3sKZ4-kpCen}A#%oYqt{|C`d=(JREoSB_T?pf6a{aQS+eF@@RbR7(KLyuF z(|K7f7@xq;XvmZ0WlFhq4e!`XY}GWpUc~$Oh^bm@fxhUQ+0e=4b03Odcg2;|<87$w zmEF$^Z)l<$k!w8@4P27r89h6UH*kk@RNykoBGUNE7~gK{PT^1T(Q59pOlK-3d!D}$f*f_Gn)%8&+YM_r z8u1bJQ@pBr7A1X>KCmXFaIX@y_X*6NV6Ha^X?XD9Yg`P!HQ&UUE*Y-N;N$|+JE<*P z4``#F_It|7MIuvJXcuNWLi`pNAc`mT|?RIrnELxaqoN zq)~kp^GAy1SLn^2tNPfFyV8BbVZMHUp@Z6TF0*Ht7vUCUPi)~@pt@ItS6SDGV1;wc z;JV``;R31>5?V6-d&a`}@ok5peU=Vel6-8wSJkhe#5MVaSTmzk&DgE>`T5xJ$HTj1 z-YZe4>X`M}N=Oe4!UL1lJognMVOy2)+BicSnEceR($$^@VoCcL7}bDe&+6O!tYMXS>oTL=KJ!T~0wKBp?SUEJShjW>DvX zo-fpQrA>YuWc)|zrSjv)M>Az-cx`Ei@ZOvprBy=c!c(s+7tc*vhqv8YJz`bAXma=7Ie$LVF_+W= zkHnSSVC!BmAGo$f0p>ui?jEk$^m^!fpx7q`G+2Q{`_{~wLxMEzg(@fKYyehXmEnB4F$cUB=v%ywLjQz1=`{xGY3Mk*u@d~VG$ z3tA`VTl)OgLJ-?lcy4GSw1H9Zx*0-&FpA2W%nJKp6H@h(s)=_JQ`(k3pO4U2zR2QS zZW=P;qik$>zIhgcI!sPoel%AvnFIsE#$2U9Tmv4^V5wDJ>gbJCclereC|hJ-GzFW* z5O{aCySBq{{4KI{Cu$)uAaPBtiOG>}=vtC(Y$t;hg4A}pe(1C89-HqINycjuCegfr zwcp_aRX3<$k}gLQshy}AzbkHHap_7qO6q6Ed9MABc){(_mSAc)?E(A+BNylDb(;BG z=nLj6R2>~7JCH!fl02}Z9^vyF1$T}Ih1{87lVC|qTO(@&lh>6 zbZynMr&oCk%lh-~&vFGdOc8i4>v3}5g8W65eoAstw?yAzTHxXWxyuAVqsJL2x;%7# z8nh7A{>qAKNj|>NpJm2XLsu%!&XBbaxzu*e!HRa3{us=TxG_F6g*!U=kLBpf3hfM) zu`=fk-E+8BWU1I&svp%!+*|kmP0fxQpWD6eTe4@i3kHsNr#g>(>Uy3LEYLtCMH8}N z$E$7Lw&!~;M5Qy7bN3<8vxDIpcM~dHMhnG#{I)4spRD-%eSSP)Kv}(`dz3)oQSP49 z^OF#)?HnobV*R|fA zJYytcKHUJO!yoW)UE7mp)!yHi2SiX`x(c;yo+ANdOd9Elu7SQe!B0qE9(RvcyWqw4 zQ$zTDjv|B)Y904^Y-)C9D#-PW;FT2Jop^t#isG<%Xv6C(KXa$ICz%2z{`^(TnN`{r zjK=x62hfuN&th_U{@V)%DRb`(|F8!- z{yr&^3K`2*NmYIM==;aQz#o`H#@fp6uaJ+(_HX1To=L`_5dr`_;(|edQXV-0j&0I{ zp(eCz+_8^$iZ=|zk8WymuiM**ti;j*BS07!F{>@fh((C&&4HsEAknvRQB3h1L-fO; zqKMmZ8Jr^@`0gAB8_;RioBIhKRo--RE<>OMh{57kQ56&w6;?LsCf9cdN~^ExO=SeNZOjk%G~xZ~9dq+R%^|Y* zLGWY;lOu+7KzSNQ(Lr2Zxn%zpXuiWty&s zZRK8%CVu8?WQk;NE#vfi>m1UB?Dnm1H`ZW3gVhJ>B3rKiiK~X_;Re$4N7CmPFGwvt zZ<|3_oL(-uzLosoTQN2jo&Kq=#a{V`aimG<8Gcoe;)@mvBMm(FVL~inK8L3VETm+% zxt?&pefG%^oqhgb2JKvTY_p)H9`ssuU5IryS7xTr0-B{uV>-*m$H;9mAy-kXQWti|J0!J54a+bOoL{4A7vFFikb9bV zsQVZ^I>}@~R@&x|zeg~`DfNl2rg;$2U@|%WleCLuy!8b7IPN7f2FmqJ7x` z&Px?8N&*YTm!oX*pFN+i1g{&-z3LHti-AP>((SL`Z@E-Jux8k2KV5QHdaCZK+yaUF z`)US$eHdtmL06nx>Eb%O22iaCzKL^OJwhP^%XZYP`!N?MAuoNM480T0X1RBJG4Jzg zl1yq09W|0el86VGTEq5xDX523!hhaVtJZlm_@n zLhs)gkPP8m%lvg%X3Md&OV>t6oYLKW9;ovDs}$|qL-;hX`~>pkbEY;zIon@;4P_n3 z&sRBFeh_iUwrmZ#d%Y!3!bIp>a!I9MeCWjO^%$vF$HrCnx1VnE_KgY{$@T#b`qEqH zl6Qhd7WY6oKKIXX-ThAXef;Mt>c*C2rVHUlN#|K)z;}-)>tZ*C<+4j}czp+LBeNe< z@)cccu_{KOkNtw(+H2%^baw?@+KUn@^Xta9L2WbMG_&B(hI`)!-(CGt6v|%y1?t2Y zo9t#Idtj<@bASR=yPPG4l5PXXsDB$p@Qjq7UVj@{u&nm-(wjn(8zW6|+=d6FBIv!`JA+ zvzb0~%}+AWC1*Z$*qhVfcvB+~p}LKa#$JHAKqOsn$$thoPB_t*(n&E=Pck?nMA3N} z1vN=jQ@)|D%;n-@mxe_j*UXsuoGnq0*3+t5cUf*~mHyUzO8Up5LjuJr-6P5FGwbJQ z_K#L8penUHld|9ba<``aI1vYff9kt(Op+65K=iTZ`V}9vxYd+=gyLK=&#u2vW#CbA zdeh5hQ3>OrFy15%HqSPz{7nB*S>I`qA)(Q_ zdbkT|^iK4!91D@D%_lVcV^Jj2X{>h(As$!9`z!jWcXbxdSrAPA5F3VTj90jA$0u!@ zP%3AGFJIoxq~%k9oO_son}Y(?(tm+Vpn8xZWExI$hLutbMm3*) zy_<=Q2GTwkU4JNrf*+=sRRK*{cr^~puPTYu@ZtDyOSF&D{r50;@W2Lx|D|IZY4eOf z-{mhY_S(-wKVjeKb!TawUo9(C3p4E5O1Tk=ctcP{&Q)AM{6Yw)wjG_sMAB_yG*ia_ zm*KqwzJ>>hH)-64yXW_J`np31{g9fK%`zf*!kDO_jVYa2tyR&s<5ze(A>i@JeCPPx zrAd~3HL0dGLpVQ?i)EEE0igg^;`k4OUOO?OHBF8Q$p>k8w#2laXDg0zzx^e2GLAdVCmqQYRm(LJT?^1H@LQe_o z39$HN4lp8s{@n9)UB(B*WfvUp=41zwbsu`E`0vrLM)~nbRB0Y#dZ`4IouX}Y+#fI| z;vxWYi$FUMzXsec(V1kNi&yNyWAmv=S1yrs8&E`{w@AU{+v&^TT2pmSAa%WI1q9gi z8JL=`dU9>Ek3ZDSY;3RbIVDuZL;xiD5W~7Qu5`3zj~aRS`s;N0_Pw%k&+)@w8p8Lj z)QS#}S(?s|KT^56Q0JgQ(63S`-*%4gg?SBQFt}LfS*DU1QL6Y8wZkHW!6{g_=_z5I zG6=!Fx&~5brJJwh?S0jJ&Vh8iF9Esr@!3C?5Z)eF!hmD(RY&Z~u|8p}JVIk|pz_cv z)?!*L-QcO@Vy)7*Ey>?bi7(Ugl935q14;Mgr5aKha?3K&9_79kPjw!nwR*lDh*&qk zoGIR9={8V8FlS>aOuwT??1C<5-m*5tU_{oCP0ZQd`Gm80>>hq{VZk~|TiPCm>@=BY zm#84oxmSbX!Eo1eH6Jt%qGws3_2A=oGpWHJCeRW#=tt{P^?&kcn(Jszcif8szk6Bj zgSIeC=VP4Hu-x{Y6g|78D>1!4&2u@`7p;E=pCr046|f|HgohGGTz_0d>{HF~6^FUS zZZ-?mUmAqJC^`?G@~onc8c{@@S??$#%eOn+s6OxVa-5?Ky!kS^Gf+*UFPVKV`;EZ^ zUq|4M`-E)MfLqbPYw0+#+p;_lNz=o@>pI149)R8dSZhZ z^vq7w)N{2g+T{C!jt0+V17(m#v}>!uW*wMQeMBxEH!QcYbZp0u%BOZG)UfY)mb$YS zoZ6v_n6WRjI@M(7c$_mXzRF}?Lo3+N>kDMMJCF*siy`xb_S z;PAn6%}XStE|xr`s@{Uhn{2wKPAa}K{F7<(`Rs+2%zcHQO0Y-XRYsmi^0psGG55=^ zNc}pXJZEIW|0A3E;YL)&1^n@8SS-PyS}rr95iM_&y*N3eC#6rF6=d-VgT_-Cq!kOQ z}m`ay?|Sv^mt+6#DMH#>Vw|7 zH?xuX^lTNX4Kv2p zacj-tHu+tqU5arF-Y6EVVbQe0E~0$c@BGD-tr?CXnoUdsj?&G;AeDABz`~5uwdNn^ ze9q-yt#mc;3k^At5dCo+EVSJAs>WGgU}i4g=L7R5?&P_$`y2k=KNa zXpu^?97&b1uB_Hk%K50Kssa?b&pDQJImoPfQ6-S=4CsQ&M&36AvZ6^Mz@;LP5(Xpw zyHMB1i2WE#UOddRT;QJ#v{``clFl*gur{~{& z7dQZg_NOxII#42_J5#$GERO>AQpza6+{$Yp{ljLat7OVr_sojK zK}9q$+{m!?2?N0ih$gcGS&NFef#6v~A7?7|6OEIiw559gU|v6$oG5?$I%wQWSc-0e%d-93lF z(nt_ZIsH^~g^GuJI_i)am1m|DP;rA@*;q3Tz zJjIooQ?M?^Pd-VA*A}JgRSMywYWg#nfBd`^W5nwaJ9*$_4EpJ)ihWloE{^v|-&kL4 zfDpI5d??@8upVj_GvM|pLeHesm$9*rc?+&R)ks3jh$<{Fr6vS4Z4CpOSeY3(uO)~c z3{2T2oyt4Y7burkRD1J9?qu-X{t|TlwWDNoNfAPMj@9&uZx(_w)5(}PY})N`&sQv2 zH+f0$8!`O|FaTSn%$!A56DCT;R__)Ff^ zafS*WN{p$>>8PDZb?_lKQY5GzGz7Cfn5`3_xMzVP{z&-Kxk()g{@nQ2r$sx5DTBJ* zPIo!-lWD&)mYcKYTVm$rsdBR$Ai#WeeOR~yp-u{&3uA`BL#vFN;@yLO%D%09#y%G8 zs~$V6Jix3FXqW9~pRgy;S<&)s_dgWMTvNt~_2mA~q0OLrQNpO<(%}F>F8^l_a*7(O z`%)gryKI`A@OrQPJ4Iad@G4BIWtEXhx0tO$#{dNfk?OUDQib!O4+WdJ%8lj7nyPrp z>x3D@?g!3b^$-mBBaZYC6omsaiGef?2wagg9YvR#6%hRZAg!ln%TudEdB=_9q}2@H z@4(+?FD9xJs)7D*ZJ8Ow1iDfszJ-?>%lyYeGj8*>opK58&l&iFV%t~(eZAEuhDeAd z`Q2#ACT(-;C~-_WF#c@3s*nFmc(itV(jF{@sFuur2*YFmOLUO6Q^*?WH%hV`b}d7b zMCmtMOM`Hob5(Q{*Tu+NeqzWllX{98@7|p72kWk3pc}y__b=^-lB2~Lb5XsEPG5m) z1i+H=eUx zG0$~s;#YzoK~uNnEADx=lYk?q#KL1Pac-r-;9YRsl+UE{0&13V?bT*nLOt=GiK@%+LcB9G2%c&Ic zu~&hYN&TgBS3B)U*%JNO$oH;7lFQ%0JDt$S;Oy@Z2n&N zOC=Dyl1yX=#1`463!Xzw6m8_s*C8aSDi&BkILZm0Lpr(D?gXW-{`sLOP|xD{{Mkd* z?KeS6I|*e;lc*$=moz%PWt}Z4FD6L~NU5>*p(Wzm@#kb7M0{_Wx3>-d$Fhd`BTtp& z+UyH_6*9lgIyDK*6tPXhu98BRfpgj9bNI4xA$@j-%%;$`cI-ZVzoD|582_z!Ds&>N zqX9?*?w5+{K4@wf@;6a_vbE_Y{=Q(e>e3Ixq_J?jpl)k3;VAEry?yn{?4h-^M-Bda z;5)dvD%=UWWJ3bFlPgO77rG4Q-1Sf%?RToogBb@4QtmzvZ>8N_k%-@gh%@_v%^Lsd}YWT@aga>5o+;zzQ9>+dGj z+98SEl8Tn9|Md5+89Q79 zmt63jgoxjE{xV+GwRD(uaWO?<@m8C!sm$&aPAZ50x=++?S~Kbp?PGhBQuf&5Kog5- zj+dVV%{h0V$CHSDFw1uEg|e3GCeL4<%KPd{nXzxq{q!#UgzwA9(|6R^Vh6|vo1zQb z6GpEY20b%ZN1Duiidt(&JwoIxPJduI&Y4xWKHAi;M>3vKIGn9Fy&1l3Z6yMAbo-j` z?vq4Yw4RzHow*fP=BhN>2VHVp*o|+48gm{f(gVel^eW=z@&4X+7qr)s02ax?RkP9G zyvDi~99ik#hq54BRo`rAQoa>Gw`G@WwpXVAY|&rqcd`C zV*O{j%yXs2t%SC_+wr^IKS9C$-vL9glt9l9p_@pteaG&{@?Zb@6jpi|tL*+b))?=X zxxYP*qG*v(o5(Y34uXRVLv$_Y9jMS&QI?0au>{MqcTXz%{;plxskO%e_OrS} zMfz6XS1s%vqT;8ozWSMR{VMRa$NfID-V{WWrQfA`k*f5_*l0~*;yE6`^8KN$$PJag zEZ_;Ey#wV0`X$Uc*C3LB3$b#$!)zRDR~x7Q8_2!Cf-$(%yOyFRo>#j2SJk=~IL05Q zydge2d32w{VPzCt+0wkgHAWy7wv_TNPH@FFNyy{Ri@mls?-NrtWIHFEw?5d+ zPl*Etn@0K_>by^IIxwaN%uta9MnxFZ?Ug*1ebIG-wi=?Fsn!UvN`UdyVe0RU8m#(j z84i0p1SyNT#Gd8r*V!cE*T)ijDBLw$#TDm8_wg5{Bwxv_a6Jz=;{x~Y09Emt`Vdnk ztz3%pgn5tppD8R&l^O=bcl7UJtBqI76-D0uHma)|v)iIg2NV2hfylO7fX8q4oei=J zXqxb|bKUmjqfg#r+I;~xUk+Ri->xQ<#2gGnR7N#X$=k>(|k^hQ=P{`je{;gHNe-DRqNi1yqpUwO~tF0Z=AIG zu=e%0b>P@S=TOmO*+;(*vCPwrw3l7vA3yMO=tQZE8e`}SxXRb_FGI!_1eJe=2((J_ zt*MrSnH*WP+ti}Dc;;ENGgL*pdNV#dlcK3Lb>Gkuj<`2-latXe`VtLJl0cE;J;A#m zs#Fo3ryp44U`g&bqE^g*wVscP*vm1aJ?1)Zmsg9`;|%Qa;9kDh{cwdnai5|>=ape{ z6c^Et{qbnxBAIn&%EvZ^o@)!Y8y&>|su*m)cH-{g*wFTd0*mBwOO#+(0of-_b-I~| zhG_SoBFY|Ti#Y9V!E^q@oSSpF@uK++FgFe$n|SP~k7thf>xby)zT9^j-M_;VAo*nH zQKE0@WHB!hfN1z6F(K+^KJ@`yiwd1bMW=+FA1>pl>!Un@M0We``atER6}jV)MJ1GJvG zDSrWU-i5ptaKH3yMk1_g*QTG*u@RiNb)Ay>d3u0o9B1O@;<1-L-Ex;LJ#H+oT(`|Z zO6(#5#I${4SD#3fpZCYJt*M7QEUEc!ct48m)T`TSZUZjK7H2l4M0C8)u5QF?}Hq z(~3JyO#x0eexN=4Pl18yJJFJkbx0u0naNSJfICa)9lmWZIc*Dlf2jU0^IM=#`QZz3 zuM{=)dJqzXWJ!i_bgGFy8MgXP#-(h9E?Z|S2oeR{RIbM+hf@_(#P>rw6XKeCzoy zQ|a93H6~5uUFqIV%%midN)5@kRUX>F6{=%326VfWt4@I((+P4C;d#Q$)isMI2<08{ ze$&^)E|C&?-ZIZoo$zzG4l7?oTRt~uVKJ9&R)m`L@TJQww$vDMBQT|1r2B*t<#~-t zp}}2bdB3mry}J)Oe)IhH`|a}-x**I~cj#dF=Z#>p_BQ4|?FOHfDRYRYbjUQ*1F=1T zmWk_rp%$8UvdB6F%hb=7lzF9leM>TX%SpOey9RJM{Z|V~`5D*B)P{tMDK!{Sy~t|Iw(`wPoj zolzn26_P;2FQ5Lv0xcr8ZYSL7eGGjZp-DcEXIqYT*CnW8e!;>edfLOX(YGD{xHQ|? zqPwBk6m6{)Fl=oKuS~qZl`rj*wvFZo{QZY^g~`O+ek5hp(*MY}bW0$$*A?ibioEab>N~E=pt{ z%T?t)8mB1(JA9&g5`5sUivTz5aEa85dQdYoNaTn+C$zAA=wNrRvmDk28f?~WvvI1R zJ)oZ@XsVEP+tf|s?CkoB`U|helzEm#u`aD90e+$uTN!-C6V;u;G?bMG7ep{^s1u+2 zEr2$DxB{@4W7`iHZ>zD86BDa}4w5vTN_2N{0m)%KFg{zY3Ts!GeFEIOAh*C4TSR+o zLzTZvH7NKC67WAszH$)fYzy?-!@zg1Au(xGngVsf zjHH|&=-nb(kJdf|P%8tkR8J(x-8H>`k!y)(mVL~+8+_U;s};=KWc3-A^f*FJ^SKK_ z8#KIcxTU!nyt~QWePqx0dG$a>#OLrMHvZfei>8qOEvxlW%20aa?9td-hk4QIok`C~ z^hPlme4p%`u%9$;O)N-nu#VU-dtn@Ue7{CjzJR1(4vaZA8qs|TsfY{r*q)y_vW`Xk zMzUxc(Qd;bgeDH+x>6NE6RZ~dFzU4m_kQ9N{A-^uEp@T9bs&))7~xS3ey7p{sRDG3 zs2VQTJG0N48izJ-NRscR;05?bYbo2y?eF1RxxPGaXuX=&qBIpIUQCwJgpgPldgO5R z9(k$dqmr-;n7dzoqUp{jcygCa;8j&T??IDB=GFUyna0482j11Tj!~FMyIgc1tk^T^ zR8zOB+W>Zcu!R8%Brrgl2k4#_6d$dT37{h9vOac_+$KJp+>&4L?h>1sE#l z$ULnl67oG2bNZ6Do zf-0!ifFpJGox9VthjW3Nan>iUQ$Zm+ir*cJ*ByQ-DtA5pMjAU=GTn>V$mI)9B}Ae+6)v2QUshRf z5>@QKDvIej7L)PVCfR=^-<^xwafwWQp3o(oR~1K%w=-uIhlROlV)>809;uVBTfC2bg)K ztQqM*L>Udj%>mwEQ4dX>IW0dOYTlfv>!4P^FSUq>;o8H0EH)K}%W9$*7u^xTFX{lg zntvnYEBsiUS0ecAmeTfFTUafmf?C`EAk+Be%-lv@YX53eN>Z-k02~9QnIZl_NXGK< zLYOx^T@7XNOc0vud9cZH7LxCl2w5^adg^REH zS_^ny@Qa5?e`sYm_%tiKuZ#hk!;`|=> zUQST&11Af$)wkP_5cp*h^FR05J!-@}!;E>MG$|UyN_SLWouK4jbnO4Vt-EnS^xYf9 zWa_is*u$A?ZO@j6y*ESjhH$9jJrTvk&LL!r!@@dH8=$-Y$Qjc$@>>t+)= ztYQ-qvY1X2a{|s>6eibL|*3-;kL!Ic0+E?gz{(I)b9(!0Um{Ik}S;nN9C>C+s zX{yC9@b_tT|C651b$Zg&dzH_^vk`vm4w$N74{9||Hv!j$Oma{%8SwxJp#mSchZMK4T^fovlmWofS7kk4YK`*k9|(8DIUDvLD;HH(pq;kaB*hGals_o2vQYU)1b%X~TL>4(YeGJ)n0v|wkp<&A~{7mJ7`IgBGkw-qSs z19~1T7$22@n9A*{s^4&FKYv+ZUyX`j08K|<+-|B5$iuN;rE=`BXb=|u6T%-sXN5G) zi`{HSi~Uq`ya$Ov##Mf8lKT>$L|IySk5~b$nmjsBWu;xC3sarH^hv5Cvhv!ziC|RF zweKSSlF8D`(EqLlZQ#f}|2m{u9>@ceOO5SqAK|!XU?CmW=IAO{*MpShdGJ!f#;teY z%bcC55S93j_HqSZ8_V!YW&@TgwgthfpD8qXi64NB)0pf*3Mo* z-`#!&lMryo^&%pXh#h`i+m& zbFN9IMk3+v=eJ|W2EQ!?T+g>S&lJM$?`T~e3VlldF9A)uhXz*Rm{+BmkHFcaqi<(D ze1Kw#plCY02IQt^L2nSe%ivRVm)#rb{3+P+1A5Yd&5Ze)h96|q4|9$&x(>+(Ds#E0 z5|}8aDivu#1>(ZSQM%Na!cOO5j~nmxJcv)uUzq>xEzMdG7v>Y5d+Q7T%`|qJp^I~L zhyJ%9$!cu?%!HXD{(PtF1KRUO--7GJN*hAEvZ1nyOMLqCjN!XvG2~MGY^avxT<8&1 zWg)6f)_`Kf_}rv7C;H;amRHl2uc04Jdqw5)bz4-f!qgtT1Qk96c5L1S7Nc(3&dWN@ z1V$Qbd3M?@Y461RHsk^`f{zG5M3ht@q_Vl|QD)O~1{0&H^a^$#*{^Tkm)c|h$$B-z z#PfmGwYG5p%9j?C)M`ad0B{2=YpAQeAv2_are=nqOhy7gW#*ZhvMf|#lk;* zGjV)mf90{OiU+bGX4iASxNN~I&Dhg@B{siYo)VQHG!WLL?shtib!STyX$kSrXuBdh zPNu?2_C*#cQ(v$)s94#>Hz28B2AmzB5K+a$(a5a%$xu0^V^+%!M&K^%Glv1?RsjXi z8k6bb)*609+Z@-X1a0L6{?fF=QZ+qGLUBRqqmue-vDGw@3JE3%dIX#smIXTA>lE4{z|;VZ^(CiF+9CyFyM zOB|BZkb00=);(DdmcbS(yRxNE!GEa7{zdT8)$6Hc3!D5Mwb)Ekw11g>S+=!$A%1-G zh4bH+scfu8s_XU^OGO;b7u4#DYyzgMF8?3e-ZPx-H~jymOHoo))M~1zwu;(Ys>7(F zs6A4(N@`OplD1auqNrU})J)Z0No}gAy+>lz2#FCPqyNwMcO3sm_whT9`@wxb$df$C z!Dn38d7bC`{d$k;ChtADV8l08>sZx@-uUbFH;wIr*VE5oAit^iI_z(M6PKSH?E@P{ zU{ywo)=jhl-ZHu9dqy1=;jv@}_<5NssLzOSjjIH7bSV%C$phV#qshz-D2^>h7@Dh@ z|3Hi)zvnD&*8@)4p6<-Z+AnYkVg!|0Dth@lt9njB!zJZ7!jBuiL$9*Ep^u70rfW3knPkpOng5Ry{+U%VS%L3+Rs_}QLK9^!? zJMNez(!t$+vUB-5W!(wcLPpxqqTnFPMJi+z4x{KI+aKUcYIV=NzRE%f`B=TL0q+U@ z7I%XRI`qyy+=4!)o*lnI%Yj3%@gQs}eiSZDE)f8F?zW-d^hjmyVkQ}#~9>E$%UqmVZ+|7Sb+`UIyAJJCq;S-El7qg?Xr-iIyCMQ!}?r(m)UI6YDad| z>Vv9;*6u&G=O8aupUxyFE{km+l_ExXa<3C3<8g+U1DiX85g(iIJN3BOkKa?wI0{;O z>+4cJMDGPTUJO5_fli6XLkQor2Ipiy%7sBjW zD@x8#j73P!8pxX^J{}FTn393-MfC|q;tX`?7o}&KQE>nZRT0>-V6>!ix?-T#;H*A* zm9R4a&`p3UG=7K&IXkI#VmnEGn`D~4c&QP z)|sh#l0`i6hXnwQ+2D=;)qZdd8N#|0S%WXYxQMGw|3sa zY|evzM}1S;L=)D?12Pd4VLxETmaP`L6i%V`P z7@?L=Q`yp6YrVRHZ%_k6Ja#ZUvB_O|eYaiX@mkpNh5CS_l-7ZP&Zx4M_+-OY_po2Z z#%doOwz1S9T>7z~X*G+@!okP9rBGYSe?Ih=0CIbd`{*iPEudZqKaKs8cpCzGxfkRa z#D4eEno<7+ha(5(LsZHE=1jk@TUL@g{sTzj-fT@sFiXMLSpZ4vHbJ=UA$5(xVb|Ps zdFwBZ(CO9vL!x6)1{v{G%Ia$l+)!LRP2YRXJ&H0x|F~Lwgvtp5E)W0fgX_ODUiPy4yr3o z-|}FQ-@2Zp#>d?mIjAYzt=~CvI^(TCHv<)xO3TrZbAu9|AQR}yWL=_IdmbSpP|Uj7 zM7_p17FH(SWq9DOHE7qhd`-nqcmpc`$>qb-k9TJVkWkr887gY}{_UdJ#uX^1#)VB_ zB9eG06-5_oidc*9>dpx92(X&hnr~B=ecSd|^RV(hOtqiCgqvjXk72kiL22Y}mW)r} z>9PM*f0wgJ{)C~fp|=RZN!;Z2WY;9g?1;|E&50%sI0?&b_GK9qGjObdZZ*nWWW>Udj5pvf9$z-|ayY zvtjI{gsIK8<6lh*dYtFofpQCYnU&3ILeIHzWJkC;+|VPPqvgFO|M1%j?8;1GX4{n& z9$!rpHbjv3um&&3YPW2G;i6+klQ!@1r+*BOPcn164mEsoY@Fn`ONuufCNZwNv)VXw zd}!#|o=y;_?l;SgQsL?md;xc`)4R7ntpf>BS1VHNRM{Iny%mOiLB(QjV|gI-6><+L zhUiq6^4ax>C(#RgSu4W+O@QRR4ZA~%A+qiE4#WleZpJhARf}V;%-*jaoRa&t#_uM9 z#7-w>k^ZYb5rgNImNWMp;@bWs7d-w&QyVg*2y(Kf$&ioGMDr{sh$z29k& z1vN@8JFVByIC7{fSqoGe#g5b2)L$XbPe70VK>26WOfzrg&*m-7+kSE_bsLrMHu*T? zHK{*v4p6-+@a8lWTg=%7hM3ilm3tIbqes`QV?*A5ofTn^y4f3YQOnn~0*FvtUb7sw zZS|>juguSK`(wP^F#ah6?B%)%I)HH}c?2 zzf%tSN2AE%`~5dsKHh&Qd?#DLDYedt>_EWiPr&8I0V`k?3#bJqXUK>AOG+^snwRQ(o!;G=Z-e z-{tvDzhqiIG4{^2C?gDJHp4wZ`&qx7a5pULD1DG5)uP3Uu7&l@=*B_45S8Dn^bkC)rL-yvD3d1NW#rr|V(lmNX#_I*-E?~J4yd4EIH^czhjpxj{^HfrDOk#JS%$x6WlvXW=NI+5nhqLE6`vM9}Qt*J#e> z>9aej&KutLmy%XnMh>rCRb~8RI!;T|;3xkY9KsbxAjDlYI0$*~2uL5aexW% zd)hsuzyIkKHkyfj8MLOJ%B9!|=A@r>TRaQDE3u;n!S&*X<)IhdT%5-LF+A#YxhV{a zONSGaVpiLhh^&_i`~B*zMK|x*$;1@zwp#8iemBJ5n<@IfSfdz`D+n;>M7I^dym0k1 z4%?)o5NY;C7Ip`AlgFbKII1icJvOzBS^-Bzgk5w2mAqN>__ z6Vk@ZOF|8SW*kTj zfZ9J^-wAbj`cdm7wJCjHV_+(@ofWNKwsD;>?SAGfo{MIQOj_=rb#U7t27zVZQe;aU zDBez~im(`QkTu|Gh4vQUPTOewVZiA72ju$}T8Lyt{%11+`Xx)b7*ILlI%0g`=BPiL z>Al>JcJDs)eBtTq5E1y1fja#jOv(;e0^+FRw2v<)Gz96ujEzmgA9M-&|2?k z1ILyA?mbS?9s`+&&-cUZObCl4^9h7VVD(dACMRn$j=mjuf}I>_#vJ3_byu!Eai~Av zpb7XddM z;{K!bD>R#7|GZdmm0>s#;3zgtPI+uS#P6#38u;s|P@H&)#CFA#;|BtJ4+Ii^JX(|e z_Uu*f<-F8r9y&izITk~z74j&88+3l6_B;G8{jOr9eh#3)seo&jm5Z0voZ)ZyOu66g zpqsF27Jlv-e@e1=JH!c`VC6}@JWF~JwN#u~TUbl3SQ;kfF$P9jDyYwDCwE!1khU=((_x;2XpIFx};K}=|5??s8oo*a+_p%MhB+f<9=lquC zI`5MWEc-vjPSs+v2?Lm;jCWad<`KA!Uy>x!01qAY-5!Yt)M2nL|oTn<`; zS_nlSF}!e-jI4m05e;IQBIH_ye}0&+e4Fp;{V69#eTuW?hb~|C-F5_F7kT#%(tl^( z@X2I6-;ZX%)3+Z&qaj@WG!!+4^7N^GrCq^}#K>yBymPZa?&<%k68+!QqyMkIzh1X# z#qfXgxf1(nJG-y^OKt+$y;{7NYo0Qt&?gYgV=X3xe!P`>v#p!e9UM`}h|>2IS}iegN_}ddhwAOLm0&)SjM|9Bg~w%rO?k?lylUPxyQH+9{!HzN znnm(WWDLZ~lglmLEP&50-{ov%i8Iu@wslmmhBV^RT)o0xyoZ{Ied$me?GSIKwEVP` z=gZp}Ob&=Eu&f7=78pQc>#trNIaJQ-kabI=UmMLB^|6t&5dm7LYAdIu8_u|#Rz72n zH{AYjuen5k;)e()yfw{R){x5_$_h;PPs{Wo$Ty{A*fu_JejNp^3Ku9+C)}5 z3mBIOcw_qt$=Xk9tRb+H-bVD~N|GCi%6{_@+sKrk9WSg7LLh6cfzzgIWtb|0y4}jTjJL3yoe-8i#9^&#SLhp=|p?0=(8~uPS}k zsVC-J83t^IoCcTYv6@!2*~J|QCwMSev-$ zLH%UHFO;w&=f01j@L|QgG4bFZ!?{fc$=$oGen{Lg#pN%X5n%=5GK?RCmjl+>ZuOAK zNnbIuy$~??{9rD(iFIExY+q2Zt$x&fuA1W&Xnsbwk9PLKmzm1+!tR*&EvF2L@~S<* zoD;Q2+suNZ8@)6A|ft3}+V zCGJ?Nzc;yN;aLzfCf_CU{?TM^QuG zg>-DFRL9Y>0TGezfi-!EPUn|2lFh6BZ2-zw^Fy^M?T4epV!qDkZ>B@ZOq+AExxS;% zZf{PSY=XdW@F?UJW_qxF2qzZdH(REhD_%cZdtUADQV#pU(tbjQU^i@EyL<6e&F-{I z*MbNc`3+`n1rD#3Fse;FyLqLdh2Hz@zGTg}<=CUfjx{y^D+j0%sTk-Lsyh}E&&}tN z^m*eXEw$`kz0~D;QAroEFIsOdf&@Hp7%AY*si6btY9Y7q7hw7n=1Plx1ByTJbcbZbg=UgIj8_sa!lytH{>AK+|>!6e)pVBA>NaSlPhx+l-Hjtl?ICnERG4 z1#Q`8Xq`juZ7qy?#E#dJrCOGM6Q}$}%JC>|)SM%LK}Vb+doB&(b1J05cWO*WsSn(_ zt9=VxCr>TYIhy+zdAI>VyQ2V`p7$YY{@B;fCFq-Oi1(VF zxT?!Lw+WzG^kvg)u0t$E&gG`|@k;QdBg}RivK{n`uipgLY4xN@;dA=;_}HAKV(JgK z&6+?A*4d(aqHZ4wozsz6uc?3E=Y6Mm=gJ?S07}5QRv0OOmUJjJQ`xO=JahC2xDogy zs5xeA=OOY1ATQCr8t~h3`o=(5RUfWah>%tc+^u*Z@||_ra+1y|b#9YmNVK(6`jg$> zaNE00U|f(J!149%D4ikHdwE$lMho%Q;#bg_$BgEs&n;G`mDpo37q{%>2#{#e=xwzJA}?;q z!B%LvM+!R+`*Nb*elWa&W}}58WZjSiLuevGh;S4mH-z8f)~%5A6Bf&X`HLOlQhfz{ zPo0jsibFFAW>0jL75Cpfm^9hGOSTFOvNCE4)rU@nky6Of!1b6VA0r9rT|7UEJLXMH z_73N-9;Sl6Azf_AOON*Y1)>G8 zBJZhdIvpRFmp*uT+w!!d0O9XCewP4#Mjj@L;|wG0^&y5Th$84yJq3b)`|0m`c{zD+ zo-RcR%0hFIz?k9He;!g$ry<8?9y=9?Z9uy9+{p3ueu;LfthjPc+Ut^LA0$*D?j5Y7 zB#xA9>RM)4QK$Y`P6WjZ;|>Xj)U3w=eo8=*Wi>?()2Suq=3}GWRgMhDM*Zswi+YKT zX|rNSGCB-iUU!$X<0b)3X4^xICmz6|3K97Y$9AaFUjh|1|2U*AJ{*;Rj7YwSSPW9+ zVagC#{>;y)7CafZIa5?mH0kD1DXIu9g=J3U-%8sd?JW(+Z3ivv_*xDB1<-2to;50q zb`GMPs+?0}+Pb&nDGS;UUAv`M=GOfFF-Ymgyrg1kI)u#ql=k@rumTC}ve2)KylVUu zt|@vOnzQzgnmLx@{up=ukl$6(eV%F^B8(NSZ`2`Ma&)|7X8w6?axFLCix2;-oGiuZ@9JcOgCE$ky338a1h>D0~;^3s)x5A(bcCwco~dd-9hRb!_}{?-5m!veVpVB=9! zsP4QU+OZXWcs-j@|9f4{d?CR?x@D>%O~1ar!e(3+2v@M9ihrK z?jnX4`7ldA@-Ec?8P|bQZC3>WN4y_@wXb`zD^{p_G=SjL)RJ=50Z(TnvmD3b7Ng+y z6bSY4c#9}*7PL+CeVDE7eLAW3EsH~vfWP*A0q_H8q2qB%nZ6b}1rKx?@`=htwnoqV zZ+=}~!({Ai<29HqpK*N(@K_8U6Nqas-lF-Q1|G9`?;<~@1=Z*yd1gg zNmCXN_ny{luj(I#4zhX8Ot1}6R4b%Gp3beh-6XM6S=<+qUaAcI`>Cu;vzDn}-(gd; zpWBD|KK$@E^J{;4Ja1E)PkGNoI3cuU@5RUl-2IXZg=irS_EPA^r5lc{kE340UssmmG0+JoNv zE>~;KUs_(4sqdfN*|!xAMB^mBz|J{A@3}o9zD|E#TF+hHvi_0FsNlR+@9fq%YQR|W zAVA%L#6?53C{tAWaElk<+Jw4%;%O{2QLf}pEfUoBS|~}9b3JlzE+r!4d^h#o=as8> z{V{Gsv!l9XBB8jwi7B#$vzW}I|7XWJNbbsYy;w&EMz+rM7Cm1tExla^_USFVn@xy_ z63NwMrMrc-6*K$lp&p_rq-I9PoYI#?2F4ml$>0z}=Vv*c<={?bTJ3i!AwDF@aVYu0daYBSKeLIa0Y)BBriWJ>*PF^}RZOkk9>8>-b%LslXHE7aH*B+q^`80q z;F4{T9E7&Y>H2;--(r&#YS{tMhG(MK1tOQt+Y>nuzafGv)`{oIKSXN?EkF8Jin6Da zYc6Q)4(%5lDWAhA-GO@-_si_a+%FCOI8QAz*CWc8r=OpgjQMfv7srjB_hBD2w>8&V zS~{ePV~TrMD>sf~S>rnGOMR836diVArQS_~35HS$fJz3*Y1#fmKL?=MPTh;HwB!u; zQH4D7o^Ct*FHh+wQp}jl`n53xX0a{StSGHT$=t-QC?%aZzUR0Y?6kGM8-Y+91c^_dDrXptrk08Pdxdly`kD(+73_%ViwH0MEknd2;@KD;hGU?%A>1hEjm9_ zY2gXX!k-6%hw#2YLqNZ(iJ$@uq|NP@Xxx9LPGmRg3J-4)2YdGdnHts1*FjxFv(}wR zZuGG0mmbBagCM0K?)#IM5(DV(S~NJZas8a}5peXzjXYU1D8bNB={F$|u2zD}r70?B z={uMK5^)i9ZJImS?vKYW9f=kG?VSQ8$?(@hYTnRNG6tgZ+zyZ+nA&Hj@R*m2 z5z-Q9j5~t`)XoA;HNL5~YhXkiwAIK<{Ln#q9i%ARlAZ3`P#dDXtxb6m7)FvL&li!K zJ9hT&H-s7ekf5|`jnT-9V@FI?sEt>nx5})-U0Oyc6x1H%a{F@0aOJTeV8>wZIWVPM zpiedN;7bTH9bLiJ73c!+$&IRFY1&TKYs{9g_gHWoNgi+gb{?9nQryK0pmo8~!BD(C zA>j8U8ertU>`ACm^&WhCi{%2I@8GzJ_|bO=1TC5o>*|NT2cJb^r3sD@LYj7HkvcsU z=IJecD_h@sT1=rHt5URj- z?+9@-OaSvh+!o{Mx5=DD*={>Q0%qG9i|78wU^#pcZ?H3IKvXDE-y8B5oO!sJ(secy zeE|Q*Q0o7809wlDndrYen?e#I48_ndllSRdwMU(TV)_%W)b2IO@paDlw=6sx)k@n> z0%bewUuV1KAD@6rtaqhu(V~${^H6TM5rEeL;)4Rot&|6FaUgUx%VON$Q-G}Z6RlEH z`)4Nt0LTk=dUvRqpT+t%%c$VfozI;|Spl1`DfJGm1hSO5NOn+-hmS4^6L&ez{E(q)vmV{1HU)?giOVz)a2Ajl4(=AYLJZaf1a|nk0ZGuo`R1 zSuy*-@IF5qfA955lRwK|0$d0SCUs2?_yn0pl z-}sGC2;-QMmfK^N|JsZHUwyPGH8oGqcw3k13=FPq4FJr<|Az?G3>rg~h2em-9Dt8B zd}pFQ>C?)Czacc3aZ0u9z?+ zp;3e1W@=_T(X1Ns@_Q0}_Y>2+#&0EHpEU<;>X!>h)=k9F!l9V$gGQlAxw*FTnINRv zW)|9~bso^-j5!9bnn_7^s%lwl44ur8x7VdeT-=iHCQ%uOUH=%mcV~x4E;SLa{2*uO zf9&|;WzSU=+Dop-ok9k3^{BmOQmzaIR@riJT~7jH*dCZEOdBj4V&dSJ2=uE!0s=W-%fp!_GX+)UGb?F&m+6?=Yh^lggI)_Rg9wDHy=+@yWD zZ430rXNI0HQ^J_$B%a@}g^D(Rd-40ynY*vihjeYxt0G0?*)w}TkkN-sT~co#gr^Yl z&4_`C=w(tZIRq-SO;tAaNwIfAQX&|srv@tKpEmiR+ko2V%%49V6+5{dz;4j< zD&}m9LqOC)Mo`-sc*c_pap@=Ky%1jHE6+G+jT}NdLE{#X#F5r;&3d3zm#uDeEXe5N zeT^?I3$ywbrbb2_oS#pxLOTjWl#v%EiYgSZXqU$C(5xqV^5TX{ewjzi?$7S1i;)Ux zWmHcJ46X}6k7sC}H>%?+YPOV8oGMcouN^-vw*T3umVIF|Ytb$3(L?y3#r=J4@v>|qSpB)1& zxdrS1^FOtLXVKbYz0zL5aQAff(z2j_(EmI#r`s~sW5lBT4#%bPea>t@f%TMtL-HO# zKRHwNjaw?1U8lh=Z-2RtL{)o1IDt{xfJ$o~KBEK4BA@Iup zx2o{jChG?-*ZopS`*+@CueRQOl>OF$kdmsfb z5Zp1to``!d9J6aay8R9s=ym{}TkH}N?L;`MwPgovWKw$o$}Ia9xH_tP@lv3$^(-wP z+dM6i`|zwogI&q(5S5EaJ{qei?y=JP_Ojok@6!IOgdz^RqbKWJqi)~8A(P}%^?Yjv zYHO8g<|814m_Fe)CL^MH4sm3461E=XBzSSWHbK3x9zq!}B=q3yFcfvF!6;lG3mdAI zvDFmC*OZ|r4vqFMy=>A6LkTAoWEQTSo6ngIEipCaN_yAgKK7!)`xBop~d)IM)*GH#0R zfM-ZOZHvI%)+GxX7wm_)JAsE=mxfl~pWLpX;uUbb4kDT%xBf9ChI|u=Uj~LrmWfv6 z$Na_Z-y|l*p?U~FbZ_E$3DK?+0Ninnh$1otSmdIs)rTVeUBJ#UyQ`hV9qsly4Zm*Y zwx!AHT*6{)G4Jq#iglS?acnA4q`;Ko&ND)}K!D}@Z4Aup_X zrK%+^PR*<1gUIP@0mdEJPoM=NMZOu(xjP#}d_hE12%;jk=R#xKXYMI9>3?F1>xN9^ zv@R050wc!TYDbEiQtQ56b6npA-@E-?Ss(|pSO|=NZqJ{f(UHoLf$JvI*h9}U8i!!( z7puNKYAlP_3T>EtP+nouo%=9WFtcXVg&{Emd2(oEKL)pdw^~tQ{TY0_o;*?7QxvE$ zscO1npF;b`K(7rUuDn|ff0f8HZ3RDU-FU5KTO8&*A^Eid?ai+f@G<`NA>GuADj&b> zaCzi90P)nYIhl}bT-K{FvQkQ|z)vk*4_!Z*%m&b&un57oz#4&cilRa=b zlhRKTj=~;w8cxMb>~>_XNA92nx2&wD0w?daSa3eoYke!JF(#eCtb9w15^mmxK27ZD zL;&mK9f66{4{ty$1eC8_)gk_ z%f$1&NiFFd7X)AeiWVZeP&vX#ztNdJkLrlX4nyAQ^Lcs`oCEb^e(Uh}Hvbqd5R`kp zY1>Dr??|`z2toP?=6hPYH%Xnl=Mj-DJ2^0Ta2hBfg-zmzSE7d&#asm7pWr9vw6VT2NkTh@KR<@`O;6?YERm^;OE7Uk6D+CBU@a6D^*DQ z+5$OKR~NjK|GDj4b-@tQ1Mh-#QZQOhzK$?I%OcGErdM#Th>5J zGXt8`aT=0{Hq7}$L)JyBf&cpZC!&p-su8w!{6WJDBEma^N=JKB6!RMTXddAyXganN zT6HH^kZ>*n=S=L0F0f1<)bop{N{8~V*y#EpCoY7=XGlh6o4*4n(wL=hbYWWSK^YiS z9B}|XLzdEOw$+l59Dg*>S#Phv%hnN(RY(cHa;4ih<~UY2QsG&2hJ&*Zqu}NB60W#{ z+ZAJJiTeu0k4$V(#*l5IDD7uZ+<-`N(3xYO?_%uQh++Zn%)bXiXDV|0;|(k&u-y-X zW_Ay_P+w;@PBc=yW{f+6g20xd`m@@lr>(e+ko5YLr)M{?$J&U6OTp{QOnO9TT?nt!Zy8TYSBPrv1wYEIy&)VekjOa zr02zECUP;3TBa6CP#rgm1aa5~5j(s?WiLMT{FrbdROyR~YPgf5J-O`XX7vMKn3{xx z*XfkJ216qYAFZkXr~LO) z(yES)s+RKElVDD09)!0B6ayxh?M8D3F1G`OI=B=zp3_jlD)`}QW?(@d%f9aZ+!Nm( z`#^uH6x6JZtqhh z;ipGx`w$}5WcfS3o=!zCGlOkx++?h?Uo2d0P}&S!Ykh*b`hDN@`tdp$!Nle!Q^sVV zmkN$7E2>K#aFH{FdAs4yeAfl1-?=2zQ4rSaf9)M8xL7{EC7#l|>^{w~jE0S3V33(p zTcj%5XSfs5w*!3^Jp$+P4*X%)>mK&C9Pz;0=a*WQT2y+EZ}v)x9kS%X<%z2K*>lMg zD+v71=k3sL*kN`xFCW3UgkLu=W9flEa@O7bsyuq~HF(sevn z5+-EtM8DE-jPpl+E_*s{W24x|*;ikA)=TP(Hsyz)9!Vh{wVs zHj@s%v~*!s)oDI?wI1cUzHTJnkV;y;XNRU>=c^D<1}x;&YXyk&n=hq%S{iOWS>0wQ z`YZ02-Gf9t&TAe89+rp3xwh}QJW`q4Uo~plzwUWeDy>hnlv+@U*j+c70j%v~!cY~7 z_)$@&gR)@5D17CeLx}*ZXcNCkBM*M(?ftjZl3XQ%Z5*1po_IC6f-P%KqTuIBwMYaj zF}IaHR7N}pcfEDub%+XQa-2uYqz`y|{^~!5PdOaT+o2W5d=M;%Wj4RjQFBrLSC6NB zcY9WbdG?ukeIU!(Filrj;?QbB6||XRFr0O~=`T^Vc>+f^v@Dbc1C;{b^D+5`esSyL z+2*$vuhG}X+-Ei52`z`JP3A^RhF7%9G=tc-Nu+v-tL`h1>(%U^^L9fX7xT%g ziXsgo3T1VsTRrj4>gSL3N375`=%v` z_IZ}V{+`wROnyB{5mnpr5BTJmjKE)BHTL`{$|C2w|EvjNNNw}W;XcIpUq^XID~#s- zB<@g8{Al#r1szQxIXOSdi9dIH^L<|Ot;f)CQv9Ay} z0}V!`mnAq2G=Lz{hl(vp5$kx4l@G|(FW%6!yBjAv$-+q<@ZQ-X?|pEmIiN{yQwL6t zpV5-E2)f!d`R((Rr-aHy68|djQ=GZ|wANc)Fx|8sa!AE+PM#4kw zk!?oE7on<4k$GRKj^tO4M5Z>#`$Q5&{8NEy4R4_`MXmMqJA;e4RP+A^vNW{ztyl@L-#eL(R5qyy z4PN-Ww|kD>3+1G`7gpc^nzC*4n+?*mG0*eRsw7K<3|STD8L^p1_^@HlO&SpUm`+6O zO@AUuDlu(AQFeD|nSMj3+MC>0Wagk2pYiF``Sqlyt# z+v_!WF{AGIEHjN~0e^SvZk=xz`I)WDE6l5w|7r~*)J|?oOt=;D66F$_wzU@8Wq11L zVEkv=&Uz0JExkDVVwYq^E?)oRUw}HItgY(+_2>)q*aMzEe}gB=2h#8-HTEKKLJ}&UC4a|x@S0qLmqTt z-sShm`{e1~|2#k|Zy=}6Q^j`y>-ZvG_X}b+uiB#oKxA0~<)*xzr+C}Ue7mrG`NsZ( zs|Jw3#Q3~L-p4dOnGWM_Y#Ibqej}CI3{VWfOz(4{(SdF#i&iyi;#`BMb-0;vdBYhl zHNG5!O|m(i8A&lEC$=rz8UqyfvFVzKYk{JtTzN*4c{;g;-><~gOGJQeyl2pV&G(ro zwZ{wB!@rGrAqne$m295CMofjrd@mS{jRI=Vj~GCB%!9%4w1LUD{BpT!33*}b0H9ZX zxm65{iiVrt;bD4KHzDONl0j{J)ZSk8^OxGsKUJp`ctz8B+xGQMtTFp~`>yc8oG&EWj&F*i#YzQo-8 z|K;;-=6QKpQe)|3eT>3O#+P6Ihb@`=Tqwh^5Ds);&Yq)X7mfQZFDHVgE4sRxf`VIr z6g~N~L_c6(L0;Lp8zMk^?pC3sC$|gCo@eMr4I)lhU!mcHyrO+Gy>;C~=b0kN+4b3QW3Iw~L+?Co6ZTi`3Mc{iNv)ZFhh(;VQP znN%lbcHG(udtfu-I3igT>F5|JkpF-xHu7UF!`zDz`0Zw>13qOOEXEZYrR~$-Os)nn z7M@g&_2s+-h;!cTi1jy=l_$!Ff0@^OiSZ6xY z+TRb#dKlYHyezE$+SbTcKQHYyCM!Fiss5VzAdyMJMlKbVf6$^jWXQ!`2eC!EBIEKd zB4Ow86)n~{)hyeyk;ihOk|NcSNQY~`TM3%-{fbf8hMJm)g2)A~x5lb|;M?ze?rG!< zgt&Afr>%_$<{gX7`a?__}WydqEve>R9G48gQDlb_*U zDg55jx-VzMP?&HgaOJt<%85CaS}NnFJ~X~uR89ci^xD?+4%!RAjYH^8VK4NB3GLhI z#?1cgsMD7C$H0iXlStYm&ZXS1o+5j|_=6OGNmN|rWe@S}lV1y-sH+nDm}?WWyANz8 zIjw_kR9{WO@tSn*!3D41-k)cFhlXyA6h;)KHGLZN%v_&BRwMCjFd|1TY0=S~&=Wg< z8?HE0F~=b!s0cDjNF4^2r5_Z;^x}C3^dFoa>ixon@2+w|4iviR2*6NF92!s)4i`&? zsE~)S-L2n%$0m&@^Oo6|a5~%w$(l<{+EMCh4Q&JFyq3V2?cI=micV8*``WVmPP{M1 zb81KRLO^_@_SMLyn>ev|6?`>=YOk*Kl=$R>1?0>~s?DJmOwH|rb8cdj~YWh8vJPCCvnTU347vnzzxz=QdYTrkdca_e12}r|g?Y zSn*DxgT92(3p3N>DxiV;%=eb_e5xt_p%1UfjGjla?CmnoW9ws+)v7#2&62zNvk(=4 zyZkJ1qHO1`qNd3WC)4Nr{!a?0N<^Dk;dw{sRK1>LRjUmv7ov@hix;LVm+7#eGu~(B zi|d53RL*L&B$)hysm?VM9Omq9=_x5y&_Yq_yTPba?u*Y zBD-;pVspS8?>P(6_rew^{B_yu6OmvG8+7es@uV3Fx_EyUn|M*I9U9FCj+L92>9C4= zG$z!NZrI3=Z8(pO;rM$`cn0I#A{#`gCoPbw(m;v-S4D=iaz}I*TYp^(FFqeN0W+5Q|$qgu_4U#-B>+ja6=450UrVV`nFoB0z(u;{PtYv?9#r zY$W2#Z0vOQ;CU^5$AwI}p}rGnGt*+reRt8ZliPv*T+TZg_}uHX!WL7C41Lt9u7rTZ zagBChvyRKwC&i074&1l~~*bx&(hrj98CWGrBYZaK}lqqrRDHV{8dZ2FYrjJ zzaeSrsLR)sy~@ z+0-Qr>g2~)N_e*UzX9jYw_^B0tbzP_s6wF=WIFZUrTJcp$?0#WTNQ?kIi~y0MY*%e ztPhMy20BBw&2xUGj5W;py@s(`FTh4`_wc>qZu>Q$gwOWdFx{<%VK`jr`tdCa3NM*; zuDe$*`S%U#b~(@3UW3XS>FfesxViW~Qoj1zv#_Vq6lu(tjvfbY>Xk zI@OL=P$`dj4`e)I_049K9qPy74+KtXW(p^M2c7X`%HM>ZPGEZtu3n^avUVbCj$+g- zanLxv)!)Np>HbY_<2lhE+8118l<#P#eL8bS^AHtBKTn^g$+CCI1DUGL&(Ndp+c=Ar zWV!Pq(@l@AW*n5I(b=reSP$IS|2_8sx=Mu|vREVpii5LE`^WhbXIfQ6n}yJ0s22CS zE5a0s?C0AI)Vb`v;LJ~!8w+eUeK(Fjt>z$v4HJnq{kF6xVP*rER)+TQz}&Hj)7)~kb7QB}32t<_f1QhTJTsJhT(tfZ)$|Z3>nvbe(w9Y|AX)M2Zx_>oFX~T_iH?#kLST0 zYUSW@A^CH#XPv?YD6^oA|4AwBy@~DU5!2 zLb8`4VCf|_fprDtmRdxqw5!sLdW+JJ7;#0%ROK;>EW)>zd0OsUBFgXVrX7hhJTBX) z4B^12%yy)@iCnrrYW}aD>vq%lMel`c65gMion`6hqF?1Y#ln8_?|TcrXH;4$^d;oK zSiPXpCd4C9%6gy|e&F{d0muFGRL_lD|HX!K>_y2|tk~pKjWVCZ=(})bXgsJd>LJ}- zTSzTWHf3dyslAYl)(aPp4iFuCkk?!vC$v9ZokXerlXXFiM)m!!w-laq;xXUP4~J(F zN&~?W-$wR-4?g}w*`vy4-5t}j5_r@#QothOcW}Fk*dLn}eM{T#1T1yBTqE4*%>0@_ zSg=hv@GGo=vh^Vdfj7o%E7y$66}Kg{g!uehVd=rD&NmmUh&(1^hBdA+&FIH*R2%n|cv`zi~dn;!>uhH%dW|AMVztM>0st zVH(QTUWqto80IN9X}{iMBMT!5s!J3w$2RB!Lfp!H0f2erxJ<*38{@3!2aa&#Rp?WD zfDQn1Wb!Zc-#do207sz~VlpEltl7Zxy(bZifAysXb*+($q6P|Xu5try-xj{CsxEBO zcI;<9upo0W0brOPU`8=h+RI^RD(CjGWHb5vN{fx2{0d{px73sN>F&QQtVJK?w3!pV zEZO2$H@H1VaNy;CzjGG%>zIGl6K+BVfZP(6H#Ey%C;Ltk)jG%qE5Ifn$QRXXwpJjG zV?P~}0TLa|M17dCKG;E59)%mRjKK%mg_PWtnyXNA zXjj{L9Iq^d8^AiHz~2F7r7^lokP~1A-m7aFsQ~=Gc|X}+vZ`xsee%#^vD-!psF;yn zAgiEi!nnlwCA$ASM1pVY(nW*?=n6?DP1s)0V145F(A*k7k1Y4TSK;t=Qa?>q{&85g^rWm%vUBmr!}h{_qgr|+ zI%z!xy7EZ6tDqDN=uaFMB9#iMoQ}uuYcuBe^+3lc@|{ZSzld8QPZFW8Fn1Icd8Dux zvgNZ@E=17)c1VaDefAi*h+~HimvOBd+cGH3p571WQ||7s);8($K8c8rQ&+k7YxiW!iV(i(jAsM&2cAPh2N1R{9x>rl+v*9a!IJ+Ngf=cR=iAP8Bd+@cKocPM3l0U| z%LDTFcJIBZ31HX-MElqyqp_nd*P$BtG(Sw$(N%j}3h&^ZXGKNoR@K)`Z$1FS!HyUd zLV#A#%Ko=in%KSLH?39cUX^z~^>gKc)_h#yt*Bigw`H8#*LzP5>2BBet6?w;pTCF* z{i9X*oEC&R3Vcbu+P3ckJJke!1U8d}G>n(n#be9{X1QG{5E z0-jXej+{1!gGjHPNHSB&eAZiP-#K=Jf-<(-Y&SlYlypz!p#(xrGpzg3{Z?Z#k78Ho?G7s8Pf~A&vunLLMo-G{o(er~f5u+dag+6~P)o>i5rU`sJ zEAZ3T{_1k2w}Cj8%|-IThrx{;i!HEeB3aw_kwKv&nQN96KkY5T8aMAe&or`7WyH9Y zdfJM7ozcESNYL+W4jwc&y0fL+5=RB^5=y||VE;1|7ksCWAes1<20u#*r5AoeI`-bX zI;_YuHE8f^F98DRk=o7FZn&V&!9zC!TR!S7L@ivTYWmnN-Q(z*7Ca7mUWk<3nhTcpS2&v-;4R!K z1&GPKxz1_XH^*(ABbgHG|D5i%uQwDevkqv@Z`8uYNvTOo0vc~7U@DnCwRMRsN=yT% zFibw5L~aagLww8`D|8zYN@uGl8g$OF>D4=}G>_~o)%j`9G`{)wI+%Yl0?~#0kx3Q8 zMRch>N?hJHuZxZSq@kvlT;J}^SV}p@6v5>el`+>`e*Q4)e=jm{;nlONF*9U7hK9ww(UXGR8^KX`vSLT4IU;vCRPDlOifx!dsTt@o zxRn-*kkihSn0A@JPP+JGTt%k5%TJ@k45u(?AT8~ya3*+kg6>96rEV;5L`XGrE(-{r zP3t{!$c+6Y)=MeoCR6BZZT%+*SVo!I*O`x3nl5UR zUbiD20vHQ%b0Rjfj4)|V>|d?pO1LpSZ^LgF#2&(y!x<~Ejw`jiZ!xuF9gF{sRHE6k zp<)&bhSAv*y#-voeXR$%)ACYanb$mDWFCQnzB>)cUKsoCCP%+CdZejGd`sV5p`mPo zc>Q0WAb(H#@cs@GbaPcHHeU_W;Abcsmu+dzwh7a6I0OYzNv3D`sPaQhssxscr|t5= z`%Qe{Q9s-9Ir3mRoTHgs(x@UAsGr0zc58H_{&KO^6IMY}!l3ZEq!6zsDkf^;kMqzI)~&Nuhe`P?(0DBE8aYifj(*WVa&;&5mYQik-k{L)&D#)VOQxk~4lB3b zJWWKma5Z2j1;lo?wT*JlbO76G%U?Nj13V_u%ToG#v1ll3x1?h9;AxwHJ`-pHXN+_m zCGi6NOtXmS)LZ^VV7pi~iiDX3O-a$2zXE={;rWZznO%aC5lfSwRX)kr3Eq0`c10JJrTOSo zSYK(?Gl~i*9DexRTMjNUiHqJ<%M|Vo3e?lpUJn%8QHGI%G-#Qwx5-lh(BPHSM2+_% zO%ZQmQXloKGF<)m2;k0Tf{9)?dfL1F+XzDQ`ZkkQRL^!1&bn6^XxbN?QLh0F|plD=_m7=>TYcOb8M9(~(2; zr)&69bHL|V)j$$yV0QCRSF`jb#dT6>tU&0~VbfnK0Bh-aY*Ff2wGQ5k8&HJ~7MkhF zrEawRax7kTaO-?~YTPJwu1ULC?(dAPR;Sn`zfBEHh0R{J^F^x-VW|!5H(x$whA+Uc zb;(OYpZ5%O9S8tH$9CBQwb{E%*;|t*Plp`e+cv0{3YktgkQ{QjZ|*cRjoeO!P2>~z zA~N5kJ0@f(!({AGCv~Lxn)O71o69^&dj5tyaGX41-4l@4V=^KOf->&5Oy6~CwCZlH zh81pgtn>K^e`((hifSo!@|y=GDwfOFh9(+5y+Tm@>(Wa`CgbbW9Xc!ahWWKkNWLB%8M*+)%)Y;S1MH7%2g#{qR(#TuLzP2KDP)Vi~HgCJ_2r^B_dy+bgaa~XUMyx4%| zpsEw)HHf0vAkoPchv7c?Z?(_RqXKO*?nWpUAIQk!hTJDJ5As<0U#WtRG+;Q3wA%XhN)MPWn0U;pZm7+RK9$Gn_F2P!pZy!NNJ zoWbK=KalWScUVuAd$XQe*@DBUZE$%z+#S%HziEVo6KZmfqc=I{8YDMXfmFr`PH}mn z0OJqxHM;*$T^t7c*zcDz&!|r{p$$WX4pWyYTx;VNMtW1ja0_p3F!70I{oc_Sn z`MCN?-Oh+M&$Zt+IzqoLTzggj*I!lB0V=4N)T73Q9bUnvuS3J?v)7++?cRR&gi$>N z8k*q}C>VCdE3x)@5&mpqy}7qe>lY;H*4y2=ryZ4lPtvM>R^r`0NFylVS@oBArntwN zr$*PVq zB{5=I-6GcJuA0M;tk|+~yf54BTc|~!6U^6+Wswi%M=rf{NVZeKmAnU5vWCf{i3@{$ z`+HMp`sIOz>*d~=b6NuC%PU5~$AR|se1*{!C#vD+gh?M*f*BTmV8Zg^1QeS&^JvK- zEWd*LTB@7*>9RWzq8{?5Gy0ku%ha~cgGboNn#{ zNfLJ}3wtJQ)h8qlDexqZ$EU{J5yf7QqUdhR`ojGrp0MY|zwb-?zSxxTo?iG&x%oPE z>E63{To-mzW+ry13p5P)UGLx&&Y|%8jAbnA^VEQ4KQ5*Oux_M1C_rY+M}R3GIQ@eW zvl)Xs>Lefc1P)UoqCRBCa%A;12Un-Uh1dIg8NV#Px5xjt4#ZI-z}Aj^iAOpXTh?q! zlIoZPgzk8QcdnhMbCUZ7bFRCj=`h3UunnoojspbJXVwn3`gY7jv-}{`(e%X^ez(=l z8S6Sk@TeMFjP$euZ)Mj@;|7WuF?6{AL*+185shBKFfQnn10p&;v8XrfYiS+wBUwuk z)M|bIxxX*>FCvPad28z`ziR|QAN$?JKKg8v!fNpNHwTid?s9%hndV_ z(QFl6YL;~)6shIP&*mdE60>)&_)22qNggg^Z+o^3B^MeM8VGJb25a7+j)7WUb$Q&x zsQ_{zKy*Yj8jJ@0z(h8SFM&QHIEl!ZW@n!z8nmbNPDIzu6Zvb-=7O0_0iw(oh(G+? zw(=7%$HdsJ!ZS-!|6>@(BE8f)*w=lv|9*IUF5`5j4Ou4@iFEppfh;B$N=jPX`{YXX zT!wM^BPQPrQ&oKcL3786bh6I7)TNXAOx(TAUKYRX8HIUIWtM;;A|LR@1_lHd^~ewa zmNyK*@6bo1BwO8v=E`QW)%z0Wuh+Vg6jHa8*BzXGVm&`ZKGglp*Xutpi<+iz;Q-|E zP`{p%^|%`@7i>`UjX&z{-Txnv^nc^`eYxPKk{3`P*{u8v(lV^-r!G97?Tsnr|1spe z*}rSw{iO6jZt1|c%=@3_D0^2>OI)qBuT}p^FdNzE`eLJ*Ps%csXLB#XmGAxI}l#%CEyy4*8jIlaW?pPK<@?8*c@vAfugQ# zxBY@DP+HAY+42evCR>pD2+?6T6}{ZqKM;$~0LK8HaQ}S0U-z?_095H00C#Wjr($|q zK%+fvs3ya>2<4gM!YUuYh*gaeWI8;X945|tK9I1#OqF`SanSdjJMz5`m=A7{KkMvg z__)A|<0QnOxk4FK@cyhe^Or3&NJg8U&0QhPN(c>27&9qaa8im0f$J3eOId$(JJORh ziCgG9H9B3F$~$5t?pX(5oPKN`{M&OWVngUH=>6nBxHs$TmP3JlV8y~-E%&c)_J%fC zi@hda4Pb=ypgr32?;yEIqBdYf>Yi+ed``WY_FDeWYQo#553Osd9I@m<1mg-M+r&80 zS^oK&u=XE*;SUvyTI%?m8-NLtoC`SQXAH(A>=OBml9iK{&D6KVd-@-GbQ!u#qcu{N z3tyDf;SUo4AJOFz_^Ty82#>#W`TDSrtA3)Et~Li~NX%MQ2a_<t>X z#_o|FX-Lx_0k$Dqs-SbReW5NTNrPg$s6ZlkhH_k2O;)CWai8dX z!~9B9n*+XjH?9}nir0FssPaJ*ZVS+rGYv;n+=5G7And@+7(_D>vy5N(o!Xc$L^lht zATsJ@c}De;{JQ$zuZ(9Qc!z4fc(<@T?+?og>LV*>95=^6WOK&P;6WJ`m4<@XNYs zwBybJ*2_<_fCg&LU!IUStKuhL^?XpA2BegvNVN+o9Aj7jHHz@CuWGzwJvLrv9X4I` z(~IfMruEPNy52=}ARZ6-$6C1c7B55EIZ6-;{PXOfk+z{UlW@DtYgY z505%ph zHJE6Y5&mJ_k*I-|9$8F&z|^CqH2H%*wg9-{BEhwVQ-{4%1nQ&3ukx#-&0;xXQ;(bO zwypSc%P1VdX&3#Ir&$U%u3HFaQ_B%y$%~~$z0*$Fy_H0TJ}s_n0(8}6tTtLNQ1yW+ z{?69RS((ARzwtNhVk6TJyS+J{VpI3UW$w3X_wEx;$|%a*hvP=!vId@1BWF>ksp@^Y z?4h>@wGb84bw5e}$}hoTpy5CRvGS-0a9thBmh|FxxAz>(tuCcxt}RJBe?H(t&n};k z9onPe?{l@f;Y>!^@Jzmfhr3 z{q$U=%c3-Lz~Xj+g5!tS&$z{M(Dl}Ph+hZ}qF|**+8O%Os@#TA16D_HpJ^x(-Vq?p zuo}pJb#i^yF{GF`s$6KV9`Z0O5YfLW3 zt_B2u*#9P|r9c>I<}x59&bhEAJ^fLNEcG1NE7vQ7o)t#dZpyOQ9Iw1=Oro3rrqmyv z|8ZO*Z>|))So-s)>txc$X zWbUMo=!5wdsW#+A_&btq_o$OK@6gfUH68vJ_BGX292OShzbb{jq<#61jxanK_RWy{ z$n+p&5O~E3-Oe`6j9;kI?vjx2L9@Y4ik+1zlI~;)NAxyE-;R;Fy_DneQ2i{5qGKy~ zKcX%VXS-IsM#?jLT|t0tZT$U@VJ8Ckpl%XT5jFSJMBpxyle)y#C|(_J@l0fu>}uq> zTMZj;H-}ayf8mHmpy}6b3p@y+iddp`k17y}7ZyLf7}D{l6Xqc#=8c+*&T>?t)=na( zK|~V_u%saxVmQqH(piY%IZF#l^N(AinDJwhA`C1)zdVa$Vm=sZ*rk=u<7|OMs;u{9 zrOxFDf_(AR-`4ZtswC&sG_d`CfiP1S{$qp~27`budX7O~AZB<^Z5lz&5o@1r+;ust z#sfF%XJCjs_yJu5>BI<h=x#mY z=nE`y;e%a0`{snFwMyhr&zEzv=#|wS9{$M*pyt7mZ*O!$fGVXM)w96w|66e{KNVKz zENvAXByf{^E(P9^e>46=h5F(phAX5EF{E3NcCIS-Sk;<&^`eCFJm0p051*(*b>k{9 z5SNzsaH)+Qs%nh$F-myVzW;NswGkAFH5coI#90dy>(aa@1^G~~pqg1dubrPh@wog` zprws7Wtru=9*1ED$3ZE7-iGhmj;8OcvO?zc-}1^5lJh;x%IW1iH|N)dgj4ruOMgH; zl|Fh;2Lj}3*!+LQ$`ARfna&+ze5dA)eMV+|3Db49aRDXD?`&g;VQ>C*=9lO zee`|7g)oEay6>~UC+v+XYw1IE_4WUA(zPsjxb0t7ZB5CnaNf(?N_^7W)Tp3r)V|8Q zDH~onx?1lfYL;Vi?*Zegk6Ll|_~4e`t1TA6uJm`YPndRi(gf+rnoUuLt{Arf(KPQg z_7t5Qb8Nvd04Y1sBrRY?G)DY6Gi$w*Iw)Nram?Jc(7h9`ne;M=}C!KwG8Wf#oXjgB)P@C+|PnynioRV>Kunv#~ z{Wgmuv}`H&ZU^!CWiQ*I;%LbGifM*l&jbqFVEpo(;Lp)pA_v zDU48SCC+6jIUYZ|In8kM+G+4=aD()7tpKqY66D^Ti%H;mj;GIiPfsK=;CAZz?y`n# z_gF-8;v*5%*rZM&^}-nS9_h6;(6E;0kL*#!AEch;v+aKoi6v?wS##@}gY#^C^cQf3TgSj;i_&p`6q=A|nm5p$r z#WF1 z%HuRDMRcL2OBv~NW6p=|hMR38pJn`OGE(v=uaIoW%w_y&&wkfsAg9z~^P!DlY0p!( z7Sr;8V*kvOm%HKPaZtDGyFX)f#zq8pbf>XVd7~%Vmu8~F7VmhKz9D!kw;=2@U!|nV z60+yB$Gw0ozAH1Qqc@$Ad*5C1#JZrp0vdzW6cv}sns*|fMU7d@B5uWaiwQ<#k0%!d z_iw)2C1?izqKC&WM3x=$!K$aV`3LeGnfEv5ODvq^rw{v8cM|X0-jM44vD~^kz`7QBW^|NJ?O|Ml1bRDB^k6xI=8bvs+!8@m;>rpSmZl@4>NkHNYK~?O zq)RaGKHNk-JdLfP)&w9W%^MqT=wC?@lMSex*njNWw(H_uCUn1Z&G?YglQkUK01CPx z>|pP%Mlg{Mic;IJl0I^i99ii;v#Aok=LJS=>?#g;TG@w{cOSP1R0pIs!bKmcjQ-}m z!5{j=L-A+#`;+N^%?ofT^8EvTsKtuH#laoaGCFR0dFJmr>5v*KF}qk$!#tZbgf0ZU z9p5FxFR`&(zj$O(x07&a=Eh@tr>NVC;5NWYg264yEHz-aEu7YF%LQ*T!n!6$z>Gjj zVPIX_q7P{U02FZP5TloN5<;C-`y1-VeNu1xYC|2KOQ83%O#Xm=EbNF8_ZBgc61gM> zUD}I9*XTD5>Z?mDwF&SSbUD{Cbg7C_FFr1J%=| z^%hx%1T0A%{ZZN}ej;UwEFrs6`mDnE`Nbp7ynNkY$|dSsl3yDTfo`>4Ol;~=w;jLT zu9rtQ-Kuk}A!Tu(p0fBy5ELmg+sG=D9&yZha=6x*kU!A$0)Ew0TP#WP%OZD$5TW^e z#QAvW_TBx-T;iY4RxP%Yz}ft2@lEdE-t8N<4y__XXF|vEWM?2p?v4S0%f~ste4>Hq zhab^K=2^BHapMoVE@Ykhy$pE*?)j>Y@g<_E{9(mx7iwb(hY~((U#K&4w^Zg7ewnaW zQpKf?*=fZp;Qv?ipInQZa$GU${yJX^0C?HTw>VM)))^vg4+6`(B(*xJ&h3MWR2&%? zhIfOi!QBLlcEsaR$;Y%H^?LR>&65PY^R>95m3Zjtwg-aaQMpK@JEt*0`Mu=E=ps3> zKuLG1;O^<6S}vIcTurTsQ(IVs-O#xeyPKg}A2!G{aE*OzQDN1jgLiTVOww*| zd~e;K-&rzqYvGRBEMDl_87uOuE&M(?w1mn-{+LTH)$$EBBF^V=&OSAzLj!E#9~Nm! ze&vt2`5#1Ge{k)TW4 z!J(Gb=(V7sh_?-|<{%6kG)y4%kbDnV=R=6Ez~p;if*9o){Cq7i+(2FG*r(q5fsA4) zeax{r@r%8la{UkHtRcTIW<*|x$T*LIkU(9gI9Il?GZ4XusQ>&B9fQ7V%h+`$P!A%> z*QsYl2fXp>d@FK!D_y`7@(o=XK?qpF%or?&C#^`aT8f>$c`j9U;-1*C;v~fp%%(AG zvd)ugo%3oOtCg`chap=@y*@0%NEX&hhB-Nkg(kIk7q(IPG3pWpEYP3}ukB+L|jbkPO4 zC#_r0Ss~kHR!CVHFTZ{x*S(D}cl$?x^LuP2L9ayWOWCkQk2Jjcjzs{nb(?mTn$u)h z!BoLLhM17e-V`Pj?37oW7z71oXXQ4C==r#9j~vhRdm}>AcBAh0bBbKN;dsLVAky^n z{2!OTTyS47H@9p1k~vv>-zz%1hG7eORA?x@TfFwqz2vmzZ%%Xv1>>2Kvgh#1mwKVJ zt&R9=KMQ6QPfIRm_HN0)8Ifwl)VW-GTS{9i79T72XoZm6ERQPKR`%M1fke8GyN@%w zW~34Hf#A&S%cS-*U)jHgTGiTL7pO*tiPB}=xX_85{}{Y2TLwD@$#*w)V!@H+uv$JV z)g7w+lIQKlX9n3@HyE-`B%9fH3~J%>r5bK47}n;I2dP-%TgzrgXwO`}AU;R1mc~g3 ztYJS%-;>0mAN#Y{mNFeLba1RUhjL5d4H?&EAfLflv7IxZNr5}F#Xe>>qIZsq-1CD~ zuSIDbTnlnVJjV=?AqqxZ<0UwQ*Gmc!;)#hET{`!vviXSU!L)8K;5|5Z&TsaQ0OOjO z$<6z{YkCc~Ny*?j)zV?aZGSmt%nv|w_@m#wLgcyRIeSllMmcNCUGd^TH)F+j%_M;i z4-UZ8g$wj=p|WBfxr-H{e`1>%!JqzPsM<>zHN@IU-iZfEkE6Vco8912-af6ZEe*kH zebG?Qq&iU{1%Zeb^AT?zs)0yL*n9!3pr9!6d4)Uk&VWqyEsjBV@kyKwI>!1sknYEG z2#QkTR}&^fmr;jq?zefIAAE`Z9KhxAT2Wy&ZhUdwQf*sI$=OP9fKBZUE^^lcQVDLe zqZK!sl{+UcRAgrerb`wHc^JFt->qENxZE!2z(kdSxKnv(UvO1@a?=i(FsK{O&O_^; zn!?KWvy}CQ%YZXYf&L53qatKWWHTf=M*IAPYq0d>E&sB_+d|KIsMOoI2H=E};UAbT z;oK2Ch+iN!pS_6b;NxguZ5dv0#p?3Q(2dj$f1%v7E94m8OSOD2oQqn^%{L|%Nn@nT zCGG^!P3k2w7r4_(Yo-gBJ09t>+WKGmJES0#=&$12eyM42dgWNGj)uiK+^m_9$XMyR z2^Fq057D~5WX8zqznT3|*<_S{mu!-chrKTpxA%>w&P{+t%6sU^M3JY;320|u_i@3hdKv;K{hLc^8kuzf2d_G zRMkW$zTK1OV!+XvVBVhzr5QFEN|`F%oDxK5_M~XRWdOX1ic@36hePGBQbyHSr=y@v z6UUiz_!LSdZB{UFak5+5Mq&zNPQ%~nGQxz#z8J2-fo1kBr?cLD_RQUl8kOozk*F)R z)Z51z6a-H0oKWtNXO6#2UZ3ndgO*o=vX2*UVAXem&;@?zx(zA^TQ{zXEzBEptylhd z;&bsG;L+tIKlLK$IpdQc4lN<24#Se7-_{3L)hr^v%D+zeb81X6wRc5ck72zJ#12|0 z3c6M4T>Yf&@n|2DQ{)5n!?r_OvYARA&hr`h!j8V&Zl^zlb`B76W`&OXs(qICk+$M3s;+4^7lJ9ZhLB-ADOh~IzIpN|em!PUFW^`y&Y z5t<41!RYxJNctE`xNLB^c;aeo#uKkz8%TM32NB`F986Y=IMv z4Z1$I*uD4YJ!96Kk|{v?LaSPn_!j>$3ue!=y4>QL`Pe_O5g6(Y_E#;GjjThis{#&G z9L1|2xbs(OMFgsqXKv>*jB(o+uS;T0wKYx*()OUciqv!TykwsWKUDQn3#FBU7mIKl z$i>2WVdOt>NuquonzeQ4>C_h6adf{fI^L4|KL*b$tho;jnli|v%MqP4u6AC^W}{T} zAyU9u;(|Q8ONO17HuGuZ<;eUG3W+Moh$+knj4TWyoD#8%z_es(Swg%=K2YjYv;AU_ zqT|r+t~GOzmHFIH`lVaC9w;i${7M)GD%UYwZm=D%Z*8S&ASTr(!b3BxKsAW%09dmN zBBRvnY1Rs~@3NPhmGd|2kkbjy87fP88IM6*)iDu+uTYs2I5{AnIFf^$u?%A+%TZpA z0trv{O-UM2hu=?u8N6>|m@=U*}^uI#f zI(VxqR7|j;A71XNlHXD%Gl$ZgJ-gy_9bOa5VnJt_2k>lCl>5`v=cLIlab`-3#WO3t z{Oh#rK|R}RNwy8Yk_jt{t8o|M%-^8Kfwf)J-1TO{Sg&I)u?JOnTHje9kk)2^0`UML ziw5leVvF>IWdnAXRz52&767co*}Y@|QOUZUd}f#3&~|2mLkxk4>U)v6s)&yMpzhX3 z<28Q(qm=BJ{mo}0S?mH+_ilsb``h?A207P9i&n%3HHQv`__p7#Y)8)D`)bE$p`hYc zM6iR(%^gT~#slyg4C}XS=@EwpEgea>gAIJ>ew-TeceMl7KBCvbX_EWaWC0&{ZxFln z{MQ#-I%{?dkHl^VQO2cr`UnSv&2B3rtr^}hw^>0o`+^MF+Ry&(ZR0P5_pLZ594HC~ z=|QN1NBO=e1&6{uy3P8-zWz}3?nvEKnqOa8Xt{Q=anQqX&IA+hnBJjLU6`xDg4B)Y z?Q)+^v2Xmi`W>3Gswl|7$lrrcl67^HW8+Mq@ci|Xnr(j9-+g^JB-jTEHYZ)Ixmi|z z|Mc^T5GY9PNPCI)72mx8SkuD0=jzf}u|*n%pErUN+D3j}Q;DduJ9uT7`^Pg{qZTIE zo=0Dw)9jl%)uA-dYq!nuR1WQxOAQqH1^62SHkUMBfe?wVS0W;a2G6vyD5_eNPm!I$2Hw~@n8Yt;`&8t&poU`n%f`wFH_4^lgOHJGMfGhWU z3?ehI9e2xA&MoalMG)dOot;pg1^DK@xC!Hn%blz6Pad98L_mhmG*0CrJ*5wu0ia-@Bb{4-~)ohwR%K8Y45I-tYy{~_z;4#7{s(bjg zpKtbb+7dQY8$0zWmTOND99ShQ#mQs0?`q@BPg=M6%J%7q#n28q6K*%iO_y@1_6aWZ z*I4_^zT0@=&DGAYQ%!(xrPrTV_-;U?*^96P4B z&GQ6#1wXE$=~Hg`C?)-s0ekt&X?LC2mlp3mvX zjyY!tqL&7lEL^Y?82Du3jW`v8(fQL!@nf&Aj1x_J;eP$a{s=e8O~kOx!TB4G>woYS z;@L)GZtUNsEt6X&?Y(e`ty~eh<8JTlMtwp^+``HY0&QyPoNmdF=gj^CLSW5C-YxLJgv#}OOK(>p@@^dj2V+ES>Cxj*?%=VuP&Lyco!HW8|6~n z>B#}2TAjfQE-AMywB~m>-@sSDmRcpA_&8?vJN7nkmPyO(I>6GhCUD_Y<)CE@hw0yG zHFQ9!%XD%FpRV|GYHxHg8}SYsy*5~a0&G3oAHq#2+EY_xT(@5;niatvkgHJ!73*!7 zuw_iJhn=h)4k(i{&bHf;SnSRUMF25s4sHjrQKcuSV((zBx7sa3Vk&z{ZVS_i(-j;uSfEd@EHoJL>C;CbzZy@VcR^9Pk*$p11DGEvmK2cbKc{fQk(f{N;K!ANsznp$yW-)zz3gp@8a;mrMY zcuq)EiYgm|_6_XH#!3ZY6E9{`OiV3v&9zo+Qp-@ zEkq;$?8}hQF4de6W1BGq_zrU@Vu;ZL2!QcZOIqpOyE;2-X6quzeNJ3M77f;u?N+ zD(T=0kB4rSBNGE&7RdWVa8X~<8XvzQr%+z`cfi6xOf^lOegHHS>U@2DYc{x(CFb4i z?F;7~gk}*h24L{uDd1fb&Qm03ssGY44i~PO{UNgwcBrqG2<8ywH`xq~X~p-i#d6-}+T_Z$5L-XPwUM)o@8pJNjJMK)*-5M@68H^qzMM5jplJqTJ|Gsg zEapFbnInGl@B2;2_iVw&{~?u|a8=_cQv`1s2pFBcwrza)T$7|1C$~gn_K-oRkf>6S zOgGS1_wtnKKLdNqm>0BoqzmLa0uK^+j1lnHw@1Ak9Zd6dN0=V**=VP`)A8rCyUs&i zXWCa~83nQ}#4W7-_4nrw7M{Bw^=r>oY!TcUtc-`$=zm_ELkzp_Ny@$}od09VCTf?! z9}&4h-hTuE;9qJC&VuL3HqrT;5^U*yB4J;f*(xP$Bk!e}&`G_yZ19Z&e;{_3vZx&n zhJr%PL4*LJ`TUYkr2B2;^(nJ1o}KR~MgkX8i=aFM$L!n5ivNYS)jEdbT-eUd=)T7Q zifEN;HJXWiLw%A?lgEWDR(Lwo1+eQPAc#>hjFactDeb19nXPUBHJHYc{^he;?icLj z>=Me%Pb--=xp}@Zfhe7ThLc|x5(QAGRYc1E29;Cj*s_u+(gA-)Ttx1iCN5C)r9b+0 zdM5C-UXsuM&|~0b*h(Q!616)3(3=WauyzR-ogv!dDagNR;`iwBqy|0xG~hNZif#n# zWvHCYE8kH|;3mY{O-ZW*=e`f=G=815T$HiSp6KK`OKt;h@A9j80Q`i zstt0hE+e52wV0o2L9+}VVn~gO1jCmv;D_?!6$|T_ZxLf<-TAT#RGcg zr}8_wnBp(KxhJ`eEBT86r8-#mG=?Bz0N6FlO0d+j)Tcw*d+p|kmm@yUudh!mi_Ru# zb>51a!3=<=4Dd>6)a#SS=@E;A(Xu)|Y@gJ?^@$s8fn)nHDOx$XS+b|}>ini(|TLrTfs6XwqC7%7qkgqAuc2`))t2)Al^EoUXxmYCD zg(MoF$q)QGK{Lz%wIZ_FglMJ$k`GaV1mymyJ;H~6O!U*8vVE0;6}1ypM>X7`ZNv%_ z!DO)wf)SJyO=sR-bQ4=-BM4BQQT@r{!AmW#%}AEk4<=-xUzN3+y<3>MrgkL=Bg)>Q zeOmoI=T?ob-|UEkOROhuonqFYHRXS6f-RIPZ$`PfCcA9}L3RTzex3=@FQ)*--~c(3 zqK{ZGKj~PAn&%{{g)XtYHzi#PT@-*l!!}@(UgCz=U%z+ua%e~~hg9|Qf6M(g_{8s> z573{43{&+XQ=P|uNio?VqPPpBS}Ym{M7f)$ju76phToeO4q7@+904<+?{=^$FwbmA z{aHBHo&+%5WKj^FrrTCfPM4tGqvgOgRxszRdSvcwrAn*c!U{-Z*-ztB#GIvXE6!MJ zQxxD9SXu$Vbwd+h8$>qh#U7QTP%5v*B8BR*uM5}6Uv#$%YYZ6<2s4d)*i?Th*O1m( zNBW+5081&{E=y@{?!VWqR9am$-XzkOaTo}Gy$zg}7cFV^I7if!d^@-X-z^mmuHHkb zT_A_*{+Kw5mWr5EDo^`-sH%1>>|c>@u_<_IzpqG8f!dc8OZvW1(H+aTg6n`? zC69JuS$vj&Erzr2bkA2A(Vo3;>m=}h?#S5LV)tdAQoki@k_(FAAf7@i)d-nzE4h?3=G8KE%N?auT9` z#ejO(N?Ca3GB9^%PITSN8ceTQJ`;*Zr>B=(b!W-iEiNz|dEbyZk%vs9m85H)v(}m} z%Ud(Ycr>MfJ7(EUL_fJZ7|k`68)vR*u>csEqWf|(6%Pm7jAtMH$1s8U_#XpoVT#RQ z)a}SV$iAKki&{7V_9O>uiW`?VlM>a!Tj|XaYo`dS@m`=rV9g|ncQl4al+KiQhZlg7 zw@=J;{w^NhS_Cj)|EfA_71n(I>hdB#fNec#8QZ~!o7!8p-w5;R@g0VtrXNVj36x<@ zL_oj(V^CUY)?8{(QK@i$+lZ|GSz7f#+(TV)&_*T{QUr*0V1Im?4RU75ke3h6CQ{Zd zodQGmF+8hR&%j6xNcyAN?M}a3NLlyhZv3Vy*XEi=luEne_R#-=`1OJQpJ8>xIgLT@|?+QE4ZuUv-^+J*F&u-_jNK zvaslPzZzw&SGMX4vYaHaQLow3uZXin9s)|rH`c=Sc8x~R@_)=ApB4I2XAi~4f*f$1 z>&+3b_xpym2v^<;pk>%zq#2Mn*E7AVEN1oGr+z+aFj%wJa!Y#PE-;+->)5e8Wj(Qd z+~^+0$`5P_gWd?;T#uOm!!DP{h7`lq3g$r+) zyr3YF@~$fpPuZLV@AtD|%Hee8JH7iwL9Va$ga2cA7RX)ZD=%F%E^x=+I(BK{8r+72 zO(~q3bD6Hl5q+V}?)!^wbdt6Me7P<-*EiSKO(5>%EGAgGBs0?g<^M5e0 zDP}J$cg@i{chw~=%s?SPk|XL5xC8WqF!_n#4Z7hU+Qpmp`Qmtgmr30}%23l+Z86$+ zDFbX51cN4fc++-g0#oMZaR9(%u^z%hB^ zwKZe^u38t8GoT^ddP{vge4{$F=jrt~1!I4y&LnB^071TcHyzbOB@ssdF{stD#ey9m zk=a17f-Q-|j7ZOUw-jr$YB6m!i;~!t&g}Zkb4smJQhTTeqqnC`0$%NJHMr{`}YiP$CA{}`~0UAF zdB%+8dy^yP)C)2-|NqeTl@Cq5Z`_!ON{I+aOr%rqmR%gt!?TF6+CAK*kA@0Pxq(1X2l$yOAir zQfj+fwXpPqIyQ%kRgVf<`r3Y7eB`ZnFmNjKaCaKXJkMK-Xww1T>GSy3^TYYm(cZ(n zf83p7=ZCm1X2f&iKI~%+hX6lD=D<7`ZXrIIidY(tFBpQUExSEsa~Rq_Gg05*^0qaN z)!>`%nieND_6YVwz-r2DxLTu8u>o2W*0?#44VOo>sbHnx?My*5NiM!3dG=lIwwYJw z1+8R}$7cr2u7Q3xN0}#hTvglBa;RxI8myYF1spD0tjMX1N+7KT=n}hoGg6+8`nd>$ zO#(zdeg|60SARb&_W@Js_gWM}=1Q{@O#`TsFGocGHrsm$DILGRbTXpZ>+TMSzc8vo zI^X9IdrtoW`xR)|5bhW9%yr*zhfpg8R|9NiX@>q%DP_1k6c+|fUB1l=c5oCUbf&bg5GSD zqx0aG<+>r^6kG5xT`@GMsDpL-I)7Ka{hLw)cL9M_@d zzAl>H%uK<9Kb8!fNM5o@s?Quue89P9Cl;Q$S`w`@WHhX~25ed40Mu|6{uhKX`$!if z@y-JRnM-(~9LL92c>;k+J)1%a83XrGfD3lmJ`<0)2zd)Z&Vib#_5s&z)f4!leRaM~ zx)jV@JF6VMe(fulNtFQaGC*FJ9BdAvy>YRXpqed)AXupZU12xvhPGqOf!v+NmFRf4 zdtBnJ3s)2minjqa$mvxQl75-511pXmlX0(|@XcZqnYS7};iA^}NF!>y+wkb$!+t~O z99><>11;|~?Cy;B96MkYAqD(qBLy5MOpW9a{dNSE^Ve7Hb|>%7mw_G12TFlDj1h=Z zCvtA*7Xp2t$ZcQ4IP%r8tip}s*1EC2`n`9t;!?0z|FMKd-OxVU(nQvylFATm3IKCo zMh4X^u*fj|kHxY(#!0g2q*mP{-FCLe84~{Bb6yD@@#Fva=)5juiT_w4bEw)Sj>m4; zT_le#JK;|Xa)uf?dt%~x&qUKbF1xQppUlmCErs=8W67J|Bk2k+zH8F7nRr`3JP{Vn z>>vA&lllaqc0`izl_vrm95Lc8=l zE?ZK27dcR?fsRgN_B&{u(}~GW$p=&ad<5j$p7~wJ3NxB;PAiORh|>Uf;1-k1ji(hi zRp>UaJv{7P_5{GYTG`b|%|Ae%9KquyAAUQJxkseu|HCcFBYERLo-T#dA7?Qy5NHN4 z3F;Bar;Wm7ZH`=CQp$ZhmUFNEFBzOF&tBkK4?P?fOTG{v&ms?Hb%fs-bw{ROtX8|Z z!rkO%F$m*T?8DM>4+6c0sXrm9)+36&h8*}63vKMX= zA}8CF8SYA(12*+&nC|&qfg8EfG7cN?Q=&4I8X@6pBVrcf(ry=E zow(jEI|Eru4W#z8iq_$?iN8AqMptX(h0MNDuc$QNeS-=TcN~nYS3}OVU*g$6`4fk( zPtrk6ogRbu~~ik;R}^Y!a|@4&6z`k^s2alrU)ndI@YHdhe# zCZ!WNcQVmy;HU+HY~OU}+)eXVIdMlVw}qo_>;3SlcvE}LQ(A}6qpt@ls^>w;=aPSjz2!w{9+4D!eUy5s*wnmO~bD zaOgD*$zz!nFwce$S`KYNx#Xmju~)};{Ix|2nm_BoPu}8=if2*f9(gg3iK6rHb>-HM zT#c|5sl#AN#UBaSF_OX3m7HOL(~w7Zhv#tWUE? z@yk2cXN}rC%{ly!4|!LQ5d<}&GL!9#b0cKCZ&83LOZOj%8D1fE9TucN&%Z3f)t2R^rI$1}aophR&UYpQ5v}RR-y%uz5udH_Jv5m-6_Mwy zD*=kT-re$k&?dfBRFAK%Lz4LVnX7P$6{1Z^U77X>X31!BO<$DTE+(#l!f>Y##$T6E zk$p4)9b9~`CwN0FIVL$I$qHH>@E+%|JE^x^8M9z`aq9}?GFHhsxt487FS;`mobG?3 z)3mEz{{C;)`|Cpc(1-NrROJfTQzE>KxV*#~G299uic{@2_vUplbvoOZu4kORc`Bhm zh-*3LKC0U=cAk}PL6e~V9)CI}h8=db`!wU2nE}Mc*riZ>+L?b?#qtV2beeRQ3>6)z z1;ERjO|QIYxHV!HYB-&s*UG%r2<5hhJs8|AzeH8IB$eq;v+eHuVd)_@Zn?U?br}JjxoN_0Z#yaq- z;DjZVNFaPn&(XsnM$-0ohn^(eW@IF)xCJJ1#1qNY!p-V5t$q5Alz9-6^`j_^s z)Ks{(Blp0aJk0Ww(w+Iyov%uNU$WE~_bDynh*T09nJe=UYlkf4;i}=t;(v`E-Mb(C ztM!Tb-9ASFO24uSh(!f(Mr}UTPVTEi-trLE=pAE|z&4*(*|EG%C|*J(GVhTt{}{LB zCg#S;+O^<_*o4sAsx~7%@p`v|CdEkO!Y<*pSkUCrTvHV$lW{645IJSVX$4PU7XMne zh8V|^4`yi-$4Dj{iiVhhcgr(8x`{Z=q`$#eWKas$+k@W=sQm| zhD>}%OyKZS(9Ycm%hi$G^RU1(Yah!tD1x|}%!j$vIvqclYw)NfsGxT6%hc#uLMDR` zSe}P~ZzwDE3o+l4k-@yJDKy7NiYPzUSlQ1`^Qr%j?ScP6*#r zH=>;Y0??(Rb_Df^v;A?Q?jPgpLMYddGh*6A4oMJ_z+ON!nS(R^sFvO<|p04*@wA zG&CXFRB;mysn0CC zI)z4*S|p$xy9Py7h~M-7jx*j;H|w1T*rB@G+H3Gut?A614#j;6 zooAUmK8$b!g;j0l=xtzc46djmqJ2vud&*^pS3S)JKY7{GkxoI$M6J3}1wvht!7)>_2KtXRuX-; zUXji_l4@MB{Ehk=1FejZ?YZm3Cflwnv>+jg8P;8^->k0w8f9P5L*(w>^8`c05-ONc z3USCnP8Q?!%FK(W)CHFWuBwNw#?+(;2qS$J|I9k7qGIxg59T?j&I6r8I;4!)$1uFH z`F-Kl9jQRiC4f5>3e133?Z3l6SP9a6nc|$sL>*Tu6 z`A*lb48mBlk`C%CZ9qn+|6}RxNX%z^=z_og@~%GqiS~W$yU_j%a>ZKepO@bvr{&I2 z8;6&kWEmFCPs~jITqUer5(|E>J=CNxqAS>IK5DGEo12Nd4?tZxOx3Io99QiuXS=^L zWTG*`$FRgwE6c5xyxe=k&|&>LPDfq-oDEps3oVW(8tKoSH=P-(4YFyx*x2mop;R=f zY}^ znz%V*)48YX<2BNhHoGmILaiXeJC-Psy9X^6@V|BlP#Vc@73%epU)IlC%yQr{{0ud2 z!7VMTlLD0#{0!He|m|FCcdp)9{?tpK?tYdW_9fvwQxG$91fTyzV?+^Jlk}N!;0^?lbErVj5R8vFPvHGdZPF*& z=G1L*R4|GIR&h}~6}U00Xrliw`L7&8ulCpxkTTDNQ{OJ^!#+YFCC*!_c^5~#GEkAhb(-wIanwO7~uo!JR;MYOr#77DR|b!u1`HMiqf z>cc^(iB$vfYdL59?m0AbD5hKF93hNzcK1ZbSKkG1eOS0x(F~A2sN^#-C1%~%ImF%a znaryczPRNkB4Oo7$HP)0ZWDF^L1bx5$Re&atHM|^rBgS^?Hws9vHt`!$!jBpE_PT- z&Ulu~k#8FOAB)XxpRpVb^ z7S&V~NxIEeh_oJ!Ch#maI(u2o#D!q$qaH_UcVf7;MQ?BfdFPLe{}V|mnV59stZve3BdPxs^=yXk&_wD#k%-osQ|r zI~K1+E!EQmCs%%n^~`_u<2^E?nK1#{0szYuLWNA8Hzm+tRzh=Y9FI+tJS6*6=kIs3 zNg)i1k4>YtLulunK^SC=qKxc5KJ)XyLg+oUCK-+(k+sduzH^r(a@HsLbJ2`u&FLdK!K89p<(FXWrGP90@jNI5wR8(J22 zbWxQD$^#$CMF(`wQ*SzSZJ>4N_kU;?bx5Ta|Fe9d3@V`G|cBxX{H-{|rC?fft z(=Qpw$b3sc<&Yn*N?f{pw>yJhOyvN@(ISAFH~mZ2xT<)4HotTSZWGvH-a_@nO@MEP zxwx4ae!}ms<}y0Ar9n)dK7k7Qz}+v?V&}l`Dp1otUa*ZPMFf&1cssI0gxt!YJ-MBYo!SPGx2YSD~+PdY^1t!{0d4=UGS@E>2~W( zY+d8K7Ivavr$W@&J$p(qy+-{iTqz;3%gP+GsY`f}aa^s#-@iY2@LHk)n3>e~>zw}TTRF|VunItM%TyDZ zc*i2-GF@?8#_Bn);mXzZD4Fkl70s`~R-e5n)=5#C_3+u zfJH!^_e7vw=e-#_~;X=RkC3mI)l z?L8E}rz^m_;SZ{!gQ|18vk({PFNXX=CEO1AyNjcg#+AscM+VE3n6HqBThJ;cM3qN7 zlzNkOyKFHF`tk0pCDp8rY`k$Sf(k7F_JzZESEWiq4Z|v4Kck(eNx?3!*ds9h>OEX0j|DtV~ zcMSokpOKln+v~tyaG{0@BJts`u78Aa2mQe2hI$Ca2v=`LM{Q%BZhlf9NP&C)$8rr8 z3l#M*VY)BylG-Du_Lt1s5HZ|yf!bZRQiy6t%a8kn6y1@E_zVn;c>33i{B?GWaF;if zXoVDpiIGNvCECW{jo=*1tOj$g#c2grD$uNqn%}K0-9-FzSB^c8rPW?tnR}5m5=gq`Tez4QC2~sYL3g-24ehmMVe?x(D!cq zS#0m^#mJ3mzKXi4y`yxVq4;c7d3j4pk8ZE4o4In%gGIkZyX+{BSKK-`Yc8g~lQU;n+ z3+y4D!hJc1ho3!v79>abgUxuNvvuYw9xtypiDAdka=g!e0xj$G`cJ}+i>4N_*;4Oz zLZhzQ`mrgxR$bdAf$)LQ(Y^!E1@b*fTsDgA03@7`BvYQ{Jor=`=gM)WtEuvC`im2--9lpVCVqfQE2meB}I*BV@z?86R*Xu;PwDc;8K&M|oi>qByTejP;Oj;E9FIU$Plt zl&0x)58gi|*F`(iTswAK&LB1T+WUeupKoo63&;8IRef2;SIs)-W3hnGQ&>36Il>7n z=mCT_8h2iEOcQqUKlZX4wvCx&eW}&?^(#$R^RwONojWe$xVJ5W%jtwsB9A69D!SPrbP*W_W=#}U z9WZG!te#M^K8<<&Jdz22@GK?%LndW+5{S!X%U=MZm6A1Fx-DBUUC3y?wb_};T7)yP znNM7WyYFTv#vy1WEc$M@3!pxkc3EEUh6=$9>VfLK$)~D5$J21KR7UuZfL0p_5iTpwDdx5ER&NC9|xw6ye`Uf;-gog=!7>* zi!1fG(<@J{lQrXkq*SvlxouXU`iDWMvdH$szKGZW(>kUo@egU*Ik+&Hx3Q)6A+vU$ zGUJCY3K~wd>ywG;ZDfy69Y7#r!*8D;x6z7Cerg53jRa{{T}fyF_qyKS}S*-sJ*q=EJ|M zlXBRD{7Z+-sqp2OP5#Z;hEJ!1gqrSdTGK}7FH)~;b*4vSt&{5d79hX-S&LlsmXzCR z6&DOAlF?nrdBfd&yZYl7dY20b#%2yrgw&nr=YQ?@K{}PM47>ZAB_OYjF;)+r&e>yE zwFRbgGaDMzA=m$uzO`v_dDA`N_F};G{7|-5Vc%Kao9%k3c_}WIIl1?c67FItJ6@DB z%_r24;PlXoee7MeN%cwM3FJnhL)NNaKSW1zx;<_%xRJ9a#z3ZR(}-+Q;;#FMunqVS z{^9eQAuoq+ixKI5j+K!5tien7%-kRIrjood#xnt=UY#x$3cRhIBC3OaS$sn<{X*L(4hRQNr9Nkq`>a6UnrnH) zx}e-CW3n*cmB8196;9n&tl(I6mnlT9x~n2Py^z5SW9nkj1bhs{R*nD&zrmr2dCLiB zyULlOR7*B+sO{jjKY4si+q~`rsokO{uwA}|yO(-PUpci%5sx$o|N1LIU5h!Yif-ir z8ol_dgNxdTdouj5zIP>t z!TAZXP_~=zoO5ev_n-+;UD35V+;&3D_c@=qWC&ryR+$E3j$p4dl9=*N;CsZr4vE$9 zh=w}3I>8CHqoq&2*O2b2V^Vlj0#N2_wL3lP;)1v@Gja`U;`!{Mu6{nbPmkxx@<2^i z+RV8|#L;idC1%FbWvBtgNos8+Zv-p!weBTe2tRj?sI>k*nY6zHU1{_i z&!hJH#ihyLO?ACqy?dPd3`&2FC4v%fBV6S^5R@twa(T+V=$gdZ`}?jLuf#ic-ZLMN`-Q`Zae>7mx&SQm;ekmjTow_fiF&b*Zcy(BgwS zQ=*f#A(F_u3wnuvQ{FFxhM1)w7mp8rqIi4D;S>-=A^3}Fh}OrKkzY}L6kyVRnz3ox zC-d?rHjz1Ye=+%f-WSdMyqQYQN1TNg?7L9jD$1k3Pk3KlHhRMH|NQg9MRMcmV*Tz^ z!MBt7_UA_>l%9S$aWPj~`b1-%(*=2ZxN}v)Ukt^$yeYNn$kcoMfml7X@f@Xe|E60r zVSTmB{5fz_LYScNRy!odO^C?ZFu>yCl%sTrt|Y50vrc2h+{)Ua9R8ngU&ksuu*PPmmpk z9MHgYJ>pz0Z{K>HgD6H%6l{o2=XN=W;n*rS_u;mM6g(u6|A?Wa}{- zqjl4^zb1Y`?gOwYVn#!P_V4JKR|(B#S-?xGi+D9_MaD2v)Xf%VmG;yGt(tDEhw%^l zj{9`CbsMPATF!*B*$3ENpWdt^m8Y2r5l(q`&P5%YX_suJ9Y;l0p7yC|ntAZI#Ou%F zcpv1`^)3^?Ys*|6J&(+i=uR+CfFnUa1sFI`?W|*$=Js{#9SgJtgGK5UkJW%>8w6f4 z(M_<@pf5-`aLXuBP{VXi#-QU_tyO; z+C2*ai+~E%V<#E6i6XL}0BDv{VXrh+3{p$VD~7TOkjvz?yU#PG(l*!Bto)snx=VwW z8d^?u@dX&`R8KVD2)}tBk&3Hu?5m@>=r%qcI7KzBS=$tv}JreG@NqjoQjH~>o3XiNn#d9kXppG47>db*TMi%v9^^{ zQvB9_sKg4Gpcl|kaXHUj9(9}Q=(H4G85`&7*{i8_HyYkNr${rSS;7=^m!6OtiZ)c` zqTjl?pBpy9)YT?mZcOIe7fqEtA^1+4B@7#eyAMcpsZ!gBlgta#fsxY&fTCt;R-&)J z*r(JsG@oXklB_MH(r=(EmE$tgBkxgWm~1$U_=3-PWh$9sW0)=W$Hzf>@AxHzFR%)B zukDpz{Y(Rg)~K~#nU`}?V2ZvT^-)kl=U*wJ?xse99W_f2XvH6Q3GpKKJ*P`jbH8dIFcr#`Bo)+#KD3m!;CqD~vc*aK0iw zo61cP9Z~FiDjiew+#9}m?>`n#PQ&1%b#gnA+_bbh_?oyACw!2gULnz!-H^;Qy>>$A zz4!B12dF}v)9%Lr=y|k^B&DNqJCpKWUH`T4{KrF;v-4;Ro}|lB%}Fcy4Czzaq&HK& z4xy)UlgH`w!)VvHpM2pEOT0ARkp1P$D9y4vZKVfa-?nhZgU#NSCeOf5o7Eika@0sU=EL1_cfD@kdz$MKJo4}`5FGk!>=gD1< zUHN6K7vg#HT)5Uk(#*Iv%^3b?DlK=hDK}o#Ew*p5uKAA3_tSHk`jaaHEdP>uK85Q0 zK!`w$5A{YsG;SdWNYGFO$Wj}@Zdh~ywRD^YF&&mb$P}N`>$>fIBGp%x?km~{Pcr_F zUu3kL{tApq7K!M>h#wnoLMMVi`HgFZL_X#@ADUdp61$+*i26f-Mv_o_Sns>H($e%S zD95^7WpAd)-}fv|7Z&iiX)>JFBmX3g z6Wo?|IXad?t@{7^rsvp*Jxw^-Q4|;BBgtv%^P%UUQrHfupYr?hky(+n5b9&GWj-oy z9`kzbtF}RcqL6B%L+%t^DXX0+itN-CxMQ|%45y$VCUK*DrS z$^6IiLH+&`CkM5uQ`I*eEXtqYdb@~wkx-F>5*IrP=O5tRN5&P)XLj6U)2 zK4b_D2015Fd5nMJsy$@a#!st&lv_f~69w}u5AyTYOqS07{9gJZIM)^4|3BY8F8B=g z-bk}VIkvn`-YG>UttwbNd2Y=76aR9uLDw;7=lEy3cw-Y#scq<<=uvf(1vyUYmu9s9 zzv7_a?;weH|FM`+@TYRK#SeMO4s@On=6Q>Sdice_tae*4$%JYoSzi@$r(zXcI&eoD zGe6;7tnP`=JU~%z?{3%F(QN3-qY7x?$aIPtw`h;M-2JQrgFOBF z(A=?hbxDcEQa6T0uG_~hZJvi_iR&gbUuM@3d>T~UH_B{rKKAI^<#MXq+c5KLcb7rk zZkiKDC=TJ%hOvN7j~Q;u0pB44vFY;@yM|OBloRE+I7VIYI+9~E$MHpTH84-hn@RaK z-TG@YE|!{0?xdnC;6wAmegiQ%H*CNffOTCoCCR*NrM*e)+X5;7l)Id@BwY;`v{WV>$V4}~HP^Ur_hs_3` zKgf?RR1B>7RT1^0)VrQGpCMD`X55s$-$NTUF(rv#edby%Jmk*;8_kl6mp$y-^PR8= zSms1#@p26k)WKMIh1Z&O&0Fo<%&IgoD=}vku#HP-uP0z-)oyPuVDtf{ofsAWh# z3zI-s-=9(aoNRy%2WVV%L6NOxdKUg_KkvJX2@5Lro@$4@`5*h%u*-0&OcQ#=xlWmR zf*K$sN!(2T={ADC!6K8TX4mT=#Mi1;-xtceh>K7Lon-Qw&rx~WHx>{lwxX*;u?rFd z(dv5PNfM(2=8<&J%{wQyhMLRBpQ)oj)2PX)yA8hMgjFGV#Ain%jfNEi&gBB)=d`q6 zNgw!;AfHp$vGYV!Vly}C)FMYZN$x>&UCP2h?8V{P=7`2XIipYSjP3~BZQt`;|1KmF ziRDzmFM0WnTG3G7!8I~%i^LS)q45Sh-57Y83Sb&hi=kOm$}|7So~lgk!rWjzfaoELV_ zeS2KKP7o0pbii|W-lys1uUzz9E(`=rQPyc(R2+GRL@q3WDGt6PQr$sx&+ve>lQ{rmO=osA5!UvJv(t^y~(a8rPjHIjL?^+MTSR-B2C1^Ed*8>jfxR zYrdXAe*E3COdGgI-kvq}kBwI0yvZ6O1`tL9CbVQS5nDyNfX57CTi9bpeNh*j(<9kU zH|OpJ)d3YQP3P2Co-m)pLv1FT1kG>?#y+C1OH9EBJa@zjP@`ed%{o0RbAiD}kkO;g zLyYW6Rgn|mi1ARG57nU?R}Cd-ye8$ggRhNBj>}e#g+$e-uIv>I47lq4+I#yLk+Nky zPnahnIzVW?cB|bfy+xb&Ot+RcRy>$*y5Ybj5$PWdS&g~hvoSvgYT6UC;0x+DiviEI9zj^)a^clQ}=P*a?^TvC=2sOAm$ms#`LHS zfp9&LQPg#-YFrR8JPqG5@YHEr!piYPp&~kMW&1!*5oH%`)V@G!l{>P5b#0;0-I4m4iWe(cHl z2Z#jvNObANB>(G8g7 z$C&zP@%Nm~s;1nZJ&MX(WJ*$t>57qRagKhVTB{!Kr>Bsq`ra6T!}S^$*x|m{18keY zKtI6`)1vu?y!NZlNZVVzOW3O!F%`yjXc+9-&y-g6fHIQr9vSiu8x-W1AKXc86dFjw zK*ii<6N{;UZC#XmMS5T4cHh-)Hzb$fej=x$!ILZdsyAuHLcxD8%DAf!Q_^!>M%$N# z&&PV*_sR%-bJJVbdXngl)`*uA&x8H>6p{U>HTGBy0HA61)`&I;R?#{z^JH;{>Y$ar z$5VklcTuTi9w|!3E>tcs%N*pOyPcmDaBVI(WNim=b*Os2%t;9wv^UxB35lB+pBsKr z^*NMaIN)U-JfS*n(6j4~p8%%y#=8@!Csc??3aM-{VKXp%A-!{}MxEzz0HR$!9y0lA90tO<-L}6Bf$4!@|%a5eU%3suOhi zplKiy2yXSYLWIwq7+$^-=TP)nkMQUkONUPQ$_8C3pvC94%hF=-<>dhSpRJNx@=@qi z0uJ?yQlZ(6sPUk47waeYb`Upk0$8QnYO+#uDHa>mVI4v01?Jrsbpp&faey5Lh9pQH zCq2t7PDD>ux-Cm=AJhwV6i+7h2wC8lyj?mm($Zm8z7gqCyJ`Va*ifHmHiN%VbPZe! z6qtT3@)1h0K@>#Z{zUn2W9!e1iA+5|VRD6-=EXGst=z-pFUnrS#TDkm?jH+(-@|wY ztkuA0*I*4tj+hL22elv?n$V4G_#NbTOCS3dyG-6^o&!#DXH=lkOb~{uy{xavl)4Ig zMDcG7mmbfy?+vRf${*FAMn_e!xx{mpv*rA5~KfCI%NR$c(U9W7PY=iOo1g zu%2sPd>A}12aN?|F0vFB<-=;rfFZY668ZlhTo&I{;#dM09nObRY$OKUW516;2T$C2{N^U})e&u#4UUuX9WRqFhX$Ac8jQUq}^R#U}4 zd<2#>e&7#KVt_)26BDO!IDXI+dfc6s+nfMd-Q(Ce6n;pTo+wVhcq%IbCwW_BhpNYv zq^`LBW`tH&ws(*USwO+1FEI6Y=E&asBxWfL@GB~sE1fa7=A835vXnzO?<#J^)LLPx zzKpL4Xwl}J$=4fl6A@?1Ve;R!mkiIhn+mWcQ}LqquMA*+e90j;$@#Wk6o{yYkEp-R%_t zE)gx4U%L^;&*mLIt0O{%7-Ou*<2zANh=o+9NSclZ-6{VcShO*7aLT$@qah?$uHLMl zCkJ4BeEGkXmMT?&-+n^6*T1Zrwr)&hjZp?8L!|x?f6~Z9Nv)p2!LhX4QHo|{UfUMV ztp1&x>i-!rn^~js&)#)<7d8hjYVSptF(YQh_|!^L;=$co9T6 z6gcVOB6iy#=?}}nry@gZvv+2*M-Z zU=KaV!6(OL2YU0JvkARqT~d5-<~mlI3Z^XXCZJ_lt*sK|UJO-Uom=aFSf?W)jLkl$ z(Jj4Ba0aov%z+yRo8?f}GZP3$eXsmYiHknBzXM52n+==i{yhmjL3_ZQ72#xj!}3!- zEJ)j!DYI@Qdofw5;r5lR@h+}wC#BQH__H5O_>7}|(lOiyzLMWZbL|eEX}mOsa8+%n z?sm(4JRXmb@ss14nxcly+yA+8sfQdgAhxclpc!-8Zp2p-YeWiYw=r4BsSx>6dOhe5 zTLOM2)n_C)F?F-iknnJ+EY!)ZnN>3HTg8xIP^H*I^471fuD()0TwHi!=+@T2)eS@q zB^vi8t^%^e8jY)>yM1?(dhv5q1X8PCYDh_I&Ue_XC?AX0W!@TZ2C@h4 zQQy2?gWGSWcW*77?pf{La^Q~!HPtTDo!8Uerud{CHSop(cjYza4Q zcBqCl{NikoGv^Hy3wSVW@m-*-Ji!>2(wKgP_6fYamASX|+HtJ3(D-I;sK#yYjwgU&Yf>ta+*OJ0{1j=v2sF-<10|Iy z_#{TY@gPBK_a;}bD4xUv3?e^Rq}$#I*Ym3#{`=N{nZ*=bwG=m9@x(zH;h1gLO@~$a zFQZN6K~e3)&0o5-PegYw2|JcaTbYc41pqlIq#JcbJ1@{gb3~C~`Z|fdHl(?*U-?(C zR@|m15coAQ&16F?INUG9h-;C_T z_@-`1Q=>n&G1D8B+urtQpWgI(C|x=?oszE2@}BukL>}4iiv4C&im7Q21p3CG5|U6}g5=0c88O zjN$_ulg!1!dV%jBUO&++Qp|tatQ}fM+1`M(Lin6i zLq8q_uZPiJKwl8a4Q_kW&S??xCk8l0{8dFB@-i+kCvZP^KQM1I2Xd~X#}5TVuk`QX z`;wOq|B6*7orSgHcRm3RAW3r}H(FsJ*7gqIQikJmo-(NT?mQLo2?i#qpL>VY9IJ*^ zBS)rZLVH-BeR8pmy5}7^&)K!sbeyl=E0=Jqd6o>Q^k5aGfUuuvJ=`9f5)^lug)>Vk z8L^vW5e(_bo_6=UnYtqj_SHsYp?qwB(dWlGaq7dR>D>#|3TMhsleV@xro`QZYm;F(0LxY<2x ziy6C<+YY-v6nyazRxrB0u>~??9Ea391gA?aZhFU}UY3AT5GMip1L8C_dA==21sKWe zk-9NUf?o>jiQjOEvj_b7;u+sDDRMrlEJ9}mg-&w#0IE>D3y3O(A$)NG8t{N%c-7*r zprxG|u`7QU6Z2L;{KQ|O+`Fvi{U&HN@*J_10bJE-m&;|IjjmTrHSB=ji~ho%n;NPh z@CzaND57&W*)u~-!(|mEyqPK0p>d`*lw;t9{+q}DvFJ1>bsvJitnZ!0YI8<(*{u&K z2h8TazWwB)hN6L*|9>p`l(>>BN*~yWq#F4Ca?z zQ^dlDc@A|iV)2qxr`%;*C(N-SV9Q_WG&EC-75!{Eb<``jQ_QWqCx3K9Ge#0P;{QZUwW8Lpq?iq`2(evG4#ue z1hip1;IVlV7{=th(pLjKwumhwL5tVX{q~^|OtRr8yARMO+ML@rRE_;@tfp5mu1DK1 zZJkS|;k^jsH5Aac-=R7!4#Wo!gdyy3;deJdmzupw`}e5dHmY>V7SO2V$#Vngdk&@A zBV&AFh}YSWC)Cf_+l+ignUEz65-p7cFL$I3F^cA{g9=w>`4PjX+x<~WjGqu^85f}R zEUi&PX<(|nCe>$gdh2%25-obzoWvP@A@9=NhLn})#9ut&fR2mKJh%vXOlHT|m(Gyg?NI+-oehzd{{S*Wr2$jF%V09AA};lsPAk zsY@}>r_wZGZw9eDw}{!!^&f#pZL|Wr7FYN%^c;gVY6$~bwtapI6_FKy+fUwj9t8@(>r_3!{_Z~( zAEKg%%mL`)%yh?(Ya{3O(b7LsWm zpId@4BH1fiGo=3M z=h5v@kfb}9b(yrYg(WdS2HW8q&-o$Ry<+BggvzD=PCN^mS(aH6GVfXbC0KFY+ac^X zo-KR&c&L?^<~@pY+KEjg%zV6+VqpW3*&Sc$sgEH&NdknW{*~BI4%txi1mN}#YJ+!Z zqD1kGz#*C0o($*}+1=~{j~lMbjxV`C5X+Gxb|OE}oudpH(!_KQkV=>NSA1b~HvoR_ zfH}LX3ZYi{kmxDw`~>Hku=xSwt^5As6O!%_ZHg<=# zy%5f(cS{C2ToSAFc6W|~QBLyy_@r`-a^&IC-iRIhS_}2N-qI7{-?!A|p*r9@x`a1i z3)do_QVJg>?7C8P&&ACs|91jjF}_?j>)M!rH?lREx0|+q$$T~I`eB6>=FHJ8oI`Ao zwO+QI-mjx?As5CP>tL_6+-p7AY0b?McTA`JY!H8Br=<+be~-{KP?feCAMR3WYdPL? zB6(kL`kBDJJLT8*Y}Ssy$YYbNL^GS9QQy-$d-6Sa-)IUizS0fc!CfBaUbku`;MbL;-E^%wp_s zy>wlT;ifmSXkil5IItqw;rW9V!RZpRd@28|mBj1mED7 z1ifG!c5lg{^OZPKPggC$E5|7~e|&F_k6+Q)-I$C5^mC!GtXjz2OGMlY@o8iY@-nOP5BS13!=TS2|MxzCT_m1{~Yfx_e8aCB-H8!Sx`)uiz!2FLk7nrxC&7__pO6HHGoklp_I_py|`A8-9oH&gU z8nw$e?aHtrl)tXX%Jbf9(*6>JIsi3d=e@R8nUM(WPlI|VUv^?e(`csH zI!;usa$&=!5R0g7JlI?78z6K`1wV&;OjkFfiCnD44tin~rOF~R$iKcNBA@oFkL3uN zq8s@VE{jUsJzQ(>`EYkA5l2{8HN8sPSXf`wYacZ;Z-EME}6qW!+3N_xez|7;)L;_$AOIH3KT^Pn8*iknvKZKEwa^L&^G(({e z-CVyh-T&LO7f>|t|1wPd-~V=w;VlmY9_Hrfg1s64{~rO+r&3d4tUF^u%Po91`PhkZ z;4pm7`D)(Luj-Hsm4EIg1$ma4Xs6sAdbW)2Nj+6)^_KNdv9d(q_Up6SI)9omJ*Eb+ z8l|#g2)y9O(g5p|CfZXfg6{mPwX4%~cdaQNx=k$VVt!!O!Ravt2MlM@cJdq!m{x29?=9i;}r zjmA=>`dX#noO^Tlq}BlsvE;Qqm6X9}FuB8VqhgE}&_Bmb4vMCYbC2$hwC5OoWSD-< z+0<4YhVqS=QqaJQ;CZ^qLv%-mE~Mo-cfrEqr%A@{^i3*l_r#*#CP3VB>A;sTnN7vBv6*0FMBi@vNKy&w9bYeCZ@&@I& z!&ck0uyct3gc=wni`X2c{@4--@csqL=+RJ>A*c*OyL>@yizu`B!^i3&*y|Z&=@+`1C7bn^Mlo`^4e(pMfeU&D)RAC?)lcY9j6u zNc#{n+&TO5dX7=Y3Wb}S>%deg8a!|A0!-xW%RIasb2$T~D|EaoF69jsLPNoou zMw$Cf|JXmi&O9c0tg@)t4oW&tRrFI;DqV<&cnlkYdBAGVrnTeYpVIxn#b{8{UJT@(mjeh;4FDs z_uF0WSfLEM=+#br?x+@n(P+GLy;C#>z8PT89N^)4;PSm$ca%Yd_kJys!lId(htXEY z=0qKEZ#9qNRL>T`mZ6z}YWIz+euxOnyo;+s9>L;iD^{= z$V7VR&(_mpSEBSG7lV!K;?<26T!kWH)C!s%8;%yQEMScRDKN zVbf3tA&A@{I~uDCJZ@0odH>E==cNxY_7-dgNv=dVl1Foh=*#Y7R-+9ix=!^?nLYB5 zd#WclrOG7dgU$zT&w!SNR5>ENz*V%6p4)oI)t)<`Ob~Sr5PV2tkJ#r+Ec{$Fk$5PF zPo++l7|A{M>vtzAw0!?txz+H3Nh@{y;)unf8}|p$c=nqi;zoEX5FIZgQ)AD*dW?_3 z#$I``=oV;VtH*gLrp?B564RKdYT<5EH-2=EYGdGqEXR{v-Jl}@SLjO}Mbf}B2={2c zi{z@Ry;y!|Qd4>I==+nzI8N4Mn^APyE}Sc zsD36?mj9ldX5|9o0yq$#)gb?OqLWqM3heBi@(h*Au__RP-yHg?m8>JK%201k7W$Ql&um}bV=RCvSze7{m$LP~z|2y%@z=)y=jJOcLz-sk` z%T2nT*QWQ(HVa+Mx`R72hSoXRnEXKP^VhkYqu?@L!s8GdX`vK(dnojt(#>!}Yv@P& z&)E+*H__j4uAnIcE!gxKP#Pb4cwt7%BY1?ELy+4?g$-A#l=hei$|@=7XH9} ze{Va{?}`fZR(H8muMwlMk%%2QU>fG^8bpcfr!cW>8ix4Ue}j+=V8C^CJGHT^Wb^oK ze`?IDbD7fH*YUPYlP~S>bwLa+j zFjO*KY6lHSvTvqh80|Pd1qd3#Lezg6wP@rg9oagm@Fj=o&d(&x_X|ae3!t}E>DMe9 zXuVVNAdk&gAgYJo~$0xZiVq zx8=bn)7(hAx#>Nl9fsw`ZQ{wQyZyFiBTyk=`P^o+o@?~V?%Tgg-;a$>9<{CC6CG^L z1}|%E2-~qMfD(AMeKdejT7X@eb|;0!8@4;t3bCKRkEQkP^AlBRP^%S`oUr-;iYxR~DUGIP`jz8gPfff@-_Eok!31 zpN)ak9HMhb?2!tGylDc$8P{g*9z01mG3t|HKXL7y#}{BM2SdBu*rNyNQ&njaSWE$p_)aibz4jkPfa)m@+F5z02 z6>ifHJque0`(>0Z_TK37<3s279n7_`HqT>TDWEkge_t_RGQ{ ze#65@GEEuU{|)f@dM6?L%GuaHLpckFf{>L>& z_H+m&K)9@rHvE0<@V-F4`i0P&b1D_GfMn4ozc-mW?>Hm=1vE`YNOXya)SNF^%ZP=% z8l9h|!Kn>GMW&NU9(!FzZ*ZKb=iZm$L7iC&BrGL;9>P2@m!7I7@=MCFP|>`&4ib8+u8h%( zs=1Cyq@6^j+T9QORLS+XHq*Y`_w*#8zMl|J`2$2!J>Yp;S@NR=^^uO!ZiUv!<*qT< zRDutXL0%>P;0qlznpVvVPxN>iV$-sKnY4Zimh(jB0eNjz>mnj!3PEyO#Sdk=jbm2$ zHh{4Vpv(*`HoLbf&~I|C1%p@jRbVyY)D|k!u5ZSyES!Yk->dR*A}10@y<(+{$Onxo^95P($#A6@=y)9 z&g!mlVcAHlcmI6W46|kYH5iG**dy)EdM(tHwz|Lo6eoeEd)Qjibj2T?#ovPpUJ=_< z%>3Lv6^#{5?8JRaW${x3JF!PHOFQ8(u3G^tXy9J6^<}C2X++v#6bv}{KuXe(|2HNL zLc?ciTx9Iu$E&0+nmS6(MmvPVkSq~xZu4W0*L~VLA%}6`&tM&^V93A?5Rw&oOB;bV z>>p?1k7=kLQMy#H4ne9iT2{VD&EMHyNx#$r?<0uZ*6e~MmyGI(ezp``F;Ss5d8Cu< zN+cq&E<*t)t9X1rA%EPiY+S!*qLgQt024|Z%afPn*P&2Ql$`O(k&XL=pF z&w)axAYm-7q6QfI>ogM`p|z*zx3}%>~-=zw&KGVdEN#QMHZt4Nm*%%@@NE z!;f;=s)y$j^1|51rL`EWtWB^v4J=KQ1$tULRrUGouVc_S{qY)Cbg|=S4R=p zZS?HT!YQVGtFpGS?t7jk0Z}ly+MaWK`x;Ikc?Q+?vh@bwLU~aOXrfBB!aNGPq&K%6 z1S{3QD<|MyOD$xJAecs<10Q_?O5Cg>6T3iJf^Y}#=S8mBkV+9d8T~h6<;-i3YT3N4 z{1T0c?zm1>4od1c1varmDF>oU5E?%KAI~!Pv14@^(V?yBp7Mvl6?P-{b*L;7oSu1M zPVDF`NRzGLlfhiNl^WqBnPw#;QZC+B}2IVaPbEDn|^bM1U3;GR?T;`v!~135M)13|xkw@@g@`)4I5O2C{Se0F%2E z@iBR^UXALeh8>Wb9xVW22sTlSBT=L3jw`X3UJ;lz%{?t9^>)#?PItJ`FRSc?W=)U0 zRe~p@qTDVsjbi4*Un!v?e8~?Oo0_e{&^SCgM8wGo;Y8`q%%q&6305J$3`W}C#q*Hv~L-XIEx4~1o75a5fDI>D4QfOXz5yO_-}>NrqMI%>Qwr% z`8xaN|I%J71JE<8jrIvY3W0c=M$QLyO7G9-RA(w5T}onqZ5Tp*HUZ^yn>{t6kSWu} zVk;cwnP9xhrWU@g6SAW22A*CghHws(Dg_?Dy=OLFrMTUT-g6XYxBn2wK=r8`{{0c0 zJ|fCy6>8~4n>fxgZ&OwWU4u%!P!LhfxS&S@{fBG}v2g^PlvQ1-SK%txl~K@~+62wK z=I{TQ%zxt4r#7K6kext!i~??WeF4vJBkFyXGg9(hjoWEPz4O#xcb2=<2!BKWJ8}A8 zZtO3J&Pk{7$j_tW6pUg-t07YE} z(SW5jS!jQhrm^nb@UIC^zxW)2G^}w^#swJZkb)&k#HdTm+nNwp0pw%1!Rf1s2U0Ko zJ0UH~+H>+~A>+7Qzy74XlvU&-F8@*~g)lD&$A#e$T@8Ne%W;#D(vO||p6ABhd~+i= z?!^De&rP1^MPF$nQgnioi)_p}hW(8#h?1eZO8SxwI-{U_GUe{^uwjtQQ`!txmFt@1 zhhXc{CV5>@aALK5RpXxT<@Ie?`p|mEt0evXgQ$gD<=>vlmC2rUAC8X!jxxSw@R+?4 zIry5WAXx=2M4WSzDN!$>ULRlN%8L8#7f&v4PllF!yXMlHGApz7R~0;-7uuEVE|Lu} zvHO>wHUEI9J1kkpfCzB;17VGg;d1<^#ip|CStiSlCTs&?=>7~J6h5tS3 z*ZPZcZ8Bn^X#>_SWR3tSTMdT>>kdeuH^JbkVQjym0e=1zRA_y}Ks^Kb?dn&Ej_eWvamt zgRh+#yi_V=i8t5T9`aV9^2YU&UNg_MVSd2o>LA}~Gq(X@g`md$6pP=Cuo^G*`fHz= zPb5We*!S??P)7c& zARZ+v;7+gea;!rkgBZ4r9!atOFJs$XG~uk~F;6PEe{H)=J4?L+xaf{l`hN;Q^DA)J z*tiFkEUR;>o-(=L|J;%nBS6FCi0+Wrdv%$r{Uc}>OL8i+YOJ`qUdJ0_VDTAVT@|@RO455Ni4hf## zs1_@pSCik_{x$!1qQ!Fb$)^`j9#zYpd5M`UEAu)TxB{Vv9IvZZ7^PNJc5Vb%92qx! zVI1Y|nM4~pn%x?-xs?2nPgbmA^~7SfI|VWkPmv@?Z%GTT^XNHz0}MNV%>wBbAFSPK z?I{C4>JR3eTk4439k_Q8(qr&dR8jZq_brAL!ZBs}Y6&o-JFw-i|77k@+R3VT6?Dk? zCyp*EmFj_R0?@7Ny)r!qs=hSbTu6B0Vi46Vr z^rb*A@XL2r2?Zd-%4Tq`-uxaAkSUbS=9YbW3j-AZ!nUD9^bO&kD#M$1PO!M`5j> zwU7?}J8_JBTmHb0r@-OrU+-l6C#I7k*ux2#;77(3>9rvmI`QwW>Tpqjb3Y6~ky-3P z#GHg{s~V|dI0IRcYZD){q&3?b7BdIp2_)+Qb5an4<@|h@#DWT0JDs%B6>=kPs7nBz zU~u=_M29b)2Q>EXze zaH%IG+phzk6d^q8cl!u41ro*1{PC+&I&=0k4yK-`^!!&0NgDDysh@U5Kqfe0Vf(TglhY-nI&iAP_kgEhl0As#)%-OWB%MU;!v%W+16Rze{ugK)KyJ%PnK~Z zZyvn9|F6~X6^_f*o=N?o0}*}R^3zv+M~35FuLapxDQwqwj~)Hj2+i7fyGh4%4t(qU z(VpIPjd>WUj&UAbY~x~E#WOtb_ERAbqfEJ%F{OW`H?Mgv3hBbV!sKnTyU-CKML$s- zwyUZMYTFL5#uTM#)()5awrl*WHrOi1J-93lOv7@qNA;qo$a1mOX` zUKbgCP&L4h=zR`Aw;yJSC%#DOp(+{H>0=v`+s5mEXEea?FV3iRU7v(A_k?);RfN)4-E^tRrttB*6#GC$R+u=XTdW?6VP(3#Jd zSu2iq0A$W(T2n0O`Q9=J-col~@A;OOIwVG|!`+>L%f6rtL7z`LzaqL}|IkE=gE_hc z;|$*)EV3LioF(0b8N=K_BAj*!X^#SCYa@v)3S$bH(50Gwmr9!y@UW zp1w0i?7)0M(!;vxy_~MC2FzVElR8r`Cr{QM$k}nN{Mmdtwa2TP37HifA|t8aX!p_| z4Vp|_Efv5tvZ_QIw zPq!my-!%H$+lXx?FBcDZ5`Gk}5@9lgA|g98>X)K}P?wWSs;KuNdx5_|T5@nMLGgIT z`}1u_-Tn(wAoox-yu*w#5V1?RlMb7aXz^eR++uxqXWN%TuKHb(I5j4_P;t!@@(eqA zi+`YEkz?>SaUyk=IM3%OMd77+#-gVK`VdFljax_`Wg zaiL-kb(+x~*yzcq7L@>#=;8j#CDmAz_Cgb4IE;Tkw5ki@*Tek zP8&933i>#1_^B1iAfAnex z`+H9)WcZs*yGTguX66Aru=pjnYMK6lGMO{LO=bQNb{ppa0moJr5MJNU4#G8!M%Arx zJ}EtqU~3o0kA#^KA|*4pXF5N_V3cFhb~LfY#}jedWlrM~!F6{%?WIZq_B6VN2cH(7 zuu!LXqy@6jI&dT-_Q^7%(V9t~A%y1K2byL9m!#z2h$BW@I4Bdo_4yU=dURDJeHcJfz#!qC~vEO+n z`6x*=poI#N1{R)<>}OBjBo56N>?_%c{}@Gf7p#Y>F<_mFT94k>`>2DVR zgHlVHCcPXgXE6r8Y8fVUVv$WF+Tz>%3_4y?Bvp0s}b65rJQc#Nyg zPLE+LwXrtm{&GnmMb9#DB#T?!>E=zJ@S2eIkex2{WcxGV?KjvPq@devngZ!;_a(g| zw-iXNdpm6Rz~^xBVB%1t><>*TcQwPgxVB$Z-@o~k_DDZg&WPoUb+MO!=Zj#kpj?N* zT`4XT;7u*`n#XcgUDV^<&kGuikL!;z)n!{WINEw|*?2}Z+NQ0TvzG6|KRYPe{@ZLu^Y*#3bujQ*m)+u+3w;~lOV|&2&)ax6 zPpmcQ!z5Fi;IYH$Q>`wyiE*Z--^YWTK(b--#`9gPVPe@cvp~Sy1ig7k+R>zkgLVm; z#=uTZ6C4rjcYP_k(>zwZe%OD)^t_M+!}5316IBV46IGxH1o<&U=`m1AH{{KKiW7?Z ziO~5X#y>f4k517PJu#tosMB^5R5r!{2$W*o8Ul^D6@DV|!Y#)$00jKa*+pUzka#yG zcHrGKO0lfaPKW?yO!uNS@#SB;5lWux5!P~Joc-&)8@ z2Rr}uj_e5r?=GW1|L26DMEwV$?(FT8cJpNj72q?~2{42}5I*DwFcu{HsxqU$E^C}H zsVSoSpt=eYOl20$IP3@U?B}VZ^ttTLEva8*00XWbxmy+7lNEala2XPV{!W@Hj~w$; zgHHZ;;^wg|ai@)LwV^*&gXUy`T(Yw{=~go3Udsr`jF4k%^4nb~J(=`zjaVIWS)%(P z?C!CwRF)k?s$$erZk{_3l%{43zVd}e7h}5YBcW%3Xeui$gnV&^ zySjlK^fpJ&6RWRVH5#&VID`-ZeiWnH#6eZTQ=&secoO2>%~grHGq`0WS>g}$<8@yg z3wS95z1z*Kg+Quia}rf=B*$_tP5x{6_%VmAHbaUi3a3^~p|hCsg70G`Z;(!L{{5a2+|8N= z_hLNlLRl-)v#oa2>6O__^GNCa(jiGVsC~;!rEXImetP=ZMBuh*UC^tizf&{GMG@sR zx11@9nT~2LF-He#(P+KVo0%(5j_ZEe^Zk|m$Q_lgkhh$53O3?GT^m1s*VbwvMibIEuc>cXx zVtx%?*ZQ?+iJ{`@0jw3BpddXXy~EbMaC#}qbQp|)C>+7C=55+;IZ6GU1j&h8Iy=@= zvc}sL=jE1+QB%TF z?f$69km$G^TT`Lf7t9%!x?+oe2A-~o9b!`wZ(lKNyt5iR*j9>X7)L0ll2)vSytCXQG;t;<(hkt zwT*qulkhoY9Xo#KJRs+(xWGD3RIlZXa$1_)7aJ81u*}>D#eBAI%C;|OyOvR<3 z-J_uUN-g#AClRajcVDSY_g5ezBYU3dYL{ah8+L)e4iPP1Ex+WBcYBL}5}*>q6uzETS$awwlb!ns}^z2Lk>ewnZ;bRy#+BBLqu< z1v`+(6VH-p!dQ)no0(S9UHNBDKvjdgV|^Xc-~UCnwjm~?>Mdk=$RC66KPMKpIQOy- znOE$k82u1FtSl({aw}js*9_x*9B#NIb}eOH(+2u~2$}D*Q?CMh^XyyI|7)=DfUpDJ zI%A*Jcct^jt5VdG7DdisJ`d&O-Ib7cxR@1 zbIX(99Jgla*!Eg}_&5}d&K1?BzD}?XoPTdp3XjJ>Axtdm9@>hZ5Ir7CwaP0|GT!db z%@cX#t`QsH`AGP#3zw%sODqP5bDTw6vC}SlP;46jVe;u$SvUW^T1;=VT1Z|A{_zg^ zS8wahi37~vF!Lv0I=B>vQ@qTO4?|ZrMM*(K`wmpR6 z>6UkcbHdUcnwURk&>px6{w4T&CuFlY0-5t>13S&Ac`0Soywae55xW$x5pZ-)^^)fA z{S_?INoyezTNfobE+eoj$Faz=TQ9t^Z-W!QP;(^F2;~xt40^UEZBz<2c0wjuI;0n1 zz&#m6XfXl?vhXGSTOb|hwAwH4vQJM=F`eNPLtLcvTdgs!GkT99oATZs;G>Q zRJexWv`BW*;?gUk`RV3-<5&BX9|3LHM0T@}R(f~4*L^FFk`9iQNZVa_1`8{d#fqkm z8_D^y!23&3yWyWBDr3d+$7$~mdW&CAK9cZd!?bh4j$(u_%sh=R#Llr!xX7}j6M|UK=y58bo*qP z>pluXgAKK>3eeIzw~8X(pW$VLp;OWBYq;kS;0m3RQ-b>CNyZsBfDX#d3oV6N+dO+_ z3;?;F+2XMuPVuWFq1)+7W+dFtX$gJOR%J9_BMNK1yk}{XxqW`4`rlqJVkRha>BGzK zy)#Bm!<5&-UN^lbpG+W`J7GWmJ3$i+av&v+bwT(JY+)UsQS~ze&$aozYTQ?Niq81D z5_il+DFwi}>;wR9|Ak~8^sJdydRmpdeW3ON>q-3YM3ztFs-a)9ogcW{dx^Ha!Sj}eI+K)x@XP*KFUNC;+>QZFyZgsVb zobwOTh*@-LLE6%uS2cmUwY2yASR^gj8`9onJ(%(E?+-ldK1Xnr_cgV*e~LaWk~}uq z0qKI3I4J*yl|&RxDF< zZX&gqH2UkMT&%xgkZP?mxZPxCTv*FP$de$y`k81NU`}2b)_%O0O0P4D8P}sXl(z|m zidd?Oy%u4!NzoPZvzLLJ&$AxBTN*%URKUxg;+n~d9h?@{tLf~XY~dkuHGWg5{(I+6 z52}>1YU-x62 z1`>%oIlwJQX#d_Z|e*F1}x#I}rBSu~phiC-rNM$n0ZcvrfKqB6%lV z>KB6(YI!Z`i#kKhM`HsJ2u*^ScG-cVfCbu}^7V4TKwGzkAY>#{LS|;Y}L1o#!AD-^N^n0@9 z$P2&DNNm$RQnf7w`J5)LW(3KOgo~Tsr0`e3xsPoLNVqvpOh9&XB#Kmna~Bq#OBAl6kZOyEfq;n&=u zsCt2m$<9-#r-Hhi(YUE`74VkW|IY3@)|Q><66xaoV+ST)@bZ`zn!b%@TYNe z4gJDy4E(ChV6`rrE8b)^y#WT;VA@t(o26J4r-Alkx}Dy{oU>tXkTySWl`R#bp~1h$ zk9GT(Ibfs(4m&6SV?xg_r?Hp2gDo1WZ(}Amc=IbVhYjTgcObK?DjTD%ZQ#asE)mMx zNZN@wfJ7g2kCqg>-Ayb4DriHm%WfYrhVZ8wp9f-u=@CdJRJ#R@FLe$VBfB-!6{5~$ ze|B~{vkd;tX;Td4bI4wTX{rHt5{L6(A-P%`!O|l>(X{;-A2n*Jpe&{rU=a|J>X^38 z_fG!z^=MKMMx@X_wv9Lj-cLVIM0S~Uy&x3RJ|CSTB=&EnQgzmL-ya^!q!)K;^u}G9 zb&pY&d!Tv14~fAH?FggVytn*Uar0dCbZ{lIAbSZOr@#}qJKoJ*o3Nz%8@80gTzl^j zlL}QtTnnf40wa|O1Q1=gimRUeHEjWc)Fo&8hOvH}0dbd@*78>*PAUs!EWzAlft$5C zVe<+k*)|PMNF;*^8@{=`OgOhNioM4yE0*_ZZ}^R0Z`g;b`h@~RcacN8-$(Xa5^tA_ z_-*aAz60Gs^RnSMZVXf$IbbzLlg1^4M5p^e!WA|m^woGz-;i~Faz9t-;^l@?X=19@=g`Z&CPn_46>TeMl+S=W- zzmICWj#P!CC@<)hmAswjy}dn%y*IttC)RhhAylUISHb4bvzy-C*4ZW?uyl~g5cjIrhkev+X))y#Mwr6$TZBP4uook?!&3@h$cS;oSuCQ94xzRFu z>n!8V@{PRVn!)Q=bY5Q*S0>1(eA?j0zp#c>d2jiUMd#UnTHA`6k!w>3kmzk{@RcXu{goF=q%Q81ubck51q;#P@CsqBqLt$_^>@7@0 zU6wRUc}M1rgUZ4MO~{IadeY!;9$t`G<*rLR@34Ah{Q{e>R1tIgP;tY$KlQHUw{3t2msw3qrD-6>_svA8wYI&whtvLr6M$RyG@{NQoEARa#zpTVDw^GUzHtj=@M4 zzd^W$8A;?bRb_G(UfnUnJJc0jx}h}ceH{~<^FVh&i_=f?qMX>4oeOF9G5s5C4l^i| zha7EX0*t>kyFP-A?`x=D(d{r!a(;gr7#l~Ohn|AVQ*HxJrADNrQM?H`b)u!79M$9{ zqw`f;{<20Y$_u+;RuYw)Cs5U7bz|SIe6P5jOQpg0sQPyeW?Y|$+j?8#hT;Ud!DYi|2l0dSNjz4lng*#4Yy?ox1e)5NO$J7Xz6Y-+vwFsaXej zYyOKimrJz=RlfsP!|S#h>ixA`43^liIn)HDU5k_*QA3B}dB|Ao68#rTywiz=zirgM zhX^&IQ9NiXN@_OnDfJLY>|E;YsIpN#4Z5)Ud=d5d3mTEnfy7jU!7U1^{1ex8r`5)9 zb*;v?rv-ziZGQOXw{(RV7Z}WJ9MJm5WPz))G;Ue2X+ACo2qJE*u}1|Iotm+E!v{(V|BXNu39yf+Ww(4U`vA&yP{_+;lkJ9zAiHyoB8we;niLha*Q=yXn_fAufA*EBPXqFK#e;~$ z!qTl(nCkoUqV2xc1A`)s3S-pt#GoM$vF%)D>JkVFm>E$IIb{TQWJBKE?B0_ZRJu75m;jwY z#nYC{wG0^}aTRH!xFtItwS|ENCn>3xnw)(QBc?JbgKpK9gH$+#vDA zs9*{q1!O~F6exjF|DBKuKB;B`#~%nK+xdV`fw28ank!)7vsi6o@8+>AY|_VZi|667 zjuhJTzY~Z9#eI>IB7CWJjeJK{-hoZn`tpI%*|oq{&ekE(A!%g0f(gHL#0!V?g!jmr zP@NvP%XyyYUQhk`u@3w3F~<1{47{mh<|f)G<#@j^Gp9VeRsUt6w(;Jc_qxu#JNBt4 z;Z_y*8JRtq1MBXL>3$tlIyBpg?g-8>@j!Z~J=UuN)V(M_3S^`9ZDsZES~M%5Q&PUy)J1Co0rNeubAZ=y^0Fs;KnSXJXA&B3invQ}paqj=+xOfkdlu882@eim z2WPvisG|i{{!+OvO@%Dt* z?8s0*dnuYP_&-mz22*q+{@E7{drKd$e^8w%UXX?^R=W>Xyf8^^`BlB=QDvxM@$q)zw29VLab0NDk$Qou-bJJO@6R#!3(=nW`F0s z!_44(XJy@`L&%@m0T4OD^(4E>tueu&O4BA>=i~PQ)y*Xx{nyvd84eehXRNqXOUM_0 z4bg#2qFVJ8spFlBo<5=;>Dt~!MKisq8aTyw!{p+g;L@I?0^)Gbt(TCj2yW{5Bmf?} zd;^O4J9xJpDql-D??{^SV=hWOKy3g3N4wF%yx{72=z9EA)B5EH!g>!ht+(iBgKY@QCl+a6rn*n|B=M^egYke z|ATjNdjo@>r6VEw0OJz;(o2{QVV6>N#3%+2X~O@#+I*HswyLd#jgAm|FKA9I9?DhN z$)YbZa^`&ghR{Q(aMTf1gs>sQgKVxMrEBw2w|DVleCT~YX03Gg9=06s!^e=V0@rA? z={bRT>^d>-vP_Mjb;r_fXQF(;{<6o8`9|ynK)3L z|6T954Tl*mf*UTHzwXJak9s%eEmb;7*q7vhZg4ulHR%8+`z2`dB=|yEe`guAxIPk6 zQ=cBT`WrmU*Lbn6yG3mkOnnTQ0JU(0MpZ#^1YYk~yL?e7{!?b|(ieeYwv+#s17W-c0Yqg0 zV>3DqcYZZZQijo7a&2*A!_3S$9K;7PIlPZ?@BDQ~{C|VyR}Y@wQM+WFc%TsCgeZmg zT^DpQAN~Mvh06;TPBM&otw;F>bZlSN)d$6$f}L55oe%i$HMiDG99sZbxE=sU!e<6Oh-vHNmKL4I~XW6p}cv{ z%R@+!?@7+lgs;6LxVBCN8@g#RRZH})Co&a4F$drnz@MnkWP>wxRfporWFDeKI-&TN z)Z7gwjMVYgVWE;w2ZmF^B)TY%J~432b^%ZOQ6NNa;@6A1NHNP_wBKjA^sBe=i71bL z9XhlQ4au@{;I-@%el4Z*&F5$EE>@Ra047#BT_11aQ_oP!C}=BI%56Z*%s)!c+(GZV z8(jzG!(WpKvG#I_)r|=j4oyw8)b=ruhp0=orE0IQX`iLIFPDf+*f@zXaIW1s;8;w4 zxE|7N<$ORK46g8o{uKR97Z_q38yIb}p+&YG}VPo2UK)e%qT-n~Iy|KIgmVr_E0PmoCGlyL99WEwOq513cM@ zaU#AGouFOIy4J|Y|J1Qx9v4m06V(VFU08y@1W4>M^QT{Cvi)dsQ9H`ffHBgwIi})x z6cV%&BNf@|B+4V|q(bH2+PaxC{GM+llWmzO;X-|sI#LRM`s(Ek^9H~1VV`Y1;W=T7 zA$DzY0UON`W+1^L5Fm@kZA7g%rf0d~=4qdROaHj+f%(>9(QS0BC?tWD^$xDz(}yXM*Ci#tGh~+)i9=Prs1$E5 zKk1~Ll@VvGJ^MIAfW~Z_l^xn42)Q@B(U?6=3rTa+X_GgV3iSJ%xSJ@imUGNHwQM@@ zYOC6L&oxvZ15IyY82B(f;fLOOVNpL=2x1oE0KUwWcmkR=#Fux2bC6z)$gWv=nnt3o z;TMLoIqn~q>8qL9S$ovi75|9SUnIUR2o58|{h{ld3mzM zd%X(X9Gpn!oY)Tf4AUOBW2_ZA+D@+Q=koE~zM6R9>+Z*;qdONmp^xbRKOq7J7Xp&I zw2WyAbJ6VymQ2&(J{xUFbkz#5NBf}ygihT5y#M(1iW3b0nGV=_97$Bmvvh~Zb|)D; z6(Bi<@6S%P-KQ1fvM@Uy=LS`BKJo`-FE;m#IEls;8EI@+bQ#r-75rMLm?u=bQIhyt zP_J$5L)w}_#>14VDgQKn$VAiF`XAsWxVX6tiDR6yrd5Hdk2a$wET~J07jn{BUqm zP%v&aiQMG7S5^kCRq4~(dlgI;<~}WL`UDCs!hslm zWJrR)Ih5pcW_5BW_FTYmjQh6s74ekB)WtnswT{;APz9w8fE*@>TtKx{L8{YR{~~$T za>ZzuhIhaMFmi8Ud8sr?DW-vY?@t9-tv>Ymq?Kr2h?*<3olrC`ojvFxLc3D zJRi~2jZoNKKXIAnO08;l0?jXR9Qf9xR1Z5k2*?2-;{ zuuC#`XCb<%mlAft?3_6>Sq)Dt!-%0s0H_A-x0o}miG}9X6dkorE^Byeci$mG_l>XP zH!aS!lO1fpT*56J5+mw((^EU!kDa)1e=Jf#t z-~lk>C`+30m~;iMOwhBcPfS5cQ$x`I z+%%4|-+y9f!wpIQxZ?3VN=mW}2>I&qg8Z4ENW_`-?5q&I@B3Z9Rc41s>M|Hnehv362so3u?PtW3qAo7d~@vG$ z&l7`ko0kk-*Iw6pg@2$9eDLB;w9j~ZlF;!wi!ZS>$9MK+c!S^8SSqfFh&GwgHf+AE-MM=fNOXOip(T#v%*_RSp?EtOQXXy-kj%NzNH z1-dN*+`SM$&wz#74VQ6*W;`dIvS``_^Q?Qn)p(s{+uDPfCPKn8{t`EtwQEiWz%yZ7 z-b-v!CJze2dgE!^~TVp4p4i?VF$>{ zmSVeq`+|(oov)hGz;=Z>i_>G|(c|iX!`E)^sY83Z^|BOS;dDk*JTQL2rj)fo*OUTh zQkWd$abrD;Q+*t_aZxZOGJwpJPV!k#B_a%rhjyi&As(;)&kiC|w_D*KSMPZ`)`S6A zAs)@Af&daB5KI1UZl)B&--L30HBN4|*IS%|eFf<&xq>eRbcvJ@sJHR)PCSsKj1-by z`=jMt#j#CPl~?tNIOCuahyRYId0d*;=RSg4Wo7|E-ab)aUL*)QSyo;V^lioWuc>a* z>@Vc7-Y>a%xuTVLo4&>Uw~jKik~eBYMsw3FUKhl&_teoYz}2uI>^v~>JLrOL$Q-Za zpmAIqiSQPFwXh?!00zBR!{eE7I>SOIzBl4{Knu26A6Nq|j}?*f@SEsPq#|{lvI+lZLTG4J}R*P zP;Whh9@YULWeKyt=pR~zNFwFdkP=NbbSy%vug*25saF5(s8&uRYw_N~UT zsy@*TxUaJ(NAjP)Qhxk0K}7Eag>#`Cm=Yu0f4QcaC!4(7icB@{!f7Mb0?erKnble5 zsfpnFbdI!>m)5|!1^?eWmyHx>JHUJs&AUqncy$l4Llt`o!LtI?Lv^Fb{xEp`1)l_- zeaFb5au1w{m)!c7*)jFNmXLt@k&$FrdaQ~m-)7<^w7fjzlskAJ`3!z&YMrWeiGs`@ht=ikAvBiP_>*zjBjPj zH8-fjkt9d&GN>5j{`a@GV|PBe)p)kQn!TsoS6)ZnwE6tNTc7sU)32};Wr3lZ0YjNh zV|D}Q*yOD0pSHPvQPoJ>N;&987ys)Sh~O@u`AI`DZiLm@IZ?;*(>c*`3qMvz)z| z!g+|*l(mxdbdT6Z*_|G{Ckr(r_b%EbJ(z}B?Q31hBbZ^P zEQa)qx#T+UUE*_QrUkisYr^gVZ^Oz~>=)H?tDC{TiM zJZHOuGs?wa+k&X+;jJe{&Hx*vz#+VCl}xN>)Ea}rE^itfTj?P=@&>F`1D zZLTXFKDKpvZ}+GlBmqTz#P_!x;XgS?QiNj!+%IiC5?$5M_jP~!2L2c3`m)lrrx z4r-1|mN?p7&#&&XmU$3BA7JOqGt9`cG*`5D*;hh$*2g4$+Y7rF_OPI_D*jo%%)NU_ z8huAP`BwF-nZZXS9yDJVEvRJib>FlX^c@{hU6bJboBetb^L|Vc3Q9$Y%w7CsLzG5K62x@g6yJNafO}hV!E(+b*TwK*KvLsYp=-j+ zm2KrRp?_T3lzoJ}M~t|42|Yw>$MU8(h4TuOTQt4$1=U~#T(H;o%5i{9u z$n1fI=bS6){mj=kbLSryu+=40&4ifcnn5Y*ByTC$-x3!-i_e`3y8#C5B(Mu+5<)}_ zQZ5(5P)?&*RZSpoI`d497GgZ+xLK=?KrTWH+v6uK^`jU?SKA3;3AoWGN5C%#@x4L1 ziiI$6yTQ8t#i4l}QbVoWar2y0pO%r;#3d2!B8%M2J%D3=lUu~D(UHQrifXafmxfAS z1ms4pKs|q&B~02E3O5(Cc=TiS!a(p-aU}Jumf%4Ou;v z*(m2NW}j>ID3X5TAJ_fqEu8>J8iD!*|F^Y^cp62mKuX@9Om72$PNx;>F*^UKa(q`YR%z%BqCeKT4%z` zLT1?+8!jJ94MoCD*UHn@5o@$H&Z(;;$loP0xLxu1R?l|3#=})f^S9MsNKHQ@ukP?A zbs)WAc)AOt87RV37%iX6dSXIM!wK+&}ie}ot z?=o&O53$U~bOT7B(*WT-I=a|&!a(G0l5pn zs@Yua8^9%vYSEPmZ*crFpwg4;dr2OjJx7rMch~8PBmcOR29}CJ1`q`}FJp;p@%JW~ z3AGnfOl&4iWn9~!$h@EqoF$Qc`7X}k=4`d?q9jNKER%I+-aMxsawGB6vDv4qH@|SB48o!Svt1T3x0@NLchd*$9jc3PHkL9ibeH2 zE@2Em9M0YP$Mr}l;^yTl2wWhy>9QxM4=kdL_a2OH@JUqO<(2CsoKt#(^&#zjm~zLR z|N8*!Z@l?U`l!xggT*n%5Pg;GNY!XpmgNk$|LOKo{&>8vt_A&@@4<}@xcBq8G?8MV z%EUBIt={@E?wALqxe0r0zAjV*U=4y!)P=}a&oygwXcqv?nbT8%N^9h0e>11ZO*V+y_6S(IDNhKPn1AXK# zW7v9J6}6s~6{(&?bmVFduT$Wl0^GOsn(aK@LpGOaBMnJ^La`V;afT4d^OwTtTl! zKZpzX?i0mBu$3GIg+IvbA$LeB)=nmMl{z*}K1kO-bK0a! zguY_Sxeg?gTx8w*9n^?Wc-%DPHQD1%*)_W^4YlqR=(&IPQ@FJGgG_Szm5&Iz2}x+96-)K79JlQin*X3(1+C`m%Ld>pY<|1nQTb=1mqFo03kwsMJv9sL{fD>pQs{N;s-^(uE7sjQ z;AxeAb$@b#_#^Jl_o+@Dz~_)K^<|>8;%+Y}WDrFy4sK`}n)i^ge#tCP*t4&w#!B8u znyWT^lJZ^yF}d$GSo%jnCM={Clwe9Mao9Yw`a-1XCibinF-6Qdr7Cjv6W|nEiUbIn z7oYZQKUT7KKkbG3TF3dHj@Ns)M8)1kLqbWSdqKA)N+t8IJSp!pR z?n=(U80dZmrv-bWt2_A6fNo2~Eu#3i?DJ^4b-EEWx?QXME(d8GiE4rBpJ3f&*f4$9 z{NWOfQRJ4ecE4FeH!cOqEU@XP`~SF(8yPcq7yfZ^zuGl_usVj|HfgA?pRO>K5t&l< z#_jH^e+G{35k?Zz2!5!EQPmLc=pLrWs2MpaQF)g~M)r-F5K*!a019x?45D}nlw8nd3c~LEP`f4yYVBx(!qHV%0a5Stwfp~*&*`54B5 z7y#Ql4HtKbXAC;AXXu4x*`0?v=lA`SwnA)DRv?v-76L=I003nf)o_e3QqlB6THDW> zbZ(}y`THFWCG9%B2Y|WKWD0!}5K>vds+F4zc&l?$Ug+lN-2HCA8^@S(G!DNAK^3Ahh&=(yRG|@b{kc z`qziQrDVuJ{1rB@Gwja~{}|mkz{owC`?60ga~2(JYev1`)$w!Y z{$gSXt#YhV;xBSMdby1BZ*Q+u;rE%~K(Or_+Y=g)0VIKaZ$bo} z2D-QO?k}J};L%415KYe-9(=x>zx!cqTxi2N3A8EAw|(#=jiWTY@paJ)_jPRVof;G? zzLw&t{XP*|Qm`$P-g~NPr~63rO9D*4b5498ta2bxU9DwRk#O&$F-^9a+qlr-Ua_@1 zVM^_V`iXkb&9F$@1mcyK@l67{;dr8hCr^`Hp+^~RmeO;DnelndkCCKG-I2@JLM#w2 zxI+sK=pP@mbNX<;l{A4=u9Qt+f;9z`puZ1vW*~K|&$ho0g(sn&#U;2xZzm#34IyU=F=UkCnDmMN(*y#`;6NajMC#h?iZ zUA~5J)L9_j9&^)aOFvJp=$h_2rh%@fL5~B@Hd*+kI+{ic9Y`BdMV;y@%uouf%I^G8 z`-+@>Hq4D%jpPIwtPhc2(uG&=peP8c9!?SVqH7KxrSx^QsyR$8cRlu0^M|@cxj|jY zq;G*Eh-H>rFe%_u5>xs z#q#ELQ1Iu5EYp;>TA>;*>26t>fz3Kk{M(?yokn$mo?)M(GT_#(**bB_rq8|8le9n# zH4$R#Y5kyA^7=_o)0MHNP(6Cq#Rx4hTq~)Qg1Ohz{CnOi;agIg+9lTOZ7;!sP-nfJ zq%QH_T`$_c@RseUY8u-83R{n}N43?AC{i{7olde-Jx8=}^plr9-6S0 zr~kla0S%Cv>HoM!nxqSjsXB9xWo`)9Ps`~c+}?~qldZ4_ZBh39w|h}q_FH}*?H(4B zl+!bHuEPq)zI}}?{3QOzwtW>y0w_EjcjeRnlTT8`Y+9DohLhp_|0F7A(OtXW_QUOS z0oU7@*QdM!#*+Rx6it?l<%oNhcA{^f8f(|=ex0P8`7^$_S9qB63MKr&bNc5dXV=E{ zTJPKG-W4OFP0FP#onYn@6>0CEQ`N=6(E;A_vsI?Gbu4+r$Mav&{HT*7kCkUS39qc` zrTPA#w4+SuHC#Svm4~zccw5ixWyO`qpeTwSCZDs8s#&?Wod%^>AM>ifTs++u;_Xtb zaW?i`YSL4Oh&PDUq0AZQnVOPN>0rM`ulrxl)jr;4(l^=3uT&8Z50faO9;`7 zEa{)?M;W}x5!{!iS&$Moe}ZH7awSG0%Tt4t5A+65(YojMw;@Ar?Ss*D2*0izB5(EF ze%fAar40O6xaOYV{$pkcvU7V?U3)xg_lmVS^xkpugT|FbY{kY2HgrwXM%OkBH&6gH zswH^~uoO8f65wX(Hm8&W&1a;o@~SK@uD0ri222}Chr*8LL?+gEsrBz?*|=(W>*1ps zx~sBcGri;<8b@0VPj{Z{>LY7P)w5q{?%3`*)(o=K@a}C-;y;IDK8(D{dpr?zwF(y) zUn*i96|Zd3lf9n)s5F*kt9qyLWs8gT!T1wr#Qg=>MpWr5;RTN9dy__g8>ogkJ}m1u zal>`D@E_N>`gOuvo2%KeqORNLxf*Hi6 zjaG+mV@*L&zIL~&qCkMivfG@l6*A17@l>IxJAFmrDHr#0&zwyO>1?P=p@O-}y! z6%ATquQJgb9tWnO!5r$O16)4Wc84J7uJ5(^R%w*3o-Y~F{ftvkbbq{uCiGbJgQNmq zqkhWeKD``^lJR8(ip)1bFku&h-4KsSMtF(hwX~w^HR;bx`EQvWSvAo`C~PTP(+1m7 zQDH+2HLp^yY74HxkbIPP@6{(~CDp~VZ#?h?Vh!<(Yi<;g5|%RKElJOkU|IV;#c4>Y z`Mt*;ex>&kX~<2~w;kkx zJVdq-s0RPIM3KKI4bd?i4No+Yz%~1zmbT)DXPK+L2)$z=rMkK4Xu&!Urpp7f(suxD z4-wZ>p=x`cnX+W zgv*IZk}0G{9ix!%e}HT;HplofeT!#T7Iz3plNDiU0la_$WM3uRhN18Y8`b1O#Hi~z zx4}Rj4K)vv&(_aK6%HW!5szqVB%e1(eYo^@#%q#=v1xyxc9< zUzz?p_Ga9H1Ba)UR$>e|4!ALzglQ>10ReQA9+6qyG}Lt4PpH@ZFbXhG^l6UY5y3j^ z{Cw{BBu!06l|2uuch#>E%4@4GFj#^BRMGE*4nD?JT=lcSDGAH2HrfE_3C$IM6{2Q* z{E9LBu&=f#)1aL|y*2nBfG6nltk4g}-&HH0uE`1&Tr2@HA6rf|#Oc3`JNk^2MDHXjZ|c{fPU)SlFxG2;)#f=EivoFH`cB)7+cgi< z(|!NmRQ6Xu?t_*N|AhfC&#Q%UU_o=@7dH$72d^@c}8n zW!?C^x)+Anj3(D^m!C+qF_}-hW5C(xdM_w;on=$ba$%hN!a6~XSk@kG&f%mNI+#ez z-`^x>vc%Z$z+Mm_v{@f;9nB_hwat<0V_XxM%G9lK9x2N*pRC-ZPrDY zrW1@35&<39e1~IJle4qN#q@fiyxpOMXgs+CV#x1N{>-5!4T$JByNyS2b-#TSYo2zC zaTc#~9~1k{h7u_OZHn}6nT940B~UtIp;llzWvm%W4`=MTeP&oQe}=82JgJ@aIrA)n zOS-t`PN|EsXL|LFB5!lnH$XvC9-XkfXI*KRKZB#>m<&$qM`1l@Rg*PsjyG<_9#v2QaX>4FR}32?xWRHM#T&*?e8 z3d2U1Mph5RN}v8BydvitK5vu6;$deX)tjx8Ob^^muvWZE;n{Gv65fz zNNhv?7`LJrmjUEh|6I*Gn(N&WUAw?b^@+QOl3t`gmzk$!FIFx-DcJNBl-GZfVoX+M z34rL~RKu>H|F}fpCO9e+AZ&Kd@&fAZTI$FfsV1(My@Rt|j$t-@zzaG?8}IUoJ4aXz z>HR#I-y<`$uDa#5PPudL4OftE2sRJp;WIJb0j3)HOeMELYBZ98(6~D0oud}hvkvK! zuiPrgT7o%1$9kI`Q{}UsBS$W1HL+eJ5#m2OHrPc}scD?L;;qTu=H(_n67k>-+G5t9f0 zYzXD;^IDl2+4*Q{iglm*>i#UKsjk(u$SB8)pqqXqt^(L|{MgC*${t9~KO9BJ4nHF3 z=wv6VT8;P7+orID8XcpVhX>=aKvjEp7kg+1Icr}KtIs_%?Ex$&*yb@x#l+FttnScD z(#3(|zM%yU+-B#lK8z~KTMw;+yV#p+XJOk05$Lf&hFn*it{p9_MQ9S$ZZ2#*)WrQQ zZ{>udK=0Fgu)3?ke6&RW8v_bN6hjk8F98Gl=Yb-+4RhB0VC*|F=dtndyxsF5+G~;7 z`jZx5Imibat30^(|IG)kvr}b;ktZ3I=2SOysW%HBBMGXjOB_{pKKFt1JIWFq{D3>7 z2Iqq|VMqgaOKh@Jb{hin13itmStX_+j1YsmwTzd5Lr^q#?fvo8RF@#%zwbI$bGs_z zI-jrot~O+c(UpM@BT( zyvU@vKI=KM<%qJ(TJvINFt|kYAghf) zHG(AM$}o6?$lX=V8m5V2u8lwb0HNi@tAAdnEEpzgE^%ivr8zvCRBqxRU~H)`MYCxM zm*AT#h-FOLLf8vg0rzjr3a z0#Xho-T7kP_<%Cgg8kl0dqO+E3Dqy$e`PNEF?4y-2*SFkp3ciGdYOPJH<@z8<I-b1PO1?sxe5cmBj zb8^4d(FWW$)0QP=2jXd2g;1N{kpiYtS2+|9gSnYIB0^eaVpIc;d06^-9#fgIMvq~9 z1cnjOQMBO9vX9F;_3};YZc8ulndAT;B0G6oJDr#n_ zDJ=i-sF4NoBlh=TBIcyBF5=s&qyQr_e_}OB_3-TC2Vp{sUOX zfFvmwTvZU0?H-b=#CRIG<#8|{{3q*O_&Yf;O7iED+P0>?OllZs=xg;;ZPl>4T(SHI zDNpiB^rgnD_IG%12Z>ou+5O`Rm(&RxYfm;PTM18r8eG&miWr7G0QMT7a(dAV`7ex~ zHAgt!*D&6SmNcaI3p|XEVruC&SLMD{(WW2R{HjT}AnEzN_)z(Gx=tKEg;?7tBwu~< zt=Mt`qxpT?V+hkF0lay{jN(d|vg6?F+d=kD^`CxNf_G)>6gedcLn>3|_n?m_PqkdB z*?Q@-o5-~D8(ec79pNQDeXhEeKyYokErV)*D49{1D4iDUAQmnh^QC_DE1n-6TZ*bG zv)!O={w-XpMks^az z!}AInvr~(Hm^r~IM;KBp{DSk=b9C^D54C+ulXY5@zVIwY`tb%{<<4IElSDd5r{|*a zXz*CjRgF@!_{JR9GMIg*=H1^@)5e^NZ0~LE!txO7aorr3Z?*a_K1twcrEI9JcJ+2| zLTvmY$IX}~FTN-nsKjRCS&32Ao(8Bjh^bNs;>^2 zt|C`Q^iPd#a4x~NErv~Py*A5*4zWkNJE6O1vKvdR_VWtrd%|99l^L_lU{0{Pa71yz zfEjD!3NH;$+__hEe)Mu9kEx-Y^j0NNF`)~sui$ar(@TCu;Ay9_Bj4`BbP@e&n~f04 zG2m>;`yZS7aCs$hxeB3RS5f)Y!fZ@@Gh?0$tm2%#gZ+u+UCoTj92Y&EIO)|o4N^C{ z5Og(ZA!P-#0D-VBv8!>i3^XYhL;c}pzq)-diCpzPVSp6jdsehFU&E-l=w7$5jJvd52JT z$i2eyA~8Ce*I!bg`A$dwlMGmcBm(tgJLc~@a?QJvX?G2K$$Gc*AyKoNrzBVwBcFA} z6K_o7;()Fgd43h3ys1%xMO4{Jb42AhRTB(~9t2cMwhRerxMVY6uW|kgnc8h^{D%|I z$kbf@d(B~SVgvtpPeolnRc=;r9#gSLG5E|G104$l+Tv{mwbrAJkzl>1pZ-zJPaXXB zp>r<6=38cg2)2Ah(J@Ogm3vpd#Plq_Hau^|^~mu2|Id%K`XraV(O{Y4d9G2BS97TY z!uc2Ut5h~V9XGy|sn=nrm%xvhhF1~KEH36v_95w$eJ6Tft!g|LiKslR;a$`RRzQVi z{`Q9K70Owbl+TWy?qwNlT6LelX6qT<3k1}x9{GrsxtLI}P&je>R24_7g#W4?xY26< zEkfUw0;Dg-xT5E~iz}~!C7?g5K+gl4H71YYMNyuE5&m$%7vu6wwq;FZ zaRlkc)@QwvT_u4*y;5t@ywO)kXotxCBD1ygRk}C494w-HeM?JbV|?vuRJ?bks&*-t zpJnw$@4fHd{yf+l*QXPrF|z`Ulb$RE!cTi@foHwdo{-*!&0z$*&|)F#ex~Bc7fYU$ zwf=CQbsy#l7=b=Z%kw~<`~Hv1pxRe?mj~$(e$mKio3JeJcOfqD*{W5r$xtd7s(%+Y zQ=X;9`qSZcde{-LeD4zV4)OlUXU`m@1C-1NIatb^O|(rXUT7nWwE5pUnF);Gp!!ey zD$bZ{&E435&b|U9w(7vb5!KaWe=hC!q6y4Z`HJv^lQ;u@o!nA4lE%y6Z9wr~$)EtG z`|GsD!6&1_E%?*q6z&H6&L4ayOUKo*6%>px za28d70Qc<|;1knuF#BVbgzW0V?I?1)iZQb$<+HDaN=@hvHjyI;T*MuuEKHf6`<+pO zn$t6I7)!HMKDwR4+kTWqd$pYR`wY>h(gRGrM~JHU+xB96HC?0c^QnE3-2?ZbXSkOLTFKFM*?XdpFOlrG+JC zg{mbM74*~!)!xwWR$MgL(gtmwJlN)(U^4>%Bk*?*84gc#ypbRV708J^h0PTUM&6A4 z$@?1!|0xA{=MUW2i5!{Q*rw|VLDbFm>M;3cG6VN8ABPAjQd@UFJ4 zPj-Ww<{sq9Z7fZF#(snwGM{;JWN5&iOZ_pls)O)8;-feFX@T--_Qs_|+5JNox1hiO z&xyjR-Wh;3F{d`JdHLw-l$vk11xT)Zl861I*rL7z=%+9c1l>_=P}~9qAU3xMO4A_Y z;{dX+(65DObZx=c4qhUs)vP=C4IB3)tteOvAB7TVvLgCK)`Cv$42r-awk&S4#qJIt zN?OPmxclskU+(B`^g2MtI%-E->QuC83oD@T%rVitE89IUe^5C^DEhk(caU?2IZ4Ud zNk9n~5eB@&*KxAQK~%MRB@JXb5}2dVrhlS78+3M+hRU1eIuSaTfR^KWZ?Ob{!xTvA z@nDaBp~3b^skR^@z{;{WM!C)LZ1R&Ij$V5Hp4%NDnfeB7I_3DdMOGE*tkk#k+nk?< z6wRY*LOLzp03+S?7UhU0i-K1CnLx48iYn?}G=K=z{Cuf9lqj{7GCiJ;?6Bu<0Z-Ww zqasvmv&^c$JKC-U?>$#6{W-N&-l#1HlY}J5USS(FrztNT7-^ zuBdyT@$!U_pz}xpQ-61pKy~t&l7=t}$mlaG>0Z8*;=UrMUnfq*A0&<8&H=_iiSF|l z=P8q$=uMk5hpRo$?Brz3IGi#&n^IUFhr92)dU{a7(PVm4ZlUayp6RBd_4GApMepX3 z!o6>+nVnhrf4kpWC>dQow4eC{F7lO;LUxNQ3*_Sl?C;9+LoY@tKs8S%Ysn?%a5q0G zx##blr=2HwV(Y6NEjsSi*y!1u@hf`aHj2)3X7AXyg^wxz{qNR3bO`Kj@mFrHYrWge zFMy0b1p#y*E=kVm{cWKx2mT5x02*My5*Ta&yqma-fHpq1up2=_@o6QSEA`xziGN)9 zp3i>jRCJIFGFnMN@Z{OXkR9#KzhL?)F!kYPghtxIj~Ne*1D}o3U6D&V4!`5sl>?p^yof&B z%avU+!M+!_l}ELCEb6fS>>B-(z_$8$aH4#WJl;mYbR6)$3FgTBdAt~W;<$-q-chvY zL7)EP^@5YB=?#NP9j>VghK1l%K$c>TpBiq5T)^qfKpSQ@G6`o@eJ>9y4joO@^X}l@ zyvEfFq7AE@d9Pk;`B>nf3aaPUXkXY~C{^O+f z%*XeQT;0E{{*XkHHit9GbEh-oup*Db^rNlKGEE=*7UQvfU~fD_eyIgAZ_x`w468HzY-2_F92UjMRxzWb)zdgI=}WEuiaC_`yh@*>;N}>vGZAv{L#W3xoN~X#%x*a35;d)4 zjz=xLmnmTcfPP-LMU-4>>cWF_Rs0`Pq%R(bPEj|aYQo-VBU7LI6?>*D{?G}xjjz0C z@%`xdjbhl;qWiVhVmGm$bnN&bL&jpgm%7~ns@%vbVQ{yLB2#F>_O(fBIVh_drukTc ztgqBtz9V`eOdBDO*n)_B%EfYP&?$(><&)?%Jzb0YFKil}m zs?k6+PJw=^6T=Pgy8mK3{Q1s%K8BSTkA3M_{2Z*o{*?Q5Y2RkShe9L5z^;TzX{S2I z<2eOEDk`C@W2Vpjh=FJO5?8QqSeVV?h4nSTgrZ+rwa%OVEG%zSfrm`y8ppT-exA|d z2b>LUj11C@&7<)qu-e7Lo*|JjD zV_TZsTi2>bzL{aCLd@cwue>C$Dr|qBWQ07VA~;1ss1m5twfgwi0lrTsvR1>Ls}Z-E zGAtd208@`8JjA&M_Z<65D~Pe1*g+k!lUQ4nn+bnCyj>oTzf$%!)77@GmsiZ*#;pO> z!rvrE6XOVJylXQ4pSBk$Cfy(cr=mvkXh&Zwa(V(PU13TBB5J_oA zS+2KgYdO~>fwWfaoG}GUs{nf{YINBH`-<8i<9?HJn0?Qa_gzBSw_kOgH<;&%Fn(Yd z%4k|3Ykj``_0P&Pf0XlyQX@hv^AK72&>CQqxmO0)r>bKR)CQep`%`y^Xp$wmb!!S_ z-Q2uc{G}!xGA0HBz|54>4Ox&id*OJNLfAxe_jcMXKPjEu3z`D~Nq{UK&=muvoaoZe z8MF43Wkxdm(SdAdj3DI_75uLHQx0^;L}q-i$dqtm;uKa^^t5z>3D%; zeNPsRR?zP9)cHv*bv=F3C)!6&R>9z^>(+KBG@JI6I=qu*`vgA3cfFoDJuW1bAZ(MH z)>ZU2PtDw@q|sCbN7F23o`Z1O3%1tQB*8BZ9DqZhfz^}6gCUco+Q-~KS zIbcqic>O`jo%|gSm~z&z-@On{Ydf`>Sfr#>$dTW&j^hod!{`3Foi-w~Zf`dQy$%%z zIS(EG6jyDw5^M!hgq%Lyyb^|=uL(~+xNmB5@X?{A@S1Pg(q>m3@cJJmN1vL`D*J4& z=LePSq9jTgXaBbhDk=*x>vW1BepH+M$JPx!KL2`T1*$K_1d2u&bIk5`jQ{Z7_qr4d zTax5v(HnW3Cw7X7^$3SjG+U`G`y)`Qk=d+o@?3Y&p`(6M$n{+#olS(&xroy~)t^?= zE6FAM5Xi32w`*=5XbgRfN_|cb`yGk3V-_Hk@(|C+_Sg6qebvU?w`?8{@T4dH&D3}1K!!%L(tR5nrUfcGvQe;UQQik z+Y?@g1S8vU$B|sLo%`K zGDE&n?j9mWZ`QhrofC7y695-bS}g#-|ABuxwpFgeBM1js@JU&DrC7ZPN@SS!DEDk| z1=Hjel%`J+pN|6`aMB2+GI&l(HJaA}L`zwJap^>t(*}IV;SBaX1y3?1)2Swt)wX@m z3ECXx)!G}3?SzxMnjrsC!M4-yAU3Z~Sd#Pebi{bANg*aU^UJ*E88gf+2WnKKtIi#u zEgq`Dnz0ND$yz?ZoMQx@-4L8i(pe4V&_aLXZ{5S<(NQdoF_sh@m@`#neAwQbGq|k6 z*X3Qxg#rKyye(jOArXs~r3l6P^$kER>m?78alOa?v3aYki}2io-f0BMddR#B7?XY%>DRlLZs9Rr_4JtTh5zq=rUM+ApXK{l>z(?# zYyk0)?LvGua833bGnK|&K_dtC7pmCs?y!3%u<~mW>M_v|Pfr6MnU*5{vGI+^{V`_C z?{OvTUXgrt=2OUMAL;3=Qfl3R%?n%rY%&+~nv`MX$G&%MAaW+r;`MO}Hu^-4m$1Wx znUhDU=*nK{AKu@2KRt+lik#w|Emhqg*X+)?-;w-#$KvplrL)h4{*Vd_8MOBzip#Z+ zd+HXTt$97~`!+0XyB44VUYzd2aF;<K!N2MP8Gd;SEn1=b!)N)I@KGe1_zPmpXcNZvab1)U8 z`QpHDCo5h3NIZ%+0JG4W>-(FK(}PJHHQPxXhV-X=&#oQ3!_LA{Dv@&B1+^PUb&Rul z+oZ>vS6#iZE6kPE7`h?r^bS2_hV=__0o$ZRcr>$!5e6x)SZF#7B3|fY3}`j3Q+F9BGuUdxEXI9R!-4NtYW@HIplcm*$*34W+4D?;Z!t)XtB zNttLE7M#BkX)bB-Lwx0yaUc+v-mp4Y#{k4`J8tTrT`=wZOzoGY&IyH@kg3&_W1>Sv zvU}y`)Z>&>Ux3S0cuC7DQxv*CTaRY!w1LZYmLcaM}XTa@DZqzJ4gNJ zLaY$zH|r8vCEg)@|Fu(SQM-t2Z~gu2W`@s5 z4F)_rk{j0>}=Ly?}GDGuqweZ&aA%OTo#(%8Y zc>yvuoLHT-&{`RiE-yXwIj(Fwa2ekPu3lvb@EeWng_s+V!xI-a(^ejj5|mQshqU;# zACn*-|1h*;I`M^uXM_g)MoI!PAs@QU3ypr2$BxrrrZAcw!nxcnb=0%AV!YsS3@F9_ z4!~x7z&f))w{=6+s&BQIAqR2%GSzhx?iV#TnjqI5Ta5GX76^) z+3&smW-ynC|A{`&8UPEZLe9Xy{xa0IHOTBbKZEV$$NeG~M8>-8Ypvh4}|8}=1P!O1l#6n8=H&mW;m$mwWsy<3 z4P38{$$EbZNnyYeR-@I^UDkIB03}b*RKvN%a8}nS$JExY z=Epm*jzs$d#`%A2EKbz`;CxzZ0bGKJq5uhj=KIT~@<(rC)#~cC(=6T)jn^$;z@W!8 z&zfO5A>SnKCq9|6dj7&cwzgbtxqg`uCuNlbK9!`K8xwoN1)9gK&J~*`;1UyzQi;Wu ze%F7EkbJg4w5zfV0UW>xs^#d2f3Y^IzXUop|M*pHHR`d((p=dmRX6_@85e$VnC*Ia|gAU1L3r? z9dFVtw{@@a>{@M~4v*S8NIL&X(L_?1&~ln4O2A$~wO$5h&I1oxQM@W?bu<@3l$uQ! z=88~MPjc9mphX{=)z$$CLwAD*P<1GJQPt46kTlCmXmq;Lz6bAHcFa)BAz&lwOota+cvFXkh~r5nu7i zt-+WM%3L6u!+v+oP%UVQF9}NLzWA9$wrCCPL}6cuj;$W{pGb(xmRpC=u2^mTW20bx zV))-Q*`ym$W62B8-zVfsAMP&I#U-4HuV+B>m~l>!_n1oi@+`XE@98)~7j zbk_2qT)rBCPmez~4%uAeT;NAMWEN_v`w)0yMPeBIG}(fjy0E)7Z5z`Ab%Q55Q4?L} zVzR2#io{RXTXDVVK;4}vN5Ma7&GBdWwvvr0LAGENz6SfE9Wjvfz zwBFuUU_qgQv&2*Pvb}@Y9gvtGm>3;pcYiQ2vjDg;vu-vgIz3f(PPZx@>2{kXemJ_y zP~Ndq>iC}(>v5C^jNN@2yET$;@2VqD^8-&i{Mr-9u!~V&SbY?p36Q)9&7jVOYI7tW zR5?w{^34b_x2#PVGNw3xs@QHCm8l^PhWkBVKn-=9+CA_6mBr(x51pg~C!F~0H`<%t zLx$q0gqAx>aV+i)3^(hvn-GSx40ieEl=!LBtcAC~7YCF~aRqu;nxd8@001iI=FjQc ztzru6PeuooI6$tc2)LTQGQSpTrhHAicgHTEQ;BvJ_dy;3qyXnyj?+~4i~`Fj!Q~s8 zB5%$|!5fbOBQh_#5kic?{_JmC!nwRJ*AN9m9aR~DIVOWF`A(OYd=u%@DpUkX`J7B#N}m%(9U4m z1)QB}HVW1wxzHcjA*X{-Vf#=tcOaOzihkL-Y=b)L$(lcXQ!Ijm@(uvj8@ZLbHom7n zgk|#Tc|l5EK>wOsO<;Iz;$3@phn5HC_y_P+(tF+Y(L}Fmk4|Ss>fyo~svapb$L9>0mvaw@5ZYSMO6z(v^WHo;q+IkN} zckU+UC#3M^JbyE}98HYpe_ChTD5v1~*|!n+RKf8HDme2skmwU@Nvaff>Q9QVH!bOi z_$;wPAp47(L?6_TB<7_A==CLlB15vQWWR0)ThyVaho4P1GK`7Ta%P>5z&hZr?nqN7 zW7;ft;U-V&45PIyg5L-|oscnB&)Fz;5MF|u-2m}o%RH)r<+99H4r_EToN0L^JAU@) zfC|hKL$%an5pq1SNEPTb3ZOEa>f!hVn|%=CmE99Rd}Os2uyu!ihM~$#MQHmhW$A!w zXN|mJ9!-XI+FiMYkHLQu#ibtfPHR|&Jef@3R?LzfSa}N=n(7HjE4*URLD`rysKsQK z1YqVz-vKe885VHg#s|Sdkt%vzfk985q@ps}z;H}wB&eIh~lt)j|*lXcq~)P z8IVSEXZ)oBqaO9%z=IbUFW|TVPpsREbGSq z8ozS1zNe!k4}|HlRL-8f(;xK{;Gphw#@s~9wN3EZH~T>U%^=O(^+(nDA^sf;$%K}a zj*SI@Cc|>LjrJ)I7c*9S$bz|FnuJ-9NUMuJ&Seacq?+mx_m*UC?f3T1i4J*7;eadK#`7)x#FiT7Xq;52n`EAWyfcNt6ubLCT# zi9)?GlH~Gu-Z#FkQaJ!y5{KsDj4G&(?BCvzv^V>unE^?^!vWsHYnQEUhHzf9v=%Cy z%p;pbbH~5+Sh-HNdyD$5Q$6CIF6#M9yk|BP{K29vqiAdJdRp6rxviK&QcXU;jUCTk z5gZNfkZWRQAZ2VBY7~O)ron-P#01BbD(5TzlHx;e)LgkshlFUl$wE7@JkMt)TpMwt zz%vZ}&-)e5+F3mAyT5( z(t^+oLKCoufqHqeP*F5u?|cy~ ze?G0pj%lxOe!|8q7K=YuyhfBT2 zb;2BEtU)Sww)&atRXhC+61q?P>~y5fF>Obfuh~FN5ei|b(l+y4Tcl_fOTIG&>mDAZ z0~ZxsiUvfk^6<*0&4W^aA;#DePbbin3JqW_G(cj~d&{eub(Xt}*I~OoiTu&0+Pg?i zaR5XENYg!F5#UN&JN-OpkS#(XeOj|GxKCfJr_7M24!1Ok(?PvKhXc6;*>Y#P0N)L$ ztpJo2vQEZ}$?2h(YHx+yNiP{QkF4+S-e(&_u~$}}%?k-|cJ6OkdKhG)rq>$vk+Nfg zII=DHIGn#jWMVbU5_VpXpl@c+e?N3C6&h{8wTM1+i5k+DTL#UDc40^l8IKtY*Gkx-FquF>kj>K3DPAhu3ye7 z?^9Odo-FAe5FmvqdffxsTBJBUnD&A9VwrV#*B zc2&=v0UCtpi{;p#NH)CA75CnkIc_$Q74YS)&_Q-d`dhj6YvcL%wfS@c_>KKQ*A?9Y zj^7c|-mD^{W2A@uIBhemMTB$SJ`J^cDK0mw0~B|y7m?bGm)~oe(Cs&9!6u&+ZeryMXXS-b8>0w%V*-;$O*Yr?n+w-g@{^YL#Cqw$0H zhRQek8+j}T4OH^B+|8j(AgWW&7#zJdZf+4d?T1))_SphRo!|Zs2;7$|T9K~EGq&=7 zQUNs1JNf_N@*=$J@^oh!vh=?{WgCbQTEEZqdEipbcCN8F{vzjO%N1Y)bf8+FHbLlT zXigMcJRMTcKW zE-w@4u(uEKvMxI8;1tT!{IQ3r#k~^|(iG##J&(Kvr)gJu?aNtISah zdH{)92~eO4ZSByd;Ih=uv_dkDilFTLMDx1&i_BLzlc}qgKPZnP3gxFVHNwAlalL$q1b8TKDT<*8}`) z8WnSOz*ES}wBDwqmwV?ES7XV&w3T+QlG$-C;n$1h6C~@d5Ca>GHgXI{Hp9KgRTOpt zJC(*kFhMIYlnFx;w-jSv9Qpkjny&4?^eFIh1To@Cl;^s&P~@GqB<;2pfx82Zuxiw8 z0Ly`yd9Vl~KJ5rQoSOTy4Gy;(LNFkWe^cXIb=rWeXri3hf#gAOw;r?pE@6_|e6?w_% zxf2GXJlewE&)74s{E1wJ2;h^dYW8YvN#6MvO6cIqZ?G~#vcG+H%^vtJ_%)h#4fk_s zMwBQUqs2}h>P~Huqqu~b>H7skJ=CaIJx1?@pX>FKk~`72!h0-w_QoAyF?^j7C#-9O z@xRkSg*Aq$bZN)Y6d)g(l*wtGC^xcFG*ZINfrtDCn86>Ad&?lU(oMCRlaB>*6XTS7 zhORz*J$R;v!w&NEh?(MLmoH8?pS?j! zZwk60Vgo&e`aV0wG27=`fT}$725Po<2%(_9-J?#D^%sBKi2f0_o;MrJS!m^iRADiX<0&Q2-ZY#8{13pMqW zS7CBFMQRqabva409WCNFzNEgi^yO=pEB3SJ>Ax}Mq2ZTaJWS)Kjx%$bd=@dZtN!(b zFJ(>uk!^`|SNEmsJJ}Q{peoK@`5t0{oSYXL!2x2I-#gJAurqGdO^WhQpq}A3Q~`LI zQE{?^@3I8 zflbKRJ$d}iL#L?tUi)x~dlJKOBR=tjs_6xjmxJIr8QMHG~PJNMEMdx}=A zGgf3fgH8n;{2=WA$yOu83urp@ZXKD?raOh*E09g|Qb*dCd$(CBYfE0A4W0*l@G^b7 z@M|XBWD_1U^0i<(wOeg^FOBa|P;J*Jid7Sxm7v9by@3X6}iv)xr)G61`RFy#=kG0J?^Y*bhJFaI> z&{&Q{@51P}?ISCpo57If5UNo7kxqAd$v6X;YKQu=epj-(!Js{ykTojb%?I_>oi~Iu zoLvZ-7ud%z1ff(1@=yYU|3B6+(CU2YR)yian*5x83;E~y;+flPhno;(U~xSLJKm&U zqperR^NkwXD{i0^2{WQe$Aivq0RYIwG+b>&TBxUI3nx&+07Y3lMwH)EXE*@$x`*g0 zseQ@|^538OGWku;b2A(i1-!kw-mewwC*M^iL~IHxwUq&$HV~&ZAmK+@=&0)0!~do? z#W)70OEq4Eb;AbT2W zw;oW&oWCRi;%MQRHzU<2{zzyopQBqD5&@z%h*Uw=F_C}=xYJhKsY|NyI^Zwmp*;Jc zP4a))4RW71XlmoXtU3LjGIfuKCF{tIOe)A)cJ>FSX~q0*naHudbLD9?=tS~Cg&iR6 zrut~iQ!DL#Dnb3~p{R98N!EDNJ(ZDd`5BE@P283v`-q-(mBtX0t|Mj(dZ|ye%#5{r z?*gxFmvfS(EF0T(kOYF8f@)jfhpbD;4p-ZASd6{(B<;Mo*>q<;lQQ4(9e5yN)+8?= zKn3!XI}hm3*-dC!i}?$h4S7n{Rld+)5Y*#HX95~4q2;L7n@w(jBoSx~VO`Mk!}gF5 zvf)p;*TO76y{PGTjbt33V;XFg6M4l?(pliIjtDaXw+OT;Mp=B*3_DsMFcy$)7rI7` z)pS9nFLHZro8*TmlVL1QNiras0S44Qa$3x*7vP;n`ZHXqr$?y{E6|hSUmT+KbxY@DJOk2arjqRvw@|Xk<&Y zdZ%gB&cr*kwsZ&a*GRN{o>gzDcv8mbc+HV zM2F*?yR!q&$9bWBjPE41{(Z4g?mWEo+#n@igglZ7VO-FpD$<(io(N9BMOBF#U^)&X zc%(nQJ}{X)YcufG=CL~CFKGYW`LXrM7FaDUeh~uXOKtWxt4rk{=E0P3MFmAISUC{z z`AV!!piW@;5kLea%7!xRDVS%KlSs8qKDVPcFF|@Vudk1FtBb_B#;{!7j_VFULVWTW zGkyON&G0MYKG_jqCP&$O%8pzT^>}4Eei(8_qOb&J<67*-)8*=@!7T?u&$Y$ZT$u(+BJG)t5Z&SN{$l2S9f0?u`H-ct$+_g6v>`! zv-0=(xTg~(GL+;|e$Pi|#lQCtKX_xvorbreO%+bnBo{3>SQo^43(+++Xp-xMlL6JS@-0I<~}%_+o|S zbO6DM<)G?=_lyu=P5q%AI#MdzHMINZ&qBYP%DEKB%sO@(-n*upow5!{!$-_4g=DAD zpCW{~is00upRP^gp#qg$C>lA$hmd`|phq(-a)@o5 zgPB%Nc`s`8{@@F|R2|a#4RMYpOFzx(^hN+svuI$}!$Wg8lBvpu_8zYq>uW^>ApWsk zr%HZ6{!-b1DpZkH0xiBhGFvUEW{e!d0M|nu9z5_*+_bSJwGuCxZMh?u; zTYQTK>P$N?&JT(H$L6EmR2Z$Ep!pYK0Y?#2i|J<73P=9vr{a=wepgpn1_v*TrT;ZNG3r{S-lID zE}=jV9ZwPH?t%#grr{~Pv3}Q!YGvzWBLK@u07_PbxWO#d3Z#SAAQYdL^R#q=$8}cl z34YtVc_78*^PkKzUDh2|9>f*p2CBnZdg#nQd(u0%7jO^$B0=JAHnCFXwp*_k->P9- z+@=pAXNzmFIzux3yM| z^mU=V=50h2U6j?%(q`6G8?l5&@}dlD-=?LP{odUob^Ff;5vOs+ILC$G%0D5;Nc$(q zB5wcKF6dl=qxy`jo^s37j{fn=yuyBj7YBBz?u3q{D?r^dYRMpv5?QT*2dwSu(8RruIW)zWsLiM+$FHv3*v1F=pnC7h`PBrw z9Z7w1cKVkUckj&hBdaDY=K4IGso#!_bGYmCyZt2Qejk4bYIE~Uk7%jqUJkGqLG(gFXbuyB$el9I$AoCwv)3xDEu0;^PmchJzX;|I2 z@AFdGV!FRd`#BOTcUDRUoB=;S!PTej*N@?MtiW=x`5>V_kMq!ud6kftS|8fAk`USc z15F}B)ijqt$)3TUj7LGtC7WAr0UB9DX(vnlDP6{A=mTamw9hl`J}37wWa3X7<5Zz% zZm&N{QyJ8G{E+h?&EMd({3~>*Y>+Zh;{pPlNaZb#`6WsBt<=|R>?uUXLY9i(0FYvPt06iHNcYV7J zJJ9Lxz(G0IR7*eEdiam+PX=zc9L&<5O4U6~n=D9pUG+uWI_2XIp(Rw^crDK8qD3Ad z=t4RwS!Pl*14mbl{k9(ebpzz_POYCsK8q*M*R@<3t5xswIn7*T?HdnAqx?4-Zw^{j z2Z??57|> zxI^aY^}DE*BfbmHLJS5bbqn3gr%0~-$n0Gzky@yu?t=5N5gIHsU5oKJV<|3GT@Vm0 z0==miFL$;~SOh=s)yjrrfw4SI{$Oio@eu6sd2c6N;}cS5TNkf~V zjwX6+lck`TlsYlMCD0aI1#fuVvN6+D@gHjk#A+yBTsSuem>CLc_{Dj6`Gsh-UT{0e zOnz^1JuzG?FX$q?R{!AvnkEbAM#~aRW`YS5<>;3lJ`!l*!5n1q?o9UrU~DK!!vG1k zFz`yiYc=y1XpsNb9TX_zro?AJeguS6p9JxROfl*O_*lm@iovH&Ju!>`=i5FgU>Hz5 z3cmy^wl+T_qL{mKyFh7#Vn<3N@$eV2n zZX*V?D?%%?Gox=FSq*gSd;@H~{;{#+%i61KCK?ZK;eG;3^BSZZ z9ClMrEuL6{ue4B^K+d&TCc#DPr3g+gK!%sdFtn27?s8-7`6(dJ z_^wxmyte^tdD%9UgnlkG-8g3n!)KFex>+g{#xiIz(!!b``E;Cjt zI7ST|@xJv`jZZyvw}f>%jqWo?OW#;+YhdM-A;VwaS(ZOw^IG8vVw%P{XA3wlt6ynC z^eMp&1~YVU(gT;{+rPyk^Tthe-)7hS|0O$H_*QZHjxtxeTDPuu{y%ur$H*v#5I~CKP*C4EiZB(74e@f$b-!_f^K?T6m)FVhXvv04_mlKaw6aXA zaW`0}WMj*K*ZmPwn;pA|JCArm!Ed2+*CxpfDZG}mhm_A;p7~Z29rQ)agX(;9DYPrG zM8;oN(x93tXll3H{@1Jo;01QXeWgRcCfhp;e03{Rum4fzHkJ-Kk*lOFK5g<6 z#)k~+1d**Uk$}DggO?7hfFJ0ebd&(%1r3ll2HdODP2T5|2cwrZ_gGyi@=FQZ1VZ4~ z$8k44ET1I0JoT>>K>NlP(#;V3v|0)eHHVo1c2WvAXK3OPE_7L%M0r&;n zd*V%kec-8Q{WGT(W9oVu>@q#Ea~$-lfwGN>Im_Cr4y_0C=H|!>^W|D+VWT12n$Zb2 z&&OlSUyI5<*;(af24d&xy3-7$vbF%RCc3aYMijT04I;nwn?QH3wFvyKB_-ylw!+we zt|0Zygzw&!D_{4{SbFmrEpD6Pf89Gl0#%tQ65sDmg!=qr+bDS4nq21d*Cy^7_1G=ukx71< z`W}LG6TgJ*o}LKA?=LASPEWSYe*L^5e8S6~U9bAB&Ox)T$}7EA3rJfbW|wk=A}H;E$c&}ArgUic?AB8x%lfr_0yBy ztEY9|EMszI4qIMUTjdlfN@}7Snmg66%`+!3`D5R+>fh8fvw(t35Y7_{et|vB&;~41 zedu?mHXNkVx*W8JNeFO}^^g~*+sB!iLtBxn9rrCh9vUW%e!p{@JuX<~gKYpP!qq@s zQ20<&3^C#0I=HZDUiC~vp{d-4mYKbcKa@&LQ@L$<@zAD1>*XRHEDA?%8nxI{4@^G; z;up()<*AQZp2mN^{doA}aVOHg`lKsT7wAMi0>27W@K_nmiw)^e94fT)Zh4hFio1>7 z6V1>zTYWGtx$9ZF8~ah`1&;yiBiNniT?NCNhEmN#+6AT5NL6A)ZQp9e(eZ%R#05F3 z?YK&Fkdfv5(AIQKMxuXW;e0nLh|W4c)cmOhYrjU_)e(yR;our=Vz&{vofn=y)K+_Nsn0q1Z6Va)zc+X9Z6-o;0Ui!;3e|G7GOZRD z5;}swfH8^NimT0+Lx?Hhr6UEyXL5&ZF2YNWrx%~)9?Y|W_TdgOUhTL4oGG5Ps#p_g zQlADQeVg0`9_nY9&AlqdXm;4{ei;uhf*sG0%jpg9f}Ok3rT%#R(wq=z5C_)M1j-yh z{BMgw*hF(7Oh%NXD5qk826k|srj+#U6GwZSHYh>xVzud}NbrNa8F&2PnqHcZ%=n-t z{xA9{>dRP0{#iw%t;v376y1mOw$HV^hS@z6ntWOpr*<&aE8HR6{{E7JFC9h*WK{HH z(rg&*V}&1?+0Fq8PHa&Rs_WM6)w|FM*;340t!E9XI87BV%E|B2Iq!ncwvSb&2CY2W#!Q_I5Bo#!F482Jk+PsTC?G^wf?OC~XSksvYn ztKT7^D`r}~_m5Q!vm#qK$c%ZQIStfO<73wLwi-tHb{CaA@<5Hau*A%u^8+s#=V=vK z|J+JZH}k=>dXOOpo;{uk`v3!+(lXz zaE3@Em%87Yg}+<{Nte72^9<$?II8p_Xe;T`(gCyCB#^R0O>ohoXMAN80f$kd0f``~ z*MqJK-)L{mzMe!dIlYO0wf$QbJcWPH(q|(zB|x{qv}^be$Xmz}h_KdmfQJ!a_uVjF z!K16#!>49}o8J5P)M*k#JIiT1K{g4@sgtHKkYcBihSN;9z?{ckEb z=y45{mK@h(;uyzLB_eOr92b>-I}B=@69mf_F1Bd73&t`Nm*`VQolQnF{r-dJxey1G zzD@`~*o{jE&k_{sP%sk>d0M@|xN@XVSB=cfeHUGIyi;Rwb^ZBRXYg5vU)&^Zt>_NZ z1Vz(KynHYqd`wzFRu53ZmIAg+$VYfxvQX4gNi?4l9@kaO330!{D6CEREx~_1&hMcHLXa^n1Ek#Epzrq();Ux+9xE`domw z&cs9+IMg(owz*@6W?YzALbuw3sE%VuIXJl6CZx7QPVRHA(Us|!s}A*VPqT@IHv7bx z_j#G7ScyG>A)6DP_}iMNgg^=jNHjvRVT5&cT__tgzDK{fUuLih?bUj@9Qp?IiGPsC z6p{t1#*qeK^cxFs;?MMnsF}qieV}J1c??m^Lm`f~6f>h3ZbiruTm?ExD=@flLqeP) zlX1a+I->LElyr9zD!@CNIN#z&`vNR8M+%q}NVkG8?otjq6qGu$&yAm*ZPoe08~;ZP zxqUB5;~c-;{_fC%I^YK=@ghh6e!&`}n6E;Nz8*;>ah!JV z;@Klx6F~ApnsJ9&qjep}s}d~kxzKjNYd1FqY{3VqVlK|eDg-+j-G+Lfo|-|%Em20B zz=6Jz>UGiQzhwFcZ2Q>pkhIC>&jE@qaG<@!g1nH zH9asp6%v-9bY2+mkM>+GLfobScg0yk5|M~{JI`gWqqR;I3>H*>dPn?bqW}fN5HO_b zQ>;2eWESp^m-%rSKCRbl8s6?z#GeaOjA9&=gNb^i!aU^Ach$N0*<`3-yD!9r-s80( zum}Qhc#Sx~yD?&nVfd{NR;Ct{r03!sAgX^hjB)JPpov(V2&GO>t&0fLs9muSQXU!j zar8{S*jkSQh?ZYLn=s2-xHd7Bg`H<)Mp&2Nj>?`TK1PApeheJDvDf=p~z7SDX0%f1zO~dDzMN^{TEe{77R6 zb#2-*3uV7k4#M^hTSVMb*$qckH1B>$mwLaOv>2!M=-6K8OA+Pg0UBqiYMJ)_&AGKp zG(X^^LsL4@41VHbYB2#4=D-uxDWOq+dqN9FP^ViQXgiD6-`)b$WB>PPeJoCK3Ydyu zmR3Xf;pvA>Z(43AXlk1&=++!Qzw;>eB4=D;oG*45EXptgjKY;pGV`}Dg5^EM~hn@ky2J2m?{^>`B)n=s%-$;-C(pA6vFznLfP7u`duR7^Dbz+{G5!7f$yIO z0^&zmIICs%XOM+PonN#sbZ(QTNA{(bDS zJ^_oCkfs!%B|aX-jXk$XN{o`u@C@0EqWI|N_J0?2lliIC(g-`v0IRnT1gdFZGEsc# ze}L#_u+jY-8dupx6PC!GEZj8k2?)x1MyBLmC@#6&BHV;_h#Qy-Z>lap}JU= z=WOrGn{J85j-ZandM3AU*$$tsrpc3->6r6ZR((7-O&(R93GNnMviD=ima2HC^5VEf z@so{hee&0PW+oj!q9W_T;_wi~G6W4Z89>M&?{q@e`U+=L5A}CvfpJ6i)%9G3uA{8b zZEK+{zyK%U!MNgn3TwbxAjxt5yW^+rR?w~ek|SsObN4eUMin2IMW&x&*}_xyHTqzj z|JWQCY^w~0{$$<(k5(&6CWuBznDw3u`(i?#gfXNo1JL5*X?zby3U2~&#!5AippW&G zx!HTAt@|>^oXuaNvG+)VcTE9?AvNk2P^t7q>Q~fq@7(i)TCQR{?RNEFt1Adbbuy3+ zEa=5&zqV)WYj1!e7pB1?S|Kl&ns0&k%4{q`PYjMEK?@C#`_X?^>OG>rD32yu@I%st$CrN@00 z3|dKQ#xSn%zJJ(38nQ4dkXI=9{$rbQS(K^Ay3VUac6UzOen;!yL}wmL#KrxETtYa~ zOiCEq6rG%0sG7Ii(PZqk$mc!nPC>yE|Ba7znU<)Z);3)+E4;0jisEDlzb`iQS;~m( zmWqF=%%XC2zYcj^rmz`!_DNi6Ie6z=cN9VE?NoIcDP~q@AkNUE5dKJeTH<*nOqMMj z&m(6%EGI0Ikg~B|6EgDk$4TIK2toy<|0b7e?ms@@NxRcp8g9Dc6ap5R9-i5%QCB}% z!_1ZelUxMmK3GN;#)1Ni4l^Miax&~Gf;n35+XHf9XoDkV01yaBX+`5|@$Y;ai;^A_ zaYFLpA*4+FJGg1Ow)P4Pr@Z|p{RrUPsT22UFM%ZfG|jJMJ6D+W& zOTM~9_rwb?&Kdf(Hw~Dtm};vnY%w4-4PMNj#zt*>7Sxb2p^K4n^>;O2**Sd;PG@q^ zIO$-TA@vQ}qvib~Q)0-VvgV@Fg_q8CxBo07^U_yXd~nacHed_rTrP@HYnf0Y;sV(Y z=Wl&x-@{r&G&-l^Fg|A!3a%Ize%-C0pE{oYEVs8hUeq?MG1qqux%0DI`0FgE~mRXSCZMl|9U&FC3shCPct2$=TG z%D$#2xju|1LP#&^;+y~2D)c&ChE?k$_TyV`tp}x-cQnT?jC6bLKw7*S5p}A&c!mI- z>W-$qVc~&L&C0%9Il7OUf$a8fr$i zz2Os|irTJ2mpw=B$J5v~+|Ts3O^uUHCCs0wH0P1uyW`BhS ziwDQ4$~OZ1iYvgI%})tXP$_S{$5+qUG0-zd8~1*sRmwNhuu>`?r7|U8-SX1>cDPf_ ztw-NJcQ-$f3Z5_&?@#e|Jy18mN=a#u_KM{Ty-S<#GpZe2r|Lm|-eh0zyRSFo!t zR15_jt#cKjM>$|zNN(qMPg4V*LEc=?78|*Ak*>WEQA(r>jQzJPP@leZ0kg!{8_Mk! z=ag@iWZY+nv%ZS$WcH@?9EwfSrRSz_y`bUn#Avk|_cM|lnVx|02TmEaNZ^UAV2v-F z#=VaBF`+>z>_olxDoS-tJ%LNP)kb$RKP32TFSI@;*1I&@$s@v1%28hDZD1LWc6kWU zn{^Tg6CfQsoQ&f%TM9d%TUjDd3lX5{brGLN*{F^9oMRac%>BB~QRjTw-s$9f-?JmB zqgjfcP6tLMexuVz?k;9upTMsGj>8T57wzS>{J7#EFt8(hqz8Rz zdOY_-NJ@_KPbi$kR#uBfKA$OMK-&zjL8DLt1j~!(EBAYQ=Pv!NUCJRcF0nfirt6YZ zCc%mylAZe(o`$AOHRZo8ODHa}bt>|z&#@%uMiq8j+Mr7Q!`;7t0YaFT+t3$M&_t;4 z;5d+c8umHGw&qR3X7Tabvw>o}%DgzKdp!g1pL=5`HMc3;lRGR<9RMJ|sFhyQmT_=(66hzC(sl%l=O0#J8FsTm|t-<$G3 z!|dmb<|&g~`3AR7EqP;N@OS1b>Iry!%tB+G&aDHl-Nu_NThQOp?O^FY@Nd1B^&Ebw zOIu}^w^77s=oUl%@fN03*O|iDjq|2ozJEd>J`G)}Jj2_^PGWe2j(L7qx;9~uMn2KG zBaFRNn)sIGI(h>3kx7d=T`H_H{oTyE0iCp`B*ef={q@dy_`Ms`wD%$4PM>|t zva-ZGYxojJ?S{%)be&H8vrd!OvE0wRQixa^!+IM?CkeO1+CuVMj%_l3$ZvPt1}?+zcn#I07+J|$ z_EDxTdBv3cHJN6Sv$}p;-nCbLYo!C3$#FrEAZkE~6v!X4O}*meWM?Y9@b@l}pkVz) z>8!w?JAdF?p9eAk_D$)wLksrMMUS$`bE?;?(y3R55PSJFa_YsE zG}qBB%^6=|%h(7_>;8?R<+;#+6-|hbw%GyJys*_J)#P2NwM} zIlF1FIA_!!wnD!$>?yyfA_{3OKQB08gYY6+vITmeVh}L9p_Q*Opkc1aUvy#$#HREn z$YGIK-JceEAWxniuq3Yl2$mo1*q=SyScp!qYj7F0Q@(m|?jxewg{Y&H;_@5;z*c>x zX=_J?@iTn^bnBYmQ`&^ukLyVVGIzFIlvlwKIglE5I3mmqw+vD&r5U{HRi$ajPL1NU zdGOw)Sya)DDQB3GXRr$d4?bSIR;Sd>JIopg{eVLR~!d4?fGp6}%QpV|knKiaq7VBO4bopZZnUKS*5%YKf;X(V_MG#$F6e1b znBcR(LITpofCKE;U_Kk|Lhk+4slf3%Ns0f-WR;uSm115PjkvQ=iLy6F?2=` zU~hl)ClrAGR|!1KQT+I|I&A^Tb5Q?ctx=B2h5BG3_k7-{$T6{R*08372-XDh{YI>h z)8Zbb6;7^zdEv8;CzzLn9{?$C#8rNz($H8H|nvzU_} z^;SnpCtIc1(GaH!x1uFl84?VL@e~Uq_!58Cm~t%4$WY7P!xR;4l*@fWS}ZhNvbzrm zO2{9{jDSV`H9R&}>TyE{8oKufiQ_=nnJ!FXgeD@u@_=XkBr8*zAfa7p>@w!MhV||9 z12ceWT8!*Lw)!kh1fJ2=7K#N2?d_q}uM?uZYuVXysHK=fYAwQdWRLUCxN;c>z1wEAaV0(O{}u zfetQI(C9$gKwzvTVK>L(e1V#bK8(pP4GsikV^6X1fH&!Wg7~au4D{p{ZU4lC5;iYL zZ))14R``CfQ3}j~tHb-mKf%4mkO1O)A~3DYretb&xyfmc(eeof^XDD?*Ca{>E&@IM zHD^ClyOkD~Vc9V$U{6eOs7k*2lK*6Ezl_cw0na`7G-WL~k3UX3Odozsh`{G309Mhw zlTfno$%U&c8ClP=k=iwRTWh1epofo?FZtWFq2ZSAnx%j=JZn5fA?hIjD)lvN%5c0R zyI?Q+236OB>s5=xGR$Go*yBhAUpiIjn%jWiZv5MSz`CborDHj2tSF{d9mgQ3Lap$x zs@#B^M9sj@K$8okLW^v8&wn*7TQwhOcB@4oW}pXyUeMZV_TC>BdO8~@JeV?UEMQrN zo1e_WOJpf9N1B}UM^iWfnT)vl+Q6kx7=%1Mh%}i z)SOZdH%An7i6q*oT*G?N!Hx6`hFH`Z_zGD4mARJBWMvj_>Roa5N1C=(W%g++Q#se` z3^>f$q)AdNF}S?Bvqb}6yEzj?zjd~5H-JOYoS}*IDR8eDtVsJZt2iTNvURVEHHTlS zU%n<=j@l01*3BdseFYW0a`ps)?00`dc0RbtuP@ZCJ-~52q?4~$M;QP`+?V>H`A9GI zb!)JqC!oC9p8LIC@XqFi{o#S_(iw}Ml~?(Fz5{HnSDTkCb+SX=!}E}baA&gDpOTox^eQ6?{rvce_pHp7;o zW5iApV`sJ#GkYZ9XT3`6giZ=OP4i>1v&*4Z#OSS!1Q^2-8bcIr79_OGxSIP7oCD;d z*N{J>ie$55HvvGu7Lfr>@S};ibJ89RdfNnj0B2qZv|R)Gn(PaOZIr6hpWBFC@mG`3l)}^RQ z2LsXOa;&G_XHkLZJ%P_g_$D8pO@#QGOc2Goe)wms{F z?5XrheH~W-Hw`5DxC=al>NN^0JZ$H=R90I!J$h~hB1LRN0AJL*=SxHoN{VZ2Zeqsh z``^A;+~mPj4{z-W`ySoDS0|3~?z1yFAhs)u%|_-JG{x$}Bwi z66_23Of#6P0Fe9+t;D9Y33RS>gk zRl-cGY(}|I=^puD=tFD%+~;XSRMymgA;XVz018nQAD|xu=(zshoM#fbj0Y zPX$9|6P6FVC=cBN;Fu@T)0Q1SpL}QM&YUOPUe%HOD>tJQzkPNZ+*!hLfS>p^^kBK+ z%-#1nQj@5{1vFQ5kyT#LOGdjVC^@N5s-|dsRk?YDG!?zAvjp=+w>&03{S5U`6By+N zu|0|71AXqeZ#TRTRJC6*nhum%X(zsbvgJB)bjxv0d(J*)e44l(I_kbtSl&77`Uuj` z`&<3W+xje1UZNjt4Axek76CMo#GK$cGWDnV{lp}hGLDFDziyfO@zw;rfwIUzII1i2 zUF*mvB@5h7z9;`;&lt^p;>ayTo3_)mHP6BI$#mv!)YONA0xK@roTsQRz8o)s ze-*~IY!~^t;(agG_KQ{*TEfi|7P5(vxz{^mCgsz>ifMsfSDwnbB=(JSH)Mjj^u(bw z*UGP_UZ$!XbB69&{{qhkvny9-h>3np-oI8G2iL_HFbqMuxKa)0n^cFPnZ~MQ-LiF2zgOob%7xH6ScV0SN`1tO<6rQpRVfNGvxXR# z6*eF-Czhwd08*Z<#7q`vT!yHz4a2~RjiSEk-dh^AApe4t?mN3{Br$fE*vmdAO_+zd z%i^*$6l?WK^RACY6#2m&XImcjc9~#+RI|^_Hco({#yxdl1{b4BtlAa|(hJZ8Li1{di^Zfsz7MLr=UXxC{oxw(IFi4n)*%)riTv*h^g3ooeW zV|RD>$ILm_0Pe<(mw~+Ty2PoIqL-bQDo$?U2hSy4*~bOGhaNs`)u=XfVPu zJ^DXM`ES&YX+L!WWR4|{3|u0>v?Yq9br4UeDOL?VNBn@CUe9V62j2aN?m6vrK;v>wv8ATtNTNa1 z_9goCk?LPHOs*BGbBww@J-(4O_)Fw{PfJe1w3)dcD4{*^8 zT1&k^r=ZU}zFej~nJ){B)VOmGbX!N{R!-IUVpxYt<;}P)8_6b zM>A*Wbd#!wg#l&b#o+oNLLp3bDr$-*fYN7!Suu<#t~?mj_uajy+D8Q6LsEJ_%iwDMT=oufR8dL;DVS(7j0R7`#QI_iqbY;)8oq^5pJQ^MrIxW$XU<5#n*1l5R$1O39=VY_S@72pWIprri zQM=Bx$KJAXQu_Se@t1s?9%!;E45$+ijsYuwng7edhb!7Jy$ZzVlG`X0g!c@jHehg?$&zR!x$$8@x@M^z7xg$!qxo zS(~4}h_U7t3yOOT8nzo296Uz0O{gv>*z{@OKCsd5BK8~kWCr2WK6S!<$a!E@(@xcA z%jSdV>AJV4yN^CT`rv%|b)E9)tPCy@c(gmJ8*Eiz{C7&3-wFZ$Z{L6@W%-;-h>fzt zDWKvrkW(`&87;2Bhg74JEg&^!+@E6y!}pB@%RO4;;GfSthCIX{FuwVHJ|j=dppezY zFu_3NP`$Dcz}eL%1&Dl^3r$~1h3|69COBEtbv5^7iMsyhSvty5k70^{KVP$-?Nh)0y*D554wJ`dH>HhZ6$fz zW%o`4a@2sxjr-TH;9d9#c?txw}qJ*=vwy1TjctC;~yWd!E{s6N__GzMZ(cq#we z_n7z|BEW!QAO~E6R%Y65>mh}OLGNe}ni)IM8jDHhABmo^7ktj;kTtJHj~LV)d|$D9 z%7(%fE#x1?FeRpU*5ZIk?I-re?8Xr|RuUpVW|G@o7^FAo?k6PPsea^9q#58wO;;)F zbW)v+Kl<^z?~dPlTn{?(OXk9STEMb*6)UmOHlG(rC^8^6JlgXp4D(Lew0xS?qcw-v z^-O5LJcw>`NZyZ+ycGY#yI)&7|B0Nrg%Vw$bp;&jB3M7@GvxU*uS1D>TT$mMWey7L zi7dlfyN#K8f}MZUsno4dCa2A@|3xme}4a5GybP8|D0XbP4a8MNtgwH99s2$ z>d=Tpd&V=NGYwdL2c~usw28~cmuL=O=2N_>_G~#0o>OC)aoJhnp}zk%RJ!kqnxJ*A z)GtNzhCnqUGt_oTje9bel{f_TAVrL)t?n?zZ#7mB2|lZ44N(&aYUMv+%Cj4zT|Xd# z>=@2X_Yg3q9Cvw3=BZ_sJ?PbWW|rI9#U{OMH$YPQE)e}4+fI^3o@0g^Ar$7A z%gxdwN5<3sm3_1KHc@$L9zokn5&hp$e8**d(EwckdGeU$3fir!c z<9nU6j-i?Mw<_*M!E+CMfNujppZIDt`*PH3xYGOWU6nQd-ryMi@+Wxj@PnpsejuFuIlmYUm&4X+xbXS#;wJp{2X_g}joLd2e zqaz~P4lHa06u%RWl1B!@_OFO9Fo)DZ^dkw(XU>AMyhmM{TXuOJV|LCkJryIN-i z4Eo@Y;Ji9{Ni8pRc6kY5M>+OEXlHf;gKQb&aH#B8fR;Mu+5$}K=du=2f0*$X%0zfnA`XLuq1z=zHg@kEa9sF6tJkS0s<#| zj;C*n0knODg8vTW27KlWt%VrHf=Ja2tLQRS_JY&Wq8c!k1#l{K`V$~T$AP#GylnK$ z0d~rlt}wc}Og@xKk`CQgNVf5nk1A&p!PhUTAGLm@%cyW_+RF|OaG9W%Dd8+vT<3x2 z`$dyAT_9PRe+{7hy@U^WK!w&3WJBnkK{<}}l?x;gA=x((zb(K$iRB;rj(oz=D{KJ} z1=KEu&QC`Zdmml%4t}f@A;(!6(hOyh*@iPd<5lgpvVsh!RK60i_MLKX+;%5V-{2$o zEfj2doX~cYyUBdg?x-$34<$9%j&S$RjuP>hm+wZeZe;X@HZu8J!j-a26td-?~;9o%D8jAcl}5Iiy6BsEH;Dm-%k6Pe;zo;W16Lc zGCCTKu@Ki6W}0zhUgA(jiH!x28FjhQARUcd7KwKgifWE*#IO3Ww> z9xNV|GrQwRtRK-7jQT~9IGHZ*x~(~H)ucEK-j!{CSzK&YQkcdSU3VmnFQL8F_QPdm zMu@Yvv!{)mJciPCv%tGAEJL{bk-2&X7~@ktX@5q`{@$x~upi~gO!m{Aw!nbBRIIu& zGb;)(*+IwkAI8l_G&NVByR&^^Sf0IdL8j03qSktV6{d3MY4wG^D{%{!=~AZwr;v*{-SH`(1SZR zwN6J`(L%OEepbA4qQ|X?wzmx%)_qF1#p{#nJCsrzPkL_EJe4XsaDMgvoevZ>ts3K+ z!Flnab^OIDnfjY5yOyk?zS)-G!in2{995B10^pEJN++nWN~lk+h>lII&{TP77FYNo zyP=LwuKxlwh$TgnPyWesle9M0Nbr>@4b4K_?Ibr^3nw>3+k^RgfjDpZJjm{*kv`mNg?}k5#iGAx&ipqvbctj2E6z+2)RHVKPmauN{Pfi8@qg+;uVb zra#%NcI-68V~n1clX?$loC&(ND?#=r2dO~ zzXyHjDy_=1yWY75tE4iwp5nH2$)4)Rlt+8m5@K}?mLUo_OWy^rI2dMygw03AXv9;G z)F^kTUOTcb3}*#OlU`gGB^*J z5^c_BmJAGi3XON9Ab#&=L>JF;01OIo`ZGio(@w)HMe$|W6uZVjzXlGr>gb@W;8EzC zlSlSYnjD{LXd>hY@3UsM(M(R0FXFjtVaK9T@Kqt1);rf8{BPg*-cV6E?p^0=;|*L9 z$vEEtB|G8_1UIr33GE~xB^XxooDkKlQmPFRsQZgh}qLS=I9p(eGpu=`8B@gO1E z^-9k`_k4ucqWs3FB_pt$-cH+(0#slv5Y+LdkXWwa2t+Z6FH||Ptabt}c=X8J-RyZ6GW)!2e8N@zM`=K?CyrD3%?)4AMN!s-nM((U^XR|jM z>O+zaDxn8N%{F;5RlWSAJ}*=bq|8^~<7H2XHXK@qZ@IC`*x(sUwsPQVt{YSI#}dMa zKB-7WelHN4_$tJNep`v%Q;G<(AKGhe4Bay6CwGNCF&*@Pu53V5fCs(Ky*sFZrIJj@ zjUL6O3LVTRtln3g-vbb}dCF&UAPd+4t6?U8LmI7^dPX#nOtLZ0@KY$a=j%x4!SeLHtf zKITog096;)!vX(;e8#H)khfwk|6McNQ$y~J|9Ue?o#>XSejrDOM7=Q&=~@NGbq5Dh zrnTRc8w4{8I|-1ZjLCM?^Ulwzzf}BktKI~cLNPRkO`lZ<`8865m&VlxM(uFrnva&x3#qzy*k==X z>drVIK~lbVTE@XrjNQoshOP>9$>(*AKDv__rae*k?9L3j2%eGs4ul{G(qm9_hM zb%jJG+O^JpiTWrf5n?r>KJC%cXPF(!{DX3@?j+xawq+f+ju2w;ROddR(P;=|Wt<>B z2aBLR07OaSVESnAhXeIeZ~y!WDi@}kUY+uyHXz_Zfj1hM)>~TQ;%ojdyXJ0z10ma~ z*B-eUk9?w}Q^MOHS@HT8|A589} zbIu`M>dnoJ*_Nd$gL8Qj5A>)NP^);`9%vPD^^*B;V6%LcNj=gl8uST;-vKU*+L`71C-7$+%>%f&Sd$P7hqV_HhYPIv{*xLUF4Rs7mETKdO zw=&)NWBu>Yn z>&c<@_+#vh(F{DTc?(hqN*&0nD=V^WL!BDpUVI``j&<{aABR_8h7)2( ztf}`BuSt|al?IEm5ML%#PCan`zY;9|OR@O>@Fn&avo^vx$93X;LEe~gMo(|7NzVGb z$vMZ^vegQFss`Akq`>d>p0OYoT1$qP1Ft4S@mhWcJbyf> zhg-5>ah3}W5N@t^D# zI9S(XoK6eRItIvu5MSXglI*~LmzvL0&@&g9hp~k%h$1-jsTp_;{xQME5qtjHL$#}I z(A2!*^&itVi|OXnx?&H`$4{rZS4~xGOzq{TYBrmj0**F^B;v*cee$Vzsw2!Y^{0C6 zi`=L7cIS#}Fb-~e1x520$_P6N*rvg+nW~KmjXOni&VyIQT>N*5<6A|ax)(0=oqn-U zQibf@WE7ICRnMu^?rSK{ODzzeKzZgodT=nd@>LhYDp~wRdj$Ge-P|7DNRgDu%jk6Y z)Hj@at+Fd}oEGt*_Kj)XX=ORzpJf-X5?*pj?wkMf(>{iE>R|rs85sKlcD2xJpu5a* z{PMWXHyO33o%0b55M|&pOfPJ;Z$84knLK`HY^!AU-b1(fe~9_u(?K>v9U(&G%utcq zn)>+8nW(8g)FYsZxB+$b9|S_vq5h)5*W{c$(&Ul9pmi|ww%}pLr=~1gJt>n^8U6I4 z?lwf7mx4qyx~9=FnxGTxjoZTpMq!0(X}7B0fG(Nd=yzg?ZFeQ25hP*Y&)$JP1z;&2 zD20(P0C$h8CY@FzqSA6_F*2G&FAV%CGJts^oQuKkNYv?Z8I& z)`y0BFZJJx#$LkSqgXNr{47tSNFm6bq}KZFh&BgEs|4wN_&bw%SoA#P?4sR0XWjnX z8r=ZykLlcYF8ThMaq@Kw5I!idJ#GUi zf^5}J=h^INC)*j%pBxlo?Kx+;NfULvK%I3yY(>%!(h>d;xSEXp?J{W@Mh|Pe&Zs~FXP8pa%$4r2J#wC73e0#R=-FZ+UWw$tK>dgKa3pQ>llUN_Gj=HJBEr)kP7GXUoYga4bPACe)X z5gQ_5fLdPzD>UBYGI$^|DXLiqe3$XZwPYrx5FJ?YhxfqR6YjH8Fu!pWSUi))8vuC4 z57W_nFx%xB=2?={f%*O;e|(3;7SPpcYyJS0zl+(?Su|T_VOE&L{aHGzfG9KhSB76u zO9XKZgMX>_ubfez^Wpq5Ecrf!yyDkn?sK-GsZxv z_zJa2?}Yto>$M$WzRcTnVqD>Q+#kIkgLq3r5k#l(&`!j2M*{1;hdiQLORDpdyEWzO z+B15_K+B!z?D(lmZv!VZ`Z+CBS(J6T=Z;HVs+N^9!uxaS63zhcb2Uk<2_0EQZ>}Y) z+E6VBwRIUr?@xRIax<^mcU~zhdexZzienRJNtjf&iE1TAG%NDH8eGqSMwI3?HhzA8 zJ$#)9Cn0@jvVGdL6J!Z)!37P-7S*R$t3Z$8YZ&%9^qS!eY%G_R`W@TB{Q4(kRK$>) z(CgjyMKde^7w*Je>E`WnK!Iorl-K&a#O)G&A88L!kBuUwbdPhp^sG>@!xo0Eu(4JI zU4=9Mnlt6aX&yt*WL>_T0Jp6w1GH#i1zrgX%pU+8?>oB|yw*Hi6ZXS*r_cWh1AobQ#Zekx@iP8lNj~Yf4_jG)d+Ll2`$F1# zz(}!Wrii%o>oRNoPhhSvD!l0>_P_Mdcn7VfG9yM?S7uqp%#QnBj6O1kSZlfpUjeh_ z(XHSJ+CjfGre%z#AV_3I5}~)zwsS=0gU;-Or0}KK-@In%bnK4oe)h$3l6g2XoswGglD zs@IHz__MotN}s1g7PoP~Hx3{L2VbyV{einpXByz*&+n*9HH$g&HyfP5%o+7!!ZKit zyU_8<6;><5Da5z|4z47vWok$HapuXW z$+JxZ>t3%}5z)l%g+rXmf3Enh!vB;xvK%v8iAVgfVyNF>F>e*;WL=f5P>*|Ql$FGj zH-qIiak>De@oA7K%Whbnz{sW|@3P|}B~a&vk0wuz8&M85Gxuz}o7LH4vzCdnS}Bf9 zt&-Qp&RTZCn7Z?_(fY@D0-#juvYQZEVQMMc>xG_1iKf}DJ+vdZ5L$s-D`KS4-C_(( z^Ohx8z~x40#x6Jh*5;9Qd=|Rb6r2SD7?~tsn>y)8jD|8S8@m7FnY%7K2muoXGmb&% zFBY-WwTsEg;D>0g8JqRJ+B5%EBA-Wx0wy74;M5i7Qy2d`C^CP@str>BS%ufGjqe1s z`+)1Z@Q*WpSLVy#^O_93ScZ2$rG2kjnPA^s5XaX(UhethJCB_)>{^5YqO+FE|J&zP z=EkyQ&%2(t=$o0mdqez-&$(T#WXMZUekj1ekOLCm=pIn_xIWvN=ID&BD6Yx5y7(Js ztqHE(U<>#n8rY31EQo;W=N$j^3YdA0JcX`wItuei%JSp>g&A30X?yzJTV-nmtSqe( z5)_?}ClwK=>j3r11(dSo%tky^&@V=4J&RMVXj>3Bw5F3da%MV%q4-x#hkY1e*y651xS??7Vk}#avCE3H4io332Th zKGBWZGme-w75)1O00`@OlAyP2-cETbbhy~svvd}_S&(?~2~))PLEO9+)Ez{9-G!}@ zXkS6N&1&I-gTJcu5Lx~WpVtsiNw@C(eLF$<$UCZ7Q#C3;}!?=?+oPZd*4@W6q{94J~xaZo1F(IvmBi6rjoUM=ib&8e)v~D zV-a~EZ%Nx$)FY!ZzX{(XBF`y1m5mwF96)OFzE)2P$pZOu7@Nq&#n^esi)X7QWx)X3 zL57*xidgitsn7~{J;GbenXxC~(b`tM(zCe&8?0qi$##?!&3myIFlf51(tXOmvg6ER zT#5LD{U^}mZ+sNK<-ei}jflgJQRtt@*m4&$?RQ*LT>`NtX~#HS-sddPC$$66L~Fd) zv(&f*iPozdHLml9R36PJb`k9g9ffugt0{5GhH@5-j_?>0Y!LHPf^e|z5^PXf(n!)o znH5|RgVdhjX2vK)1f^Y8-pS!LyZweTYykQHD*6!8%7>}{<98Y5E%H7e83{`Fl1I&f zrXf>!W>TWmN=b0J4B=+b0o**S3MP>WJZ+Wj>T_Sl>yC`Z94)30uY&MyoV1gCs~wrX z1uV*?U5RNhpv1Ena;<3|{+i6^{ru2Hc-0;TY6^Q6^zPJma%nla>(}tl=h5ZGRtS%x zznE6=m|Hve3_jW|c^m;XeR}lMkcThq6^ewekO5Lb`(#rJ3dfHed46^M1q8o^YeA0! z#!y1l8>&KCPX86Ha^)3RB=PVTCTb6PrRA9EwS9uMxX8ZRloQcTgrN$Sy`}JA8>d^= zlp)HxSTXbjPaJW5k)*rHgqZ>KdRDz*maii64AKAJUKh2FIb7J^?5y2G?YkrFQAB?COdTA`D}HxJ3&+8$?`twQ z?rWHb-AxyjbbM9%M%nLMe!?>+8Jec!g=a~@J{ey#Xa+J{Ss7+o|Jv9?ey*MoT#Su8l`5S-*(i{d~Sc z`Qw*s>kgZwamQ&DOqb>UzQSL{gx~zlK^Wb5YtOdSscW7=?67_ojc{G|BuPy_7|#hggZP?_7(3d9p&ro-rN)?tGq}NT6BCT5AJ|9V+la3tU(~5 zTDS2*!C3C3L*bs6JCxEvgW%a+91G+*V0-nTU-UOuRpgTzUpHOdQ3rUYGqPu2nF-m> zp@Q4TPF9uOV>IY%*VZR$B1+qZ(eG1S#yGc79Vm5PS~ci+Q23*$fb?0xI~$jAh^$IQ zLuuteFfnX`SBn=`|!7@!}v?fmRgbq0dg`Weep<7uC915d!ZZ_)SbZMj)t!wV(G*u`)5ZbQ=S5I*KSi zQM1bw?V7_9gJ@+kCD$!@1RjDcDx?cKx6LNcYCyFStH-SER>_Q@Pgq z7g5JKiPEI}@RDxg>)}!$m2XYol97$i_!AQL3nOA44%V*20cQvthhahX{oYUrjq_`) zz09!hx`24kv2E9eNj3%p=j-C#%!k7&8!8iR^4=C(Pg+jnP`ppTJSUZSiim*EjcniW z&tI~D()rxA$*n#l3e=`EfU{_ZR69vLFM(vrbPjx!zVhAEr@8BANPoU+6K>MwSD)Mj z5YTKg)#r^=XU7zCm6)lSvqIv*D*iHBzLza9gd{2x7#*^BACRU%e3y--&Yc3afka`tpIV-#R_1c3jG`&UgxIS*U3pMMPRu z4iTp-i4`(AC3$@aa69He0pJkGdBzryqhxTuGR1+@&iU!0C6Q2D(~SSnVQ{jb(^%lc z4V(in677X}&AP#EDr9HgstvB*@s;5fpzNQL4A7yncz`u8CdV=vYK9_pE7;o%^3a<2 znY^3M52p@t3MJLLe4S2R3NtwY=dZ)UmBpg`=^JXn;2a2;DYg;eABQlp%rSFZu|N31 zOmckSis9}508VHb)n2OrMfJMQ~AbcpuFUiEx|Y_To$7V;wJ zanS27SoIc(nK*-3h5S5ENJYxKcmI~1ESZO~m6g`g8Gq>oO;7#}QZgYVn+xBJvQ4}a zOQ(_n8N<7`9s%f+TtQd*hR`LaCB5$;UqF1&TbkV>#`I#OD_UMbF+-TJ561CJ=AC!@ zz(r4jFR6Ld*ta%F#CVG28#WfbUN~E95=r%osnXe zVWvNyVOaWOkGJf99^2_}TxcenrD+Z|%b={eQ++>zTk+Z7f@1gV%WXQI!95ZsIJKqj zYa1J1_`jQC(x3E;f-l7`bG3n-sr<@+ANkLn1*X9L^Xq7(31VQFT zd8WcPMQm4 z%F$!i%`O5{JH_`JG8ZS=l)RugXSgfklO&qGvO~DG9sUapL*ptIisp%A0b! z?yikeV7c|ca-WV2-N`!9R|G5PN5zssoaPbfUYSoi7AW4%|ekG@u? z!Lzk8gqc&~$$8<;iFmE$xyA>D*qW;`j-FdTb{(3VfR)ha_vopuIWu1^-XZ6RCl4z} z19I?iiezb4)`^FeJLSl*GB_pV)6m6$L`|K(Fd9%di86fN01Rt0tvI^l8f1Kyd0=VK z#nttW?hjJPjv8C1gntyyps?UAA9r=Cr|k75?Vqu7p^>0{VzJqu}kn4mj?X^emFkeP^iz1_wae#HQ{Ho5*lNk+BK zb|4WmF~?tLUeO{QJ#c{&L=T6h5D#t1z}nT(FYFwe+G>tm&=%XXrNO>~SK)LJ`=VPs zq-9nxvo|#0Z49yD=JGFrdpSI~HocH53IJa!CdN|>_dgHQTDa44bki(+7;NO6?yu)R zzZ&3{me_9HI`r^ey-78?MGn}eGBTiRV)@Gsq>kGGjK)i3>`H*aNft@BRBb$$f7B?9 zqrpC44K&nU(ZX1tKqVIH-}|dMA}Awlen=GegfZMQ(FUa|F?AkmHlpE7@W_ozNLtpB z?AH^`;80itzZbp4uiI$~S-DifrO+TF@VHWKij?ub{wuyDPwFAd6X6|* zP(#zARpypxb14@ntKMBfh5?)pK=H!AglD(-BiuB|H=R$iHXsiDQ3W9f2nFyZ995q$ zs4z>4Ujn!OZ{OIuAi`m4#X>7&Ct9{|F0w0VbV<_SwVAzr|~eQJ>-THt4iVnhTf1}q+#k0=UCxsS0NDL*sos8gsc>$C{IyXhDjv`T;4 zkYh4G*}v#hwC--hql0E0IHiZJ?qY}v0Z8xXSr*l6LwlSUS847k7?2&W6@>D)bL$5b8F9(;=Bo2Xg1>!iPJSX>gBK6Rk{luk2S4{?d|5I3HK-J zOUVY}*Be;7VEaj~1c9Lx<)td#IYnLTy81&zbzY|9##gSuQ1exfojuijSFb)_$;~9X zP%S+_w4D#iq+c7YmJqKYxp{rxcL&yPtAt}q*s$ehdylTmM>Mv5mXBX|qHO+hO8^X1 z=CnEvs3KQwvKn;*MTSI0XvUjg6$)lG(b3Vc8i}|s zm3Fvt)F3;ye?r_TsDO+E@D20_Fp0+@#63y>k88<^S7E%!@5ggp=gYay^5OBx^<3P~ec%7>w^%xTEDR9o;hMC$Km6*s zAEtSr>%bR}UNeojI8u0plT=L+N=ga1+{E1eM7*M{4jYH75Dyxf$Dl&!&s`dR1D1iqF2Vw_}V_z1vilh*xAK}^oiyg=d zrbUw$`9?0FvugJF04iOoOw1;DFyHKH7%mQK7V+@rLq3%2JuTH2F?F`)FD%!&3c01o z0YHp?K|s7aelNt;TN5)}`N1YXZpFF%ULqtAF-a&twh*=DX>3$y#X+FcRr1=qHJpAb zQ!j01X1(3u$lAQ}G?zH)mI-p*#E!EAbR(5M!2D`=WJ5l8i&*wb9S2&Wg;a1{_9aiJ zR=d33;zI2!5V!R08-M#lm6x$>c@d&oG~_4O(ACEKQ2y(^ZcYMxyI^Z$ z&T*hEBesS5c={JRlPdO`u@)&W8$w(wHyjEE=6#`T0_mxRWcg^9=yIt#bTS}LUCs>p?^e{->9DVZdce)liXT@ zj3-V8XY^JB9GU;@kyQr%x|fSfNz&(aUjzbILWbN&6+hU1iremM@S?S7fj27s-HOr{ zptc!eJZQBPsz-|e2cfBVmZ0kywIfck7^Urib$ryQMav7u=CHD|Tr#C9U?u;*X;&u4 zd|<>FDj^*NxIH$%%g!a^Gl8W5W(ZBUD*=)Aa_$x8_k@LJ$FqO@BTZ{X!Dlr80cK`c z88^qXY$46ovIitP#23%mw*q}?47pP1dVWiA_z25?Be(pS{d8`AN0&h`|082TCZ^|l ztpzbOOBAd^UC}$LdS3JLVrU;AMlxL@SLV)3<=-^)%YD!{gFZgL+WWA*BXegAO~h*t z5xnJ}SItui7XPyViwhR#p7LQi*RU;V?oJSi#V4N!Rwp8Y9!fvYhHfBP@7RhZa6xu@ zQ6S8=DkLNers6udm#nKPP|wi3m8)XA9IU1;8==>b#R znOV~V`EP%lGEqh-Rw`RwtC=ExwHoA~8TcXOR{NjQ{HoC6mNB~l6WZIATUZR(l_2Gg zuH0_cVt}Jv6TrvaFF}lJ`Im3=kCOTpMg_nWeGe4!a(kW6T!{KyW;DE0qLZ)d32yeV zzw1&XPuuqh5UY1ze|lIx-u0ke3MttZ`DeVN=>tIK*?CAdS{Qj?9pBsB zPHZ+6){Ad-Yj`0H@(44v?@{d$L)`x|O~Cn(pLM~K%v)za*JpU2b1u7|zmRn?jewuN_`OLbFU7fc@J)8D40HB)EO`=&S( zPsKCB&uhAbVz$V`kM-1Sm`}axG~lz+_94P^@bn~MJhlmW z#Mi{an5j1QTD9^|=c(BP?xaCQM#;kEzK5b}lf;FEP*hWv@eH;VW8E~RH2AZODVs5O zq3R2KBG@XeB^25UDeogf!6yS9sqnYn4sLi@~SyL>x-0C5TeU1+fjh#)CL28q4+9l-y3V0V@TPqA@ zPohp`>a!DpYf5)SwQ|(r$uM?4y3484*&!=35UU2b@X;`cu3g;RJT}*G-d@MPSHZMC ztOo(44^6k$wqRors_)dnLAc_D?dWrfKVq#DWV%(p-|U+k!4rA)glV*-0bPy*T9S+k zr_(8IP>F`w_-Z;TL;YVcwW`beV-~`0w;h|dPgzF3H0oGYto5E9qIRIVk49$4?hi%j^!OaMl$B}m|;}AIFpcq&V`l( z`N^G}T)l{3)JhD;77pT7f;3E~kAY2K`{6qGlZ3S5TLUr@{|VL10a$K5V3`dG(^7Qb=%-&ICU=zc0?=Jd5=HYXkXZ!)g zRbFm`ZC(#m<>eA}EU0QQS4ZUv5&7X7F?2aO-Ke>6L+eZt=pqCcxO?*xJhfvFpl3D` z9=q|zejZ!;yZJIFKO%kPZJfMnTZrF&{(f`9)Fjto@s(v1>;WX5d?i)yox`abrh z)I1C@&-#^`Ni&V8+hmp|dnpe4#@@qu<;n|3Ni%y7!Y=^%@G>JSwJ@Z>iKriGCC7hCcv~sn;T2fw2>Mdi|l7^_Puhp7I(%?$fInw|qbC0O~Vgo*$dC$BucuKY*UbHY2I$T^$F>&AG{Lod|Ar{9;?d&^{&q^imd)wKmAm5 zosJIsIb51bo)V}@GWdO8D!s9I1vZ)w3|gro@h4iSa^eRVeUUHr*}kgLks)D&cP0Y% z&e{YgR04O)kq|D*K!Es#s}FVs+#1~&$oC+5{siO~r{zYm&8d8K_F#eS6vW_6lFHSY+RgUhDL@ilhrwa#4IpO@vZZDUGzp^GhZja< z^%%b=)$tA6&4dGR6J~N-EQZ}@hi3|x&OVe60GZS(etVoU3{j7eREpCZRmrK|DgQTz zyJi`Rb8rTfIDTt^G!bKt*LgovfRY(%s4Frp<+q-^LhH<+g6|}x%fyS=%J#n(2Q-woz9*G zR2A{yt37#_)-mF*LiMFn1}j&B)|x0|U=zkOv`4zwY@&c!ZQ4|0v0;DC!0UlCW|pGl z65HmUO4Q65j8Nch+MJag!}-=9*5$w9@~gS=>_q1HZ{z{BO+dgTkk$+msbgxAMk}NJ z8edXOlPznyP!}g%{H}MV-N9Xd+mfK~FFAs7ol%k8embm%(U{aSdB0k^y6R%{92aq_ zqEo)?NI{X{m4|!wnIQg~dbNVfQST5^aAWp2D*KMypKL9 zH`u3JGWBTB{ix2^SI(cWnNu_oNeHrBIr<&g0~HqU&J=CAflwWUt1D#8#Yb$GXNm?$ zpZxLGWZ$ok)0Yx|B`beZxH0+r_+v&32T@o_$}t(o&zF7lOVO$@#M)Oj-q68@A;opi zF=DQ2 zALadzkn->wEoY#JUKppToE}|tW3V8nD(>||Gkvk!|4*Wx|NAbnQ&pW;KK?2C(YROSHvY~!SN|a6SK|LFx~D&Ri04v z}x23v26_;@K;9oq=8Zb354M8*_&KWS~jdKrxo3}U{Q=v*In z6AMxJlOI-6vZ>oJxc8{OVrbu2KqOZUh1cd)fM1FTv!j}W+lXoIIX5eq7t>xu)CB(C zJMo;MGm`cjJf_t&b&TPdg87%&UU-2ERY-$v;HkGd`!MirMm05Md&QVpoAGdJqX}{T zk7RrOkXi$Uo1w=np#{ojHB7;8J1=J&ZY3@gN#pZeaVwzp6p*9oVtSIuj?~ z`)`3>^pWhXez-d7{@~UkVdesgE2a00Y4k?lAYQx{bVR{Z@X;B`X7a^!qB=0gz6MTX9lv> z^oW!zGduZJ&iX0N`Y+S3fW&VmUxBSo1Mh7eSh6!|{Z!E15#|>H=+)P=MjCi&po9EZp2o6TA^B01H+v1DB7f}eR+_7Wwi?QgBcJ5upZFi<$-9U2zjPh zIKqLu_t5qk4%fPO#Zl)B>?Y3?Ml3ff+hTvYkpeA>?UWy4Ua=GP47e4~ne7*r$Yi zoPYcABP$s!x29Pfe|ItCf#t-6HNBcEg=DPFpj&|{zt*2L4LaE9CvwjEegVTh?GW*Q7TZ;pbO6+7ZSdIug zOe$e;xla~1gV$hNmmoTRwZk+#H5=DOuAZoNZ{NULT={M)CSa6ViBgn96-Lg@4~GKH z?Cty&V1RP~K8U!6=m;LkrDame*}3M?&)h!T(z=ox_bLE;4uCE;H5&5;EtxHMKuVGG zq!#|U&-x+K(Uv!AiOfxGC@%)Mcu*o-c|d7MnW^3;d(*yS=F@oF4^w}MZ(~ERm&Y65 zP#90Z>`S2lqhQ;hf+6xAB+H9>IOx?{&d%ojhTN4uv&bHP{svcIJ)1h|&1oCr0tb-?8pYfSZ?SDc@1&B%XFM1mN7Uy&)Go)!3 zpGOrr{_~6Ksu>0O>bnrT+onoIL+a`k`_Q z0M-y;%hx2c0C5k9h#jW=eS=xheD9}=bGXhijwVV*xhl74`(STZ@Dp2^it8DF$B|j*2eA*6|J;Oi(;}p)FKy=G)8>Usu&SCs~ zP?*+Ms8IpL7d8@^)KGu*`c)bIm!ZO*3k~FxNpR+si%7PuWqiJJ>W* zQ{=cmMDf4?N3}egM?Et++UbA_P_y@fJ zmJM0N#iv`@OAyo7iIowl3d|r5@&f?|axeBjdkW*Nt`^fjet*-vOch(`TCEz3b7gz; zO7|V?{_g!r+WPC$!N~Tw7rub5~ z-;V4!N0&c}Kb16cqc($LRpHAUuaA7i)l-Jj(%OM2znsdLaG$4``s&Pnt+D)#?Lm)M zvs3_2Ga=?jnsLG^PeZC!Xp!W$;ADWVMVmQ-e@?I|RKM9^=f?TM0z=>X?x$YU3A#>V zJ5S+ig_owpoK`4SID^IO)FmZS?EJrwDDJ6T7QT{A_xr&H-}kEnIEl$Yn$4n|G5^=M zMc&*3$NM15O;?aKIkIW%r^SpzX}-+P@Q^Txb*k*QZJ=rS0#I6S9Krk?53HcV7jxWx zeM>bC>Lq!T@*Rga7h=Is(_>r-9Bdy~sGshoDsOt8W^sa^u)jZvJR z1PQGe;SFkJt#0bbuI$$ekCXb^0&2%vf62FaDn(CxS@4DLZI=gwEkv~k%f=6GNnWi-IxWi0+JQTo$`4gjUh5vs)LV+u_KVuVU zJz7mwc0)a|{42jq1N;J)_9B(0CKb|$wNw|LDrF9OOQq>h%GK!J3<7JBZH2$VwxIH~ zh>lX6`>9E$FzH`C(Cg9~K6kGF=*M4edZm9QuH<^jj}0P9d%-S`kXA@BucV1dxQ90I zM2xBuk<-SD*7E6gy3`+4gHDeA+^G~#joEenT94g>%hDv*g=+38poOr(jO8CuW`>yz zBWHk%XXXUMG{SEje3EV5OkrSN`-!j()-W@NFK{5_m#H+hdC=IMJM*68yC1iaG01Wx zT@c{7fEbi_n``74UvSLn0CSmu_S_kKCLrP|c&s?4shZ#8e&FxDKDA4jezwL(B2$_-XcGv?!iGATM@X483t&!0>C8) z2o?cRE{ynX`eDLJ{Fx@tHvp9a$Tozaxky*X9__Ae$ZPwU{N$U7@G4J2LkF>6dG&`* z=Bc(So5?R~7xSJ9^M6GHEBp?s3x9FBr@Ga-#r9J;2KYQg?2ZBDA z)E6M@Z=X>2x+!)zYCFyj<7rvIEvwhOu0DG<{i!c!*!EXL22TCPJS||x%tUsTpkjI@ z{z&ozOb2Hw#lUNF91rmrNJKc_ED8{+_ZNcytoVF8S0Uub%kB-eMoSl$*a!|TXjYlW zvZ7ng#;4ft|IeOb+mzY|x3yFSkQwE=CNmu5@x_4C;)x|Aq=%OM@e_bFq?+FDka`jP zw@7craJPA*X%}*QgLNmWc^B84bw%YOI&f}9_3+MU`+dS8;% zTt;R0zUHq9R0Ax`Q8Mpm&&{r%h@lR4UT5XkfDPlO*NX#ga|<^c~TZ$t~>vmFCJ`2jLT@ACdmk)9?^*|0S0KYOF<48&Gn!9_lswe>dS2B}!GwhUswFdem@ zS{|+sC#Km=ANBy1EZVeUSinzTspLIYiLJ+CB+7OmW`Ot z5DG~l#ZnGe=G8?%```L^7>ifKADnPMo%+-KFRnvaE2)<@l-%=*Z9UCvZ<0|3moFB> z@;fgwp1|L+`tm}LF&babg=uVDJ5Z|o8J~3BX#=ss^_?fEB44k)Z=Y5pUOw3133DwlRCs$4 zVfpFgF+_LZI>m%7u344mTG;NVpcp=-6{@_R&p(pKyxvWmx<0U?^2&e!O~)#ZarXek z`mEq=X;Ybdx8fBj@{`hE??|5fZR9htiDh3T(4C>w_=_9UeFlk>PYoTq=g~s8pA0E!i1wF(L z!S=9QT7beGJ9cQHrHOjko<>G6;{JOM^vpFLXh`gsq zfKEsa_BjuYP`ZP0zs^=}eOr>M_0`T0fJ8r;`cNwpCnw}55`oYds`NA$RKaTOJn~8a zZR<+XUKxH*m%RSBPWl6A9qrMDJM*$INIfUs;4uO~GqpDbpoO>GO9Bw|$L9ArrRj8t z8Q@z1j7SrL*XT{TEkWMOqodE-zbtHTl?u#EmVj{vEmn-#WtiMY-^ zD`v;iP~w66f8)=MSP=o)(yuQsQLCi%`|0x{ef%A426&okD#g9Pe3W7Op+R7F3U2qS zaV#|7y=vk3?I-A|=T16hQ#HVQ0FE1hyx)#vz|$$1Hbkp zb{t4HVWy%(8O?pIpeqb?I2Lq)dz+A0>L-I()nis>O%UM0!pi-*DY`cl(+%CrP^87- zye?Ykjqx>IIaUzwLxcJ>dOsl+q2Zwhg$_A&3%4C6-L3s)zq%AtOHVwBWS&KsK8=IBS&u!PH{&{g=?WlN0Ko$l00Z8d$q zD-8``B+uNNL6d!2b}{_r*iaDl@`A#u>$#o2VBQDdvy{N)(7?Dcf~!YG3sy`bUxwp3 zx&~_nkMD@>C~}Mue-QFKpn>3aEaWy*rX+RUzLz*96-?3zsL)~|Qzo!P#RK*gV;AIkJHfZDD9>!YyB~mSPiKIu0Q0~CxFS2*4+^7V1v^=G8vpKqhSvc& zdj_RV4o9K`eT2i5_dTovvPs?ekJO~{A4eCG9c1)V)oG=4FtN*Bz(n-Fzon?Yo4_A*=*40rdZ1&QUGqrF$f%x6N5h*R>irOM%PqV zYzW!6ikQR z81@k<59}lYOA2|It>PE24UNBN^~AZ}^}>|Tk_i;qbcx_O&j!>|8CoA@R^d`uIio~kK!|{ag&79^p7DI0w*S%4pv+ua)`VanB zQtk`@v+0(Ra8A!`$S#Ae-waHSw3IM75#fk;bpnpTePE;bi;N+uD(!K)N|$kVqP ztCPU#p2q7I39Y0~Wxv_g_*|~?W(81>bMDz9M$r3Vcp>h?x m^(06yOZ_c<{oq~ zyN}h&L-}FHv}g|VVTCPIY}V~(h`9uriG=+ zO~^e6L0~&y<(@k>m2-t_N*yts%s;7P_-_yPkH}csj9kKa>l4bNWMtk9dyc4B{VDg? zCJ4uZ0jGYf-G+pVXdL>1A6Z+kU-g>k>Ox9#u{YZWT6)dGGf_@!*)a^F5eA#LRXU)tW4dx>Y#HOG%zXylB2oMk zrU5e@tEW;Tne%lg4bLpj2RXVa{tdm|LYV#}c~thlL3SE3H6nTVINQNb=Jb5vi@lyB z{HGa)34h-=bdV%&ZuLSJMaZ%I!xY8_3s=r|4Z;MrP!}TkXW^I2Otc=bV`eBPrQ}W< zdY!x0Q8D>t@|F8r2THd{EgGuSdA|B5;x`5OzEQvrN)(wGJDskpU*eIiJTyB3H=vrH z^pGQKFGR0NCoebv*wvN2XAfFFOMNXK;Ih=R-fWHUGE_xnSeveLA1QAZ|y|o=^?D9;XOvzR&O2t#GORYZNlNj+wM8n z|J07JSrkP`Tg3S(xTB!2EdJ$G&H=Te(!2jRnTG$@?@kUV`?fdDPaa;_rl!+asNm3T zarQjwsLfOL2R-tx^Ol7)v($oloyZ9^7#t zFjF)|iS=JRor}%y$^D_t0rOt?uzhs*+XmDNbIUQurEz?SbuY4tutLqg**{C#?Dq9E zY6Az~SlytlUV}V*2JimQo{_buTT;$7)xL>h$ui)^`${(rA0P7jR%DR4f)HdcYNEzm zY4-yAT9`dNwEW7D3NnJK_*s4gz{h&3z2AM%I6cZ&3Y0nRDQYLRb~btqYHRvzH-z*r zjXudaKfb6Xz8irl2PGFDI(gP~%UpJAXMvHrjvQN{ZncMP{eYqm1?HF?_}hhen9ip3 ziS4EuWQ2NT#M3pa(TO{yo~b;$YOpFgeM=n3d}ka{)94R;v0>K)E!=Pk+2H16-80t% ze806|wH5~h$7*-aD+)={b2rJj^{sZ)PhRv3$Uf)_Nmi^bjn0=EYC0zQfcqszHk`Qv zrGTV>>%>x5-f8Akb)B0Ty?@Vx8-x*pAXQkVRksUcw_V|xKRB?k6!iFoQJ|4mM3oM< zVidSEgyH&m&_p_>V>IT1wniM^_`EVSjIm#bHGb}NR zHW`Z=L)PiV< zv5YqyC1Qm(RmX@<#{;U>6E`qZwIcumZut zb=mQ*ep=BQ_CB&H!4_|8+B>7T%B)+jYL0$T!b>RBO>S8-9Ud*h`tK4%|Y(QzIh#}?%X{6p+Z@pEt| zRH}YSN~~tYF*9g@+?U!|A4fwmW>e~E)Jn_tFN5uL=mL%ExL-WM<`UL#5ve|cIyl@i zlV?`nv8&AD@=`Y;klLhEUr@N>EX#2W1cuo`eeL)-l@$W2`CJ+6&sL3@Q0KWx-usx0!FYJoI4Knc)O)@dyNEM`iZ9v9(l#)>GAsPRf6Z~4 zO1Q7G91!E9XZ;6;mB!x^na6WXbiy>Eqft_ zgKLl6`f!%;9{=jeoBew{*sPn9Ya&N}S(|o{Zu2&1nW#(!w2rT+tq6s3&P^@urVJ_7d6GI0(yJbMA!|&XAoc)Y zWr4BH(&i=6xwbRWcH>0Bf}h{>9GgVa=P$#*bgt%wSoa}MgOs^ID*A!wrtOJEm23hA z5o!aj9Qz<|fD#dY6s9_PNO}5taA2GYG<3O^#a=6Zd39>!@ub&(_L#2UB#Z^{kAwmr zG+J&ySAdb$j6Ya2tkxj$Mge70308micw*NNo7>=?!_K8X!2Dc7%IQ8|w^tQ?%xHMK zYT(tHZxy_=ZNsb71@fE&Kzcmc7seN{wOy9nbaSd5aS-ja(t8t}3^`Bck4|Zj@HY&o z$P-K3lBGCLZ&tKI%`KGP8-W)Ph=IcACGC;9M-1l-{eG6l6a{Ey$#2X5M(%ZCiiG7R zTN(d1XFY!6`IiJkTDx`MZRlUFSrHrjn@~=P#&Xp?onU!3iyH_0_9p&{+R(M8Qixc# zl3E*#Y%V3UZ{vx>b)sv6KtfMf<@EG(v=L93SEkA00T_(wPmHnq%Q7SR`9i)5+&{0* zENql`OE?&5o|8;ieMHTTjw@UoTm>I*xPvuxW$w3Z^z4QeI-0yO*fy@!4Ysa8bRa8J z3pv-|ZUb=B{AY%&kf6P(8ah@soQ07ZYy{9v+k%iq+fO4T`=>WFm8l1w^Cn2&*qJO@ zChRu^B?)dpOXxL5@XHOx^1(j93T`bgL7(OtfvpR+?PXu*YOjsoGgRx~J>!)VT>smg zZL%gf9|IGojza^O`r)##JY}_3+b@NXT9JE^(}0;A*ZCU-YL_>_c68A4{gn=4Sxhh? zxpHNs7BGOnY0^L(#bM?f>LPl79EhASBy5NK$^>()+T-E+R9IZb~c${ne5pX3hEy0EH`2Cx@S?y;4 zL~~>HWoS%T+!{c;>uc>h;SS#SJ&O3BJu(fp!nGLty?Xc<*u_!HI$F0t#s-DFpMOMU zh7hF{Ki&5}!?Wsp=_7b8?zWbKW2vc+qeu{-Ecu^3;+k@FLbU8zKm=Pk5pQ}m^(kvV z?(Kr~op(*Pva9i;O@W~avxtJD^Ifh7p;~kiA{ibLU!KF zq(QUx95D)WcZ3{~IlZt7Tu$^ilv8sOUmfL+@U4bsdavvHi>93%t_^t|`adY>GOzR; zJ8QZ-RMaeRuvHth4;G3KMtN`|<%FlW9#C7_`d`fR!}ri|(hT^0gJ%I;o;ep4?OP}- zm3ix4hd7(mh$w{%@JcZF3vk6U=D~#AVChD~+@*eFmb)-Lzgnh{0F(}|k)rT7gOnDE2*!!g9!?mRdKcl64MNw;;C~XJtuDqB zvt${^6>e9y2zlsp24xkjawq)Mm zhX4Ek{RzP4B82#VuDNd*xc+dbd;7h)*R6xfRG39$LSq>amTAR+=S=OeymewwlbnBp zG%coRX#4r5UP*P-;+?_{rs+Fm8E>Q^bzQTFJk}l`6JH+@3c!7*`RM5^l@~U-0ggZN z{3JoKhtgaU?@9jfj(aVef`z&SV2^YU;FWM5DHlrH$IM!qh3*Q4oRBOKs)rfv02eb8 zSQI)FAZaMFJo`5xhXCOfMqh%i2-O~Z+D(0_KfQ81w*Jjh*|P|P7ZN8$Qw-*AEB(&c z9T74cg%3CV7nHQ!LKufm)7#%6E(iL9Pq81fs8WTm?N+J%J7qW6lg{sHDTl$6-k%=c zIuMpt=FzJ&sX04nx65*P9NnGv_a{2TV`K-N609L7%fAF%AFarW(qtyef_*KN28#kT zwYN+jh(soOs6c-#4v-%u@~Vt0=C2HNp51%3s8GQbt#O3+vl`_K&7v4FA*0oRRRY5l zUF%$s)(ld3(AH| zg_5}vrq*RLt9#Mv`yG;$^;DMhey9vica5_FbZ2t+dt*PKN_tH(jd6PV> zIN2Utuypd1(tMV_m|1+xkxMxRfC$RB|NGBnxz+xCe@$$!kGl`;G1EWwf9rYjK>rkK z+ikDB*eSHeXV&vZeckxx4*_Ru96HzOyTkq_WmU+JC66*AtUbqn8FbqkKcBx`32v2Q z6ugQGfTUDV*hRCkbDITT@;j+{#iv|*golY*@JS^(#eg&9Zfj@M{L6bGPer{Z`PgVV^lK(R2E#Y{Bh%=Be9G!GeOWgT1L9|HR zxQy)<8SiEpC$}(`BwzJk@9}!H8%n&fDo2B0wvQ;p2kxXcM6vRDXgXgbQ0Y#!*LM#s zVC>O`Hd_8o%a152xYFz6HzAwg^B`&NZJ>12 zottfN6I$QVWwbEY&?k3E#Lv^uWB%5O^~PPEG95+Um|o3epoytdm-`2d9h~&jd+w~W{1ixYOx885#> z1cSZ(L6;KRR#kP|kJ7VCl~-Zx3v%?bnKi*FN4N?*{yZUUtMwJ?k5tkjJ$wVHJclY6I-jOiKff}Kl#i-k*e$K6cc`*|81SUo0B zh$^3W>}(E0*IUl)+LwFJ|4ba6{6LH%ePKe1P z+qcZaQRg`AVuWer7X-#}cbsk#qQm9WzwgIFyepim-Y?$<8?=SsMj%7)GGdove^M~`Z074vr^jo8 zt@|vxmlP%b1_TU@XMbLHunV@Y-9d5m;Zk*MQ5v#}`~y9@J+O8+Y%Ye7hX_YDX(FL? zIo21pdI4OV{oecNAjJO6W_S9-$+PV;KzoJ^WBoFXJ>B%avmX@Za3I7`C5ZlY#VfDJ}VgHlVv`3^T*`6 z@Q6s*b^XcpU90$!Wo18DG7L^KV0lSqnL@jZui12M$*)jdHU5-)Js;03HJH-8*D7f^ zbk^3%#W45Q8I0Z&#KIdLOVpVH%qz#J!3;VJzHD*Es?Z4Dx#UZ!@G5gJfLkyac;^Hi zhr8l6ik$aE69fs_WJGYGoIs3H$^ltZN)#Oy3iEoIk_dA48|x=cPj0?tBh3?b`>$_o z(AW{7?VOW9JTL-j20FGIGbrJfTlIeD%moE^4h4&n@lH3JO>kD%D-uYcTmiex{6Lip zwOf5$Q9y&%x&YCQzf#TIPVjm$xcZuS-*ml*x#sA@@#FXW&q5#;FeJ20rBRG|RxQ(Ili%ykj-jsB6fQzAZb>yw^%O0u%vR*)mlC zqPVzqAduG9KaM(2Hh!;uzokYtduykU;|;vo952rw%=kcVq%As%8Z^7JD5`VxBydV# zKG73Q91JWnJrRiFSg}^8!*sWWU%^`Xt#p&`6uB>1TIPBK)XxgYz0WV+l&YF}n6HI= zy_I?%CwTd7z1}LSf-s!{+V_j3Vc+v6$3%;P6jccY`1bqk7wt?w=*xW}o!Ch_wY!P! zUK))|M0I{G_BplcMa6UC8WZ8Nz?ZWnJ8R$-XYaI4W zMfy_=R|^V?TK=l`u|@X?>q;v_CO!)r{T){y%af&DGDg*Bu+#X!8Zb;v8K6cd>|&F6 zXZ>-FXwZ6%g2(`#!R9fOo8GvWP1x|V$!?Dw-j727{l_PLg&u_wk(IX`U z>Zo2MasK+f3a#gR<_SM4{B%7*u~UGKX2WytSxcZ&Z~Un=+o;D%9J z%v91ro`T;?sl+J8yfWllz4+$?Afx^=t=s$dAUgOmFhTC6zbbwX!4pA_a5L1ToOy_K zD%^;d-{8l23<06@4ZLR{hp{K3I}P(t;{(;8qx?Ud)SHzxS!1ZR3-Uf)rf)+?E!2&} zceRr1>3`)Q@4M$TgO(^;g-sKI;8wIO{0?9$-uQrKS*up3b6>GDdSMVx3EmZ&R$ECT z=PIOG#lv1_?Uhp&F=By%F;j(Qb@=c_{L_rrM_9+yjqPuaXvAAu{{%VUHg1-5S!PEK z&b-|c_|t3g8wse!?Q8xpa$rN8&D^kdcg^>77#*)~wEaMu=bxrwAb{$dw$iG!b=sxs zT-U!!0)dQ6Ud8p>xs&r#>cqh(HsJM%aj#b^euE1r_$hT`RLi%%4eqh>I-%)WHY>>xj86I68MJyn}-A5tGl{iu8! zNVeYn|NcPzPAy&9n|JST<)!KV$L7iIrv%JmhX!Av=BHJswsf2ZauV@YnrP*HUlRia ze9R3c*8REo-@`Rc&a<9CfX;P8Fxw6gZ>W1EA4}X&_bX7akh&zB1%2=^;D)|+?Va_R z0CVqJ{X-62t&uy8MTa7)02|1+ZV%>nii(fMNp^X(5%sMglU3j&#VYm2O*;X|VBE#( zowpJQ$6*r^^!e)KGWmxV=nk(D>HGz52D{Pt;&mxTZuiw4?KnT|9|w>j(n*aROlrN> zx*iBKzbM3hx8q>AWPn3#LhByc*GSo>%!g92K#TW3dlv6%Dkb!CY~xX+x{-s`IW1Z zKG@Q06P&%giim>%GU*A)`8#+I?VMLckxA@19u}dpID!`T9o0Mp!MQ7@3u~z!x`xhQ z$L%!yOMe<=lgXK7VTZ5Fp7{Mj?xLis#pY1oP0?pC1x?3dvyEP7x{;uQm$-t;T zePKkGkCgi1ZRD(1U}h@`FJD_TjDr@(E_X^dBz4VA_6?1^?L7TGzobYk07Rzq%}>&s>~v_EcXI!SrY2~+Z!7F>2|N&xn?kBPH#b;?fB zt(+sZeUoeUzGc@6yPB#09u`+}367Qbgh{hn!5MwVN4q1)I4@&gNTO|kf8oHn-t6dA zf(tnO7u=uSn9Fvw9hlNHGLvcuhvzOq0XIm2XwWHSlQcqb(VvxZ62i_jZ@zaaTD#%P z79Yo6n^8OAAuGtdP@4Zje%#TvCQ0Hrx9c})Nh=a=k^=<$X9Oo5l;E=HJx^Nvq4Cg$ zy!I~x!e4mGbAeHUS~p3-ZN7ScvKw#aKepHF`$}WC(Et*!b*ob-RmEtHe}WUF)$T0i z8DUVf3SGt?;EE1#1-^~;YIM;5CKtx3gT*!gI8n&sI<_^n?-X2zc`Sdd!7%U9-Jsn6 zqrLNtYHD5gJysM%q=S^GC@NK@DJ@p2fOHH9D$)W8Qltjr0x1F#igb`(Lx@NxlF*S} zq)0+X5P{GMfs}RUx?k=Y=ZOYWAR(NZfBoNZdK`MNL|p#hMJZb;@L}GqMa0 z4=#hd#|E4S)&T4U7$@7_A$rvLEfhEng1`gS!L(z`0B?-8GU zp;Vze1-XvDrVF6SLshWq)UaDpCM^I3Ma^PXaMUaF<>9oNonwkFLsFf8#P(86$JA#o z6lC9ULY{JE3*ds!e}l~puful7#Cz+#B8 z=YL0F1<$52*~0>MT(G{W3HwHj{T(n?ae=_A0Y=-MS@U_n?Oj-i_}YU%2mj(WiI5H#D5;uzgVUEHv{TO5M7 zM*0j|eDsx@!`Cjz2}@w-(WDQami4qx&!i4tspiNs6F=w_Gz5#RMysQU&DogR?q~lb>9MemaqWke@e2kwyJ3w8>6_}=!oW3 zm3=v_Hg@Km{jGc0qOWDL-s8Q5O=Ci&3bHkejS3&{09AtC6P)G3RX*-$6uD&k27Pba zZ;)Agq0tQp7A#o&x-R%NXA1ghSRM!6F!u=gK8mzm3_M%vX0c53-cgfco_a=epxZNw zg03RoYywrdFAC^Rn^#*Kp{kr`=ubWmiVu+y4=&0|1m9%g-!7HxIEZq$m6y=r)=nd6 zzo;d3D9Z$yA)C(;?A=71W;Tt$F*8C{pm)>Kj7);#fbi2tb~#j@HvSMjTq8j%T-kP_ z88u<1hKoOW^oTF_r4>x=UL5S?NN4xd>JUb_B|TspO%B*=tio;IaqcQjwjUYD3LZ$Uw%{%5q~8}Znf}fVfai^ z1{zmPYpfX=YEk+HlCix|kInvJu^*{4pKrM(!MSCU7cC_xvt!y@Q2PE<|2i0FNW3QE zuJ`ceQCHq7Bgo&13H{wz(m!%udWgw+X{9+sGq&3W*{7c3H#_@?IS%$Vx){hKS|@Fk zcPMOuPc6UeM_H5hq%!?vPF*(vq+9#*Kq_m)L{?_2i{02LOTpe7)ilDbRU29NdeT%L zl==lMnW{Or;%K1T*EE^$14N^UGt(Oo9!<4^1#cqybqf4LZNW=ZH%|>fAk>LQ0byg} zz`SE9Tv|5A{AFtN!jj3ewj`#*5}4U%@#&U@bkIjmq!;i!H4yAbJ=aN&t(YGM5~7-4f|Y|d24aBJ4;aFD&iJfx6!l(=vz|~H z#gyQ$NQe&HvW*9yQwX#JWUo`s3w=UYw8@U`oA zVG(BIm^B4q_H->Y!dwe#RXA$Bz7m2$#{ z;TvC+TNn2v<#!4ltUMc0Q^$AciWd5#*`snqK~m8J#tOr0OKa^JO^hx&!cVf<3QL#2 z(ab%WyH4*jNoSt^MY~KlPqg2hiIyh6a`kiLo%2(#Q=A`oe?_9+87DR>osG z=-P)C5elRa8e4{waZ2bwPTjrNe(mQsk{u_qRIQE}XHG9S58G=mwK670Zdra=wRPf# z*&0G!S_ceq%g!lr=?Qg!Q`yH${VE=>VYvZ48%owiz17QEl_0VZHmGlgw+x|`H`$&TU9p z2UX6*kXrm#wXTNI?=r1}A8hBSqf3CUXbWmSwEg1^+BO2uU9B}pzqix>{7Bp@b?P3r zOMacJWxU<$940Ugtl8z8R?VgY#rX-_3V>(7sF-!6Hw-^jWG{12xL0pF-hsb5^3{*_ zhW^y5<4eQWxGeiBt`9xuBpTf)Qb052)C5ZGsCZ*Tb%OrT%jY&vpOi1Ie)6}N+FZ2- z@Pp|#Jo<8)VPG!b`tbEOC((W6WB+lbr?ImhrR4>j{>a`#QNdmsA1b_3FVUM>qc%WM z2mbW&GMG*6#wTei##6M+y#t7Ny4Smtj*shasZxkxLO(Z?n*;epH9ACEWzpw3-jibP zFcZH~(d{-0jN(1c8fwe>(zt%?l8nk}jmOB^)pmc!WMa zf#TnX1SgWSPJ*E+n}UMh&Mso#@*W!A#knlFTOL+VmmT)Xo_Jtx z=WE#Hj|_dGP0luTeU8`ILjZ~O6K@!0fSUOVqk+i^sNAy1rvZWGL{BqQW$2C7lw(`N z*!%ny{wI2_d^yu@lu}@RVbOh?EON66JM0qhM2SxD#@_*YDgkl#FI0*2G8bK&5k-GW z)AohyOQ~2yAe3i;AXYNu%}^qpc1Omct)}9gmiHottLeXhEc>-j+>tvsz!1K1A zl@^10xyhCBRue9TX&Agk{R&_skqK(gn{_1?MS`6ISt%*u)`WQ2)pmc`kRoSuBT_b( zVnblC&c$@sp`PTax|@eYFVghM*hzO6Z&i7xrkefx#GyL=? z4KpG16M+}3u$&XeR5_Jcz(bSygYAnoBJ8fWuCZqg|A4iTVrBqv%OJ*Z+OWZZ=wAwa`a1&FjZsYKbUgtL@FjM_LMFnJ(F+j#zGZJ_{SKiTO;t@m7?;iY3L z+Wi~*jnLEMb}!4nWR!j(?hV(*2d7?Q(yM)YT-AeQLg8D(E{^Kd1!Re2-v9sfgLpr^ze0 z>XEeNYc;Y$gI-Z9TlU2`#>%}g+S;hom(&;FbG9|F%e^X0KMIe6;@tTSmPaUPyC}vl zxB2oJiYFs;4{!^Zhh>E;_~ys2*d;$Ftb~`8OPS-X?p(GUN7i9SQPfM}&FqH3NEZ5| zt%PTfVqBc^lP2;(?oW7Te%o}sNezTVxlitRWC){Gt8++yiPPA?voXk{#=oqro;~QO zyqAKRWKI0pfmES4Gb#wPm@FQ!GsnvnVT{L){?Mz~18;MW1{mtI59@9@iV{1H0Aw>K zE-(t^@`uUmZqwVgl2crq$!`3)Wm|=1qpof7lL^tUm z4#F%J#5N^MCRY&zAX?v#fO)i9Ri@Vq{H>#v^voL@prWgSLvt_1rT4=ObVAm7n z+fDs0+YZ{j@q6~J-q_(=)}Cm+_`Ln3X!^{pmQwg{$YRv(N3F8+=ng2mI+PuwQ?`j~ zfR|JOxrWD#MVs7|8l}M%f(tE+b{(r*R#u%G1pU#eTHe{!3?z4Y!6p&vD8Qm|;G17Ou8 zE2=av`rsMZDdG9+@FifoYpButxim`#_H4d-=o*JUi<5FR{QT&HnVFg0??`$NFmwF`URp=0KFyRaM-}kd3Nfd$ z0_cdg^VXjvwg#fBT%OvGpNQ<Be3X|KzWe}xGhO%jgH`%-WGdX$1Nj}|iQMn{%@%v5&# zNrQ);kE`v&;_eFvJi~<0pGlIxYTiJ9C~Jgj!_KSMllIUx6dK-~*t2_3n#a}g>PCxI zWSX$|9^}()<{Vq;bYWo_2O2dG{c$H^u2#(IxoH$s33!q)kQ>YmpYEx85tE!yZ^`w8 z3eC3Ij+~cWCE0eh-WoP7nG`pv4SCb|=gHRa18Dt&6hmp9s<`QbW>`J%m>X;)d(nR| zZ<6(|U8m`h|HShBH#|-cWx1Rv+_^rgd{5`|6RC6h!j9}uN;XeMnP*sm+!?z z0M;(9w=%w6o<++mTBOY^{ggNBc-Cm)R$sdPXz5Mg0~M zCt@$X=JTc~o{3Acj@yU6I&qq}BgrtfV)G$_-e3qsny{vXJYTWW8X=Nn_zMxO-1=F-J00=0T-B>;a5@# z|884^WLa03i2;29x2BiWbcsc|^P&U~61|ZLw#YWi#i*W9sOlbAqsw`K^Mh&Wt^=@$ z&7$xOAsuW(y?qiUv?K_{npZzrfNmx91`u(mx1BM5c2#o_GP#fw z<+aKi@X7Hu3umJZU@}L!KOQ8m&(XfEp!6!(L=+%j+5+V_6t0?0dd)Z_9}I1Hc~%LI zt--T1JNJ{5D9mSow5bh|uCy+;H~%Zcw#VN~XxUy(USXtE{8!dQCq<`f@KIxVX3;^i z@pFY7V8L9!nMJuC+)Wh1vaip^A|o4J=4_kPmFE}@f3oDY?6c1}crz83lPEbaza1nR z00~`hf_#UA8QNgSaam9VpLvSdAs6~p9H@-B16w1H@jg6u0num0?f_9V+D|Gc{y2b^ z-KXRCVA8Gnb+B?PdAw4+!Pr0-QTti9ibXRBm~tjq7x)1|>xr{ed73fe+@@^$mX-CU zL89MWpl6GKKN%mT*q71u+O95mX<=X6tX$%Zft7@sc<>_lK5VVOH?~?$=}#7=oBM$) zd7S?827NX&3g2x$C@C6Ew4)2ln7d=d-!6Hx8`R5&YbIM3bK_*bEgFCzZk?MtHn$O} zp#n9>y3Kx&GS=6l9VLG6d*l+8@;=OY@q~4iAFFidi`aJ14FBe*{E<(VB8VAf{|Xnk ztYpQi##OC{@j6$&=sm?4 zE+B-b4d1->$BU^RKGJU!O@bGKU~Q6W(R*OAYOGn>d4~ky85s0Q9yqpD^gwK=PZgxh ziwklc+5X77w4vQpx~2Eoc=U*fd(19HD9^1Y5^_8-7*LSC_!p11$DRepIFI}V;Y$x5 z4oUlm9lZXhBiCQ#h9gD74Tw>p?n=;HNeLigJ1!l0(g1oo`;iUC;_H8x*f3K=OV#Yv)pevAU`p7AWg+?Q zwCpP>bLDM-E{d5c2Ag3p*^Z%rMo?8onrRU4*JN-1n^)dk26W-KP# zTIN@4tTHl~QV{A+t9z5ZtqRw>z?bG=aa)*D2|#Y8JcD4nSqxZe0J6S zTnAD+d&qj1g=@C<1JPl&#DEr%qj`c!ZK(UO7P~co#-m=l8jLvha^S@Lv_74yEld;6 zc^9CdbRIL>RUd#IuRj#)n#XcKrGjl{1e-k!`KTnCFXDL}1E9M@13+xf+#8z| zlt!2RgZgKcA*h{coEwRUGQIVS{J>o~yh;k-uItquh?$=d9VdxOqSlgW3O$>cB$@;5 zfPez2EaA~|O~cKttAgR!hlq|Bsojl+FYX?S&o6}+`hqAAzB753qe~Q$TG)fbm!4?e z!Ct4z(PSUYr5Ka+zK=OPIfn0>JRHX(WEh{`7)C&b6*jvlj;fR2f*cOVM`k#fC!94{ zD$F8}`^^6Q!v-#YJ5zH+NoCVdjoScD76Sve-91tcgEP=LY)VPyJLE;%yOzt|ht|%b zUtP}c&eveb!PsMqHj>(Fe90GmVA!)B9%GKx25DjKw_yf?+|^KaGq}OnlzCpIbhdJL zkBJt%1VnpUAXo_NwWzJ&;MXSh43&;36)YIeFJY`YZggudmXPP9g;|%3Aha71?bW1H z3rjY+SpYpYAKPPYKC=%EEE#OAc|HCp%>8Su`1@+p|9|J6BtYKBu77iD8o^|a+#>Vx)Egy)^&qB4{z$9?`xp5(fjm7; zZ5=?$Q-@Ek6`G{)N0PL9C(UddZspYa+}?o17q2MMs|~aPBB%v8pduUZ!siegGj;{Z z79)&Itv9#Tt-ovsC%(E_Gp6bybOfT^7WXCOa2Eh<6=B#mwQ3(|Hpe1zg!JOSs20V50&|*L96Nlz^(Q39$9(!KteceVML|o3{6Y1_%|T6@Ags zpCHFj)Tw($ktD7RBWD#Oos_xlhIm9Ze1W*OEq4lWv5xx3{KGUECE>td>-WS)4g2v$ zR50x-$qE0gefuE#>nv&~a!>9AU1%5~Qu6aI{^d@SAY?U3WDj(escs_*t(L^~W!(#J z{+{31Zg*90a|(}Q>xA*T=XxK-YB}!ffaqq{wA&8frf{n!R-{nWWef1d(e>P~N-wPV zZV|&Lm1;Ji6{02fFoK-Fd-a^|x&yqrNM>KkBV+J@Jp)dZv=TJnYS|;3FVvnXyDS{4 zCtCc0@BaF3X|$`3h*F-n{Ptc6rF56n5b*-sj+2@$+)nWS<55{4fjtp`QMj$(FTV0lw_rE$`QgG%#{M;^zMdgE-pr>dY$Nh)tHl@lSw zZ~qy<+y82S?*H-s(nDoZ^0!xe7af+!ouXVu@HSGJPF$MXZes1rLKqD&am@b)z0TH0k`(yRi9DfXZ^<;tbP6-}-=SAQuTEv^slgisIXa+$S=> z!lq^v6}*u$)-n8M9W%o~tKT|ZWQoO-#oq>8Kr+cb{bi~MoHK>uJJr8N|2o7QWZ{*&m8i(BDt_H#m-@(J}IK(=gv(a5!L@u3%;tV zyouFK8(_!^{!~p&aXeX&YS?{U_hRq8P|2B&RfCuTPpLq1;|JY}*+bLf{IgZVQoX32 z17G&-@5XZJm)Gf%fx&S>=ItWc?VY-iYo-5ciq${0y~3`{sulg*&ZF=6Ixssx)iJFSqql(H1_i<#W|fd z=AqT!U>y#v?Oz+gh%NP2D8Kv{05x%95Sz|Kt04p5Om@p4V$$XU@6Lx$kq|_qn$B`?^lMyTYX;4oCL54K#M}1++P8KT|H4Sd=!HdObaCoXc^o8d!}UsqB0|+w2U3JjErJp zVhn;JNHGR9CU6DZVlabf!8CHvzqgG*U`u^4NFN0D1RH4?L%=4$0R%QMHZdjs`#gz4 z4*RdMP)r^zG?b)eAoFoe0?#hx0$WB@IW=H><< z17iy_Qv=KG*LskGNfEUFG0OI`$WbK9ze@^X1-iHqpp*b6g<@>#?8tHSaQt^E(d39o z8Z+$Q$G}Fwpulk3oujxc^1rP?OmhA_2+MKf8JZjoSTM zV0aWS1{~wY1$qKM9xzY)U~>xyZ~F{o9AV}dW*DgcJ^B(exF4>Hs<6qub`mc zqG`@19$-%|rWYIM9Lxe+A~~)m0VXiG3(%Jw0W5*x0Oz>7Msq`)5kZhJpaIKv2aW+C zVjzVJM+ch&7YHty$@OrKcEAK;gV@n%Qy#E*Xb2V1Nhlj_xjhQRJum==0mC90=)j0* zm?=FVh>S5ou|ae$f@^OKWdO1bH4U{SgSoWmh)@uc83ZUb)H1@E<7DJ%@5v^Ed29kL z02%~E<4oMZP(&aH25}|2VVFjd+z>Y2odXC6lJJ~oo)YA#=f}nj2Y3!gL1Kt#P&ASq4uayHO~64e7=#%L6&UFN0=b!^ zAZ$-3SC&g87{mraKulv`Kq|!n5r9OR;^^koAYKR)$)&Q5T}-j&VKJx>mc2a(kAZ?M zLzo-~CluM$0_fsMW^z0jG$h$0a$9zS=)@QV932%Afi{9LNmwe*3~vv|g3U(j9Ggpi! z9v#5sdAYf{x;X&e4vIpNai*3$CqN+_u@UZ|7^XYdks1YtMRCXu9%$IM%?$!MLAmTG z3wPsSr(h~60*ge1hMF%72t;U7EXgwp90+s_k3>SlQ6^C&dmfWVMWLMBVnCLxZL{MZ8bEQz0MUY*lb0jO zh#ea45WXEZ&|L{o2*!c|cHN$jLx2Os$ewPA_Hc5JVK9+wJi^=z2{m#Jj^u{2++83> zR7WHV4?;%-SRyGja4^l(C7A8Vh$Q0OqRi3uE;w)y9)WQR0R{v7i6a7Vfl%il8Yco_ zZpjVt2#KOcy1KA2UM%y-h%hr&fIBk`8D@qzLn5NN!N!s1Oe%pux4^Q^1B1+11S}m- z-4-;{Fee1r31eysbK($!9XZa?49m~}JZ)QO8PTpl%mKwYkc=apL8cB6FQTcJXS6E` zhXX~sxDcXEja<>D5DErsZcf1mJG+o9EK$au+bV*`d3XgHv7?}_WJ?T5(9 z5n@b>;kvknff@E_9?}%)h=oC%m^2K~(J0K#!x3<8k;oV#le;|)d?c4gHo=6Oo45pF zOoQD48AqChbG(3uk*0ysPM|1a5F7_}M0;99fDq;o+_tn?I+4f@o)EzOK)FP$Ju!q$ zcMRCx2M@R-+AEqwFtTKMal%n>o)f{7XG%7UG!Ka6y1CFij0vI9kPuHiDVhoAkuBLC zQ6}M$6ebN7V~W`xAj&wL77Yq?#=-))P#}gOM~4M@MH>Szb;R>xs3bSQKVt#s3FU>e z2tXq*$kLP?#WM;49Ec;B#SLch+@rm40gf)gAs*CFcVn~z9p~j5x*hFAga`0wCSFdY z(9m$>U^8PpBoKi^nMQ%J4p>yAYY@`Wix7@QIFiGONXI}97;CaUBX>loJvE$;aSmgG z!rd@{I=g_4sa`Q5Bor0q!9)WCyK;c|2Wsw&F+t)95K|`%C>l(l1jmF?z08a-AeSIE z-N_VYPxi#Z+)Ru;!l5`4oejZZd3Y$njKqn;8^wUljGVTEJP<1k26zpq2bYC+aq_^D zT*E?Hbes`6*wVxVYs7<@q0Oj91f;nGj7R{R*#{X#+i!nZb210*iZesQ;Z#B(l1AW> zVkjs{BH~?WZ z(DdJt^nb!?;QGJ7i!n@7&Xy)1pf2F-0P*DbPTdr(k%uiUcKh$xtNB*IN>~tlFrc+8 zTLqk`mVGc;TTH~x?pdOGae^@V?dU$oC6-qI3vnSIkxjop z4z7hQPI>w?h3J3Gj43TGjlUZfGiBvF6Jbp+PEGSW)p7g+CkGkOh`rYmcQ2Rek>PhM1?o`;WE6*?e@1ZXW@Dbkk$AK~CW4+y1}|>!8U` zRS*1Ic5r7}M2kW`-j~>Qe;{FNLs#SV4NDL1lZ9iU>wjm*9|wH&=8W)9+Kv{St;*cq zJohVh-=MlWCxDHB{WE&ejwfvMcUb86mxt8{evAu(4l_Y7Rji_l_57ZAFAc^rEf;$| z$bV->GPl}=yOfxXXiM1-Da0D#lrgVTY{#?Hdtovc-iK&R-!K!@&#qB#J*0sddJ^a5 z2YI(~51ye~GNisZ-iHWl-iW4seo(Y0m>0l&SLi&~aU}Pp=|}H_Lnr6Y@7f2lyWhOY zTUni`(5;}oD?F_ed!12-Udi6xcVH`=pW>-pQHOm3Bcnyu#K9cfX}w#^)0+f`va=Pq zid#Ie#>Q{A1kC6N*^4^NKmMrEC+4fy1&eQDgz8`^%C7m(%+GXDG5?Da(}E)TGjjd{ zjZwef+3wWRho@8^<4gzi{jd94bR!9L^E)7PWG6K+RM4o;?Q0a-X@2!7K~ znZ#YPV?SJ9vfX=RQ0pa6;CS$>ecY{$<CA-A`uAT9t z{`TJ&pT~b|X9nJ94 zD?RTZ#yvL31yTp;{T-C8+P$7-Ju*Pr(9JmGsU>1z3@;j*UkEay63@Ax(NU_8_C*6zO>-}fR!OZQ@nmZ)f| z)<84kiPEi>>{s@@AD7^TJ%zcxkM1u6pFtsAPt0(l_M>m<{k~Cu@r~Yl9$q->A0dOH?jp_EF5Vf%(@ckD~gLPpbMA@X|*~ir0$F z-%w~7S&ZtXeIOA32#7N?Y{$QHtxWqz`Rlg16BSq843&CY3|;i)m!#=urEUrBKb>>) z(8bI?8P`@y!M66Oj|rbkRoDk;Pl4lk%$B3miLHNZr+@lQ|Mb6Hl(McNB z+3b%;-i%%2>Sr4>cCTob#mh91c7t_|(izd-b$K8N&uGwPC;P%uCGwj{GFql>xM)Fa=# z%`P39ck;&%oXs)c-!_7qHVJDvwR7)_Aab%fbr+c!)=R6Xkg`?T%Ub0w=$O7h4YKkD#e!nqn5Ca zj$fNHCor29h0%WXp8_OlJ-3rWA5Yc2D2-IXKDyZt7<=;uW5CDc$aS=}Ff3s>{X|NW~VBdbmN z7*g6|Sm1ML^=qio*5m0Xm-ib7zpSCX|MB~7F814GuZNr0?#>f6)ZLHPizS?3)D}6rkU(3arjGWXvr0kq8v;Y1dyg*|i zSi5J8g1TXW9`7r?>-%N(OIeKlgqt%pd?3l_oYWBwR zke|V$Uz(%8U5=rtMU14xWtn4kh3;ZvU#{LWOb`6-fQbkAD!oPxlW^Jz4wn;Jxdydo4BhMQs+F5w#ZG zhP{|j?+^VMC> z3thfVypE~*A>X4Soy-(EWB$*c51^POd)7Ds-}IN4pK zxe0#YPNbZJUr;8DPFwR9WI5^!PZh``JnLVl>Y=tVz!HXlFr(Axt(9^d>(9fnGru=) z9Dm|oFtKx1Pi5iOiLu&>`Yme3-qnw(;(I-9=Oy(M)Mn0@E#w8H(cP|@I8WKn@ah}6 z1wR$ZT&`Z%A-Xmns~YRL!g%vORuG~;Gx!W_iu2_b%^o7JM7^$fww3@yA9R>dJF`dI z`3T^=Za!~2D=PodaCc+FaDH3pgP2pY#xb05jghTzsVfE|P^Uq`j9VH}?4R9-FS+E& z{yCC$s2POt_|~5xcfq%>w5eNu+E`F1@c6NrS5K3E4c7gF%uAVnQQufw#t8+cA7%bs zw_g5IJ-k^OfMiVz3W*d8eFAgZZy$RJ`NiesInok*u*&O=$zlk>#Rrh-$C6OQvUvJZ z0JLjs{ln$c^FLqf>fBMUdBmQ;?!5ZZSV`-J#a|e~cA(2>6rM+ZtTk1VOKW~m`k^I6 zD5)qnH*R%7+}93@J9og;g|@rQ*J)Lj1uSxGSVaH|1U)d`(!MZz=8wZ$b5i;>m08C3 za+*^o38Q9pr+W|ap$8hjKcW1y-YTYVm{#fA(~!+ues^-|Glg!pO9s02RAKpJ%84nM zoek&a%W!rV9QW|=RooGq*)xL;Wm>}HzXqEg`>TEA zj@?v@T|A$f71Q)s^~$fspU+dVvKd&6aYEI5y$GS}4)ljm4gKi4ul3&X_b1_J`c-)| z?~2g{okht!=G`Stf7aPCDVwG>#+j+NIwlsUJ}S$6xE}V%`E}4r+vADYR;4@3ec5$= zqlzU*Q$Q=`tQ=*g|mM9t_T0_S6`pm1@)WhSGsJIt??qq&Z+;{ed{R_LHM5Er`XxmUt$gP zdfodC(3@#&z>7#^{ic|XJdA&1IaXYpY7T&lve#mIHLQ#K@{NDz+z5b{-moTycdtKp zdEhhx2w4OmWRszdlz+cUEoxy7lHg#*?1eBBRo)k;@beXT&*l3^&KsqRA8P*iwx<04 z6L-{rnpv*ydSmQAZARh|O}gvJHI|)?=$UyNrn@;)xVMshK0lr`@pK|(FY9eswm;PU z7}CNaTslja5S4B#bJ;1`4zf>e(JYChK_M`XpE+AFeA=8q|EQ za--91N5V>%U!m(wtB9ev<>y3G3+6ERx=q}pGeeaC)X-sqZGg!5{!%h&THiswz4w23 ze8tJm^PtKzjPam|Zv=&s=+ZrsZ?zTDcWMkXgzB_nb*>Pi>ObgjFOG@%Gn!8@{c7<`t}lv=EYtPrp-;VMCNY zHVLvEP88Cdz0neB8rZ%o$Bc39_{PF}mm4DuijC7iV32n$wJEqOOaCk^^!eeMbs4qk zxm=4~qY*jiGrb^a3%UIcL$a-#zu|P}#@vJx9)*(lGKy)U1z)@jih_}Sz6J*-@*FpnQDuSP4~gc&((b;$MqDS z&3eibs0WXq0OaB9$^E2IsBSbydPv>%(g8vqP(W;`n$L`G5(d3&_0IG zuwt<7KVI#Xg+_-B^$;a=vgu318-$m@lEWTPnYAQFw@I0MR!<0tN|$LiP={DcsEP5K zsZ-Q!e7l5p~i z`s-_^qkx4f*K8;$Roj87VGLkpXAMha|H$HJ`Ze*$T$?ydHR7JqL6+L#W0gB-o9io= zl%8qfhE)5G76MA<=b%hT-Jmvr?Xe&6|sc+==pf z;kDW*sDr8A3UBOYOksY$raSl54I9A)U9qz!dzWl9{(249p9ImLCK%?(d#j%{ zF-PTG2qml29fr!bTYd3)p1;<0ck#|@Dc#al{&i|%Z{18mj|AmKneX|{w7C7WJ1y&w@thQnM25QWY^3zD>Q3mdby`nNnXa z_DQ7+yv(wecUID!EVCY0%5*An7o%)cu6HhmI+C|opy*c9~{^w zX-Whpf9-!x{wDhaVQ!{P266s?=`-C*liZpK%GsL_uo-~1X|2q(+cn1S#IiRe#>gX+ zC6%$ovL!0JcY+5`>s)law)Dc%J6qT>2%4HIbM0Iz_GpHLh*JaiXr5QejoX>s&`s^& zsRFrsBtBFj`vu_zXuWkIA;I=c^?B#asf4hTk>EB=z5m zKjRcP(x0TlqmK?`# z{-{uc-uH`J?4wusXA4(h@4BiyoPM&_Di=6fYeAU+q(|yxaTP#t94Z7g>^GshYn_uc zY@CsSN*Wr3K5NsH!el4i$?TQVk?$*u^PFrI+nMsyDpzZlZH4;Nt-yln3pHsF73eLj zBBa8bnO*L9bYTFLQ#o6o2JOO1UhmVL5n7DeQ=mGo4z|_x*A&96-;gZMB^P3a35)KMk zEdk8SrQ&Hyh9~OuE`BoF1JFKDaE1c^LqZmUCz>((rr(45dA3>~M_sYT48|vAk=#XN zV)KM_n}k|GyH_XG|27k^%q>Cj-|AD$zL)J+sqK9%oD*9UT1}r>{bZsJ$pu`(^*x>z zPJ4GqURINx|Aa_C|Ko6T->_U~bL-*w(R$4$UB(zCcH>?3jju6)*BM+T8Ok>j(&GtX zt$%llG9Ulym@`hINRD03F*s&6yo8D)c*EEEc>Ozdj2uO26xRv&5A!NG~nd zp@_^kz;#Oqu@dDG37c1dHm1%$tRJ-`N-8s?%@i{&A;D^09w{@TZLq{vFMIr>~N9Nmn7+prOJ$Lj_Dhuv^{9L%V*hx~S zfS}QgvYr1^Oy1CWepW}~%jR=09!K^3;Jp_K*3bQ2wsD>LJAR-FJEKAa4vp&1jH{B>;D`}jQ_D1CL!w3K=&DK*Ra`9fa7rvm;jBwUpnG^(n9d4kbp z3`B8U02Ty2KOT@Y@ zQGpb1?R3J!JZH6toThR{HSpPGV3chQGbW+ligP5aSTGK^Zq_{HNFMm-h|E-S-9Gt))Qe5Vd4g%BCntl2jw30JZYHNm*sb~;>vPt1xU#< zBB&+K8(q8HCS&WVx&CnM*5$3`tB$R{4}buCC@)R51bai{oBzdBZ9cxQ@2*>}`c=!DF}=m;WO2lv_?@{Ka<8lB=)U=1ZFV$xCR{@al*;_F2u2T-HUFgL;@khzrc3M?G zeZNZIUO~(^7a+i_-wt753b5=Ciyux@^q&BT3Z_osQ4zxT_Vc>O4uyJ8IY06q@GEwn z7vtH^NxGELH%puk_0%14>*3N{7N4XWMPXa0V)JXcZ|$KFfU+NZt{!L;Gz`HXQ#u zoI>yLYT_++>Kr_M_M3u)bB)I9*oOA$Q%Yg(syZA>ib2xzJtsJEy9Fx~wl-;o`Rx zX)7nx{crWJJu?N`G1(3Azl*MxoP^|QX(kG*7nOchq}g zkL_{Uu%<<9t+H(O%hAFj#MKgV>Q$d;LYValKwY}3LjL)9(a)lvHlteums~qDk~0@O z)HH^IP)CR=WUts3AbC088K~6yRxF+^w_aIM3p=YocUuOmmWBmB4hYxHN?sW@uVc!W zb5-fdehG0cHr~pK<8J6)Ly23y z-G$4E!5he=hSVeT+ky51etd1*&JVwsLUGF*yRzx(_ucl7NW$`1%TOca*$nejp6m9oclAN5SLw($G!S^ym)RSX{jv@KsCwfX z&IMauM`{*!8-8j#Em$#BFsevg9g;mjL+&VS=^l_|0+6=WTw#q2l1?gbf@(~y{(f{# zq8x}y?iF3;8Hpx~Cta@0@G&%9URF!^{75D#MY`eJG>#aQxAiNWkawK6@eM%Vbvykt zKL8Z!j~kJ1E|uPYRB~pxKj5tX74r!|;7y?0yaa$M;;wK4OKu6&$uuqXhtR+6?4afG zZ!0KzvmkHJ$Fr8(3KjwW=<1~T9jN3^mH59SodtZ*C+9+dE-!h1&+y@oJ(kmr^CeA1 z=b?f!9ow99=YzdU`Dpnaw1c(@*0XlKwlh%1Q-qXZl*1l9`M<3-LkI0dG@}CYTg<|h zm(0`2d+^fkdPN&heXW|t=As&r>b}oU566?%TzWqqEEc{H`E>5VE$i5l)0fKY`b#<) z?}il}sN8~i`8g^u(?m}(y(DYba8=SsJ^H}N5ci;Qo<~ciWj*Y#)dTO22qJ0yR z|3Ni&68-$xy@Ij)UC7(?428{d*cIET_&jiu0yg_uJNvmqrhcHP(&Q;YTZ_Ijf=B$u z;zyliNvNdm!=*2gZUrwC;;)zDDx{Sq28&rQj9RMC{wnbQ+1QgTsU~FSu=81PTtbk1 z19sN^>CZ2ij;N=nBPt!0(CLSPEOW`Hmrq_iJz!V@#Hq#m!Hrj{HRU9%J!e_2--}Lk zs@F;C>ovD<%{b^lv(lbZp|7HVM9*ZmPG<7L8p5#2^QQS2#(!73Ug-FXfBYBVlcP1^ zx9?1N`dr+x%k|e=oxbl=YpUP&sR}lBf$*)>D$U@yy1)ZMk1z<)rc${|J=tk{;YW5l zKi{^lJ-Q(~OVSsK&%TH<9})N?nRHwo;Yp@ z{(UDyFUjtmY8O;hf8z=KaZ`)u8B^ut&c{QBY`Z5CxBW)yuLrk28+-3&tDk)i{w`T^ zhiY>NUsCZvZVJC#WG0bxUBF{exKc}~E3NA0jt*Leg7+Nj>gML!G#x8u>svA0+U|9H zK~n10`o5H17Q1DI4CPZ}Q97i{noFlP0Faq1Dj)Ao)fH*RZ8nV7rjC|sqpx&s(S02@gl#3!PJe}}PDi3deUjW~&McWs;eHKP zsvTZ=kKC7{xu@fj5wQjubu8CwOP=Rdj@1>z5odMFRC|(9YBIy7WibSGk*&Je zns=K%n%64h)dG)mhLc1~PU9N8D;WZTsh9!Lr)s7C*fRX?t_P4N;i&Q6dzp8Z{=BUS z8}iYZ^`j;c_S|3kKQknk3}iEfUMGu@9Z?`ge_sQ{mQu!DBBwnap#_~M^W1zwYB zi7zd)N$hSx(#+=D zi7l{yC0RY};IYeAMXzNv>eS-@k``5GD;~YgA38Mzm(AnPKVumj2wnuwPWsh(>rmaQ zz>qxqDt3>2h5EBPsm8k-aH;HtwBotKuN6-PbcrCFMG3vHPt+IN-fgWb@C_uTyT`@K!fCo4Z~ zIp$~?jybp*kEHT*{Cl7wKZ} zp^Pod(M2i=Jz;0 zN{mL{=+}abxt=3Pe%6*X-pNy*c2E~1)(*&H0%@GQ;s<7nwgX&+lH95F z(0hKe849fr)?gR?s4L4<4bJ6+j_QQ&dmWZU{#@Z(Lq^q!s=DiEj)WRNbqMrMlT)0h zW}Y!P9W6g`xqtq&RtEkNj=G<|CvL~vGt-YI4C?t<-+XBU!UG3b&H#W6`UEN;*#|P@ zB%B+<3s%veUv>}GZ39i~M0JVElR`TryD(8u(605@LHq4w-3;=TTD<-cLAxeLQ(w}7 z@{cn=ig#xHq^(JsmON3zS^mIT6H<>ED!|Mn@^X74Fw=rHe38EJ#R|-5|9{w;qffXS zgVB#kC;j)ZXKuy*K~r98e)Ctp*Q2UGt-65$Hd*c$0COrL%Fg*wTiSBkH9oKsho88{ z*33m*$igli9#bSkw4coeUMN8h0JQuM-`J_555bB`H%M8c#-lTTvs@sl3eS`@Z$Fe9 zR5>|wI~CqzSgBp(vZz`;%}~3TU8~vTOj-4s%nwJOyoW3?8(4_%uUQ0Y1}7*t@KaQ@nc39 zrWGCq=$nXNKbH?|(<2&U`kZ@}FB%@Den-7IKL6^Ul}-j6P=JkcjY=2yyip&hU+8nW zIpv6#8dbbUw>aO#<B=sNJA6jc zL=}_oKK0lOdodX1O2&vOPG1L`nZT2;`;1q;I(v*WDhZJ9A4-@8r zXd_K}meH93)%CW0JfMO8XyzoZY*5b`wC#T zlqAO1SLXX@vlcs>9&IG$g$2w$2bQDnc(=syKMV3>za4HgotKc(=PVqKoHnwm=$Z4K zeqGQ+;7zBRk1OYQa=YQJPdnC_%($kv9V|zG%Z@8*e5_^EeC&Bzv&&i8@wBJ3q9xyv z`ZGiR0ImjssbX8wHuYmgVWW!|TABe3SOqq{!IdS%bX* z&ZhAQnJ3%QWN?UmED7^-%#a9}cH#4nTJhTig2cw^m&oq@D!$(7mcfM?K=G%%cbig# zmHt{`xF5hA&_Lo5ZgY~*i41Pr98i>^clRS=RzgK=d{K{<_hYEy$9aV@6%Z{02t*Vg zsmcy#9lUH|Uj-K81NJTot4^ zy#j^HTuE3y>3v#u8t;qB_>eHw#F-7KRZynygP6!(dVXl6OfOU+HNV|z4yw_I>U7r0 zKtMH)1`n<^w98zFRSAo($))h>hC5p09d>nkOD66vWPaX+O1;Z6nFBbfang$XUgBo; zc?oU}P^|b>vqB)H;T^Q}3cM>gkDs(R3-;~dY3smG-FNs0mu|zXPpE!)GQv}=Fu0mH z6>Y!4stdh0U&T6(tco=6B455b!K#tVqGG5kdKa9Ia9GgeB-ztcUH%@;)BY?8w8%%T zRz$GI!^3j_1pm>r<IkQ7i*%KgueSS@2}(e16q+kU!h~)G%`M{dA14vnju=0#kDOO z`1%+K4osa|RpI^0(@{sU;Z2_gFGNgT?qv_d^Slzxg2!K6P$?Du2~lrYCE-KlVd!!=TKiDPd$0IU)%-frehm>ZytLT#{ae(h&vq=S zeOpUYi^s>=0;QDRe>&!t&7Y*VZtUnV^oh5cyM4jxmycEPb9s94GU)pnki5SqNCXVV z;-BG1P=x4i>91-xdz9Ec*gUUS82nGp!dp1bvg^nVudNu<1U2*}WS#Q%8b*rw^19e! z@}uW_tcjz`O1zp~pI>K#?HO}$ibIKC^Aib8)>A>zeOdlEGaMg^x#BaHwtoPiqr9g~ z9kMA%J#|uk9>7r24Zm;mlU<3LN0l7o)Bqty*PD;ey);xt&mnSi%{@(?{RRpNGhf)A zaaePNfLDw{>y^eu@3zwJ-n?_X_W7P=YUWT3kcv=0cKkSarg0d+IKDJo^hZAQOU-;c zfYj?Q16a5dNIdR0?|+rWT$AjJuKYJGZez;~s<|CoQ@OQs&Ekw!zxj>0_mBFcAOBu$ z2~T{PlCJEn{al3&(pfvip5a|w1&S$TiJHmtRldC6THE!N+X#KQZz-tzx_kPylehkk zoO}or+Tf->Kboo==rz)~W4oskAdMft22$bt?Nm6Bl|6#LWg7A0WpdixcTYwpuYc&H z4M$m)!1-z26ynP0w3K(|?`cD6ncc7c=yWujpGW{H@UWa_=nC$%>hG@~>(v z0#{Bf3IP3z%L_N1JbmQW#kJ|?+!hd0Kn;MebCcEGC1pyXl}X#wOper!i%0VO0|st$ z=UUxjt3Lp!PPXr!N1AWB=1nbNDLpo!C*tQMDZA&oY;2Y58Y4zs`ec>$gz#$O*zkW^MJ(Eq>qfvyv_=|>$@^`aCGYqAb%W1HhQ0s;xz`M&{P<<13n z4#0!y%IKx-bC7)m)T!DpAKs?=8mL2RTSIt9koE0|D$5o=#E%CalQFSGwXv! z^UV6Y!PxWmfxBPt15)?>obTr|MR)9d3}E_^10AJ%k0cIhWu@H78Lr|2(525N#5$f2 zRc;(j|{7~OV z4NSv@>~Y&4-dAl&t-@Z>0KckZ9TZ+GK6)!|>2v2XRGwF|5wy+*_^4hHEzdL3G@-r0 z`lB%IXXLBLXHv{1WyFr(n00TL6p9rCbtINaKACckHH{J*pQi;b|>eL{;?e;U3EcLz$8Urh99P+m$g*M6NEm@W&!FYEU1 z+@T7&FUx#7P$6ygOMUe1T<(@x%pY%gVd=|);abfgox?TiVj8kl-j&#Lq7E@%f#jRF zvjwZImTK7f;RWVdpQ_KFKaZykV!pB!`B?UCzt|~L_HCtPL5}E+Y&Mi~&ST_7pWvLj z+_!+Vi20{7T~gb%L=S-)hrYI5$)$j8P8PDND%&{(-pByTc^d}p;(sV!uxluN|0e-2 z%`YNYM8YNY^qAvA&CQ`eRjaqvzBi5cd~QZJL))qx{s6$*eV5tipuLtePlfta?It_s zJ~9FJyt8!Ykz`v9ox`g~R|AzhJgKnJw=PhsM$NHyOpoLO)$4tT>@ESNomJQaTQcM` zuem}ZyWG1@dUbrJ?UhcJ^f!$pA*t}nUzMb`UJ;BQ%mP3c z-yLo|e8Ax31xsJM+X~n(-ga3J`F17sGJ|@1U+b=6U(tT>)x|N5^s# zu=lZgYU|BgYqqt6^5VI8Y(~nd4utDN^J4r+U?vLi&fp=A=`7^XzD_568_WOpR z>KeuQ#Vup!fw1eh>XjwQ+9;{1H<0*|N&EP)`GS8<8>9Y2)hcPrWXZ-Fs3Fh%HOToc z#je@C`6kFwp!DlDLv!y}x*Re1l_w`gLf;-QO)2P!_|!l)d%dJc&w1@KX*4I9c5VI3 zPx!xkIuKSrJ}z4EVL#=DhN4dtTIi!*(CQAIQf>Tm&^#I4FaV_g*(GNvwyICBoYJ~iO+yywDegW?H7ey&W zu@`}?`a69mbI}$4cenqw4fj?@*2{p*qR-T6XbnX8RGY7%aG^gyDDOC}LFb-T(D!td z&~H<<&m)U<&H~Qnf>Oh|pP4*TCOYW8fkrdy=V9CWmAC)8s=9&Kh4DD=aK6MjFn2D9 zzZ)&Sn=3oU0Lvd{0mxcXQ`%gZ;~|0^!F+wmK6Pa^@y+ZG-N@@aIK;+y_6^D_aLtv=rnO_Lh} zjOLjfS2^M-g@PWV|F5+#fu?f*`bXrLIi_Ujka;W;Zsa(IjET%nWyI}UT=+I-_k#{Fq9QgPO6K#TW zb$P|g=?xa4e%{`4ar;!a?D&K`Jk?yv`cy4GD4k@Oz9P|D9PD2m_gxceT@<1Up-|ic z!(9b+Rxn6mX60H~|Ce;_bVi-!T39Ob$j#~UKx8KzmS`9A#PPdZPsDCZWF);;E2=-B z2TU*?a5*C1mB7FIsN!qRi_{Y0;^QM>Or*Uhmu^Hny|sKE*wQW!lZ>1_NkxL7S2ZA4 zHKjDDr+9Bl>{jNq&2hF9T}IDIaHrlP{%}Hf1v&!};849RXSViz0V5XL zFazQQ!LjshQSDl~4Tv%;8OV+F+xFry)ukzO!fY9pro*4QubbYYu35rKJ)d*+fzH?Y z@yXq)U%`=cE&sxvMYq&|v9q#3Binc~GM4~sNX-jOtL$(!yVxU0{Gt!aj9itDj>slY z&e2uS^AO;A8d~!3*zd}DsEV6WelK`7=dNpNKHZv}nGs4KmIbgaw(Cpg6CL6tc-@YL zMmm`m1BK@r7fAdv=J3oK_kp=*6H9az!LlyqaaXyrGh}8}S9RW9wiCY)@@}-#Q{5dN~)D>IuO$jwB6 zwRm*_rT_uF*STLYxInTm_A+qg+I?jpnt6+IfR}Xt0oR1xzBV>FnL3ve!&cf}k|Oe% zH!qQ_k6vt-xq~+_k);x8c(KpRWjFq!NG(6M832<^yog~X`AGpkMQHJxlEnZgq-J~- z${zwthLKZ`v*|XcGUF}x-{1Y#xyHb)Hx(zr@Wy|bRi>9;J+j}jhQ60}+GA1Fi7Y+A zv?<0D8f+7QgD=MJ9@K`K>&1Mozj9(4C-qDODa zbTpDXPwx2ZKH8)9du>DI$|j=gRGxa}cth)*l3W09fLbZ>7$^;$bY?#S4%6N<01_ML z{+srfKZ3v#2ed|J@u)M=lH4 z%d!Tz&T_mV(g}V4glSPmYzH)NZ#&}Z%()y+< z;)jWpXv~2!7Xx+`HX6NX7%sW2 z!Fy2#?={k$aXK0Z{gb`%GM|*X-NRRuTR&y8rm5Y&xIVGZ5-SII|ic)qyp&Th?i7S~P`2xw=jp(jMRfl7f=k$W*anvx?F2h&_y{zKmTlt#l@d)I{G%V8o;{`}f_ zyy1A8M6n6Eu!jz6XlL*zFSo(+T(pISG?!^cm#m-;M8W8R6aj4d#3iMHEoki&7;zqJ z2~C&!p(JeVAJR-JJgK8 zoDyrGDfqC9k033sVdbw*(#FVu6y_YbiMGQsrB2$mk4dBLfN3zO^N@Y+Wag#lRq3Tfv^*$3O z=RrVQ|9PuyR%f?QGU#B8DHKcX&q-A>Put=IyO~s14$!a#gxx&0!@~-hkMn&C^Kl6; zPAwap-@D|hG=1~lc*rKksBuwL?>5IzZjZBCp@Ud>K1~tkr2BgAb4Xc*7oKW;EB3_? zK~q^Xq9Ai$JM)$@B{i7oqLC|Q5hQMfnf2bT`DQ_8F2d*eNj<2)NwkM4yn#zFqj0&P zvKTeJH_AAw6p(3A^Yeacgw~PU`Kseeeoh1f_imF$rpX1hU1}+#DYua+?74|{Dx*y- zq%}x><6)%Z;7R}2U24df;6zPy>1|<#>@L~#1>1Cay9Tnp+<%d^8*9T}DN169XtadK zGK2;ywOt(204j8DAO&uBB1UY08Lb@wDkR}>2;}x;Sj4D*~|Y~eJYt7 zl&s2JI^qte1!}qX@tU+@#G+dp}*{IWb+5 z+jo74`=x01?8^u32>bZaV5m7=Hxn>+=CCKq7FKJHb#~*C7f#jh1QORN4mcbbVO?>kUgruHPc9!2_-sN zn2z`Bx*0nK2`KSy7dJeE$S%6^-*Qko3wPjNT)&u%$)i=Vifl;g zpn;tY`;#ulVhFtu%rYa>6oknoPGCLfYEwKx zZ&3*<|Kln`uS)><+X6#4M2kZu8Z$+;@8b|UFGA3(vrtS@M52uLC+PE-YyInOI3+YB z%O7!Sied>>Cm1S@QX&)>gs2}=sIh8E#7din4#)wd4W}hE>wM02Ve~bLgnl!cRM%`^tRBsU8<^}2NTdt zlChOuU;B7x0y-R*s)mE~z;%iMN4|(Bc;;?TiQ_(@A&>$|90hN+!fb^kJPl>{H7EkX zHzjcDm8A+YGl5YARF|5dy%HL-ub#?l9z^Bd_8P_Ay#vax_ZdDu6Us1o1Mq+6Jb;oQ zUab``Y;XhkZOC}Am}mdqY#B8rlem1Z1qlQxna{&84k5c=3?n=x!sC`F=47n1W`OX?6qH2HFT zEI*+M7Muv3Pf-vA{1XKjCVl6tN2wCX94|^*7~Mh#Z&hcJ{7#S%04jg~UP5MENIPXw z{h}3@a==YigBy^eZ2$LIIZufXIts7jzwe*wfZw`9i1C7gARz_qHC3aQ?%aQt<;oqv zR}^=Dm2Bc>{aI#*Tv(QIib7gN0f4}=!aqM$njr~&<^d?!ewzM;A*}Z2;rbKp;AD#! zjTw{SXU=w9Rkf9_o5A_L+4YN*Jhtw*{}=}VLXcUW{7M=(o0XAum3APT6%FClp9O$n zoD-BRxX>*;?ogEDAi{3z_xxCb}&rK?j5Rbpa-KD-gCdU2}Oom0aYsFdeUTfluljr%cg9^I{v74=NubyAPk8mnMfRuUtTEipjJRm-8VjpcPTK0a2DWRSIJo^5xE+3}-$Mbu(fEAz-DWG|C}C=1Je{#O$^c?@8+(1;%N`#vIr7<+G))pMvQ3J@JX< zW;JsS^aL%9dEOf1&6t!z*{lW2q_k5y8SW&~4olT#V=CV~Da>EnrgNfJzuxx#L&Ol% zzsL7d&;4~Kk@Q>wj?FPfG8cg~q!qL{ox2w4HyMyizjc?k{K8%8Z6-FNFldk_<1-q; z+4j2ox{Hn;%$sZyAGdZ0`G5f+E6*-zQQ z{F8WllTVYeOzm|1VLB}45jiVOJQ+>34(8Ehq^*{vuy}1rU6(ioTtR`msDwIrdM<+ERqi#Ny>*ET;oFD37hE-6n(e6Sf$HyW#`(8K zv@_@(>3rNk*pz8|=al<^9mMQQXIl51JM+XrxEM0(gyC$2bKa(>Eu)E~+-Mh@^ei`U zFF`Ih!Q0Au^xwp`Z=N0Nu=e3MGfml)Rri6qG7%sk@|G{uCxD}MnQ#_caBGCGF#H5} zgjr)l;2sHxwU+jgT?t*wrMHevWhfh?OwZj&q+Z%i7nH~?U~9rB#rrN7<{(RhKhMRb z`_(gCn7_}x)r+1AJgxa4OW0XUK^h{Kg~EHU!io{~?5XhTWQb76MlfV;P^a>|{)CN_ z7O#HJ72_YpiZbQmUBFQnVC^GZ=5FG~w)jU6 z`N`4R!cqIh3{BJLE89vKz>&%S=yu#R9ap$x4I~n($ZI!#C~Ni7XVC0M*01Pd8;3Mr zR3!CS9M)^+MXU{o7)o2M<*ag1GX+y&{9!|VnViKswTIk_CEo2Q;hKlNPa5hCnUk9# zU|qfTW5Bw6G)7OxhE;t-*!B)`ui$J^ks*4W3}7^S0m*!~f4S#d5^d^)BfT=~i^}gc zxjaM^kKwCxJvj!xKatf?*$DGPL1X#ZRL{Am;guUNA-vm>4}6*{s(N7v&M?jTBOZ|R za`d|05<Bt z!ge{rdltbmI7_^LEuxaYm(nKrW{EUfUb_`=EG^)@5TrcD?)>REPb=IB&9)6K)Awjr zhH%!+{PjLX_O8sRD?xv>Hzf31PPOK^XBEuN^Tv^)8m*ai!1{#?c0wh=UC7-Q`~1gS z2>mg{ZB=Og>uzI&qU#o$0w@^j0*(?-WEk5+E9F?;%yo#%wYrDV@!rnuU|z0Yv1skR z49#=nNsi}PzCz}O&wg*8w8AE@`5vdr`8$-rOsbd3hw(MtV~0+>t8hoQktiQ(P9SVv zY8|;7_L8s>{89u*+UA*>)8Upg{=VhyS}{a`R=P8-mt-g+DDc=|2JrZNkd%lMWPqr# zbbGW7dmXk~%t7^37p9am&NQJRkfv;(fr@uKq&Onb7vEnFeU7e}zaNV5boH<7Hjv_S zY~v*0#%R(CU|^^PM(Iq;)l#?k?SQ97cfrJX$-^`l+Zhge` zIIMLK_<5(uhV2)W1z@mbYlNALB!`ivSh)a2tAng2nKVM~XcxH}ECBO`ohHvM2WBYs zL-9#bB{T9Y-kJePrC?4`#-Aa2x5D6+-QclT+sV-_JISLYqojh$eV))DyFjM;ORjI2 zdKxMP=D3k8O9yIx^SvIGeXJq={vT_y^yZ6BzgX1Xcu zr6Vs6y4JWDRX(^xwprI=_ww+GzjR<4P+!JzFH|u@BpUCr>H57}g+_oA;QXF^bD76u z#vR8SX+&BG)O@0_sz;}SuTF`E81kGF+U1##+%?E}gUY8XO~)&)cSZAv(LH1)SN?<~ zo9mw*s5-$MM(2SJOH*@jPG?7g%V5bP-J_~|K6SuxR@0m;RY8JNPtl=0fe>bUcZzMS z!yFOW;oQciG~2}L3>1t+*c^BfC*gUBvYqed3?~+D>Np1j>4a?yJq*o;mMm7hIhmM%m}y55!`M^=z zfQc$}8rC8>L*4X1n5r;3>Kqobde#%OjlR8r7L;Hoi1VG*#e>wl3}J>q%1uXH?LeVr znHEjK=)E)fzB#wo*G~AISQ$oI1sdigw6Zm-0gari1J|xJ(ANQ zoom4qsL~23{oS1>OOv3y-4E?fQ~Gd(FcnxIpJpL(M?SN7T*)evE0^c$sij6 zcg$L8jY<*X{N1Q^RVT@Xk2?adOS1--4DhD?F|DA!?Dgmg@LL{ZJ5E3LbE(|$#Uh(}t3V>sHuZak%qVq20!YL7p$XfxyzTbrU+tEmb>a!)YRGQL*%tJ;4yvM>a7jUn9-- z<(W!EK3Of%_B=7VN*F=tTbHV6$#-Z00EM!G_6_Me8f2%Uh8kJCCil^5`__z};Nipq zd;>i=s0OHl$W^5AAnBZycsCVrstB?fL!zPAfMEF50~WC-cY)-MvI^a z8-`oNqCFS5O#%G0dgF$p+gO|EfFUlNnpyE8{QN)9O(3j?jrsu`hzKo-8OU$)a&lU%;|FYzmt&?a%Y6PA;sER68)DkW%jkHu>?V1({W#ruq7^m90Po z>4UHX6~Lu076M;o_d{j=L~Q6 z>N73WzP|y6P=JP}M&1Oj_X|H|N`TU9-HXsYZAxS?UvQ!rinNOlK@kg+dlt+!0Gmd9s41^lvT+5E!yk z&B)c#Q_Ku1lHcW&5ARv(Uc>w$vdbO%!oLwD(vZBmzH*pW>aEm$T8NT}PHp^kN&sar zlj6)6X0zfSnKk}?e0Yx?Q1*8wYpsxEwt`dC|K6Vf07Y$;Y=P{k(kW!w4}`y-mdZCF;|qk`03|E!rH z{pPxnIZt2>F#gW?XbYKV0>pk2)fQ-H%7%@jKoj$>JBU4NN ze%<(5|3ZXU``=qPva;+JP_3YOF+jVg(PLC1+{Tu*{sM7K11DAG+`Air5(s5yff}DB0sqm^b9&l z);SuftjPl78%QOwa$ch4Z99bixCdNHNrfS=F!;R#wK3>`4XpjmqY}xKEnzFeC4^;u zUg_1A><}Q*xjh1mZ(ekJ$^GtOWDzm&Ce3K;AaxVB+x&|wXjn&$q!a+8$eo>s_POW< z<+-S77&~YS9E}svt4hL2IQ?}M)~2ky+_p}HW%{i!J0l8^`v8SU3z45+@72Ulfo6n} zfbi$uJS~>lGkr5`8b}O2P$b^N`YD5$AX+{&RqOHd`7Lx11~0;iv$CwJ7S~K?=d>j0 z{VY+UHJEvgybAX(l4j6INT^}_AXl0u=>AAZmr5r7thJab$~Dy`wFJEfTsq0{O99DrH1}&1;p{^H2mH2( AyZ`_I diff --git a/extras/Images/setup1.jpg b/extras/Images/setup1.jpg deleted file mode 100644 index 0105e4f094ca5714287da3aaa99677bbd8a7e442..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 154392 zcmeFYXFyY5(=Qr|bVL#90t$kH(n4=hRCPFNjUL&-{(Egxu5PmpYDhM+L>f$GJEYcv)7t6>$fHsGZ)K%D_UxrY5+1a zGQdmH0k~LUv3(Nc>;M4h>H>rT000euf{YnJK{_KN9RM;306FQLnnaRu&H&1P@c{q@ z(kDRO)6>z-o^(Q<{9h83;*yf$sj+{hS^f$<`}@Yn$ETsnr_3jQPnu6nPg$H#?O)&c z-0lA|gT(p3exwsAJ~wB(AZ1AzX;BFo(j{uT;(y;CiIa-N-#3Mje-)Crgt$DPxVWsG zxRjK*tUMU#AR{d&2Ly{tNP)%qY;C}N4)T)X_I%Rfe9|^RS$Rn*3817jA0Mf{f4{^@ zXQTrt0R~Fgkv{BfC4f?Vl7Bf8KnVwFpd?W4-yCrnpp-ZeC?!Rz#*UA4XP~$&5D1n6 z0v&8f92xt+90wp!j>NH%{44XXdSro8B#x9Msb=thaU6is(j<;8N#?&elCnT)85@!u z_>#vf^N%w5`p*Ig%t9dt0Eiyu`mbKxv?yog9#KNC4&j zUd3l8Df54jEuS6Vf0BcwE#H5VounK|{(nfqR>JQ8AO{J1iT@-yNub1k5T6Yn_&-U~ zK|=OFiPWsWP5X!bvBCdUANcD<{we=h;2#V8V}XAx@Q(%lvA{nT_{ReOSl}NE{9}QC zEbxy7{;|OSzb$Yv2Y3V^CnNj&`tL$1kn1NG}E&YMQ?i|KG~RPry|g3Pti@3bI=O@~dPNSII8A z0K6oa^AZUW{R@izcOfIEpu9vyY7!kiNucfusreKX7U^{yUM<-_&UqAnVz@Xre=+`l^ac|znr>4D6&&d3cmHj2Zps=X8 zq_pf??f1I+hQ_8J9i3g>J&4}E{;~0i$*Jj?U$ZN#sI~PC^zY3r%)#N&@yRI`clK8= zG7^^i@A6-Y{Xg`&O45s*^b9De|LR3X9!MgJtCW{+N>DLBG@!QezIID8iiSls<#SCt zEkDq3|GKTuC>^VS)XHtlU)BDl+5bDmUj1Kb_CJdKZ@p##3>0LfhevT000I!WlXq&N zQyBt79hjMMrDJ;p`_U(61mJL*f2>r58?{ic3SYFzJuNEf05}CM5R^;797O*I((h}E z{@8|Odxw7mLYQ=(zD9fEsWGJ+oMv2tJH@3vkcTkzWB5JyKY(KSen&!?8ixbV@uOce z*8>e@faBx1Q4U48{vmEe&ywJDjk5{VlXzBshM|znIfNo?CI}N{`OiH_Tqr zcc5*$#XZP&9)$N0I`t}zgFDz0Nu-#@EgLk!1=^_@dEHO5-%~9 z-ev;DlnO6XUD9|X(?GF%W(;&tl(xft%zDTZ&2oSSUjV)Xc&A>eb@;L^L()}tAl?W| z6fPSuAfph#3&Ya+aQ7_i2O&3!;deN1Fz?1B$ubb1ZRB4CUI4DTFA!UvTAXfCFU(v9 z?PaI1@9^$I2{hwec6J9aBhA`Vy70}t$6&q?x~mLsx!wj9cD=>(*C&#ftXGrV9XQEY>irC6Ez{gm2;|(g#(e*C{ahpG$AH?`RCl@+gi-_3+I@IC)>` zL(JJSF95+!C#%u@qM=Dn>|h$WmY=+n*7>W5EDi$GrVes|2ti%|$}+tX+^j!Qvr#g1 zb1C{?Kgmin9J;+u=^0Z9y#SnbEA3Cvdk@b&;@w4o64iF%=60q=qV?g9Wqn=D$wAm%3N?{??m5?6^z zkVG~zOFUv+ilYV@fIis9m$CR*Y)C1haE2S?8f$$;eS)HF*R6t2%25fnF*)~%QaR+E z+L<1N-s2+{MUpD8Lwp&9*bsIDD!Z-vQkx%xwT;bOr>^F}Lwd^&G}{S~qPyMu(TDjT zsM!dcynn_`t&_v=R*;O2C(k#TYY+k{vdvi?Z ztq|loZnR%w5G&OwqtbeZnxgV@KlQ`sy;L6?iM(ACo^&a(9_MXFvv1cV@0j$SnfOsr z%?BgHMv|EoMR+rJPm20ZA#^sGD(}B(A50!yGvoJ-(sh=BM!*wgG=qw8bNDMNfso?$rX&C9s!{Rl@ zBp+!V?lee^L@I>j7BhU68bpiq8cgcjSR~SG;n` zA;9xgAC$;k-(wF7e%mf>Vbn_O8~5 z^)3J_M2G@C=fHU(#e`@?CE^%=NuZTGNrBT#KlAu=zTDY}Ae9nkJdp1^>HA%DVB6kj z?(z6_8FXYte>l?sY{PjNh?g58XIHy)E8!bD7hN4<25N!MGmJGbghSVfLHI2@V}E`V zJOM(X=X3z!9f;O5_?I1q1d8bvXAn4ouvREdBtRjQ2wQbB8s8`S&6U5gNz7V*hBCJO z6V$W#EN$izLdpO70jNtKDGNFj=g$4c%kuOo z$q#Q$AU~XKQiITQcwIrf2;|2k<}rN#nXwlYI6WvwPxPia!WriW}7y7l8H`e&xl9?s#S3b)72$j4hF!=QG>L`ny(h z@58fh@)Q1`cqT?>-hK^_B9Jq;=Hp`{Q$a(U|(&!n?s~qx>4Xt zALJpBqN2+1XHY}A_3J}i+y%fw%=`lIs_*&l+1AATpaA*eiRIQHmVPrP2Ae1^dD=FO zOfL@H4`1`{4>0fAqLYEV)}bd-%a;`(Fd}@@8g>9_e<^+2yu^3)wf2Q;`W8R_3y7Xc)IJ^%U)RoaUpLY-A%4vPPPV zI31_%bk&iy`5qVL*Y6CSW@g}>Wm(cx;KCPx)`#BQTxic~v~H^Po!kom8^s)cdBU)M z5*Jh?)tv4-tn73rIrUwG&^n20$s*E+gOqklhA!Q^5^)$<=Cc@S$-8%ltuHxLw>rv_w`KM^T54|#yZ3_ znx(;3ZD1b4!EvscoDm@F&O+%8VTDO~(Kh{#51zm)XzUM?zg<@s$7#0(sGBFQp)d<}5=enm1tRyP#>ULxk^vTlC;CC}Udj|2$86(E zUqCauOPN@@!yrFHLMN!Ul`jC+mE>;UB5tMkm{Tui34AEwZ(BCt-$hSFN$I5>6{`z6 z@YgS1a!@aIZ#l?f=RW@P#QYin?XmYTugZ%l_3PvXbq^#_n{{3x_1(J8Vs2VQLuF6 zuyVev*?lL%N%ZHC?gMSd$)EglH=I6(m0oX_l{%7l`#bj%Sr`-TIwR=ylilA#PcT~Y zA)2I#Lia;PKHV;KnmeD<^klLWUq=3nQGP;KJf!oY?< zt`mu%FKK%{kWWQJ#A@OtB>Yxh;`!dGSv)zvtxm_{L=TR`_yTZ+`d|ab@E*rc7xUi! zMB>F_3jkzJuHIw4Z?ZQVyS)O5mS&>eY#^6`>bmY|J#jBSZBM1qQ}$v%?Yu)2h1{u9 z5g~k(bcB3(nNZ`2m~D$Ejr<1ui?nVYIc#EB1AFXtx4K50QVL^{JJA|^^1w@B?QDAE z0svLA4w{Yvr=$mH=47w=!><>Mp!p^t$YgbHtfCzKyt}?fm71uokBi z7|g*T{49yO2Kf-CwXYw|%TrBc#a1nzxhpI^|9%L_?vF@~%H2_Ev<>b>T8TJXVR98F zbp2{Rq=rJJZ-NJf$Iu?(nYUmPjKE(N5&WVbZEocHu*Nfgy{o7C>8V8YFcknVG68qo zyHUWyf{m%xX@i{b#HvbAxG2375xF)RfCGet^|S$@UC?{5mQ>Y&t*+I!0z!h)1L+IE zFBBqMdNIAig>_MIA_;cyEQn!%J7APK_uI+^AVkkMl4e&IY-P1s$#|>`>ogzE5sOy2 zu{j&BDfFh!U2fqS*PG7ZU9hH=4p_)mb1um@J9ePEf%8%k)N9N_=`=IDAdoz$z9%K8 zFiLO4Oz4UXkg$l89>L!mm4fl&?e`P6H_xV0yq5{WtJ7NF+e}OvUl+*u$^>%%D5wc1 z+qM)jN1|FiR~GY9T$!DJ5EEID<l5)1DJ(xikh!_K@6RNqtUGLF`+M z+VJ_RU{f$SXwOwJU%o!@K`MJgx@ENq?g6U0(p#artDzB_a+2Z|)~fhKqIytmI`20{ zk6gzb1)?&T>0OJyxA&^@i?#)xPoVEYbADwq3(@?%iX&|2Gu#Z57K}EpGZO~e>mRZ$ zZbplcmKi*RCm~ld;+QP*W|mkA{23d4fFq=#U|ucTt(m!}A#+AyrA}zUR4wgdo@!QW z(DsC!P5P4k0qxh$zNp;rD!A+u8t%FXw-@8QS~WAT4y4Wh+W6yb+~RZc`gxwFK2#&V zeD!MiTKER8N$IrOeIEiP#YAlT0Wis0s!*pdm-OaE*_2?2?RedJ{?CLf#R(OncoEl% z;J4QkcXDM*B_Qv6Fy$0yP%FJV(cP@(i65MHzohMG(IxkH=5nKp^&p&h5SHYRE?G^g z+>hwxp~t#9vSb7NLndXfq)}7Xcn& z08hu`nJ)mb!-Uzelcc}qG0Wts4LL=q>5xw6I6!&~VF)F2DFNGTLx+*HZCO~vL5cOrDrR+V_l50Y zV6HJmsEh>E79`Jop5n60y|%+#ZYSx)z>Z7mCoND>ZFPuW8&t6t55;tg?Xu{orio zTP|adq}*~M87dn+5Dg(A+poO$db}iH9q`*k#)x^MC?QXYtID~4z%#7YMa-9Op4INn zEtO>|9||{=z%ne1sTQ=H1OHAeKR2HV`f+Y%esyT{;pn*&9wM4i2U=6O+@KcV^p;9^nzt8-NbR$SM@JZruA<$(4^ zTYxt|KZY>+)qB^q?=#7p=GIefTX0`N?xncRCX30=+lHS!G&7Y?71@VR}v%fVi9m@zrU4bRK=^S%N`7$O+m+iE-RB z?%7p-cNkFpniRSQ2Vc8>uAF31-0zF^Bfcmjfd!Wyz$xfG9TYw8=!JU$&(00{yLYah zhU#+Ns+HMEoIe|D!Nh@N<*TEic$Ph5As#DOAB9umo8b^ho{KC=_m5k}Wt)Ex`84z3 zVh_-;^MPdWn96}`9WP4n{IOm5uIutB=_U%32`_iX=aQa1p5evrmyv>9z2l*I(ab*# z%wbE|Qx-y&)hKTm*RhsB+l#t=`M>pU^M&t7hquI{NG__V7|(J6c-G*#2yv8hi`Z9V z--(nA&d+GyVQQnqz%jnMl81|JPq2!lTk((M?W-Pv%heg^C1z5)I-T5Lt;saV2f-ZN zt8K;KCNmAbFL8N1e{g5u70ro!X^KJmK;Z#|lL0>ol;`a-<1en{f#8NTz3(ZeF6hcU zS22&O@-_%BzE6T7a6I3uo{MKvr5F9YZnD0SQoQ;uiZ5*gPx|GgXy~R@uCbVZ{pUQ} zn~Z4#;dkGDvBmbt-#``ucFv2FCXI*HRvJ-x#EC=iD6LhE_nH|X^MDJ$sY`AqS2%zs`l=s=X7UI0{8me7PJ1wd@;&W)}&h9$V^Eoa(!G_P#4mf z$#xFgC$+(PzgY4L;-GM@j|Y9&F?NkuTW#faYI)X+p#Ie^gBgPe(9tgFnW!Mk5tPfzjzK^7e+O-m=i7Q9cQ)Ollq z!cH2wy^lWi_Hf?+>e<{Br<4?1_``6BPDU$ZUH?&g`GDKQUZRQB31~@u`_LB)IsScB z7i_OS3-4@4w1(@S-w=xx#449Q3ah|@@YR=FH)r;%DKyu(<}Dsb?C zLe5HmP}ok$LxQ(@Wf86gvUzc>!`!jmnzpU*My~mNbS%2rG3#g2>guzZEmgyLceTU! zyNV{Z1_@@O!d9DYH>}jC-lD2$A_m*UeqeY$EhjAS1SKp zhOYEXfxfxppWK^<%)!AhR&RBlnQ9KG>Hvd5-2L9i%YM?hJEL>+Uqhu+6|Wu6B7hk| zUx=54@>G{ijcqp)w>8xt36qa)o+LyZs=g-j8Bdkgh^jw1ycYEbw*2H-E4?JXEPtG3 zNQK$WLzZ#qO1~PaE3D|rbwQrsY0;v#Y3W=vV{KoDnr&5 z=cT~`4=`N$Aao*Qy3GO)zsqfB3~WC!=-o6i_XsM|ERoi~he61rrYau#eEaN>(jXy} zhLnyKoR!I|>@BT)cW17V=tuUujS}lC7T>~O;xfQJeP#3T4a|j^tP2!`;ysvD11>GS zWr~5uiT+wUqzpI^NNwa_pZgBmCI(l3hS<4NiNLUe)7^{~gV5ox7;bN}$p)$HTbBt_ zn(}{YQpU4!r>j)OUP@x+cRr>}&8pd2+zi^@TRJ$ou2}PNDc*Cfb*h@Y6enuM(?;_2 z+-9SYea)qK(0)amfXml!&2!sU*KL=@742is7!wory_NEpqz~b5-Pa)Oi|#m6?ajcL z-!v&XXJ+Hp`&!7@@>S4{pi<3u{z-AJhmxdO;T1a1#! zMthP_ecGyDsCj*vVt;$v;*8@)3*?$8H%e0YL=h^rg5h~Nv)CHqz5wfKtbsJQK{yQp z;{m&7tCWK(`^P;&Eb#rW1wtDcIs}o|#F3{iPbPvsi3T!aE^TlF?E;5%!u-9=2w)xn zX&wEcij(o-!{VGt2avhhS5(uySd!f=n_u&T9egQd<)sewBBI{)jk~%_%qMFRhO+VnER=KpD)FoDo-U7UqpG){qL)6X z7`M@g36CjiUDOo~ef=fCbctEiZ(z;ey`qB4C)ayCk04h)g~ST!BjDH<7l7LCgmIk% z7fzi-8?Wc@BxYDB(zfXGTDLI{TYIOBvFMpY>kvpgy^1ghFQ{^7zoHg`=q|Hv=W4*H zX|YoL?u$(De?gH)-JU=l~vAQo!~c^0`8xIltT$jKP>M<$1lr#IMA|*;5=uNI&y$8{v&s-$ zyeql}nNNt^xx82=eIy9|NvO+pW;uc?lDl$9#vto`AV2Th%?I)<%QH9OXc!2|I~I9$ zcthp&M&=i|+cFHnK_r3XN=Z3JL~=+ar4OW8Xy6FJTM4+iJeKjZC@t+V%)2dm{}Z*_ zymF$Q?5vW|9GWd#cdf@d119*_6i~D|QQb$>=C7 z1U6Qf%s#w`ihjB?zqFgDTo&M#kf$qZ_(i-_G5l0)y72AI1_dP z)&pU-4!Fvt&1??5yr)`WC-ee`L;kJg1dY3!y8 z-=lM3(e9ODn`DUoIQAn_Kss$*pu&})elAMv$Qgxi?kxZ-UM zTBtfO39>=pHri%LE-jVV1HVGTH)gM`BD=IfOhXp{nip^18OwH0lv`Lh2b2P1sD)fr z@!Vd;)mqr@Rm*j=mwy18<_7QGcR!dWyswj3tDiHK3J2|QQX-t@{W*HP`?^d&TmVL( zXfyu0%LqOm+D+4zyY?GFw;lEbYeRV;^RK#K1RB%Sl&g0-i`VllA>SgJK&yAoS(h&> zz6@8G`eL!G7+3W~%3`NtNM5Ji{`?rVZLD&;l!x`TBhmWW1%Ncsa{hiT7m-U4`H1}j zS*c z*AAM)|EvKVO&a3Todc^f4N$UxW*JF^)$|UX-wR4717W|=*{@#Q_^{@uG)d3spvh;C zYhVV*Z%*T%cr02cD(d2hM{$6&aFG5~R!Zjm*HGcI>IL>;;Vw?&oRbWjy*y%iU0^{X z(@I8GrKKXx|7CUn3=MAcy$Zj@b>iT(jyhOF5Do(!zs!-V@nbm(ineGNP2` zKJvsE6Bql-@Y!(=Dr9THq-97-?1mm=n-9|ig#(d3CEse{AP4MM2CK2Bl5*g$qEf$3V7Ti2rZ3GlydC1tQw=%*LOMeGW3ZVt}s#55ojzT6hxgu z(Ykk2hN!sXj|_T8u%29jq@6Wg%1UX(qT3w@ewD5ZfL7)DOXHK_n=!E}4(v$C;Sd|M zs`S)`kaBP_eHyf7>7$8fX8iR-oiBJZ>hmGoSS!v7eOMN?uQ2A(htAGYTYmR0;92+v zdNEy$RJ%u8ogx1aR~uM6nSQ{(uF)MaGVwNe$f4p~A8VWlVkx}Z)#4dka2_cAwC{ka zQ1!t0pyu$_(dnh>()Jze$E2O9+bxcyVOqS?z0!#9wg@+z-RO9j_oqw^BsSIN#GJ9~ zItBtmnVD#alWi0e#(%`Ouc*fMYCQJK`A_=29L4M4Xt$}1z$&&L*5?F+L{^NQXj zK5o9f$oj=1H@o08-(CF0;Zzi-U|8Z3BKHzcUSrAP_B1HbD8t_~XV85HVgAPkCNCC zsvK#u^nB-yv+9-FTqX8g>I0E-n?u0B{gYuQ`i+KxGb1%0ZtGU@dR<;GRMp~LGZKyu zLXRJp3%DM6x?SB#dEEENXAIIpz0v?0erp}Q{XI7nO`2Mde*@I%z1ngff%m(aINC1& zu6P>W{uq7O5wcD>hXsIepl=KtN|xASG7l@S-+01Z)`VF0)qsUck!45$;`T^8#5GuV z(w1>LJfOv&0`!rh6oo$|k{6__SiL8EfpTcDbPU*8OKMz>Fg~`kJ{~NyF{I=h4rSlrwN!~bzw@ac;?ToRW zVTLa2^C_`hV=dZ5IuqHH3jienTb`Hd{8SxVN2q|DtAIF9kT?g>B55BNBD}wcy_@_T z@)GiPWaVILiWavu1w!wud~bSkAKD3-m_XY6n_N5P&Yk`i zF&WA?7RHuNx9wZLgUWRqZ^sk$`&(Sp<~Y$+@+BED?Z4F?QU_LtIL=$F<08V9Qefva z&c(3aF*c#5lB@>xQXp@(vf?_D@Y-($HqCxA^!SOySJ1EPdQ&};5gsk1$5p;Pz%*<0 zQwBtJ0kHq5fa;#DwZd{)vn>iWs5xJIkR*6h;H_EmZh_;+`I@yg-Xs)6LTx2ao;o|F ziXFUu-YP6?XgL401XXi(|NLph0*o3Tc&-$5t~nYOjQXf;KBc5s;(Q_l?CRjK&t6#7 z=(G7)?A6D|ZI>r_GLln@Iq00pz&#B`se*Im}loa6bH7XSsY2V&9M zb6uZ$odm_1*UD-<^jrB{oc@$sWAeRiIuJQL?`DaX7Y-6vlAgQ%s`Yq3U{FH^de zCr}3SJ`V4+R{tS+xif(wqPLZ6u=fvi8!(y4Wp>OTT->>;{d6$jw3gM8nm1r~5kmNE ziC<1hJ1rH^$*L?~{7xyealCC>?e8qQt~#dC-?ChDtL9VMnkBkW=i5n<=H!;uy|nH{ z#xcLFcQ^&!S;MPoz1a@wNIf(OJd8Y#uiNij*}~={eyG5J>fEyCudnv+&KP6@^1OSP zJVfG%qpAHUk+kNLlgdQ?Rqh`Gd49ruUf*c1<1Rf5;aRMcoN+oUK5@qe7KCY#W|62c zwtcIW+pjat?)%Nm$2=J>^ie$zc6;|Km`1_JbuL0_2Fr?m{PBCGhwH!_cY##CQNXj; z^WqB!^N!g#bs}vXhU|Ma_71wE(sm^wk>_hK4z$#eq2!p<4Cg${N08Pl;XQE$3Ka(Z z;D)Q$8d=%(T75Tn2*L_CTLYA)JHG~JTcrypna|2FkfBds#-BroG-96x>&~r$#$*yT zYq8c93yAdJhO0wV%BNaPqpqurfIil=m)MyBW^v2)2M36LmGo0bJl9G%1Ej(6ZABJ* z?e>1TwE^sL^LQXctL)vp4WmHT4)4AZBd6=$Omi2*X!V&&et}ld`O@asXqekI>!?H3 zdqpJMzPe>gG0tsvbeDuqazAM!yuq7(?yo1@{&6&1=)rV|PlPDXRx7kFZ>fxm0*RPv zF)?W4=x?x8s=Yruo>3#h9~Zl*Fd4+2X0$giK2LBRlT-WVO>j|(t#HFZI`Zv_S0}hP z3Ps3x7M&<5MxGuroJHJ9?rkL2J>p6F+;BxE?{0;-bL85&qxAg)+?6@_X}j;r1jVr1~m{M3doG#7l0t5Kl={?>Ba#tS)Z|{ z0*_M}XMxt$+Dqsgy1*TQ2BRsMq}Zd!3l7mCthGZ^im>4i=dPPd|NX9USfBw+WuO{)^`OTu)qu#x3jRPMeEekUD za6XKxgJQ1GARazaYg%vGGuAfc|F{o5A~_&X=C(F4iX3+GW89t>J(V}QTL;?l+evtO z)0S5Rb^_ONJmVcs7VCv;xx}0+q^G>oKqZ{};Z+)(((o2oKyd?Rav?D>7CuXa*1uxI8F>{JRhk9 z{!zv-$^AO9U^Wil=qa~_WI#AioZ7<9r&EYa0o#G+?D)sfzq{0mhTXxNCFXh5^+4=X zdEoxi$>?`hnMJ@Q?;qig)mBs)!54rwxcPpT9V*TG38ejjRA1#$b)0Y2q*=~$IvQL< zaEL>wA8NWTYy-uyw`XvFAa;sN;EOaa!r`c7J$%$sb^-j7v~6-`pNTES-?0byl~(Sw z{c~K@rnXGl_^u=&i?`@w^V}Wpl6`qa{?bk*5F7TYrgQzr6gnnpFJ}51 zgeBsR9sjS2>9d=q8B@ZFDN&8~nHyVP`O${vFMHM-g}uI%1MQBBXxU{Uy;FkSQ!fT` zeS)h%t9~$yb^{>{Vp>(jmH0LC*MMUNiOXZrQMIv!r8QaJk{){i;v%Of9~qIo3vaI`y%vEVc2D z14%KVBA1Wr<-?@@Kk*?_9LFKk+4iAgLO<%}G^092bvL1JXjhR)0p2Sc*L&-F&GYs&9!&W%qMXR-AT*PhVT zkRGACSWGF;o}@mD^L`|i=8|wR>hwo=MEd#X>WG1pFDI+>9bQdU1j9C=T! z&wm;RFZ8i>k($2yD>i1&cOPk5OC0`s&_e2HPyAGWwaY0!BgzR7ME+P~`6l;fAj@BT zcIXeoBry*F`|NM;ae0J9dc&|xbzz?|-1msm(UxP@i z-&e_4OX(j2CrJ9BjL9!4j|$3cmg+K-2j28NJl^aM>~7FEO2>!r>Jk@ztc4)|d_-BW zFS!(iK=y8gi|xQ~T?XlE;VCf`;I5F2@dHA=m$(EXd!hWa`J{eS)E#8E$N9oiWpk>7 zcEbUD*mu&)UUNDR#711lilJf-TAZuz5O1ihF`b`HqL%|4P35;*8M@tz@&x+I_C#-c z+PY|r)RlVRwl4tTkmK^kmHV_9ijWC8Gxk&G7w zzL^0xpw*?7EbgUB-KHOzrK?;x(?&B$eRXZR}PUkoWo>@Rt+ACy@8HIiXr19to!D`A=0HbKLYhU z23pOlO9GXS%Qz}zK>=+Xmf^)Ku$Z;s6~Po&Ad=u#nt(|!NolC^`DJnZFO`41RJ7b`Y!x1YhJ}q2uAQo{>mN{`njKWV z?g{_iB2j2%0*%Njcy!3gf*(4T{{0xUezSLAJ&9V!C=kC!{JsoOKLHJ7zmtoKXp|c4 zURd`)E_f`Im^_~g+&=>8n_IkI?1%r!AUN9@R`kQYp>jJqR84)ufIX=GVf?L3X7?j2 zY8+`3#re5c9{lD;zV$KUhPF3s4T3!SM480!-RDkEM_1JN$41cS()^=gFS&xZC;M$b z&l3zQ%HF2)22wH^jEn&EId*@(QWp1O+J1zQL=^>nj-{S{75;=0y-kF4J*CLj(by&o z`x5@_qV^G6cbl7#r@{D5a!)0~XeRF-57XulU^(66oBzqtr%T>%=6>HDn#K%CnyNe? zo&*=G`QEtzcth8G@zBi&v>Pw0tJsP1pyj*$S?Q7Jb@tOu;;jz_Bn4JlN@baFcAq1U zxg8>JB=ofEsiTSEE;4ETX4b22?)(k7-a=4wlo`nX0kSfTG`C$+!(vupkxR9-6D`;M zW+R$Pw(6(Ij~;)k%e8k%pBKS5sc02FyQ1_{L+%q(fk1M(H!0DXzXos(pGePVm(q%r z#+t+Tjp4J@?U|YzVOo=7EzR#=WM;?|TE@O;@91i|Zb(CUEp4oA5$jI68#(s#Dl#UI zb3#;#Kt(@f^yFL9kN52Y-rrLnq-t!%d~0%4qEZav;4@LX|3{|~yywIv3_{|z&&+a( zzr3po&jrHN6C1DoPSw2tL@Wr9@K2Eq_^$>cUAgZn(`*?j(G~i~uT_Z1Y-bV9W!P}r zU@xF|+hgk&-3+c9LLT*^NyKAL0uyQ(fchH@Ci)feVP<>^~ zw{hMAJU#qCQscU^+tol2J1Gq{KU;VPOR>^ASN0Y>aqOglSYY%l=4R?qz)9z<nCK_?;k5c>rb?$~OWM&LQ16D8gKk%28B)|a z)0bB|Sehd(yUK`p!ZYQeO?Fj-ToEB(Fg@~{g;P~p`wC=5cboC26CUjJ`t+8r=+Om0 zt~}Mbar*`JYoTO3C&sp9;YM-1Uuf#$9x00eI%53YSR;Dp;ZX^X7Z>I)c7gw}@je42 zv7OXfCY>pmpV3oN$MDN@eP^oa0`NvRk$h8KBw4?vw=zhKRldM_@2GpkJ0UmiYuw`@jQuxe()Vhgy} zZIra;&hcsRd-58ZVyf)}>8bE~mg2d`J!S_r1;+JKRoYWo11YGf6F)I^7KU|XHcB6R z{&`n53u>Q}^AMb!I%T6xI2+jTL!Ji{(~)n|^Zop7UKT0>ORXtqdm3F|G+qE4K_j8W z^qPId-wn_npJSA>AsJK=f*V+ISYHG+l}h~VGkS^BJ+URHlMck&}s*U2I~COoN< zo>yT;BVO~jl}rNW$QSC13-&3Mt=aB~QC!s7y5Dx~#|fFZ=8J6 z0V`6EX4We_sCpd2GPgLpz2um^k}~_7${n$O`y1r4>!HwNY_nh;hN82%z;vPPd0A5P zsbvrFi0`uU_MSB<%aQvgY*nwpL&a(5_-#e6(X?BR96r%mEm5=MVE1vMmNe%J=%D9~ zJN4L@)k}1j7Xr?hTf*R*M&*~|iuw1eN#XF4u7a`!kNgsVh7q9?V4H zNIA(n-R7)H;afc0=Z;%ryQXlj0RrN_+`RFg zCiODi_c^e@wWF8eNRW=UE_mkxa9L`BN4cVAz~`_mf%(rL<2-pTx(JgI=dos|j59YM zs+I|VaYy&Ldbg{jJ!KE_wC(ucNoWd35Js#szg*#??Op8NuvZI#_1~ahZAWqDau3M%JA~Fs&ae@DA9)}u=?V}k{ksIGq zf4^*`vP68$S_dZE{-mJF#{RtKaS3488@c^7xS(XfgOu;6HSuLkJ3d7K*8pLwGIqU}Ffw=EJdKj81rAQlBn&!w22A^OLDyYg$JLFGnl zPLG0X(bTi*n<;%(R}DsT&yENnPH$5|ol~aSj#0!8ZK)Hc9z5dq=ljG{HaEKZ-(Ko& zN-;IW=^_aW{qME=R@nm02WvTGCf6k|E25_Hhhx=v6HH-MDMr6*k?%hIT$QMKKi{(j zY&M&qOlCsObG+7e3**1^#vkxFp;>=nR=!xM=(StO^|-{!I+5!8DQ3PY6KA96s?Jj< zaB9H`1MuPJp!`Qssn2T?(8{#9|@z_^Ga$BRV$(lkH zg88g+*QJCwM72P~htiDrjpTX47*+z&4yR6R4*1Q=?TJjpOygr&^KV(dzf9zT&-pR3>-(77Z-YGMiQ;Tx)XX%iH z`XEHur%$u_{sY9NjXeIG79`9}rb%Mc!@zwam`xp((w`lP2b0rVz%SNJqSwAzqQ#(M#FiIsOE2JVPywCHSi5 zLdP**UTWc6?7+~lY(RjDWdtaRk#T@oEre`u8)sPY$`}yhUletKARdy3E0BUjxB@_9 zBt0!~=#Z7;^ZF&(%czFW+h>l4rPLs(HJ+61S8Y({=z?0eHD*!;6$>4Ix|Fb&@+ho@ zsRt(BDYJ-!@{rK2ic8WbWp zJy2{K;K?3RROa?%4CyI1+u_@I5bpTqRQ_TMCF+%Ogf zsqZE_ud+_2V65@i;g2{S8kSovv@PCvR3#3^S_IgI8qq9W%fE~BzR8&U(9|HQs3r8o z2gCY_8BgyLCl@cF-iCL=u(w@< z@=+?$)p#v;MdJ~_Akp{EkKeY9-y7*;zAJFG#)p^Rxj$;#3K34i<5#iwmA|K1V7atj zZQX49g?i%=ud2yFB`-YK#e0HVEi&(4H);VpM3B~g?Iz!mwZtJFHoJ~GSb{r>-wUVh zJe%R0vek&LCWnKHUJMR3a3y(Lf3e;-dXm-!s%dt)6fKyOs#X+wIA__xH4tG`C#xQf|U@>jSn%MRC@Y{NZ z9-2Br*&#p9BW$zPbh$qdiVVEw)!HWV7H91Xt!f9vnT&{X%|N<3Bq3y?5nmdob>ja- zaP(aOSl_J{2*o5VJ!-b!ZuTfiK_BECpH{5N?fU*1)CZ+Y6e6%=QjMPao?35Y(D+c} z%%PEhK$QqLwDKiGjMvgi^WX)*7d~Q=uD{4z9a6p;b^&;~=!;06kMN_G7@8TVmqCB6 zydB=Qq%}Aey9Rnvd5Z)SY(Kp!siZnHF~@s2q>qY6-tV@;aFE6_3Az?LDs#A(_x{Q+ z_6XPC)xTVb3lTSZYwv~TH>X4)b?%X(%iy`B$wKgI>!Sw^CJl`T*Q(f>_!x)}B1|Nq zl3!6Wd2zoUbxlch(UocZynF!&ovt%$#7xF(3-vX2u|%gFq>LXEtuuS`S0ldZ?d@(k+ZY|VE7k#G4ui4rZ7DtVE zZ+AyT2PM&$C;FVN2LczYG!^RQZzr8>Ls!Ap32=rM&G7P|CG8|_#8{f|k?Q9@7~>*OW&bqi=>o0JI=bam^oV>Lc}z`DYk<3;hl zSW*>NU?w+P8XV((bAX%asp9{l=&Hk-YTNh_1p}D@0uoa|5CM^H1}ZHjrGTJxch^t^ zBu67TkZzF}-7vZZq+xWA+*rKd`TiT%#&wH#LQSU-12lJ@k*N6UJ1e3qO2 zg;9nsO=8g=Jm1{>!_w<3ex~tF|C%@w#=@~x$L|M05ztOd7dZBjz(Zr_Wbb|!=KTcv zdEnT>8Y^;FNT1)7V^};-rXVMpkXwHy)E(R0r28p#saQZ&uT!-&BwBH4+ipVYZuXni zat_H-L~0)U3j|u)`|6$mtgrtV9uoggeq-~2l=({;r|e7UK&_LoMh#p-BUy^<@l$-Z zpC`dOu}nv|PfEYi$k=gdsO;a}5zv*NwhY8tQE!USuYX@5J4*uLbV{O46`HV3DPy}^ z`xA3Of@OMT-TJM{D17?!S4m22)HlkC034x|ecsGPl(jyr^RaMmj-cYt8U81zqgyLa z06vP$m~V|cRZ6SU$d(QvH2FZFB?#X(Q76OZ|5oF{BG0QN{N0=Z>aX)b%8)RY-Ui8N zvqAU5Pe?<4gwb{h}SKgqo79+1Vde|O&P&!=yS?-^v# ze@~z7J!t5o#5b%USGBe9WhJot_|oI?G}J0QR5!I%jkV9?KTyFfLseK3ZTK(c3n=wY z9pL}{QjLt_yL5RRrL%1N|8C-=w1#bleYBR(Fnfyl|Iby+XJtLj#eq||;rTZmlE0rx z&t5C8K~1O4Ft$1!9@~Z*(+U0Z9Z}t|f*PbB+^Gu^VoQLM zuC}?{++_KVv}m(7gjt5RCu~x=r1^nc%-@%E_+p%1gg*H}4)0Bz#pNO)25Rt*P%=DU zj54~&pY4Y?-@I}$F4dRfU%AHhCpd!kH}q;MoP)m9tsay1`Ch!4JyHBDFA}kHp#G&A zJ`$(x>TooLAG=21z9D0}NJey1)2iNdB&2i8k=SSo+aX0jIU#;JF_0IkLA;~wS_c_@(EzWa`>3&v=wK0S8cA*PN zXM6_eSr8{S{}yhNj^}Y_B$KT)kUWb%;rdF}&khJ$r95s_`gBi4mbc!2$Y%?QYbO-{ zp*o!u0+qRzllB6e15<||1{@5YWVysFZ>7mL|KFc2|6H7}o=_Z&aGMLFb*c4rc9uz( zBl&AXSjAzBJH-7gn|A+wa2reFCj2_`7?DB)nqmA@H8P265l4LPoRsDM3U4}6(S{8Y zPiXvrbID%zHDv?6=tzE3*FvdpP@*oGUc%-U?}+VtQ6FMen#Xgz^j3PhGn7nF9jwSvi4W8K9G?Tk*7_FIFn;d zzPrkF`=8JU(u%`*<&h6yU(3%8HBpF*HzW^Sp%;%UJV}ABt-|gcLAuSDje>N7=kBO6 z&fXO6XETwzJC(o&wpXY>JJ>OaAN`go@ij|g!nTw9&p!RxTCG1hUmTi9Hh)-ASy&Bg ze7Rytq#=1EZt(=x)TKpQBUSyy?V!ugWlBWJabK0Fta%JN9#PO+D<%h2^@ulOdaS)G zZbbG-{C?Bzb$L5@>J~j2PL~#+yK!Iu8b=(7ZmG+Cl{HFp1)d7%R(&?*tIp}muF@31 z=@w~SxY0Pq`?G?-ZE(5U?}JGsZ5GOpocye{Dyd{<-Ry%IyD zueOw&+t!X&N7L=(vh0iHR=rV@RPJ%Mc#MYXCjDs1H#-#>+x!eUhl9ER^z8;nP^k;^ ze;`ryvqv?r2r7BIz=+E zUUwK&lq{B6jlNdf^T0Cnv-FEr;;#&9`RnD(LC4>Kq<=240`aYdW?} z^TwkJVb^wbg;Y8#^yeT~Bek zcX(XhegB%z?#UA-ugk(Ap){EcET&*?r|qT;n;Oevq?J#o)VfevZWi%BP=95wN#qRF z2HS%c7bI01PeIsP9nCBM9!0S{P2>Bg(LFxQK_$b&`hGa-l@6y@1^q*;S7kqh(IlX> zw{ZhtQd5Q%cE6x53(SbN;<&H@bVCaF2EW!+RA;WxJtg+;cXT24j*z7si~m3zzjy@C z^7Xf-gI<1m71421_mqj0q?7Yrac@uM^pITYV8yETMGoR{GYHI^`d2qnkox<~mledV zLya0E2YGd6r&Z>vS@)wo-DbL#-X<5Ru1j<9<qk)r?}X3Hxzv^Yv$G%y}`Q_oooW zE4pus4h8U9pOomd>y{v~TqGW6@N{)8ul&)FONDcDM5Ui=&a@cmvm{W9uJn+hLdtxW zi<}DUmJRa`X(zMDRW-783oD#w#gV@*ETUBaf1NjPwy)KEVNt|+ypUdN%$y{}6u{>_ z-}?$Hsch)y)_5gXMFRul)pn&@v#=-qhmY6veHc>LO-Hj_H4OgREA=h>*-BHUllIA> zzAHXT(|y|+cs>o6uGQjA!iBc0nhxmryY*+=0E8uC>u=b9po$jq3)k_s)u-6MtCF;u z%Qk-x*w~}c?%M!wPW)sifw=Pm@&IaGk-m>yQY2us?q5|xCUOc22V{0VNELcbp1D9 zh#Myg6+%MD#(oOGj{<2;A0`>MMe95eO%#`YVfQg$`^GQ6`Ql-Nm`}Cx%vDo=f3UB8 zJv552O*o)65ZOeu7W2>IO9VrowuVXX%+TN2k%RaZ`0SkJCAo6XN%89h?mMD}C`8U_ zrmuba!*{zJ-kB`iD`_?n3u%@#$H?B1N{U;H#(qOaQ=xpnn_ z(&TkI(wX8=Df_xHtBKL=59wbzcGVRE8nQ`e4$Sqxm?*a5o84sZzFDvNi64+fAx*Yz z4iS=WfX{T2_RjWm3izR+i2p!FfjXBAmJnSCTnMzuIPZjUqC75mBVvN- zyU12PwK^|w=z<&`wxdj%2t{NkF=A(P{PR*%HhdYcD|5+@hF_ALhnKIzr${u4EL{zX zL#|59E%G3t%MHYufbku_nFGTbqvTcHW&9cuK#GeC+;i9UQQ4hwv5QfWVjTna(r)r-HrK%n?1FcmORbWEZQ7zJyPw zKGmX%Xcwq)e5Ghq44KaHxrj0+x%XALu^!^SWw~Jy$3Al?L#m<)EXo&}Z4qh3n77PY?(pGg$^5IXCRJC?iPo`^ zYNE7W?U#5ddh?m`SuXgXd8e=Fb&{fRI@%9Whn>`~$7uix!&K&z^)W#)YA$P& zCiPo!vY}%XX!VnwcGDo~$P1d|v%sfV9FrgihC0==-K^s5{(m4Y@Ro58rcePnF7pao zt?E#PGAlKjE9kw6HK6P#g%2(v=FY_u{Hh8f?JZg_Fu$aR~B<9l;c_T@o+9U!!Zu6 zNuT8#udayI&)mI25Y#K5eM}SiXm3efKAt;iZ|JoecCk*yk_d>}n3bu6nM4{s=1sEy zF=AokWiQ`+E`8h%cJ^~Oxwegj&;@es__82uf1$e{H+znEGp&iGJ_!~(s+06|6z3E} zefCF9L0CuDh!(0aXK%Vq{9HBHrF2oy)xZi6WIr@9 z^v16)t{%V4b*XI~njVlf1$hW?83l^%O{L)|cAaWI^#kV`raHxjvYoCZ>U{Mtz3SEi zE?T{Aj5-$Ba;ko*g<5e#;ZGFCd6YC{PsJ-rS7(BsO>YPqy_|RH6I%(6eE|V^Q@|d6 z;+8->8)d8?wI@P*TNvMa*W7tlU43)Bi0mg76IkPPDQKavOqDqk@y{MGMIECG{Pg(( ze1D^Ay^YLb&ixFgNb2-w?W6f$x~Nhvxocf>k+#YB#|k1-ZL37lgUf-y3pB!D*Q4BX zro&fdkW0n}NT)lgMmlu?54|b_FG2WMzmMAns!Fi)6eUkSHIw0;(yi?sriIs8ty?d% zR`;y%E{>SdR%Dgd&`URHOWs|3!#>G8kAerc7B9_U3B)cS9fl|F zP-Br$zt=P~mrD1l4Ui{aTPfLsh`yG7?r~=#-QMf1BF2Mq*40fhwOu*|h%vDcN19aP zNQg|O@PgT1a9CHI zS-1^ig*4co=OG!Km%E39_d)2>t&_avuTMEQ7AOLC6wI6A^f%be;I<%zC^r-Ud_Vw> zvdL*ld_HE22~fHMglj3hZo?k`8KdU%6V^CDZtgj10D?nX=nqi5<^n8-^aKY^gt8lW$IU2q-+;c>uc2sFzo4vakz@OcQms4~p@lN{q)jq6qGKzfi= zp68xPD3rxr@3;*Ge!PR%6Rw^6r-Zvbw zrY(I?y7GypL?g%aS49sxa_Um?THYlJb9C?R{HDZv-zIN=Aibmqywk2;(c}DMC!Xn> zVh)3|3DdFSqXutoEd;g{mwg9>F5K0!^(prh=a0Z$!p6!XXT>iciVTu~Oa5n5mg}V= z9v<7lM-z2M3?2*AnF$ucg|pds7Yo@mSKhaAYDgGt3p%8{PR<&v6_Al;F>^(8hY$01 z$IqFU6k z$gaQ!e?0)ZFj#2BCeO^=9vVJn9!}mdiuy6muQ#%RQ&Ujr0<1Otm)Tj`b2WcYY6kg{ zn|AJ2kR^wln83WtN&qSUW`cDb)gx95iSy|Xk-Elf7eCU54gNf9$_`^7(Z$ib{0%5= zuju;F>{117(xTfyoe7_L5gvr;IS5`9V{V{dZl5iOU7dH`|La1fWyS2P1bZ{9`*u)! z25L=|0E0=R#!plBe^EqC{MFfF{JA(^5_R4o2HdWyJ2B@?sp*npqJz z+_>(7iqPyt&tQRmE>|RNZ?@F~RD_4pn$q0sEi#vW^5x%0 zh#ljeyzN*lR4smKO2J&K&PUf1-Jo@FvzltzU}IcH+SqpEn&D382~ypdOg|NFUpd}8DL zT*FCJS2sAR_7$QlLV-~qK2a2t7lO-Mcp+R!+n$}XGMQARxtYiO{94b? zMc3BQHd)w8tPF+TWb>CbWwW_Rs>ep)m_REVb`a4tiU`^nBL#dY?RVAEspcnpg<{X3 z3WVkdw!=E0BwBE&$)Bw6@P~>X6-I-lN*@DH{*-A2+R%Rn6V5oQi>vab4}H5n@|(?+ zi+%j8_iK)jo8;v0QF!N?qV4L1l~s)(TXp|7^aX4do^QjOC3!o2KLZS;2@>7W@BA+X zrcutDnanX@l_^6R0Gng9zg_W`lf&|+^Hx3>bY?P8*>49(r``zB8>F+MS;L>OWO8*D z_&G{w^6EqUfU{QyDKVcBp4Odw6arC6_s|PTW&47ZR440Eya<=x4M;UYZ8Q2ubf3So z!erMOLQhBGgF<`ZZ~Jrtw%R#oXeKYAOM6Ga8kPG|CMI?2pSGI3iQDHYTab}pdK{+N zYA5M1KG*NTq5Jx+zRUaeha)oE{ZN%u#XgzL02oUmE&W$|PxR4eCNBomt{8!fenZlI zE2d_DwfHs8%FPulH74^~zNQKg_=Of$D>sBOCNvUMveRM82?^n16evCysKa5=XEmld9t^&hwsky3x9Wl4*Wl zeYntI-{;@%_jMFU;KKa}(#LKcZw9dSImgSqlGvifaszu8R2{vB{f1Vk zPn!Cs&37;1x@$T6b49#>)l$}O=Y|Z2$WUO*E*+er_K=4@;E=Ixx@6d@$I6aI`^10H zN04CXa&QR<1pnEJvr#qG#rW*#e`hpJApV>seSqS*N*w>ZIGDfm&buySQY(z5ef0q5 zbyn~*kMl4B6dg);TvWMoT7&z_hWJ0;WAohg%0A`zqaCg z$1N=#qU*`CRxAsT3ELje+2iO2qq|SEdY+}>FOl6Dx@I{%&p*_{Mkp+P8esR!)$?Vg|cTA5w&kIR6S zY+X2oVJbnl0N}M0A9d7P7(sBJC*a%Im)gpz0}Ii$CL7{kMmf?v_2M`L>Y!tGV#Pyxm|{_rL8)^ ztkswgQw@5z6)4{L=W?EoZYf!4AMcuw>f}Wrp@)tNIvyAQ2d{Swmzc3L`Fj!(^YR6| z?^U1lt-fm0%F1fZEUl=kanRFCd>$&i-Ux4sSvI&aq;s4Vk;O8RcGFag{Rh>lxpT|w zZ!(8sJEJn^Bi^X)-JBd{V1-mdcMzwzzeh~o6L%!Vc~=*z9=HON{`6CJMGs(XR$lCw z9l0_yS4n(tOU46r!?dMi#h^{hjiuG(s4R7UI4a+2`!TtRk~pLHlSIN^<8fg(5z^rx z+@#3cJ>OYOuS1?QN;&51Aw)ZD+V+D)Z~W=4!x#9aa_{Pa5x_%VcZv(NPOU->6h>T` zt(ae!&@@ZC`B0~eCedv22>R!eDQ}S%94epF9*`bm@7k0Y$wz)n`f$xzm25c%3`BnC zyNcH|;MSL~d$0=B4I`^K5gR00W0P-l*-*?8CuEC2qP?ok4MbgiTCBr;v5-!`a~jBm zKR+wChMGx}mB*!ze7rTMfBQ8lY`Qd&uNe2}KM;k71q8DrIzthH6)vL%ZkUfyo|%0n zXw}yD@jB$Z7+P}5&&%L9qH6iO+o_@#_RoJH40LNLP7&P=B|lFQ$MYbPjOvI8;rWIX zi;Q`{m{iTGBwEeIRQ2 zw_YiLP)Qfgm#-tMLWU+(R!TzXc@dfvWGFXeaR*WV_ZaV)-%Xx_rzgDj=ntPGA-m%W zv@j5;)R_J_1Ri`=TRUODQWeHC`*y*6wAel&CY7T`zCefh*Dr&#?m_$`KfVnOJjcF> znDJekXN5x21!Dnwl5|6s>90_dzNZt3{|L2#l7i}XZ}6k`IwxWLX?4xx!iB(Z$*p4e zDQ`-kr-wCawEFa2+GI>p_UDeGjmU^_n$*;1m9&)q1eT+11AZnbO_P@Ml@+|=H9u?n zBW#;5QVWQ&_;J$)coW;Fa?%0)=-|%iD#=Zy>rULMB-Q0fX9Dyl9XY_H zp9j`F40#4?RJz;(3d@zIYHa-d7|;$J_-mRF{ge^S7QWZKrX z-8MGnSq#O=VBaB5r*q%rKG4~_kJ4@?v|GY1KSLf z8BUWtOI@ZVU?-oj?+biKpxGc(jh*0RL_#%=0K|X!eo&RYS=(jAEmR=m6-)y3f!y@1 zX*YRr(?SyI%{eW{wcfJk3@et@J>5eNZnwt;hh9zhXA+2_fk~_?_eH^t>T@7h*Df{& z3-&;dyAAxgk8q*N9Y-U!s`0u3m*+(u+=%MeRX_4<*pp}kD*H-&Q!dB>WZxi&L;w0! z#n|#7boA_^a-tix<(G5kBNlYakC+fr#{l2xAK7E|2Q^_lI+ z0s)%CxmV&ND_(%=1qbO2i)v=e!(Mh?rpZ*>F_Th!SR6llbTBGXNB=cvO8V?7xbWc4 zYul|;IlitP&hX}1Nkd77Fy7@D$w1n4x0PQ0tpSTzmrEH1nZH*_7!>K&Ga$l--2dI* zwd2f8)Q@JU@ZiGEgxqZgw&=X}7-uEonmeN_{XMr4%7=V}2kC2iIW6$-9-&gMz0j1x zfbNIb|3J}CT@mSR$6S9tdQ-!OSud~J&EIKf18Q2wA zNo*sd^v8kO={hypLW~hx47{5!ecIbm7#81%->?o^|A68SHlyvv&=mhaiKf+W$-mYp zK4EbDsKi6oXOCtpQpR0UcKK{c`q$8-%MCQXpQ^VlTA<09NNrmum2H5E{2QzHmEe<@ zU2D%3i{=KAEXqqcwhWSSMk5T%7S>(XIESlwc&>zEk*uiN4z-HV~+W0j)_5sAaxVwmOjL&LgE$LQ;iW6YB+ zlK#G?xN}OMCs~bTQTf^g<@-S}!3J=)r&mG34|-EXaOF#!pN=*=cNk;7Cp3OYkMUG0 z@5~q<=ox}PFuAscHO>!f|KRaCidwEx4eL;{y-ZunSo-Oa(qTn8Zx&{4_Dzko4!2d!Lv~r6 zfSO6mz2K`7nP>yx#)22;EfYX{bKl;-WyxqRN-1^MOR1#c^0K(~Nv9BkM#}8)l>oZx z#!r~aZGoeNdxGGUbu?|*jpF)nb?3fWR8e_p`bO4x&{>aG-8=jLJMGwH?>^S%W4?m% zVM-qx$DA(z7@4d$zm|Gds!vzS+a1*;Ysu~hpcuP^;_0iz*n0E0q{Pp(V(r;?9#j5! z*(~nFZbvHEqx@oAFD-ZFc~+?AaS{1xp26Hy=@JcH#r^dgR;ySI6)`QowZhdSe$G6h zq?>LVhvdx0!SX@6(`AqC##(hUX+HD$^PLZWJYM{s?Ay&-ZP%6ZTF!`&_a7)>7VOBA zX=+p1n;N!-gcUSl)^&v7nRo%nZUywYVO;WVKSWgmQ8v|`#?pt3qHgVHXP zHFliG@CWZK!$&H4m;a5}v78a>P83KSW}~$reWi=9d;0FY4*=vl%5(alVV%>{?K^pc zOa>`)H-NnJQsS`qZcF2#msEAY-%FXL)UXVvCl+}4C7Jlba6F&j41==-IRbhZNTUbhVN{9Ln!*5CB^NeGu`;o`&BqCA*O zO==JN7Vz`ZcG~S(*Xl8$MO6iQBF+_9-i)jukNzE$Z&*jx-Fl4LiQ?mdaVOn@97{{~ zFLX@t%I)M?-`bR+W{_E5NJ!(S)`m6iXQWwktE%4~TWXy2KGKfhFMaTwK`T3z&Fc6l zN1wJX4J@ZoTFUo>dF|Ai^z@=j_Ith2>^6us9vKXMA3dtFP&W_O@$&56Z(L(<9z9`S zzJ}9NCYb4rR!zk{^2-%H@k)goSIc<7Z_pm^Y(Ms7jj{qA* zfu`c(4@(6C&6!M6V?oC0-aOUu<=x5V$^^FGy7c5Bw`ts0 zGO`L<1T~J&vogMkt$h>jrSp0M9%)s<#sOV)F4k^U#JYx;uA9VD&zNLrYI6ZcE%H7Q zAUliN!eRMhpesm|d%`#f>Hg6jtch%h0^I?NXATD#FaL|2oE|3$F=ktoN2Qhuo^5wl zDT#cKlkJ#aCded~@@4&tW*pdQVU;>NfTKv{Ceb8zpd6+VJZCo8v3R|z7zSGtz+gEsjRwItMFwUO$P{v&LI@p-W;UmT)guuk0EiT9$23HC^% z{6pQJ*jL1bOvR@X7yyUR=y=}x5{sEd5;$01N!D}XEsqd{aDzF>0T{#fIzgmW9Fr&+ z;1QWjer)x`*X8}<;JVczF;A@}P{H)yJR(J=HOcx-p9Rhk>o(=P*+%2fiH8yFkH5#J z!@^mf-?_CQ_3ueyz$;9`)g^%#xe6q*Nv>6V6(y)Wl*2GRaYcH3|PGnZ;HR-FheFI~tvF3DeOHB(#J^0mz0LZdtNruJUZ zL4n>oS#7TaQ?Y7zJ%TiL{DEkgzi$4gPXg$D?f&(VynFOCfpWMYly-2$o%fPSb(^8J zfCP0UwVH?%^C2ood+N=Zd1-FU@tZF}abivxgPKvaYrFS3Kk4@fH_|jiW zk;-|sarJ(Kr)(@^!iS@x+32jm$3#V37XOj*=;7a=QTVtX0r7VqVu{oA4BIko70}zR z*KV#83IQdaf$Xn08;GX3Zvi9FH}LjA<2cj^yHm~OT#MrW)m$&=zldD9!F@#?8SBtq z?162gIL+mrQQnLIg=Gv!Fuxh2OH;xO=TiD(A@v66?%>u=6bw+iBq9-=m??-oHCJAB z!#d^!;Wiz_q%EdLdRSwH1pNonehn9R)0ET;kg&J4@uNRsj|>57FIUoVk_HqJ_`W=J zbm=nto>d5JBh@hrAM#r6v=Qx^;p+^$THX?t%B6J1DVYV2#Q++5H%Y6BG}PDk3NjzX zwr(i4i4$Il6_BOok$7`7)NiuYf}X%qNY`vop`0y375cV-YwUL6lowHnP~@Mq&|-+J z1@RRBoP~i0WDkJVg66+;o6hBV`(~4Kv)64p4?l{;4}mWBVSw$LOc39)ROo~rJ-a^9 za55*)(Xve=@&m zxgkwyTq~p^r|a}S@0^mkO6~iR=X+1(jF7#i>rBK~E^uFv`yf22p^J*7%OcfxEg@Ec z{}4um6_Hp_CA!#?>2)=QjjPhWsOM#g(`gbYLXiF;nDRKQ87*#0_I5P zP(O2--}4<+)Mpm)%hD8$q3BCpiZNKDVJuV%*g|3#nWLZ~b#A!JtH*g!X$^PB0QGcS z$EI|y^|tJ1IRX&vy86*KKW*WAnC%~2D&=8D#!3JM?D2S`y>VG&t>SG34M5|*r$fh& zt9m)YtokBpSM0iJF@uVzSc|^8b$Mcj5d4X{f;jmTG&2A5u1NXaMx3oKeg8monb*VG zHY#uhcP-{wB*P%rT-AMqtT!NDLWNB?lpAoo-cTPy*#?h)RAk1JBT)GckD@l-^&qZu ziDCV4i&agZn@QY z{itxwwkJkH7LgC*s2m#p?Eg?^pZ;#|f8!Y3#fxVH^2L+T(V7ORlG)h>tchB%02%E6d?wTRP{gLeCFR*R558jlIsIc&<+ z%(WqB(*AB910bjp&s%Ll5t5cD-*|4%VVmvH>6^8DHC#6A)vWW}nSXFqROj@JR2ipd zoU|W2pa!7I_0MS<&*A@pbU(y#l`>>g%yIi5qE(AN_MLD$CTv3TU&zXT^1eI$bE0wy z>0EyH1io!eE}%rcz!F&N*12>yz5A-M%aQg^p#A61fj@=ISHaglVF#{+zrw}|9gO0; z`+j`IdnBdGCaBfXKRP*LrW6@Cs+EoXl_8T_;dX~;zvqf0_z7zGWc^^@WtjnV3jYeJ z`r8)f55T3j^uvQD{iT^$EG-6x13SV7z@OTehf0_M@QatC|dz_+2>~QcRg$$wRfjI4K4PaK|%u3 z7qV(@&pi8Ei<~mIVMuq2_c8Uw{~f)K6}aqa>?tqLtnE4IIqx)>H|%2Bsj&Q#6itT> z?>GaQ$Ag9qv7e5+bOH13{3nR=q@%Fve2S%#=@@yc+F1>FbcEdZlis$|mf zk~{p^++N5(3^rom5km9<-#;lR1XQ;lVxzRjx%lot{ctK!9M)kd!|2bQwhOsij)K?P zIfF=}3Hyz%B7(ur?MEP%x7O&Gmc7$GG~z%JJv!&5jaQ5m{&$$8H}v=&Wc$ja$~c{O zW@7-p<}gYcU(vtiP#`pnAH{FSs4-1H?ZjtcFkPhEAs8?8JLIFfM!dJ8a-7S>T?)lo zG_e?dG@GT|RkU-0F}}U$Qu0a7MQB3J!`(}RyT4KS=ZPx+M!3{^g2BC=&R5sY$Z3Th z$%6+`6Dfjz(emzsW@9e!l)~B%k#F03$8mb!qge4HRTccnhqey4M^3x1B4)QQyc&D6 zm!H@DM*5|uwp@G8dAz5-s3xu@YZIaPqCCdet1w;X(C5e)eT*mFs>I9szZW^RX`?zX zWi$*~WbUovF>rqq!Y-R*}OP2}xUix8KR&j0UWU5SLU5Tp!L zKS8>#7H+4f>_0APjt6VzD=4B9b~0w72ueh_46i>^NFD~-)%MWFxfdnyLuM?W?ehf}k} zIdhZSw*0#ki12lUvi~*U+x+xb$8rZSnan3(gWqZ1FB4V}d^6JBOfW%akkpMYjfeR{c1t}pPLow5)f>eU>m zIEW=je?xwz7L+}Ny-s#SvKW@dHM=T277+hP{yCJgK=OS(*=T`xB}(I;DCssYTI1i^ zrlg#YNM#O_PnyMk{#viHBx5rCdIq)rrWDo8PT~GPAhSvF0x^EbF?M9I{62(y(I$o5 z`~vn|8q1xvtM05Jobk&bZYRaoHX~TrSK$FwjLyl6npF`M;v9kgb6}!N#8V|V6^B2IP?d}VD(^GM7A~-6?Nx7F&ZkxM-pt&ux&J^5kR+oo zu{P;NZHDm;C$uBe2Jydk#!qdq=M~Qd6+i^#}t)Z4$iUD;pbp?F@BFe15lyw zr#t$LUP6f;kJUD-JVqGf5Gt-GK!QEcj%bqSN~ZB&`UVMJ$^lzFVgp+;coHLNn)(94 zFM}A#z+@mR#jaNFlLBi%GoNp~Qhg;Eq!%)^iZ6@M-yq0IUGZ&R-Y(3!xT5yS=JS;qV4mJSCyQeE(qXKFpUiK zZjC&ZGh)y}Aa^$oN5_t5&b!!2b1!cmMn-oBxV58C3i|vz_XX?TmB7_OBt$+)^hKw* z$OVvTtHzu(DYwG?7#Wdr|3v-0uln zeD56aV-!pBP>%ikW065&h+81IJ}VU%YcXP5K4tmHH1ELjhTt+`UAI^ArMdQ{e!Qf) z`DTf6)%{B7?#PNSrvC}4Ip$}HfMBycB<)lH7VtA>_;I$=&@16y?|I!n#|sa4A7@Va zdZrW>W_o!DC|xh>oW$ zVpik%CgfY41k_RwSck}wjM%IiTH}F2qf=ZoYlYA6L9tO*Pszkh zWju%#fj5Vb;cLmIPRz~YAC>)H^e}$OLvkbi*}a|*cij(FQ0VWkoJSm}I&i91SO2N4 zo!sY{l1+|%`$*DS^Ty5KATb{PQSRloK?E{vf6oeI(n;q#7AhRy+iyB$5yO{Bij}!Et-0TAq7a3yQ~Gh{k_=)`Tig1ZY`8$_ge2juWDOe>r@1P zIHv_A870OoHb9&+YI>#}5%d_@YjXeJzuAwYQYnh|nm3;2i|?vaPk~sxN5JBhV~AVc zP~f!in=i<$vBl8AtoQQK3J1kD&sW{fN>EU9#<>{U$vK5B1FH%IMyg&g9VZ5|VQTYR zF4{K2CeJo!2ko6@&6=R1!-Efd$7Fetke8&t(Av;SOhWf1o&JpR=h&o(Co1{%!}hh%vX9wACOF#7q3&W285x3q5%L4EcARt||!VgP3k~JTc2Y8un(%Em1Bu0@2xw z%JN5CyJVlL)oV)M7-2jfv7Ju%Rl6QBR6+-;zJK!d{2VCYHN=N(`U^|i%L+GnqpWIgysczz zUG6N1VVR|MQXYRvkY7_1eKTS2c)McXb z%ggCKovFi{A9%_>+ocy9#)U+aah{-C0<@1sNjDcUk!zjvOWq+um0=P(QL+KL-B;g( zUMfF|W2z+9nr|I*oY3h##|Pelbui0N`9BYTSv&a2ZcQYY(R{GH|Ie5eJb9YA z7=AgJr6Hw1#d7P|6Mj7TPL+?^`idpk?%K`VNVVUgp4SOVI zq8eA#HQ~8zm#<$JPIU+367!bUG`Lm4LqmjW^NjU`enNoF0W~9Aj57TJAjomkepb<^ zBTz~K3ZfJn#ZL652O6s{iT~;|XO$jkTZ}SeF42?xhA`PvkC%E-Phv(f??f#(X^nkm zf}5zMeCamJ`Mi7pnJE`OGXLRYC$qgy?>)~`IQxxXm8mJu(kZcMfwF>(*1)O{7t}|} zm`Zdup$9TnkHR2K2L_NwSW(%j^v&)a%Qzzi!`mMuip1B!*xNHG6BeM${7!=WU5npa zO$p}{D(zvMQJsEv%DXNZ)>rL{4)T$*2(vdkBJ9s84h$}M0y@vX&gnk^*@gE73U@)U z5i+n^sXVxY=kR|`Oc9>6L2FPi+F)w3j6{EnW?DEef1B1o! z#!#+lv7Xtw_{b{-5q>cykXSd}K%gti{olyu=yVe}6!ORe5xVrOW?CpyWf!GcCAr!V z@%oQ~+*X!r{cd?|0C)Pd6kot9QGK^dtGape=)efY+tSU!z;^lMjDFkq@#y`b7^Bso z74%^oiRO;k`SQh6plFBhwABb_7=Xjg>n5diss!0WPY%vs<+7s^PTJlTa|gfxF~S#9b&PBk#+TKAnnbtE#Xuozp;*t?PMME z)}9_)?ZT9hJw2giN7$v9cGfcW_tc+mTj{Ww^P-oi*-o|6oxPZ|8F7>H+f8ZTJnxnh z6ych7V`6V1dm8wLg6va~;w|SFZp$s)+%H==KVt&meAEc{2`*;cRyl-rCf6tU%*p{_4Rgv47fuBvc7k!pvPp*nOrgY!K>Hh)jqL_OqU` zZ*NDlQ!0;YJ#<@tlAM85%Pz1XhZ=rz9a2etPLa0$&huRQmNZ_I{DMC)qh$S?IOSK= zDZ%CkZD))pwcKc>(7_P5Jq-Ec6TwA%|8jad{ioH zFyZ5M{5fhh$R>f?YQu6bZgfv&*FPybK(J{n1C6M}x@TWM6?{<@FC16b^GMOtf)kG4 zLwwQdE8K|Ich;0;*l-)&^(JujK3}p(H$|qz7J?2I`?u=6cht20h-e(v19;~3SvAf$ zNNUs2zi)!uu5MTi?ynD>jk&QtzICZ>Fv1_Hl@udxXg5d)VoGjb3H(r*0d+)RxkSJI z2Qsa^-OrNmf<#a6=xc{*)c-`;mNUNib&rkfx=nC!yb9{F zI@Ghr!T%#MxCSv7IC*9w46AWu9IFtSFYx9)Rhn&Q41J#XV`F*< zr{4>EB+Pez@8PF~{%3#BhoW7$tDpf5me0bU!CjR(qY{SIj{R0F^SP{Y%uucqy=x*=jm%fGqjlkwR9ujK>Q(UE?@~*T?~hOZJr? zn-;xX_WqN2Mpy?|4dmZ+ue4pS^T$17*43OED)XA!1U3rCNinm`!b`g#8Czi7cD(9* zsyQ3S`|nJix1lKd3qYzJb|6v`(yAwkgsh6ax!MqnLCsZfOc0t<%@acP8MF!XKosYJ zdj7vGUw`n=pi88jWF1VF<{L1`MrPgAKRYizR$VNb$yQH`)D^|xvRAj zPit?wRv~T04TkRK%E9fIOG_^p(rr8vf&@ucJn&g&wLqv0?o9~UqjIXtZfN}Bc<9jr zu@^X=qe%T_D@9ZFoa+3eebfh1y)c{PQ67Qlc-RTg`&0&87l41~VFjEM`#tth?<}QI z6hOf{@a;o{`M^0~;Dz@WA9G)Rj^00HluoMPQWputr=SNU%jji=Z|7=M#bbcmF)|I~ z!sUd!k(zuLWX`s(sD4(!w*o{oRe~b7vrPDu%6OW#&*7(6sHp-Os1s?|WYUI*S!Wu^ z;6WpI%%Iq(O?nKA#HTKs4Ge^&u#xzpboo8Bwt7GgbS28DkyY<8Aw{{OB{g1>C#u{l z{sl{-eV!c18~-f}oHOv_{FTr_>>tp3BcS#5@yo;xe8=KHMmmaNTjEf0o z)tp#$;1A4UQ68QpyRX_Rp?OcJH0s8K2&$)A!chc{V4D3Q_+`K4zLz?AxxJT}q$F)o z5Zy;a@#*#y(hfW;Y)-(fYe>xtGfBl=uD3CVjY=jg4K5J#o?3Bjgawd0{k+OST7RyJ zBPk`FARD_^vtDPx^5CvXO5!KielZqYVvH312joVAm2s@=mJx8W1LAGi+WTqp-v0pF~ul7 zM5$1L7%b3XYwevzi{Zo)>aq0odI4&NkPicSSuW=LXiGO`)lhS$*iHNqxoTp`-sJyMU_!_ zIwZAZ6_A;QnKSKZ*!vc;rD7FAcTacwbxf5toGAHdYSn8##R79l1M4F3U9~7Z zEs>5RLcrMg@Vf~{(|nB%)xxwD6*caB*~KEBUDkT#%l?M#mw2G&3zPV3A!#n#3*}fv zj-B|ky>MCujlXe}EoHh_Wv=1${y0{xXw+pP6j&PeK2Y z<~O8}coA9yxp7;);jyONsOG7YpM*i8EHISrgQK~Fsfr{`)tVDA<_lF64eDSWT#1Xm zP_XLC1#tOKgHxS2d2_WdQ-}F9$|1+Jk59qd;DYDaPj=iY8{k8LC@b%Wnz*Bc;Dy&T z^Pr>-G-kdn^D{i@gi*qQ^oK&?e46E1b%Ha%t%d_JWhU*{?o`Uq=c^HN$y1gNYs&D9Z)gNk-uyf>MU+_Zl8vwk%ac5(6z`w!-!5Q!aTKD^sN-w}w^$~%d|y%89~ll*>DmyJruy%l zpBtv?l9FJIAHeoZGi>aTr0PN{5#{%Ns32xTuWCH^@V#}%!(MIr5%qhyzu zaCQiOMCt4PD;l=S{J~H@V9mTg)i+ZmD}y@jmb27ce=dDhjBnMNht?UhI; zFj3Q6pY_nWfL+cGR2_Rny&Jo6ON;e}+V&dvpXj<#hC%vgPJRr1jZ4&17`O6+!p5dB z+cZI5J}K>@d#H&j+Lzxy4BQZ+813uYuBN@Q zGR;)sz_cs*Xt9?8uBsZ3+ArFtx_mcBnncq5$9iUjC6uW(8nl0EP;*WBj%Hhr_^bXZ zmoRWa_U^j$xr(z_FN}#avdn$z76QNhVbSY_XJcBj@IwJd?N1RqGq~=6<1n(luB!^d z1KekI!aR0f6UUO^p7Q$di|d(W7q54)qAh3uL_BKOxo6a!>j68;*a&IG$XP`W;}T5 zdS=y@dYwm~Tw(K!&*{ESK>!tXIr9F+SI}D4t@#gkf(BIu=82dqhk@Oh5BZ!Ln4DP@ z>>=4FpU$@Jt-m^!eQ5@3&*bOw-H8$EQy-%m{_L=ESzmTHp5ya<06ifvTbJTBfWJ3L z$lzYum++*r{x1Z{OK76hWg2Xj5EMPyh@D{1m`B|wmYcj)StV1BTs`LiY0ZAAwf*d_ zEGW>Dpk*nsJE=CKHIn?T_SyhSZh!(;RLSVlbgoJTjyxysCf9=6vRAc(`(LThu&m#4 zI`$6<4WA^J)HY*>SY-JDQQBO-*N;rj`qtFV=oyaC+q;@K{XKp{{q@1xMj^ajKZ_6V zg5w~IKF>RPNRiMSP`F?RrA{As{w`$8)y4P!|8& zdwv zecfBt{=6DnFWS>{IhumV%5*osiA_dPEf@WLNCw_EvOJ7HHTOa3i;nW&XTt48Izs_e z;5h_V_Nv*=h;)1n{Fw``LkuXSaxk(yw_B-dwkm=~fWA?0Kpfc4VQ;fxcV>;99kX3^ zKO*$xi5-r~e|*&nU`G+`Ks$3+Z1+{G2=ehxH?pW5BsW-qKJ)4%K9dHEEMvr}NCfiC zb*LE5-uLfAMlxO=g?l7m1wj88x&45=TT77~26N?DSmw`@L$k18rtaq8N;xqi{Lw&H z^Fc=99WlO?(1gA?FOymd9hiI6>sJ7w3p5j{l7=m5^JZrB%C$rT0|RSPaP%)1O7If!gzdaIV>!;!PtE)C54Pf5iBG5QXUA{5;Q&}<0!-~D&dVI|<%}{Bd zuC11lHkJ*@2?|Gw#)I+sSKmlLEVt_cglXXFbN=iSVP3c1PXx1>I8tmOJ8Go499Nw~ zRBL@2w0K9-xEon3wjYXvl5VzMsw@Vn5pq1dd9v_Hz8()2T=-;O-EMjk<Qa4NixOu-4{aXkHIBn8tU9C@}uW<_9nuPhyZt}+KdNOaHV{{D{-Ffvd z=~kA>0b?qil9+WK!B^+A`fsVa+op44CKBj$rn#e2q527o8@$HOQ%xu zlzb_~CiN zw;czP>0HhEo0p$k9b8ooB=?TRQH9qWa%6|DM*r;exU$psRwonzwhS_9&KY7qn{9|4 zt+K}$a9%R({C6|jzOHb}_Q=qH7RxY%=q3tz*wGDtQd{X}Q$_)S?(Dbob!_KQesvsI z$z6uG=i3u8=X>}b;8zWCfY&-R5`4SeQEOFE6Vzj~HdhEWdg|*tRU-dD5=rDRT!$G( zzok^6R$eOM=~V&J0VpC#gD}cS6WoJ6P5+=8^+E@hk1}~>3S~jnKqh4{@mS-DfY+FD zPdW!Q7V5gpEEW&pbJX+m?aH*4*bUIDc6#G|S;5?}LYvG5nr0*)3A=N*lMd_FC2F}Q z7RQg9?tL*-5!lm`o`#!!sfLMp@xz&QGh)%dw*??)CqFa3Duz0|4`OG<2QjHipMHI> z$Cmn^PYmlv)xWY{u`9IMA1a$BYFg#~8tlX&gJ9CaBEKV^!r zeTraGpDmlYnBHwXruH2-0SRbRMJ3;JK$s%_YT-OV1Cywlo$R4*bh~ znw=u;2IfX`npX_;&85a4I#=qLz12V?Cj-1s{ujP_Yf0cYjzKyVHR7(9pIOio+=l2( zdTPv_6yG?!c({B>-<%T~rvuXHEC%7K0J=LO7U{4YCGO|c*&;PJS{8D~$DKA8#FwDdPVN?Du{GczKzC)6RNaWY2%kGRunD%mHl`aXb8OBcmA!~&y3R^+7-T?9+U9ZY}z!TeDWkq$mcRnfl=yi=(T>I5- zjd<4vv6**13|@3Z*BZ_PvxTO;w_ofIUP46b>wf*IL4@Y;LTpp6egpeho^GX_ zxe&N+#%nf;51^I*%G-*A4@Gj&&hN?w0?L7W_>*ohFl{t5=vPQu(2C~F1*TF6;s;Xd zjV}*@)j|1bfW@%bvVB4b=4P?9T){UX6xS&T$=H`iAC<_&Mt60hfj;NrPmXeg2Vor$ zB^C0R$4uT_i-jb4K5#k$p|>g22%anqmHlaB^HtubNs-0Csf#ysk#yEweU+=XlE9`lD-hK^gX8s)`@py;r@!j}7r02KE zv?cTX;p~lD?z8_R+yP>j-c>d)0gSWOA>^!HdPhFPNrg%adp|R%M)r5z%#Yg8ZNnYA zP^69AN^iGT_!-pJPxx#&fp|7q7^bmd^l{&om)6}KZgGlFCo&@N4Q`PgKyUI<-K1ka zfA7uPP#aI9xjh&w1toE1CD9`>pIyF+me9UR1LY!UPxqQ?m>e*_l+{h9AEzo_N$p1$ z?_xG#x2HC+2S^tW&Vf5=mDG1JZzHI9?}o;GOYmkc(5TOgleg4A!vkf8^cjqIuDsW) zX*!C8LW0+U=&|s#KYX?>&)L$Jh~%>D>36F^ba^2QR7Dj5`?50^r+tAJ@FcSudmEo- znA$+$0lx4?{@XL8+4y<%-v1ns!})u~yrPKJB<&SwyOvv~8cHqTLyfa|%@uJSGC7}+ zrZ#`|_k>>jo#lzYatNyat}};^2irW+9Emz7F|$LxxPe&tD;0W1t4B-Fz#|~b*(X>$ z`;JOGd@eIz@Pee0q{FrVmo4JPAer|wkd4)>_njxa0MJ=*6ypB{ekV|UTI$!n zjd^)%SnNiw#s-;2_h8ajUl;3C_7ewXJP4=Xt`CHCbm^=}0EI21LONqfIVGh%y>(an583xUf#dm6@QAzy%Lu98me}Wz=c#DVt+R+C z9K8pLCPED7KK=AK<~mZqbx95RnT`(Ri}BXEmbH_Pt+^0YW>T?gDRP$qyfc+ciW0JRx{OhAe~%fixPQWO@1zklKKGK!DYgkLu{bE=Ug0b`Xcy zT<-|ELYmD;5t$z|+WIbsI}v!DLFBM5g@ul^_7cOO1msH}T(qHP|D49v`qQuQ(Ll09 zP379d7rx%~8T<}Ba%;xV?0jhI=Qm#=e1t$}%s_UJ$f|?yX}Zcn+J3_3epZ|Z6ktcK zw_K$?FYMp)bbt8k@n`XS6jMBh&cPTJ3V}6*5(J@9P#1=nWo!|QN#{ccQ-p0}OWUVR zdFijen_=Qn#*IO=*ln64U*a7qyh%D<496PQc3Zd{c6U-r>dz^VD|yiTwLh8CB$Ti$N-cPYn14QypRDg_O!YH%T@RTJdB}v?#CGSw>LVB^wL{zYSd}1J_+U z>p@5RP7CMv?TRj*{N;=2du)KBeK>n9rubn--{bvO^60uScWBy zUbS7W5Lt~G+F@7-S?_bH-@>t2fv`Gw1cc$|7*XDyCp~Wm=Wmo&tl-Jk3T_)6&ijhy zJHxyYB(KXd^btu&_%`1L$1$N6teKI_HH$Ay0IcFpM9q^j;`E4%RO zyLX;?h7!v}5qv;xJXewvV^iKa33G0yE@kyYkIg&-Y!XI*k&0b?xpi|orqx>K-um(V zM9A9c6MJDyvkLpbz`pR;0~cn`KOKlvmoAlVavjxdn~Srz=YOL2Gc^&LBI9@CUjjNn zYon!kIh3Q?#d%&0lkd_}E#!Ga(U)N&EFk>Q__1nS2lBr9}RsGA6+osRL z$GR_tJ`c$#+Qezv^11hj3tUXO7D!iy7POtE8{uUdZntm#>Fp^^deigGHED?J8ar4| zrP2+bdQ}+2dijvx$cbb&A9-+Gh>=yRCO3boYn^J9wBhnHt^7|DavI*dJ#?Fgx_Hx~@N^@8NtS%0d!1($@}~(BXYK4mBewD|!YPx&T5m zA?!SyHB*z*eZiN-dh#+CNOiXdH0~oW=?N+LaBM@#`ip2xkR^Y?g;o51Q&~maYQW7GTP50BsH{osXeJ5~ zIocGoriOy&z3LZY-Oeh|Tuv8|GOtR&gC%LQ<0DJ`K~jOq%ZvU{|{h zVa`4#k0Gic2LI3|t}!T_7xG74t2)c5t-iLQp{cE{Ipe95iyNn=a(CmR$-3_AnUs(_ zjKRVS9k+l+T&hEw_!<`!043g&C9&6sySM+5K0HwrmcG%p*|f zJv;^0a^I-{6KxST zam>$4@5f$y)(N5o(O(A@-@W$M=vC~#d8r@8{0XsF#CkxU?+Sj(Z@`ny&f&%oYZF(a&x ztdm9;XLNz7RlK5ak=eo*w#DfPAvoIfdXl1r?REe4f9N=((PM;KN z`PV9|S1K#RzL*95DDz4MKTj6)gq!~0>&NJKJs@}N{RHzMFpL4~uzya#FvbFBaB-qz zw%AwXiuJjE8vGQYB3O98Cz)7JnX+9q{#B&oWh^{W>1LJExt=;$P$~Gm>qF9O$lB!jo)pNCh%>0K2taq6icaMfoAo-m-8`^Q(~9PZ-=A6U zxbA;eUKNGBErpD*pr4c;d3WwycO@f}{My8I48JkGafm4aidYsL6-Hp~ z^#=@({X~$g(><2ze2K3L36in4Q6xx{k_+3QGZUoe>N|9$6o5?x@}@g1dP30d>I_6~hZKH`7CmTWC;RAYm7cXsXgRcWX6{O)zF*z%;-Q$2v>D3VeM z#w$p$BZM9qf2Q4*w)CFcLOIs+qu0?o(sHzebd?Bq1rto?_!J&Bx|fyBRo?e8M>@QU z-C*jb-sG$a=>>Y$>{b^N4AOC7Yqez@tT}zKMr&K>h zlPohnV1N$k`Gq3>4Ex=W7ymV~$4DI0hWOh3N+3j{pOJGXsrKJ zO{#8dhJ?Z_#}Iw(r4oh?UOW%pUkX*qC?AtyUQrwAE89nf1cg7 z=9a_c!k>wp!j-Tyhh0@Y$k}z&agaEnHgE57%~l_VFH!tgDqU{7N0=(g+VUri0cZMG zLG;sFa|-5_$SkzCm3UGm(GYv`uw5iTL{|P8x+ow8ZFx|&X~GiFanO7bV2Hp-pO%lt z>mP_xSF`~P@(^vZU_|*3MCvpv>j#x5@wMU*ikQS#3oR&yOWDAT*9o0 zG4U_Y`z4c5ur|c@cnDug&KBgq$W&#&!mqw!g#iG36TPZYB;c!gClyTCh7zz~Ebo(= zHk9w8Ge)__9a^-j!XVmgd^vC&zTmxn1W;#*`In`hRBx9rCXAsDy31mNn!J-fh1VC! z12dVKeEhJQRHQlkink~;&Me(V204yvek{=m1vLo$dxx1|W@zY}O<1CI#a zNx%A_*yy}C=8b}HBKksj)0mt6IsP*;bgop}|0z$ED?v>)dE4?M9BZ~5Yi!AbT**^F zM(#JFomO^vv43K9Z9hu|{>a9VaGCxA-a=%f!e`0s)?r&LE!Qfhou0GS#HK;h{0D`6ZT-F`pd_n9c!hx=bJ;CgN}A``YL;@6n$roZ+!E=A{8zhRs*Y675UJ7A zt5KcW{tH}u@Jrzx%NnZA3bC#LKHavlk4;mq@4PH0eBex$wCw0lk)tR>y0JKsvt3hnU}M|7_J`0|cN(}-q5*&JDQeW{&3=`3W_6V`(bRBQ}xrj5+JR+lArEt zRH@-8wRm<^g$8dX2W-gD!_jZe>?(?)aXfMkwwFJTBqClzTy{$=M^)jnHC&gMi=TdR{%9-lWzf{*PWxy;ee!R%7OKw6 z9R1!2LhYJN9>-7#)^hdDZ}8#2Ni6?Sa0XU98GW2+ z+CvtxOctX1%^GwZP9#)u6Ofk{)tOFO+?5jy)msk?vx?;Rl2y6jx(p)_eq8+&(*2Mx z;x$_`Tio)*#q`tUFuAMqR_^V-sySgJLU_=KuXl@#nZGsEH=C{_Tv@?5ZNOKi-m@Z_ zLz9iNZ_9x_VK9d3L4pd1FY&RYdE@>+(4{2d5T8r<432CQ__nyG@MW+@>wZzXTTvg1 zJTO|DMeZ1Z&k(+LEkgLT77yr(VOD;!c$EmW`6ORL@A9owO@&%s(X_N)gZ;Ws(cKJL zXXwiXahf_VW6|f+ih^&)O%abszbvt8nx}h#ZY)7IwJqZ({$!cxU%$*7=fYg|=;p;9 z_jD&Q=3qjbzKK-G5?NUB2&bID?tdT`h;~tk<>vt>z@gkJMVq?*A{847MB#+FyH8|wi1gWAxv{fF1X#5!a6Ef z5@*>X3iB6}=8QUg^u5_SqNy#_Luw-+L2x2Bsci2D#uHlJ@sOp*YWy21A2zrz_9O>;JHM0_4Px} zllPO3FeM)xT{roQbNW1y^=$;s{4ffc$j4BP4J0tLcKnzT{zwx}x*Vl31&Y zY;HsGLY@55e_&dM5R6cUh#Gz3VrhF9% z_(~Ern-iv`UuC3@>Of9*>`u3Gy1&%b9P9U-K1H9G?D~$d-phYx+XZw3&owKbBvj~K z+6ktZd%V)na3KhzLp}|c&yUHf9 z{^b#vDztobN4(3KuiL!eATdT6D-lS0wnEYj(!2W6riwd8T};PI?=}X1ZP;zdBS&$K zGu{$&z8{Mlvu>0cZx(R541&#H9HOq&ptKdJ*$;6_hb>`zM^mr0A$pQ&ofHq6hh$Yl zAPyQq$@B4;MNN`W$A@w7Xv)?xJ(ketwR~Dyi;!7;mykNDS)BCao%o_v^bb2lb-9yD zHxnGqLaorYtM*c$(Nc5Kf@93@*qe~6TGAs_@NRR9N_U&HY)j*<4$Y&2yt@ez1!-#%J*=4u3YIlb>IHQ?}z48(qAv=u&?_bi z6E-Uk%(*`|J`0#TqB`x`lB`oJOtKTz$m4auN!;S+(-UB(Hf3-OiIotpV^x9A67*pt z8=y%7AcVlV#vi^0kI21S`_)L(XgOfRRj`{Ly7Kgxd2d5+`(sJ2oj=cOweJv@34Ryh z*G88kH)g0xPOB#Wfo6t)xhXb-NRGvf?vK!w&O=NXvpl~A;L)3wX-f}l6x5?#-)*p& zRduNLIUTwY9-PG>j0xtY4mB+E)}FC9HB?%G$%myt99?IOUe0jd(BTXv@X8{OgX!o|#c{mu;bt($fy0RCLuyxfKY*eMen zO7>=5kGvpZ{2t$UaTmz|6w_)PFG+%GO=9;B+}s%@b6A(oUkhr;JxA>hZTZIxT8J-lf%oS^X0;2S6CahUNxt0COcJxKNp! zW5W&p#qtW_x{eqfGoZ}w9xu;Z_X=KC39wEf={SOn(yb#%4>rI$mOH_JC7?d-9ac!y z%%JLIcE5#X0Un?lj}y=GJfJwFIJyYxCIb6i&Rvj%#*p9$D!{%gBi?We+1(0RLT+P~ z9foI=gKPJmd_Q!{AeN=_5G*$|t{#%DM$XY6Hgy6`O5nwZy=AGst*5P<%iy#nl#nX1 zk)bbZ>a`DX>0Ko~3@`rVCwwtmW{avw*B`Yv9s=h2lnFuCW+%99pWqAcpC@(?%&mAs zek5$F@_a}Frcek^_?1E0IL71{ogqtm(xv>6j5jGLYUq(q()3SC8#uz$%T;sQ>(=~` z*Fc|gaF;ZXLEl%dfu`U)v?-@MkRSTyGmB5yTN>yYoV`@obLA&F(47i@er-~6xJ)+D zjg>!IKL_hMVf9JWLk`?%BJ=c0%d(Wr59!nHfqQen4j1rSawk*gU+!0H~bQiFX)!VRB(USs0o*>})@>X$gsgS#h5_~?KstF~$*nX?`w`wwif!{o6{=Q^LP12{mI~5~%l!ttd5A+4#fT8MNdDuKW zE*mUWMk1hDOj^0N@wBw|4(1tuLH!qAh6mEpwMolfF9*K~3Fwb{Lo3_Rt6M zWM8Xu5%=Rml3KFg&EF|-L3>^O57SzB0srJ39VCk#or1FX6~4Y!yV%p=lG9rHlmA}V zm-E;rV0dforUx-SkC|BYMt?pXP^UInAKV=k@nz*`e0O(d5rmDKiv2Qa+Zq>PT-KT9kHXBmxCSk1*3cVfuC1-z zamJ4S5}rh^6z2+CvXd4psIiOFBL(kUmhq_zt{v}&oC+QADQeV|-nNrtfTcP&*24nG zwotYc?s=^+giV8QNn3IDSTaWCya-{IT6vko%mwhPGuqB~exFmGl;@mO5A=Mw>JZ9h z+V7h_2fzBdZp`!2eXg5J&LofXZP??-QGiS&I7jt8bjHxfbL@bNnT;JYUA0aMFm%eQ z2BrF5H+!q?N!`Cex(j2r*fyl+o6o6nl_QwFV%#iJBp84XWeD~Bcop#X=a+R>FF8?O;AINp_-Zn5oM{K{0 zKg~cLi;ZMo1{gj3!<_|rx7lJ74?z}fz8ZibkAFXVAo}#n97jYqVr@aew|^`D(iILY z>ew@>s1y#$FLl>AJSkEySw}t(>RfZ}g>2*J0i~^-*Ni-@I-)9J4f3VNaYonc(BOx$ z=t!RL5sL7~8Xj$&IhgYLXu4$ZWV@D ze}z8(E3vN}FJ<1)9BMRH&zmloX-PeP)A{K~vJrLlw}E$>`=Eh~$=hZJq18ksM0Z6{ zHK67^zAE@ZFa(CNPe073nd@B)NYknP=gjHHRWsi`QJ&1J;W0WBvUBPoo^-@Oyt9t4 zZ6aLZ!q&AX+#c{SW1F1?X zFq?HBU6}gasRX#_P)UfXDi=-d?YJP-4-;apqU)Cp0Jbb;RAVL9h(4~!%rW^XU3p-Y zSkW6l>$7)I6$!5yiXBHdn}sy~=aH+(k-XhSiUs0QfC#Z<_FG!l&t%%%ncAgP3M%vm zFc{u(CV-lttXf{-q>q*lZH&$Is=EX=HHg1( zI-d@Lpru+|Lyd0S;wHXWYiT?b6MU(J`tkkm7^-)OC7q^;Vt`$_k(R_e)uAFT80+V5lzq!HTP}^nXC91k31Ujbc(F~2U2VQpEP38yh4qdIpDRW z+kRqVzn~wVr>~`b{g-8pW6W~*nFruR2I>o63lL8Cz1@53WYqz;)W8o!1!L|~6&JBh zDgrpcQTlUO?XSV!H=qr0Uu}t&w4IZ-i*Wvl{;F(GamPJB`Am7^k@s_g??i#{gc3u4 z;Jda+JU>9S2S7t~+@IA_&au}hgpUUOFRZh#oQD2^Y=CvXo_>}_96_;4Uz^zFX+|Xh zuzuM%)HY7t9wS@2e>Ci6VTQk^rl~}-E;740^e}%PM|c1DdB+4D>kRH6Xih+#)JZ5Q zSFckm`LI$czD&F{o&b2LS}p~Dlr-%)9fv5j^OfD*J=GlAxcv3JycOwcSzg(M}0<}q1W51kp4 zy$k%%zIDT{g$^sLjHlCQlhU_EEvTtdEodTze8#x zyj;Yj=vAT$YWL-5VG8?n6cr(4n@F{(NxsG)=zlGQGI&$j?=YSYq+rCaG3!&gz{Sv- zZBJDH2P)Qke#a(OXytUBB4Nx5+?T~y-UnSgV7y0d*e3zZ4bUeA8P#9EsxPw5Kn`Dm zx88&7Izh2Kl1URu)5MDy2a2E|YxnJW;A3k&8~#ju@iXZ#UVXi5eF1hq?pWyO`4j8E zKFLrXGU9vkmtnCphVxyWm&kQMfGvL2*l^f7W)J-k9E_|Q|6zX~Qx?4De*&Bb!N(ZG z4d*wtLhDqU6iv$Nf7Mr27;g;zr?Y4)e*r!o&&c`~FO!t-6dV%E)xx!MrBErpApKyL zT$A-sxa>A*s%HVt!-*x&><+q_<41R%`@dca^s+VIO$;itI1BztaymEgxOTM^V5J71 z6`5B*zB4x8;qy-EXOsNq*{wWSc4+Rxt2)eF_ofveq}L!N9E0XAChtoZelW>zyTINh z_cx!5j6gv^1dx2-E8jcl&1u%R5Hzll103-Qk2+}(wNA45b0z!Kx#g$xz;mNw$qeJ4 z4Pqf!uO+ZKda3hdt#V7On>72lG@HEhm)SU391BdcM58fDYc4PPV045x>vYcnbDxtF z91fQmPv$JqiXCUXA$R|+yGKg+VP>E()8rWgL0F)xA8x%o>x(xeJR0HH;}DDVc4P7T z{*dIRXxQ##lavuU5dW+tR1*}nN)h|61DM~0Q8h#$vDy_BI^(CJkB&_v^(MW|-E`_& zHC@a3GCl6_cv5^>c1}BxP~adYT>(ia2Lvl@nn(V(lJ~mPWw3gW=~nI(mhYBmdwovn z;B?|sMzLqN9mTV&?fDpoQJKdKpP+R`aY%b;Od3f7>r)lHiV4(mPej{Copm3DQ-?w)#+Xyk1 zJAk>tQ57)NS$J0u_*R?!ca)oKs1mD7=`b%VYtq7^Xxm5_cQRMRXA!SD#r33Q4~sZ3 z@s8x$+2?|3V=e4-AMtvZo*|O@!#L2$ej_? z=b)hi6`MtVGU|fp%kWRY*dSP2(()k;5X<%31y&i=zY|17+qBlNGf*dr=Z=mH{9+bN zPM3 zH`GGFME-iLQTU@~e~E6lyL6C};O^1Ke$jq&&AStd34AGWd0Oo+9gQ~CY;rkptbLXo zW`5zQ^l8(n>JRgzZjoLf>)JOcg8?sEP`x~17U)65Dv13Gw5%Nvk)0l3H)v?w;)I1$ zy30`}0!yo=rMH*4q0S~BL?MAtTEwGKO>V8>*#DAO*8T3rZZLZ6$V(q3M8gCfdG3lu zo76HTdupNqi2;Ewa1mh3&ppm9`c5>xDm)DG@LZPZVK+8MMeraNF-h@@TK-&fInz;Y zXDpYcnoI7W1MUC8F`bA?1l6h_-P|3A0E_%mPLrOAtIXN0_(l5byEn;i`*)(vc;xsy zQm#_rwg4S*2YMT0H_;{u2yU*A5G5TszP{fzxeF@(?l$U~Lce-}6C*Lg)QlQW4tRkp zeWK*ev%F8v-U@Vrjsn1|WkqS;oM-WZDicU; zm(_zZ)y&2E!WP@QdKTGn!%t|ayMy_6-7>=tKB%C+X0^ciK;rp75X=GW^P*W4^)|`! zHrnG-chN6bi{I%m`i3_?&+g(=VOS$akcf#uw(GsRqhaB**ccxSWta+iYtj|IqME>va07@Ln+CqLoE<#}Ga{lcO38n(|yd7NnC68vt#UE3)Nb5+oAkL>{O$26wlc^5nc~bDeCnowd(yA~_oH$|*4Vkz z+F3W|#kw((xu|D}Q%2Zlpy;orXsrc}cc7&N&Xs%^wkM^h5sKB2le_1H`9lE4aXSNe z%a3>&Bbi42KOmgQtEXHu%V}4+ z!*dXshEtC1tqb6GX!rQIT{r95G;g-Xj&Gxpi z*%!5D(RWt*lD-R?N7j2seL{+kfa3;Nk&6{#h zrCdJo>(-69P^)X1%3Z8LXH+@r%`slr?4rFPzfR>YUk(koWH{A{q0+6L_z*2^KVg-k z+jhf|j|GoQeS%4Z=)P7{NLG{379Q*TU1TbBRK0G;Hkjex^otHrk(nOnV$E20me@DA za4+{UXm=5b-q05P2kL3(7p_2;?mBT0Gh~y*s?j6U%;&AF`)6wps7QR`y<4yYfh5dZ zdX2@#t-E0gD<_A#1k`F;Gj>^pH2FvLUH!zkhD&4g{iOdYxyX*Tw-j}_uu!P_UlV&< zj3N5b>q6JV_Vz4U z2w9|?r)$D9Jc`_`>OY$YrIrks7HgP>glcQVsCX5{W6membmHdqezWwkf6Y&`%~i>F z5Gr+ND7LeOAVlB#`M!u)UQI)MIC4wA)I&P`gkX=-?%lk!mjDMZ{c6Io`8^3r@;z35 z$sf&<0t2YlMVy-!qsXq4e~_qV^5ZjrW_44=IGbkf7{9SH56j41iHT z?4em^B678w>#b;{wSofruql^qXQ8$LmhKBQBkfKr#=mSXgCZQFWMY2g(Whu;|9fz%qr*Zzc}^c zc|vNX&1!m8#rxNe^Rr*7&)ctrM?O@jX{}@*`HG_f!~2I8^S!s8Bdt8`!WsrHf4wFP z(@<`7)0tkg&1G;$vS(g%wj@HTVfP5xxeq7{&w7}#dail z7ys24%}p=*KZ?#WuF1a(<5N^rNFyc~P*OrbKyoN0If>CQ zdXkeI4WpZl9Bl0W?0LNx+wRYO|L$|0bDi%sryUaPfm~0#z3Ry8-uWQ!3UrqkgWtv} zyuqKY3MTj)#A(1qA3BMaX;au{&5He~+>dsxei>IVR}?Z%R@svH5>N!f*0gR=vycqI zX14Av>MKX@;gTgU&RmoGLW-4}U`Zruu&f>j(d4LsA3o+f#RG8bP`&+3uZqrX@pP0S z%RGmP$en;$cxAqSwcpmf27&W$&*6=Br&?|4iAq-~@8iRGaW^Mw#Ms>p=Nm60C^zTX zjp-Qw;?$E)zec_(^$c0>k>5A80ucYMH0#YVnK;wk4DeTvdR{#{>-B>4SZ^0~vF|k< za{wNrT6ET5^948j`73p%zGt)y`$H6IXiiq2mC7ufpk!zCvWfW*u=INslmPa0LfvV} zk`mWQ-`hbf+MGYX5+bg&P5mUy)3&FL4%rCUrx7i&lFIzp+}?7b z;0Uq!nuIdXPNI^+3PL*cNr00j(4@86;jFDmFhY)57B(>)suZD~x}i!LKJ7z-WA*mQ z`OstSVhd$G1EK&QfQ{Vl<)o5+-q1zj(X9rTys~aA>?7XP@v5LuP;{7YAoDWaX$;~Iji5{#8|gt3gsAEzTXQ!w8ifv*SwwOh7IhsJ>inmRW0Aq9D0D9AP&PhxL_vH$}PFkI-4TN|C2X^+w1{ zT+7?d1My;siB;f4sC9-bxu=Jrq3b=%fX;7^H&QmtGlTS@<8kYKgWl!WMkP+VyE4Lx zoxS(}1MEwA=G|@`vh)(0M{A!|TPgaeH?D++^`HOnLupxdHj|4dYZsrN%HHrs68q(- zBpBR!uuYl_Mn=(pdj5&T^&F&sU0D5xY%n7rlb=R!`lJd+FH=U9Yy~koj96=%$YAoDA?s zn(W;9A0|ZtS&k{bp*VL-HZ|cFY-0Pop4`F*dnwBeTi5SddR$Yg&kPhTmZdl<5 zyGZ*m%K~YCCU$90+{hm29(S}AdVV?r`o@RLzoSTAkq?m8RSFzP>Pj)4Sru*&m=O}2 zJ_o*mp!^?AkJd`xBjzVz*lCuqoQM~iEOt>!zf^54e;N`8ygbD4e!I{hzy%wL>I3eb zJ0P^@+>G7JLKsQTybj?Xc>f#TkZ^eLm2<}ie&3U54B&*5`;Z5YQlisI%k^;fltA=s zbj(ki7G7}6`6s0A%SJ#jZ7yk@JkE*;73=-Ib9Tut@wyxnB0$4`z2RW^tdeg|M42ou zZYJisTthA(kT}mHzI}DSzy7Hdm7wLzo0LfxHl8d> z;dbnk8gfB-d^m1Pa?#lkv42=d!%_9s!7g#$es7njYT$Yb1!%gry6?Fxd-&gV#lSM8 zG}K`(t*VfA#3<|;aWz7LB0^n>ZNjjf4r_bZqx16O<8fhzUJVoNM;F;BuH<-zi7y>@ z<$3}DId{+8zaXj?p&03C3*4Ga1{!cU-ule;y7N#TPb>Em+0M~X`FLp=*V!qN>=1^49#a8cDvsQ^FJID3D(X%s zWMgjuu07|bU=Nxy?$et^s^jH~tsO&I7Os9uYCpLA^7~F&a~iDr<+wctC>`OvO~8i zk95BiFn05`TAUuXO7FG(?nRO^J_8qZ+|wLCgudmtk^G}B=U}rWzfYZeJW((cd;a;b z)jZ^=KwKl#^|xvDc6d&n>?KeuZaVRsL;{EVB)%!93xXdmQw>yCNIM`ke?lP>;Jckr=V$(JuddgBV%g@!F61R(NqUR{yBJjG62&yl8wbCq;77ml zzqBuCni?}-&h6-yJ$wcYINo@=3P{Hv_k!raKwKUgvo{Or4Dih?Y>1s8vNlTJ53G)T z!yr=1C)*WvKZ+>Ip6u1#MPDi-<0vTXcULyns6&@(rYS-jv1<(E@SN~`KAa)XGr|0|7+?xdt%l)g}wx7ILk z1tAOR!*J^>WJrR=NVK8INM5o;7kU^9R2tg(D4^zRUGol_j_l3y0lgo0T}EBTq)D7G zR|?Bs{E{8bl4D=3Qi|TRDlHEk;$*;9<0^~Ly;SuXn2kJiP{kiS=aEBFhNrvx<8E%< z8-<$QbbKrZNcQ^%V9KjJMLxo-d20&?Abr*QKVzHEECx&Qwl22*CW@yfhKn4%VYB(( zEi8b0deg0QRJY6j;_v1t#Fsw7aEN;E!SIil_8EQ$6p&fN%Jj=rA!G(8*xF^AenXu! zIyO1ct`gA#U4LWrIewp;<^WV96M3@#|M-e!B_`eK>W1+>c*`M!Q}Ud7p_Q}QtWI_` zMU-8uSjwi5SBat>LLTuRmXNj7fk-r~<7BZ^49M;^GbTQo(h0OfOYfYsj%1-}ciW`D zz#}$Pg*=;i4QM?e8ldHj``!KobFeioHE`SvPxjY-N_r$-Dl<-up8Sy@?VU&Xkq1AP zB`Vs)=9&d-vKaR1F~xMO>lNk{widui_I(JfMZ#OseblVX3p}c*Q$q9$(brvRyifaC zoaUVzWlEf;U0ldUN8g@tvnf&IUno!iZ$$KIj8r)@Pu7%ioya?-tpNI(u+Y~s1D+8j zjZ#OVy{On`_kD7whHAA_Sn7Du$=F{$J@4rI5phlx9v>5RG;LmPDD+H*PAr;QumfTT zowG5+Yh$%7{<*rre-~$x#y|b54d$iQn0j6T$0LZ3Agem7Wh{$jg|u zQ|% zgt;iLPgFDXU{=$d-2?^%g*eYhqUg-Kg`|(&%-vLeyAT`a{V2{&($+TFBh=Y1DL?-Q zut~;cVA5M~x6CVnFR%v*rR@nk=OG$31VFVf~)Bt;IfTfV&=i@#9PY7v~De zZ=|=OxM^}HDy?+IMo*Mgsz-Sy+|s3IM;65KNCRDOq%8C9IE?XRvxCYUbuEBRJ3?h` zfm>UF%j%;ekH~|wzi%TH?pr{U+8-jZu$3p3`ST)Bsi|b}nLoXG=+Wc15pR-HXaf|1 zAC|@?=Tsw&xchnmB1)9k+s$Q4_GTmeUlUy7nk#bE>iv|QJE0FYW|J2rG@80L4{dhw z#`%uTxp^>2@zAyY`@$^msnj$CJc2n26BXzMH|Kn>W;d%2;8Ow4J%|r>Y}xAoUl^mt zrHCb+OQKjyZSdt}IkRR;;~{Opq=`W7!}(j{LB{3|f=%Ugp$w=buZlj=jr>%^C6z2Z5K@@atgj&oI(;$=~Jz@IWD1nQX4?P(Y6 zMSRfP%JIkxHP3B>2X+hV@lbLZw*z~bhlIX;i&?@8$b3bcUFCy;n1vciWsXtwn{Slt zD8->YG4z!syy+aZIRd_(tH`|!q<5x|biDb!hN90j&DsHo6(!dY_GgQ@8=+iRm83`3 z67JEjeXElwWsg2YEdjH{E;s7n>FzY4sJH6JFVEkIc=$noM9lvOXr|k=tXnM_k!#bX zT4t_;UB2%dz@F6kei2K?G|0_QXQvms_}gKVy@!F9ZFh|Pp@xyvSqW_fd-HB@kJ%sj8zd*{;9|!OrQ)XTFU>z(P^heQ?x4on2mob^`2{{WvSb}t$P4%!{YQe;%fy&UihhHg^ zxIR&UvwVcV$@QCUkXV@#SNjJk_|gHWm)E4sH8vBcp5RZtuS!-fib;I&bUzt4Sji*c z*iU?gle28dGbAU`P;?TA31BU0-Kv^EVJ@8U)%_HRX{bqg z#rJ#g=BnZu&wqfNlMf{BjQiMW48%#vn4rDN*&x00*UjR}LnjD9WXPH$2@b#1yfwW# zKHzpLv<3P}Ebk-8-L8%}s||eB0M9W{&5R zy2p=Ci+-$=`6Un44>10EB^%*EUX;oe4A3480J-3vK-$${`FzQ{_2;WGCBYEIR403k!&yDetrWX{t)=!(Ruczdc$v&A#!6Q1~0U4C%`hYK-U11p;+J(5;Z) zO=ZuIS7ZxsW{b=-pkSc9o09$YOS0Ay9?VMO;+mka;=csp$?9~Q&!n*kNOC_>RYb+3 z0xGgG66(Sbp}tAnPI|HbxZ+4=(TMWB(#SXp{h6e5!^Mc@^okOg!M7FqeR`l-hFL$Q z9a#n9)}a>?s2Wb~Ggi7rz7n9wTXddV60!;=`xJ__1W5jaQGp+f=22Gdt+WUgXo*<@ zWxBtc&|oAx8RPM3wu!t<=C)gLL|;IVO_U zXJ)lMZsnFlp|D6N5q8=>Mx<<2?ODxL!8(2chcs!$?g@MHT*BA;ppdnV;HSLsKQ%`y z9IujSGpTCnZ#xzOeLhx+ZTP+57Zilb6K~?lPapN+&-tqw1z~mMY<90;zPmK~`7G^( z5G}g#=8yWNwA;+W4W8$S=%pL`Cj{>m*hA~KwyeK=ne+7L?AMZBYHk6LR+A;mdS9}D z9kAPoIK}rk$~T+}_FWo#V&5uJTz^>l#Jy1fB9dSnI?EKQFu@x!YYQJ2hPp_Hw;Nqk z|1kGCCr{VAgJmz?M#oAWD(9{BPyTQgb~a@@X03vq<4sI<0Y}byoC`HsoQ~Y0<5OzB zk3uf;;wsu7wImy#M`o{c=kw&fI9)r=3oMIrRq10b{K`5gIVQbMkrPag&jTW%=6I@Q zz35A+zCVkyxLZy3rRqgmlEFHxeF_X7~7i)t$~Oe3l1D$d{3 zn4ZCc&JmnMvJLjLP%C#SQ7%abj)Uj6Xa{9MGB&myDR|;6yI|Qh!9KS0GfG|vA8;E% z952&B5}C3augg^Qbf&EopE+oK*6mV%fU(lSt%v?A{g-n;HSD=8L82>944V}0#%74F z%yK-f6mzc_GjFoBt4-e+k^6Z2M~c$7g^S1!kD^l(2E+w38(XYZ+}>5KRJnm^uZqW) zWn$WS&4?PE*sSkf^{ixpz)n1hrs(grAJ63GD-x2AKtx8ScVi^p z(3$4CX6cl6j&a{%8P$lXvE5#Jd~B{xg(F7~diboB8Q@wPl|6aOk-t&ZG-kR8Z z`Fyd4{PS8T89{mEqW!M5AA&|J-_G)r_ANPN`VNz3i|74N=Z=Q7#{K#pmc>Tp$V0h>EQ^RFC^ULFZ*3N(UP(uogDR(Z^nEb)MHbuMzTcN&PK53ymFiS)@ zPexS*v8ov{Mij=acKLq|omEb#a(20_YJ1={RD7rEpOse3W?1z+2=Km~E+ZZYB1;3d ze7yE*6@oINRpkkMxy{@n53M!DTbJHr)!hD2J?;$*nBC&1!C@T=C`eWvvpIKt*YZv0V%G$@l$Xx@n4Ees? zBw9`G^GDb9Su@Yg;eX(v>fy_q)w603_X1tvt5$yU_@RZP>vC5s8k zLEF{|-Wn<{HIpT-G#l2I8~%4?)p=}SSM?Bk2wms^gj47QN{w#^vEse0{^jG8Gs@K0 z%i$Hrs9Q5E$}b0|*5X|UyCD|xITA!vKJspd%U2n$y`J6;=$@ra(EX;b6HHbgF5u>0ooe-T9nzr z`g%rRGcpcLS8|cWOhPrZxW4F24|WcSZH&M1x^0LLAkE~tQ*jHr2gBNTp8W@?0mZiS zDVO>dlMmB*nHs#EESo`at`*tR*^!R@Dpw#D=vbZgylNSB9%XY~0_WUg{QzOB6Rg>c zql=SrWz!yWceg<_v%;JI&ia;Fn$II8Q<;qln-gD=Q)eK}iM#+2Iy=X#kK9IY^Y_ct z2iF62IWTR-k7e8~>3*DQoBDv5b?hI1%}(HZ6RdgdW2{*0!X3813cB<0t6WLl+t$-x z4O|t@tZ)nDd0A}T6|h^le9)Dn+~RBCfm<=DS0u*lm7`2Awf)EUzw5nJ4zDTOv^EBp z+GRPiIu`$E(dK5d_wpJtIT{M&$@~96kbFfzOzjH8V_wRKHiUJ+^+E&gPL`a9*p%NW(m~oM%CW>@kaA`$lR2v@1Cu7AJ;CqHz167ZWFBW zSCLBJ{wfjQ7|vP8H7=pTVfPz5x>Fy{ZP`n?Bgm^NmD>66gl>L?`ow~t=Z8eHyZW3= zh9ccDEf1i>xW^M;@byxGVyy3-kSD+OFi8{-QfeWB2K`p+Sd(Y$_4M7a-)|dkEU$p% z(0e}-P3fxSNmRVK?AjW7lOFYlC0BN$!*DZhi~#)o39tAL2;CK1_wv_Rb%+F<2DnGQH>cYsuCdZnL#2EadFaJQ_RcFKwI%pAUH3d$&f!B(*OPCa$;8z#bxK z-F*q2S-$vI(r;G&jE#5D8QDX`F<{Hy)q9Jv#4a{JYg0Hy<)S2ZJ$A zY@P4A`rd#Z_kM{cQJ_v>YV`k(n|wgL?N6PlR{jITk(1de6`id3TKY^p5<(tXcRK)c zgU+v?^@1lel&3aZ=xGckVX7+QzZpT ztwQ0KA;R+O2otwv*-_EpthD9yS-)gmYkloue0p9rG74F-TGADa$7%FV zDSU)yW=*fbx4qe+S{I^chbTvOz3a$0d?~6#U{wC48%C(#HmCu-mx*kVS&eeV~aq~qc8}k-nJ=}vSM); zDgCG6@H!&rVl(pHN6_m~DV3FC*j3BwT&cKT#xqJjkgpd=U>?st=wlK(MQ~=QHwJ9x&pU@ttX&N`qMab}JBmhLV-`chxkLNVktXfx zvvPPs=t-pEJGJN<;v2s|c*w6l<^ydFBxU<((pa0qnYlY&wVfIN^^Fawey;y5G&_e= zIX~IToA7duO4wRw%m!0%KcOw^o;@fxh_P@98%097G)}w6exzIA2`8IOl*((O68F|B z+3J$$&{geAm0B|&hc5bet<6IFc0&2>BgY*!T(*oC}A`7@40nUa~`*mTStgs zJ&9~^aB6Mn@Xs?ESy)7J2-XvP1ARU<>3u8=f|gJB-dMZ*KWG&C`(#)uo6C12XXrXz zQHZhF5wXBKp#X1^qF!1e5M>p(5Kp*TA|clGH?!X8eJ?`pMNIGlAsXy~dOm3~;&8@7vq6^YC z9vVOde!VBLJDz1z?&i7>#P0upRU5rd)3^A*9`=@`I7zRh^_S{>>XQwX?L^8|%av~feN(FME@~gWJq4|P#%Cp1y#8c+VeCn@kJ58n2?I*bxXHVsF0LS2FgB+9 zYxO+DqdUdJBIgRB`VFCEpc~2J?fX=b7HyG#0MgO*vY_A;h$#3UAcMzMu%SSPLzhmL z==~~@<9eb$AdW3!?g!mCZ2k2s^#oJhh0pk=nY{cE^Aop;?1%wFAN^z!}?FvCCq7C)e{O^5>54b-0k54TfYk+k;Mj zcALX}J2u1uWqa_I55DYZrMr~tA3Z^B&!|7jK>kUI=*y)~MA*d3}kDd7imtLjZNbn)Hl zsi(5pjw1h+4EeG_`2nEke1*AE*B|yv+iHA>SS=DnE;x`Qg!kI~}1z zFN)$0(w6n87IrS-Cw{Ct@th&U^Qg#3{b!U>Fbw0z^ zNd}9FM=dzvtLEn7YR|jkst=q1kD2}ZYdzOm#MUB|kUH4&XmU^{$s*uYCMhZDmN!6NQh9R{6JvV;{4ys&1(J zlF5nbH?l@@keRcW#^@#NYY;t=2d7rFLLSLycS~QU!z;~t`J$y*s^TS7gBj0JtnbEhrj+mbO>99YIWf9Q0}sjJB4iqfc6$QPxS z&-cCQ*t!(!DTZ$n^!3N#T zT(31XkqLK~!$z|e7uhzFEmYel`m4d=;mrM7gk z@|f9cc_CKiIGcz&Rr|hdt1ve*sb4YYjvUEl;`?bN=;f;%hyQ?~ z@yFs zoK;LfyP8jedfTBlBYWHSVNu2ZK2!(PuBp<%yAJptINk!X0dor+dVTt(s7%&N1Sd9{ zPM{rnkxUKJH39xF@E=Oe9R14Bt0aNjHjTlt?;B121AxZ`KEA4B`PlV5{o=0I%t?sC znR+u`pCG@R$M)}J7^K;P51YC)8eFuR8+0xDdl@n`u2^&Rn=a)}=Mqy^{944oyi8)~ z2stg7-vZ2uPBp1bUp1VP5~Os_9(S}CnBlF;r>c8xB>mSeU0NJ)_tS@l$C;9%u^@(4 z6@v1D$&Ofm(KPHVp>lXK_p~tTs$lkpEsqMl#_f+0&xSwq-+a!4>k^nso{>+{#R+di z;EQAg`HkVL-|hSXkZxuAR1c+b;Eu?ccaHXCf{F#6d-X6} zQh_QPLg@%%;A(4W#>vFNdq?K>EP2r`Cnc=U4O)Es)6mu2qN!nYVJfEFj#lEgrF&@!D#<0kr zM*Uj+dCG!}FQ28P%0p)a{surucdn$yEke>-jaKDia$Pw$2a;?nt9|2yTC=s9ro&pJ z@8+jmyIdvRbza$5Ig=y5Tt0x=8nBgXQ|F8K$9)DB?wq>vsQ5^D{b3OienQQiTi_?k z5Mkrdv7RAy4CzXs*I_z)hF2(_u1g*cskB%u$yi|~f}Y;raa%{fNnNWIs6JqTp4w8- z{SXeOB(mQRyvim#28)hky1Ij!4K zCg=3gGazls6`WE75{3h3Df^7A9=Ou$-J6$A_ql=XN#?C=Np9%v-I2TSpamPz=o8f$P)57E}rOoX(LF z!Yz!}8I{hPq-jT4kCOu`)a+gqkoI1d5pUNBd~sYh+5pbhI{-v!vR&_5`0;u7jEgz) z4LN6~A*wfhF46`zw=is1@u%exITWyKE@FQ_MIx(V1w^TXZ804KzgR{wI5vODDr!Zy z_&8MUPjx%T|6+@LE99ElYJ0U`cR-v=ggvUtyNKW3zILYw>oiv)zF@6RVcl?3{4B)pON>47RSA z-hS7P17tP{g}CQ~n$_Dk3mHL>Z`#`dJ5y9m%U=z%2_PM`VqNqAJVH&#_)V5^vcZ$< z;*S+0p0k>jbPuv6F>60;D_V58?E9gUHk{Usv`cPvu(?PPYd93B{sD3 zyh1ETS<}}+Z|zt!N`?d*{26zHPhzLi3e_J8xQp76CO(A+edZRf#ZIpW^!Iw^-N*WW z_SvWF3gUKbri-a-d%4@4W!v)>AFTbp{xU4qZQiQ)x>a_}WT9=w$kN73?SpQLNl0fK ztBXHL9N!?d9xubh>K0pQ)h&s;NHHB@d)sh)KW3ms-CLag*|fjK^6@%8I@e&R(VT_V zaYlV3R4;8!s-|M+yBLsh0iAic)DRtAhoHeztsr|X-}F0S1H_MY(y0U`HZ~& z5AGYgUi>8=v%%c=WXKLm^CreukidcqZJR3D;m~N(RMtVcXpgYp5!#{!jtyz};x1J6 zDCMN$Q~y1Qc}bgtn!WdT`u=$_SG$C|1$eoGUeDB1zGrxAb7EH!nP@! z8IpDWdzHT~fTf$jUOiVDKgfLPhY_;b8x;OqgzF-ESHCskYDL|uEtqU{@X|vLrzSR? zZ6HjYHq(Y)3dc$*<=jwu3TCY?p&28un>Zv?Uf-L0HgBF3bfQPOW1#gWr)K#+^tEx` z_B$(|Im8#wq{<*NQ@lQLk&&(8>0Ql3%Lne>8TXw{PV{Ij;kBX$6>^&;?4-1|6+H&X zhX4s<#N5%$Hac|^ZA<w z!+f&--MCWEyFYa+)Cx~OS)t5go`%Y#>7n4mlbboaIO`9g3nR@*9W(+jjsrdC__<53 ziy&UFv>X2!Z|}wCEqS}8?mz7yU-=u}Bv0#?q5tH&14_ya6i1HRT3n79U|

8w=B(#jcz3&7;A|8LNG=W z-qQ_X1~pZ;&s(=Tf+4Z(Dx1O3y<=qcD`a(Pv=%vky?Ed31y#>Pr~5aA3w8W7gi=Px zC)i(XMl6}u{!lf<#>5@1GjP^P^-}I#}wZJgr2YLxbEn}D@vq`xpnEW;Uwqu5^$G0!&6iA6tHFO8`mS|4F zfn<*X?;?BHX{|hFuyQVpA9WN29*J|CeGA5%zwwC=y$iIUN_S|r%3*Qd^ep^zvejJc zGogE~w|uN_R@b^&au!tVRn2o}wys^$&dcAy_-bjFnsIx!WU^Kc`FdOpUju4}i${Wj zWyZfOH2kB3EP3JMF2}*IWH3&i zOGgLyYF;Vx9YuEIh2$P$t}3D+mo@- zx!{If_sU0k2cg~VN1fKw&|A|#!*RP(XuN@LUw}~*B+vKzfr!A?JS=;#wf#1ang0Uj zH=(B-)K=cKT;hs#>LY~4Bl*o23k#vw%qeKg5XtfG^EM#;i(O$=CT$W@> zS4Zz+`slaFB5Ql|e5Zv^ljLCoGSe*Romx}AUzg|~-Jr}p=$)E1M`NJ!Q0`i4zq`xq zNWHALo%K68mL=5X$Vx0j`?rJVHR5-*AvphpwWK>^pnfR%%tZn`#kH~WBQu%m_dh;X z$t!o7Un9s}1)uUU4R}@bAUT*eZ|zAn?JK~NRwhnjxJVa1QTN0n9bEbiS1;QbLXAtf zF7NG_dCWSQetXY_mzjQD?=XGXTiNS=YUm-LcE=(fnL|xL`0ILq>6MN1rfWO;y2qSl zf3OOhQeV9WfbgyFz3@I3?Nxs^#W`|<$`MgttDn76!Axzml1P124yb8sGT{Ty70dOv zR$JKW$hxN^k~}u+vs)(A+EQKjkNIEE%CrR_`CR5yYm$^1XZ_T8stN^Ev7`RrHCPB% zi2$@8;74h~p5Y1!!1mtC(H?x+$yo3G;1n&N4_tW|_8j+V z|Md5YfnQOZz;f2;;;) zLZonSeu{EUi@3X&&G8A7UIT(?K0?g!VFZXOc@Y%-4FpfGj-NNjyd7QBP6z)9M}I5= zS(qGH@8zuqpr3V*NPHhYGCinw@}m0lyL{~r>9Wg=i{C_Rde(NAQ@%NEpXImAq0+@@ zy@yRAxFvoeQjwkh!!jz95p_gBffZc%bukHJ>Wxax3z1R_w2?Q@Z%QZE&~#D0Urcb{ z)`P-xM1O;5p2n@r(-EIbe9?O_#4JmelA=1);9?Hz9)o_=P?i$5(BZDq+loj(_Fp)( za$e&P`w|X2Bw#b@8OoF8OMcA#;0FQ(z0momTbGOQ4MmXzETE3Ur_aTGHc|!=dXSIX z-CUYeS^I?oy=T_=n!{9Dl6I4&K{YgA;?P1bu3XMAP+dJuGHVS29~*em$rm(%r&-_) zNY$$U7?Z{P(1caxr!mXNSu6nK`3N5N&rYhqoT}Q@Rw+30biggJYwX6{+^j`Vq*=0k z!&d{5afwZNDj%r6doNxp%&-+Rf+qUiI42<=HBBp{!XOjsaCy4fnV2rBet#!y!7Q=( zz+u*MA*ju=b?R_tGkaC5x9Mgo?$*ocTCwL}l*QEt_(wD=T8%35--^zpgyc`<(tQdZ zUg}JhR(`_Q@x$!lW07)E^FRBx)8+KK>NNV8jluALau|Aqw<1qQ z`4$m2)HC;WKA0iS&dS~KkuFAWTXCzBU9yxm;5j?yq*mJxSf9*oT#ekBQ^Ae+cVGJU@l6rR49_7Ro3S& z*fxpy7)G0FzO{GO`r3S(-b94xoVDZBFmRWRy0c+?)<0I`H_u}74f&hs@9V}w?Rm)! z>nW4CJHJkyf`0{iodQfs78y%XPu1zti+RPM&*f|Lz<0y^P>6(Qdrn`b8!j>q?Q3|f z-mT@Y$(^1-qYoQ$Dpifen$pwdbtShi{ZB?hXo_<^Wd&YI4Qgb`zK;!1JFCFfMMN&$ zXt5@rI+VId2-F};OQvo`i*%F+LgbC*=2&N2Ah(QcY4T}g5cpq6zWS$)84+ZwX@;nd}T3&7@n z`^6vF!xIY{OSTU!cPuvQ1{Y>qq0~fhEpBEeNmjY^+XCSH^x*0y@_=*~nU0yOp7EMs z3Az^+qhgzc%j~ z(N9xNfj6{@!JHS!LzO-5RqlLm2G`IY{`{(OLdafU^;h%Rs5^@3m$?cKmLhr)mgnI~ zTz9NYeOf#3{oBBFpbyIM?Q2-QlBW>6p$uN)v$#*oP~bkz=~3g8?jyI3+?BQRNc)bv zW~}etG-fAjD=D;=D4J@#VsG1kRr=_?N!5SS$03=M^wGac%k13lOXcNz!jChCc1@O^ zT`ivG1Srp!GfHh-14ifZ@Lo)u(S><_=V{$4tA;BCT|?YE+c;^PpMN@}UmEo>VdniR zF7!MI58s@{q4U?g_WUNZk!a8xA2qtcpL#bglk*_2y-dDGa~oLuR-wx8qXO<0LYh)}M~Z7zS2MvlC&U_;wxHzTO0`dbN%u z%ib%b0TaY=`!n}7;N|?S+ULbBdB3)v%c^>_?A!~M@%V7y6=ZMq{z@E6+ld)KGxd*3 zFsZV6uu$w1cla;~ym?e9HQU>ktxv?^u#Vi0#@-{qXugpv1Mh4nHxrEUXv2h|W8T1l z=`{5WSPNDNWA2EWSn23Yccso`Z3y;TlGxg{{)AwyHR-p8Pq&+F8c*H4eGLGR!!GVw zS1mqlwq))`j^8J5JlhKtI=P8l*XfC2A7F0~L3)TYSL>_A?9HSlk9g7r7dt+l<*%PZ zcuFtrEm2?;)#8!_2K)qog9F~*;Bs6_-YeGc*#N&b9b+ZmG(%-EgkPmt9PXR?hAE&A zdNh)}FL`^YzWJpN5MNBQV`)`-_e-r^F10G@!liW*g&I!yKSC6&N>m&lCGpa4s-nFk zeZ}DDNW;komfw-$^nk61_&t+r0BawZaOACaT08(XsHrS#Q?r+VzYrw`={nq*GI5}mF=f8~YT?IKKyBLVrPw>-k%tYXNeQ(Le(`~0yC&~z z>z&1T$$$BOadaMzRDb^;*GEzz zAtUQnM3I#}ZxTW%JL^^|=!ey5nMq#NGh2jff zpigQ~$3KQMm=}qXD_=7U=OGUEu4=GRo`%*B^i57?qI2?r&se<{3st3s>;U{Lt7|5B z9jnKevOUC}2DZ2+ycJ(VFNekGOXxTSfzAkt&h92;(`EWtt z_rcroSu`811}=k&M7Rj4EvUOn7ZO@)5YD;}mHB70|b}e;(&eZ%!m)heU#1K@q|{BUJG)pYM*gSW-?Y>scm-OP`~)wIW)!fN>FEk`)}QrCFvh z77eC|zOZ@l9(hi6BLS&>bPi+RyZNG0^^sgw6xi8vj|=Z(L$_~R{<&kwQhL0zfZ-kh ziTNW)Z+O{C+7=EyeL&!mQige~T+nMt(U$Z+0Ht9@zGV%Q=WBo1Sf-0Ty^`# zyvUBO!=PP#c_91}ktx5Z?9cD}TRnpyWSC|cln5dHpkb)bKe^e~NBf1nAPFfgKj36( zh_G*GU$95%B(UZlAEDI9U?Rei?Ca9h74u$kb;5l?{bPV*-yeh8w=*|VBjgGUv+O>% zxEUH*I-RPFvO=rxE{KE+5fw}4c*;w3eWNLzRSA*1k|S)> zGiLUVU%#YxsYs|TH(A+20RDdS<;0ak1p#qiofpgh7io-VAqT_;Axg82$|(Q^9o6OJSy~kcgd? zt+Lh^OF=odlO<4~zfQ721aj8-)Vo}R7bJ$Pwb;b8C#~GDcEIDY&Lsh&0o*MR;%{Ysnx))JMur`wl>fA(x9IsOlzWN4m?mDkTdl8 zkV}~>@y|WJY|@3Jr|fg=ST?TjBV`{7o*w>jnnDi}n5jH0Mg%zO>-5%?yi)v|@4QdA z&Lv+-@OmE3$JpUiqTv(Q{$$%h4eMHXc)^-EJEUT>n;?^T2Nt|srfF`{fZQJ@-ORY{ zXaV>K3M%@RWr+NDMo0&oL_VCs)3X0z9<(Bg1H>pCTvwp!|zhJ8Il}Mpo?(uv7 zJ4$5lKfv-HY*|#!=!wh!fGkylyBwW}p*=sz z)*bb@F@rjFo2-wg-iY>QHiY%Q0CQsF8d{guq9tbJ`f2WO-CkDhg?jK%QnE=fcZc4Q z+bxm0qI5ObAYqYx&K?HX;>14t4co4GDZo0H<$FMn{3^UimE^cgwJH}9C!%m;u^}lp zT4awCEa#ZCELFgw#jyxAtC-9BBG|!mWrxkb zP7R+vZU5eEsmIX6I1bY83PNlr5mLZsgTy8s6?romhx1~NKl-5xYoOe5lL!+DJA=O# zH_8LNF|~+TTpPH$B+hH5uEo}`lNFy*bdfqri>pzZM9a*|-|~MKYX|oCK7&0_BrQ_8 zox97H7iYd~4g&*#hm$37)4mB2OF#cHptVtH{}`Upq@<*e9Lyli&hFcn)VzHh_`=*e zd#>!TTt5zU?q00z=mq4l%&^>3CKdWUxLyOma{#QsyDhx#@5^hCe%}!Y`|s4+m7-Fx zQxJbzS9*8X$Rhjx%tqcc(C*PBlg3_nallMkCdC|x<%3nb8wvHm7@}Fi=(onE+;OVb zd)j-gi|p?aS2dIiJ*1opzt8`!VokV&_zLEySx<=B>{#)2Pvh^!F@IXJ?uQT_B}K6< zLt=RIC7Ke#Q1%~w*hOEwe@TT3-7p%mU^+>9bX;+@*#$}NF;69?8QiGb4Z)?8^PhWO z{I(gg)+*37oBL8_{#aWT#ZAs!vDq$6wnTgFg;*E7Pcd9CywCO*8Q4RYH@-32cv6|L zyWz-;FLyJ&>?n8FnK?q&&ry-6kR4yQHjjODRH0`)ysn}(jp8Y`R_+hA__nXNO++9A zXFW5Cpbn*`o{vpo<9XexFwDm#goxcD2b_6fzN>gzUmXhPYx>Ze>3b_B^p*IXXp@Je zAs=uJt_{Qqb0pG|NN!m-s$<-`%Oe}=Z2mF)6(OLC0XNPHdjw$Ys>x%wY0Yr0HNNKf zNQ|MzC|6p3A^|QEr`7WF!18vjq?FTXfkE2if$B%1`!MI-&Ax>^lf4tW?S4REKK_Me zr=G8FAP&cTyMH>I@z-M|<;H05$ysEOd*H@c6?nNwT1%4pda`CtvMVgqG3#A*npM41 zu3&BgXnavoIFG2)13CkK?eWk)2+_fR9KBm>kwh`M8b0ZP4D{HK2p%-Vo*jW;^Ts<9k3RC36->xu{KhRi6gq3ip1r@D~ z*W!|oA+ZRrB=T#_j5K9wFF_$k({Rh;y@U46{E@N$mM-tF{%knA3`~{}AoA3gv?c|} z6|$K+f|-o4B%oq5Zta+q2+c;>$i-g%MCpnd$VIYgR_LEQd(@Lp#_qBG&zRO?9KEQDfO$INY@Y2M)9d9`3EjjO`{IM@A$}9ALl|ChIK!#555QkmT$`~v5}lq-H^zph?wuL?F6|IO)n{_dIK zHzt}}D>tu{DKnDdIBEUnT0OwoFf_==e=%m^TFU8oM^kad`hS}Dt)o|DFZ=RvCpRw% z3euoSWJ}_u#pUC0m@cMsilkI;&EC}ZACK<*FP3ABpz!aN)@l+z@e7rkmPyqP3=3Of z;j5^jWZnOo!?yZv6}PJLQbxdu+}6ItPljp}bdNh*;m}Z}him?>^I1QyIOpcCixa!T zE^%G@zC2qdDGEc&b8q{^&qzImtXL=P$Q-R^k6UG$8{9QgxXsgU;_Z`wE1`FXRAiQJ zsm)-3U4cM+c%STM-p8Jmp(@v##|O;c&ZD@Ah__z}QQOJ$25w^_Yzy{rop3=8O9f!n z$q}35gEix8*@AnoqgZ^}#1n8*kIo58&gaLJo62?$_jO``>?ac$PMFVB;rR9blN=tE z*YZo>*4KaiKF6-|S8@#V95iF}g!YLpIZb{;-*xfJ@uTSW*O`ah2Hj$=KwOG$M$E8j zh!aXygwU-kl1AJ{cEM-keWab7djv1b{?1p!{Vo8cE;rL~xa5?EqImQXJKJX!*(Q-Yup+Y^bbRX+UGe+osrXqjr?*=T0YZxrX78xyCPrQ?`GAUz1qI(}#@ z$D=N##K9_|<;d_~a|24b`_gV}*^q*!rH+h4N8Hxoyg8itIP4TxVIec|Hw9L1B$)MM z%eDS1qTDX-F|T^&>Qz;hE)kauE7P1*9edyXs&&PoAl%A&G+J;*vAe#)HN@WKuJPbz z!Eg)9$}#myV0)DdKeAw{>}cZXYeEmxuY@0$RsVJtw5Smphn#QqoAg~-=i40wY&FMJ zZgG8DJXKsNvvBBA8Qy3*>)Bfy<(VW#DV*1MIb0r!xk@!Ami5>IjxP;|AErOtQf;s3 z1>8`9bq`NKmKnVak0D8m)yC-Z6(Q5Eg3B#7^~yL9=0S$uLB*dx+Yc_n=> zCJ|s}%?sR)$|1|3_gXUK=+GgF^~WtwuO@rA$DXZpiU|-pcb*S;6I!uv=PaF|1>i&S zj)>9;s)2GU$A$<>`|Vz8Qai>%>l{_S5)h+8b*tj~7u2y;*Bd@`D>rkb_#Rg}sTh!8lH6UeH#K)|&pecH$u z8lM_o0ZaIZKF@xvcgX+%8rJQ)))sa;3~H?#G@+jeJqfx)+wKWQo`RQ-{;oFwpJ%zh5ov=nSP0Z_FYC18>ghjU73gO`6||b}q#pYD=R}Z2E7^F3ooUnDz=sQY`W<$!FNHU}VLb!*G;V(k`SBn*J8?BKK>M#%O)hB$sH{BroF8W#6)**+T zO9i~d!ZI0u+WC(`k|sG!eHvB?2HEaV^_4RcG2BRmtYMu!PZ6dTJ0RvxxEqSCxywp)X_{9PbEdRH4AEXNXjxJ07fvc8YUaJ{4 zHGz8p^VZk;`uX+ps=nWI(@vhGQ(T~u%N_y-gq>;+XlU42LjKdrq;XIl@ZxQ~WNd8- zN&9fgXVVy1sakLXs2j}df8lJ-mxGU&{xL}8BBG24)rL^b|HAIc4Dj;~Ywc>Iic9wl zdrwY7?hOzVM?74gC+*JNO7!{tk0D?3H~0nM|2_!n>B$ajOw690pnWybln;llmpz+J zdT;qOt6GdCLaqkJHYhZ(E9gu%3avU%PST4%+V-GTGGxV_%63ZukdP_XgXg|j!ovD z6bm_Bq=7hhF@a?{jed8+FHh6Ss}5Rk#Bovnoy-AfKyj!WVoDA!{yVyBjY)nQPM1C+ ziBq{C%Ytw*@~q;8=R*ZiJ8#abKDoVQZEPTxaJy?^eGbk?C<3ulK~7)hP?>B|E#9Ac zO6=*X;6x|rX{2qn5_~5hyZq~_J8Up`$eS)ZUSuPHULI?Zw5U>d?cP3s2n7wji1zyU zGC~c9UF2x7z@^qaufL!=9AaHabwEO8WDiD&jsib=hm`EbOEm#!vt`jd_H)}Z9-76U z26tWZwJaQeI?Y*I6j!Ciu3CO&%<=_WZI0klV3%*3a_Oj<1G@t)4*V(+ymI_rbV5cX zRm?Je7}69DTgW4xT7u^Sms;}0X(+MLHJqYY)ri6^GdZ^hu8KY|u7@6aRYr$&)G%*Tw_btB;RA$9&4C&dzLA$^cH^*O1FW2Y7{S z>7<+apMAWto>a`+aDEqXA~3$uJg3PNgxWD8$e5E~5rInI#UJoK86YVY(n#?`BRR(rVzi;c7!U(Mq>N>{!aDAlIeIs^w7 zSSAx4pXR7N)e7V(yy;>Q(tmd&a57{YR)#nBs7>NE@L?Udd(bZ^`ar+$?EVuA!H|{K zB+^;JS|ibv^p#*5^L(OKwS2Gk)|3kj_knLRURZvdk?(Yhy$cf^V2g+nOPRM77-D>U zxh8m+a=WSz34YtX_yppJXk&o0>U^gLe-4#1waZkco~Au3#C2wZ+N#36U(mic!)03sd{wxJ>uGedX6w=KfPkO& zdQTl!9_=LH*Y22V1nxneNB$@@^v?-hF(tRYoW zk)_~kcVfh$oIJ39e6jdHdhLFCns@70Ugzw7Q-*&G@;i_Kn4LkM*CB>SA;hZ0jc0ac z>K3dw-)S6*zs7;p4AazdCSuydcsmw(6bjg9e(MI!7WKcg<&l42mzyU3HEaw2x>0QI z5bRVa?Pegdg<-yV90Q1td4aQt*`qC}@tY}uTRK>0pW=+Pox{7Gp@87Kf;J&qw*ez) zgoh60MVK;8ZSZ_-E zff<o!DxM4YhP*DV|R;cdTbI?3ks@MP|5=!IjwM^a;^~ zu&qAUEUktmc=|T_3ORK7AH#q8)dnMed0L8sd{R%I`s^~fzBZLRi6`ul)X0+*T}Ugv zykrZ@ycn9NI~O3AqGNb(W5dyis7y*pCBdeS*w_soZtuCTLS3CLISv1Kd#_(}p2a)^ zyP3vjg4n^%2p+eQp~`air;n2pcusr^x-sYcQ8AgI%L=W5UDm9&0-;^u|1EBX!%z2#C?kMoC?^?>AZ;hz}y;w75L1)3k z6|~)W%b8ciLQ-<70bw3Ba~SM@?y}yw2T#tair{br)HjTaOac+!2l^=oC->9$n6yvp76)+)1stS}CSScz-`n3gjWhn& z!bQJ;S~^Eij!y=7@4-`2BNyAAi( z{vv+}20K-(XK&ilx4t@1f_kQMJ_nr|-zC0uy=n&jnA&}gUGWcHlU(byTu#YDte0@(zZU@WE zy`ptBLbBDw*xVwm&qp$~G1};%zE?T?H=>PAi`i&tFM=!RD{0bW4Yzji?7r-R;VOVD zL*#&L2y28=jOdG`DmVvKZXC`|)g0FV7teKgITz3McwF(hb@BUmK<4xdDt;0J?%LQf z{idV=>hgV|r1c4xOzz&39-wvLrdoBns!u*}9C736z^J4XW4pg)kT)?LfLM^X2H~N+ z6om%*^$myO%)JXkR>X6uq_W$5(%y~TYB(W7SYO`6s;kIK(wx4Pns~dheb~6HO$>P9 z8feQ=hjQ!bKZaL9;+_26J|rUpJ|(%~3!ni|VhEtPCtk`~y0yHq=I|Do(;$9oolh0@ z+D6UDcV((v9J(}&E_6zTXA1zsc_YVutB#!ghR2a*ko76~SxC@|qYj8Cm)iXIqTT@~uz#W?~Yif?b9DbmSn^Vj^2)oW9z2SI$k( z6+P5UJ407ky(Xkt^$slMt95I1YIFXl)}EK`R>=tzWFevK4d!1jt1Oqo7SL~#&v<$K zp-sQOh8x0gPz9vZ-z-W>l=jS{>RO%(zA5{U+xvVk#Fn`C9>mV;aKQVbs$R8Qva8dq zacB9v0_?Nc)@!K)wvw@$nt4xoQMi-J6CAR39Cn}l-2c}}~V3VY96GEPvsD0#-p&}UzOqO~z=+G#qgV_Q4M!q|#o;ZDJwUbdBMzrg+<{emDuy^C6eFhKi$0HKv;K(|!4CT)BjZXX>w4)@%5Q zzJ(M)ST)4I&<7U@kMcscbn1}p_?7v?kXKohim6UUc?x{(wh!{c^Kr!!BSI?4hX{EK zGhWU!HyiU58QZH3Rj~>-5%E&eWe}$IQfX}PTtKR@MJu`j%-1fAcS-ZkZ^fjDLlvo6 z_46&=$h8&Gz_1qf46syKOUG1;;3a<9)PT`|5Mi9)>vXr(&C99&62)g1XsCVtc0^6! zPT)#Bjmw^(iz3;>d9xwXs#?9#%Z~|jVq1~qx5ILPlN5cHDo5mvtdL$O{voO5}g;x9<;yEzdn&Z8~tzP?ZTu&V3WSk-t`l zd0r6FgxI;gTyWL6%q|G3-!!@#F=w+-sN;9f>dyBL7pHEu_34D{Lt@G&Jl~K?vpsQN zPzZLD>7taO?6IlmPjcxORELmIEjxSbQFnzUYtn^}>esHio?nd>AzmwRJBjSHR&(xR zpA$Dg3NY18ZNHYks?d^E_;R?*Cw*2=4u@7jeS&EcA&vI#1H0iY~h%>bVAP{`kwyyE>*UzB$3Jo_u+W#%|PB9Cp^vVi$-;o^IFA=$c ze&Jn%FCRTt_#TQp749M)=(Lb~rBkDiu-)c?O6K@#Rt6tQ;W8|&(#uuVWpQW>n z9vZ1w>x}FuG&m)>_f~7L?w-4=^h{V2(T@H|H12ta77f}owlklQu4U&o>>ZO&63w_T z-xw$uC`j>zh|qBhs&@09hX8HhP7zGGLR&5QSoCL|y&#R9ULPW7`ATesBy&MeV%)Ak zL1PU_n5&;_(o?x-mjTKPV_cE>&%VBmP1&HO9_>}*?y>;AnKLdLdYPs3j5RU|hMO#?UfgCU z;Fr9TYFn+_Pa(UWdF2lR&p0C$t;AP<-$mz|W0rE@-1Xz|OF^C|gJu3gpVN1^-^wE& zhBaa(BeBJypzvL$sd!S-olcy*#*zo+bF2zD5AL)~cTE_S&-E)C>c1Qi7b^91$2rZ_ ztYa*J)3~s7tj1;8bpA#=rv01j<gHSLD6^`*l&7s%3 zgcWky=*-U9>W|9j2lZ)A_)j9=gyhI$q^8vE;U4l9mZ2xO+G6Ap?#RYfVDwHYaj zugyVR^BtC(#V8!^0l_)WWHlksz??^ko4$D#K~ChXrS|Sa#<&S0?ic2L0Y~kHqq!|j z!`-oo;9-Z0T^A$XyzxGNb;rI)O|hpF%sCCD56281h}z8H)Qdge)sL5qSRO!LXbHWl zoS||OcxoxnsoqeU*;8qE{PUZgRdP2}dahjpv$vy*$m@8Tdi&`eTbM+NE`bU~-|Dt< z?&;4u{I#{~hI^}V0ZNg83B~AF${DP%Jw7AH%xWNDz$|zMJBEHu-XPlIEE?&35vMCE z9yYP79Bb;aNdP>ry*1?jW?ye0z*p}eQ(0#ddKES@*jpPc zo6e-#675$#q;_P)mR{Vh%U(&ph1Cn_HjB+6cC6GVqNN~mDa(nGpp09hj3Ng^J_}rA z-4&0J4UfYi=~o}>7L~MXWYDINc626Lk#cpb=^sPfjq$mT?DF5ka|}rPFRA0=z@-ec zm?r>Ih9Qfw$I$s*NloiUEig!}r5BLREAgKom+EiGV#Nl77Bm1tdg{ zF(xW^s?2JN-4&wlzna^;4*Mtb>{36^!awi!mo_P z6F|Cr=gEW0_D>AqtgL=irbqu60DEVMg+unOh_AON;>Cixq;4eTX*`~@#LS>>5VJae zEG~f4LvXQZf2VP8)GeazRp)MXT&lJ2NFf(zm+WM~lB7*9;4IsCqI<@1Vyo7x>gSxz zfKy>bOgn;L*{b=4kdX}t99Y7ApUp%^@DdBEmfkNc8m_#M5P-cZgt>UiOTU<0sMyoa zUhDo_%F8LBr$hwMt57)@X9JU3LaJk>y}X2%gy|EXV)gl_={FrJFzazR76;{9)pvA-9j)r*>6fY6Eo6_Ck9#|I zYl)}Ac*RpW3Ojrx11>)1<$=#UP6g+3sdjMm()~{g%V*!UhJFl)aypPH_Ag-4l7TK> zq?&S*G84LgrHe*6*_wY##W~&X$#U?7SHhfWpSOV@4{n)~S^vji)(|b7bf=*GQ=lsM zNnS-z24y9wlV!)*EIHfben7_S?L5QplrvG~p!fno#l6JrA6#zZ9>__C=!LrvTtah0 z@>PEr-?)wXdU=+@BmRZ*I=0W?uPa|e=Z?P&->tFF(O~jXrHCiQqTJ@QTLcCm8D;>A9^=8MIF2}RKhZm8ogj*UlDiZ!m; zTW+q{l>41pSdkU!?{y%H9jQq9&ivo!Y~wHC26YzAf{MPggL90&cJ);|X3*Rz1dPA2 z>>&Vz4&q@3{s&64YZYnD>!rusvycs8Ury`89~)GaDry5wGTNZJ>8^o`chhln`O!mG zU%e=s%O;voJcN9kce}Q13v)plrJ+^bKZTTjRi|B`$a|FvJb_VR#L#7L>)pfSAFW31 za`v-*f}Fer*;jgSr`~RM zK2)tg`;2p&?SNbZVJi1&Q_Yj}bBBA51{7U*UjYl8J?Pv)7p}>jl*#Xfb$k9nasW(_ zSZ{ox8SUGBtJM5LpPPiip{it90Jx>Ip}~Kw+jK{gC^5X(Mn6N)dOwb6*M|OZJz(IN zbmCwX^F6lPMKV8HL+3UUq+?LzIHAzav9Ry-m1W^g*Y`6%x4U^k^B{?D*n3PcFUpk} zN0=M=7#xfGoU)JW@Xknn{M>5gUZe{abR!A^X+1*KN_*B|INU<)ZPSs(Uan4oLZciv zma{G`v4a;FYl9D+ReCbE4<(+tOnP@&#I$+^_JM8#XH@$iURs>+u>}yCFyG{Ix#E5N z*^JTecM>{la-T(ZTta_o5m{31hFsZ%t5uCYOEu{(_FwyLNHSV`$&UG;x2rCQtUdCg zUeQ@9NyI=w32&g;9zzj-Gh}bpl7YI z)ak?}x~@nmmef7Jb39TM;r}FQKHOUT?9$8iBNUHcaCY7o8Yt`V3h_x&WAIIQS#hF6 z=*lV@v!Xs^i|q(;n8f#qmLpz$*S?+;G{Afh@1=o9X;NS(MAPMiAaq{^ZwLQm!uGv` z=VA~4TsuA2Q^Mer6mpalfd_x=6*1YLknAA2t5{KC-)<)(|janqT9sDhSls`#hw!$ z!xE$giGf`4YfiM%G+Y?&-x1BQ`820+Px!N4g#MF!w!nW3b&#E#9(cQXPIlJKN`qHS zjdppb_Ev8m_NZ_&Emsa-VurZmTDOFS#~~}EO5rVRwQW!37dyP@^`Gi5lY5+|Q?tp= zq#T?8okwx36ENELCX=W=8h`TFb6+=Zto$4=?dvB|hc_D@*_Q0sXOPBwX`-}5K+`Uv z^NzMKe)(G+1Sf&7=(=V5`F4IE?I&MsSik0{$*gz`^i8VZWxmRJfjf!k1DWgI=pulm zKV~V<7LiqQ_QL7IBPnT{-DQJwf2TjQMGN};0!M3Z9dD8Jh|%T5P*NxX8>_e@Rosnf4?;x)-=Yq#+F*Jih=nfs(RNS6fmi~GF&)7-j={j+3uQH)(6(2%^d9U&A;3X61B)aDCM;lY@0B(schH*YPP?W zwb%U+xQxJ`Ix4tTI68xZ*p4uGvnrJA|yH348Xf_~>7uvdJ1mu9%bG4y0_2CcR>g{3U zuE%&TdbxdMwX_Lj;=A%kVdSnW`PZl9_RPRq`M{w#@2j8Kb2SX7>)j3#-{AZxVOygu z4;zv^yl0D4TTo)5`Ndq^cPfoSi`OQb_T}xYNb0~%J9aH&$98n#^a81Nv&wzcP9dQW zNM-|fT9tC7Sk|}}3jZij-iiYrN&bnQC31{bd{9B-MA}@Fvbgx$BOvSzx8?P|g-y8r ztFf0T{6&AU;SOa6)l-0kUzq^E+M7i@u1mD#g8Df}O46&8-M_N`oYg9GnDH=mHp7;# zzka+HHF_+wow%&nM5vEz;r-T~B$gCnd8YSu)WNV^f*>PZk;uMNO*sd}RO1q46pf|3 zLoqCi4-G%2f?ujq8t8wSliW_5N$#{lcMx7La>Z3NTHW{!XnW_8PYw8teS%MfYZ_z!}C9mwsQ+l2W53CR^7#dvNR`~)k?v*_e`FLIG{yJg z@wfM~-!-FnrUuUP&4ss6PAz<~H9mHJva3#>y8&y}yV9)~TmQkFoN`OwRGQ>%gB(32 zk$mGVi`O*=An;d7gXfEebq!whT79V@loO|i3J3`2wM;cJo0s%F$xsyG)}GTW(|Qn@ zl@-YU$Xz1$RKls)Qx;1YtBvRUEyJk6AN%0jKqFQxT-1|SYx>*&u1I*QwRzmb4P60u zda+Tj6Xv_iSBxEd490hGz6L(mOng4b;lxK?qpy>PfJ#(dSvz&JnjE}bJhfCmU=#}P z=KI4~(b?^@>ob*E?e#d%NMuK5`#R5BGB}{s0Izrg7&4hS$tV8AR6IA(ktt&yBc~8Q zXWG~Y>v`{Z9|-!?!Z&Gr$9*eWYCzR`hQ0~&vhkZ2v?D8YZ;Ch^_9d{H{+ z#ODb01*p%-i0Vt3KjQad`L~l7gHjeCRXy(TSL4Xve@OF5s0tUanX)-6UsIW&jV{ad zQvIia0W&h@ix{WHnGn!S&yr_mp>n2D=^L%dZ;viLUG;p3{j?ExIOE6NqX%|OpAxXd zqHK{yiXtT&=KKNbo7U^;!%7Giec6+=eBZIpUd(zHw7vdjzwz{Dc)B?0#SR5iY<)d% zT;r&PFDJI+71FM57lVJAofN(l6wt@|Mz2KuDdRIzcZhYVRzk6F(pag3i=hP-Q~anR zZ=~3{Py_s!tXeqWcauKw^B}#xEZ*NtU_$VvwPqRh41xZo+o)W)Z_xS82aJl=C%~`W z3iv}hI+!rUzNd8&;{&x@JI4%qbE zA*#QCtm3(4R!uHn^7`37YJ4e2VQRaCHRYVj^TTV_oBdU#9&`5|8;IgdZ~%*^i)ix) zyB080waKN+G=cVz7*bv9a>Hs}Qw9USsC4i>-w16LeB;XJU3MtwA{hXh>D*o2G5*DF z9%2o5?)Q(b`*F&NE*)WE$n?AnxQ4Dg`Ceo9AmrB}Ntx3(q-;P&Ds9WIkEKe?g~u zr&CJ;ZW)$N@>-~Q}k@27J!y*T4}#jn&UMr3!Q?;PH|$J64Cr2GrM z9paE|7;sGyzh!&2b04BmWKo)|T+emcv1u1K847~5y!XcaEd>{D_k`*s`Q7UMdY zL;48FAYSozAr1034|ym{%N;`#r#=m9)&9Zyj=amBPBIqAfRAwTDs?s&zEkqV`p&V7GRWU^7fs6ji!yi zV5>g~nM}GIq=fCF^E8ZmeU7%Xdmr~u=*?B1VW^9~UG9;9+aNszcnRn?5<0uP{%Ap1 z&uc{71%nUvAXN~8altII2fx>z;{bZxz_udA$rM}o`lKXQkCD{JhZ+QvZ$Y*p-+%x> z-nF>%uK_AI@X6~OlN?I8(j(xI75qkSQx4$rX2wa`I5Y$GUgea+T%Vbd(%BD-cOvuA zJ!7rhT0xuMZ}xlX5&7)ZNN(#~R`VxD!Y4;!EoG$pG!#{pVn^m#I55rT^Z$kidDOfX z7>yCgoZ!lz+#=jF9SjowJr<|fBwAf*_2=lQjL=;PgzUUK@u7Aw*SE4M57^p$^Jj^D zPnVWR7_&$n$gbEwFu$#2`M&6dv7*RH={`qeOz|CP_TUAPB+19W4X<$b;LUeu(+l7; z<`(&H8w6~6%w`a4% z;-fh*UUH{0n?W09%%j;+JLq^P#mUu9tALT)&e_(}ap?qfIHD zKo>ypKqaoiXD=x6jImn@_G)jpAZj7!;1giNWA<23ZT@G4kn{uBCN4Ra;-~U=7!Y-f z!PrOZNpAZrQi>}Vt31NWBAAbg`y)td5G1%p9|;C{7EXijLDi1U6R^RLOPucY^~_b* zmi13mD{R`Jwa)`9$9EV18j( zbPLJOMlr^<_mug1hOXl?v}z}t{?OFSLehoK+aEk`$)8lfNa@%68`)kl0EpKU=zRg7 zYu^L5A|!3wrO%Z9w2#?V&n($^GW6_w3*Dx?I2P7IPtPnxv%HA896!-EdHsGu!;g~j z^n%^B+C7oGnl|GK*jgtI-wm@b^-39Cnjr0q{nL`z;y|>pq~I+~`C|`7r#gG@dxs^i z<5h!&%;kQ1R#vL7%GA2F+$u&b{fFGJ9k!N3q|bp&QF%XJ82 z`L6ODcX6{2P6H1sPx^?IRb$Qm*4N5$HwC#4(47B&-CpH!!DY`1I*58bD=ML43YR@- z2-~XYdO_cWUp+bmYtn}otKPJibS}ueW_{PYBiH{~<46-o%g`Z!NvI_m>CtEcwiD=Yqv zC(6J>a_^Q(pwit##KRRf5U!9|e(>8CP46bL*f5p1dp@bR1b;rE>bq!7o@Nnbmc$|{ znn4$PI_N^RJas>1_FhWB=Cb4t)GPl~YGRk;sGosO>@_)JtE-@9{hcSu15@qKBG5Cw zTCF=<`Ai)ph+y#tY@x3U9p-*o=eIb66Mb;s{v4_OBt98s)1^%$f+PrzZFo{To7&IR0x6hN%O>^ol$vc$Dd5D_MEkPh`u&f_zPO6 zb+n?U(cWN1fkaU4)js$dlTU?}7r@E(eT@NdXFwf~Lo8wPnZ_n@dW5>hQY9@b@9U;L z;)*Lk=>$&2t@)b7iw3}bXhJf&iEl65SszaJT@gf%8JjfqlHy4*kQn6|3nr&}bT2uJjikMWPJ)l8$OWX}B! z%qc|NZW-u%5-n@*jR^}2t5g$yX=Tf&V>adtE4+DwL=6}U(J{ua379Z_AfZN3Da zi8n%OvKz#OE;YYIH+H7>`y5y44`83i9nA%tSO%X8NB)(#E&J=La3yi`edsycWD8sIMfIun+z>@jq?y|MxP$6V$p$S?jv zMMcG@>iP(I(dtKSPKnG`FG3hpOJ%Zm2gg4Ie`DAEzmBdttf|NSq6jFd0@6$cX{0-b zA}w8#6G6JWry?Q^ zwc6YQz1C_TGwE%lr^+GyI+;uN)1qhBrcZ79z{@FNOZer>aHg8ntC5RK-~>(g z+)>m|il_)t57!gwP>%jIWQ@H%4wjBgCdRu7n>Qu_I!?d!q@t2^wvrEX@}^uWx4R zd=1-MpWP)^1mokBlBPRJEMi=TWd}7I(}jny!QDA<7(^} z(VL0*37Gwj`~?s2el3h}()D#1pMO7K|CqUBO2>?w9yuM5KVr^F2bq3RqLZGnX;4#W z=+2cKKDO+KS^?%0(4SD-A@7my6{;juPv@19W34xX`Idi?8;&ztVDioi08`N>P`ur1 ziUT?amja_VHkNC*s!KWFX#e)mzYZWZT-d+Q3iV{Cy;39yTme3y1KI`02B|cRVwpE8 z9Vdw-7QZ_Aw zol3?r#1^LX`n1P#M6v3SCJn|^JZf3z+HqNXS4R<%YpwgC9s6qP zx~ICuBA?lOhYJMh8!~iA)BO##3rUaGE4^s%JWMCVOwzXwWb9*M+hrw9LEVJ|c8C(8 z&usGd(<5dlUUtvtI=Lhp&rPg$b3{yr(>Dg1tVrw|YcVwk*(bvAscnYl9f}32BFojG zF623Y_LRPlBvO!nkzr42X0WZc0{3)e?YO7mHDB3*q1@CfIx*3DI@$e+vx>abW0#6; z{mmw+dT^GAqBHv@Mb8SBh5a8GPo1@q!~`2XWcD^T>-n zH1r?{eG=sG5BW(g<#7gBBeV@#C?<^;ytnE8k1@!%bo02%w8R^@Q)z;Qus*ANU!8F( z>rpxjD&vRx;YliZb`OWCi3}`vz=^@~!GKc^S{Dk;F4v1d;s|s>7)k9RmI`G8)fXx9Wf0?_s}>tmFcB~n`OZ}%~)%oIu7{9xx1Nf1HtiOKcLni z;?6?fZ&H2;MXga|v1J}`cnjW$ru{+Znn~dJ>?wveALK2SZrH9lyP=5=j$CHJd>-_U zDSXP|cB<;1_$D%Q5mpu;_5~-j4xKMC*Ch2N|Emt_)6i(iFZn~yUcx7w^$=GgxNfAa2UnZFMS2A?q^<=y7vVA+>9~1@|L~0*SSHiiEyi0hW6vWju*)I;WN)}507Qhdqe!VqSU@gg#_ zxI(?VFFteR!rc|#C54RlY*pZ%WUaEA^TIZs<+#ztF~BH9Poo3o(%tT>AZz|N!JLVo%?1F0{8R&5K64mKrbgX2%}1b+K` z-H+CEL08BDM-$tPgF;$mC;KbIbTBfVinD8V8F?YQM!myg4VN98&N&*IOF0t8!7E9H zI~wcS5ggg~(@nV5@!2Bq{J}Du{~~oCduXt1?M&j$4qw7I*#1O-d2a3H`29!kXC+)u zeCaJ6!sJ^-}WbFe#|4$L=8 zu&C`MZgH$%&$|()T1`_h{q%QpOr=ssW<>a}n|7wUQ;~EZh0s&G@2H4J?Zq`O`uKCb zpQT!L3HLuNh!tcd3}GWsYKpKFm722qq|`JjLH$VLj>|RPNmIb=QEb3OvG`{HSrOIL zQ`$f25aI7PTKFGuK;kxGerzSeZ0LS{&!!IFa!$8h_Uh@7<){`}3W^+O#j-Z``&y~!T@XrpwX>h(f~%VF35+5q&*0c7>y{XnsA^|jCi znZU!|ja#cQte#g7>$MLkHj@K`jBax}j-=c--kO?*`vie|Lteem@u;E^Czc^3Vw~oU zLPmn^fu`8qUNUbcwL8B^t<|XD)$gsENi^Pe0Uq`F%8%L>nhRC*XGCfn5OvoYPrJnsezKGdA<~x?r^KA z*phR~zIoT`Mw~9mK#nu+u!3g?$Ucv3|6Md(x!J$7Z23@c(kq2*A5HyD`N&-J( zM7~F@-Ll=OoQ(-?@i{l92rRO>QoPTyfYgb`mOdL`wA|7X!s?~==)7tF6Tu;(xUT(4&KRY&tKKLp8}q{wbPq;=f`B%FVuy{=@^~R zYWBiZx1%?kg1!Eih+=?C8juKOJVZ03j|y`u_fx7GwQ6ZqmuF>g&@l;WyDKgc_8WRd z$k6JuOdnpSu2nK&?o(&*c&_)-`)~56 z#CVql-FAaOIISukXTHbsmn%5o(ED6h5#`-x>IZLqC~q5$ZH@~;gXm>!D+#FW7Os#=4k%Ukg^?5I)l zTHpN|tyX!Z&SOc?gwpW6JD$`*$+-Ynk1}|*K+@#^k*~fsLb4=Zt(930*rXC%0b9Ij( zw;(sv5NlqI^5JCso_bL78o-i+tHGTQ&(%Hp=@T#%H748J30b!Z{+GMQCb|WwC~Imi zPx)q+H8b#qAKEK3D}S!9$T!W9`@!SCKUB)|9M@Rz;W9xr$FNeU6==37m~mNYgO8ra zKP<|*!*^qNNBFaImC|hQo2x7|<5LqLKdLAOSF)wBJiy->% z;<+RW9ti9Q@hx-17nJ56yd!>!IeD{kh8 zFmE5H{UPf;8gtJ?V9+K2+pDv0jC|Rc5w6}P{Z0NoGUqre-vt?Eu)dXO)o1ROI$Wg< z(;aJ;ac;AN-5w!UDt-ZG5+uIC08XHl!RyFtY41BYX~65IBLo};tDrRA_`6M1(o9YVROODjqb%!L&xqyNKej?zIaPt zNqJZ`c4J)+g4Tk-keTclg_B(QwdKRjY&N$<_q-kgQv4+_&4nx8&DdDHuMJ| z4iAvhwG3Gj1}Wi%1g$b|%VZZF4NX}@ z8|TR6IQAY|=*?|rFs)rM4f-%aRMI(_CYhK|OQ?^1@?2z*6VFv(|5*E_B^G9`0yyRC zoQcY}FDZB0<(N2eGVIcm5fLVcG6+8jQLFw!pG$X{&CL11NjL@d<-Q>2{q>||p8+}I z3{LsL$?!|NC3Ao`K@}N>795~5$qDfM7Gnbu2DbYuYsDuE(>8CCxt!MvN0__I>?Q~c z&AOtxzX(=PKA-+P;Uoh0>vmu}EyH{Jc|iBqrk+$Cy-!+d-c3BmVw_l~Zm43#kksIM z;lEgArrqkcf%kU4g>$FNU)XeGHQ%I$vbGnkIdk0iGM)OF(_8rG24PKDkk}r_QKQ2X zs2fjPP#b{={EnQB)?d)y3MNyNZl970FV1Bk-gF_+q#%ZH;`P3tXh zmVYi_zMN|m-n!4SFoR6Y)%AH zu4d@2+k`)zUUKH+<73m`G23K67rEH}Aq)oKB8gze@|JQXn5`c>mG{Ef;wpuloL*A{XE_=KSZwTK_KmUU z8w^pp`VFy(d9r$PhaZw7@uULCzvw|}@4)*YW@!t*5(mRLQ+3b5{>aVmM5CU&ho(F= zevXUV-jY)drkoQd)gG=EQQsK-J>ocjxwju()$fj|eiyw?nx=crl&H&-E8{<2Rf5zR z^iTiU=6froU01zu<&wOwXOm1e!&F@MFNG+TAm=<8N4b5`khYfmvpb~F3?Nof#QDG1 z9)V$3L&52`lA#r0fnw}G5!}6p2fS;iTlKu5`Yh2w0fwsylK+wn-zv{?v)m86sjnyi z$bLk#3ua(VBLt12qo@9U&%-qZBF={qxaiT?ZZky?@D3KMX)g2$6R|JpI58lzD zBWDbP8IV`3oNOz#V(Nn)E0uSM-7K^^1j`zF+_k^2Nr_!vHqoS@pI)MZ6t% z5kpxv;YT!)Y=*pXJ9*vRtlM6g>ynf&AJJ`+@ggF|wRY4eLT;A&)z6_MIJbpe{eX2O zu09*Do-O8tg9SgI-F!Bih&;h*QHC>z-~P>|o#{PaI5|l8-_7K;BN0t+!C0nUe^aRX zEThS!JDb7>+e*9AY`s(uIzxfgX|L6Gks9w5!fHOl7lpzC6+|M5LCl(f?Fb~b`q(fP zZzw}xIoqy|K6AgtW>J7Js=el-nc}X6Wo3;5I~}liNX@XcsU1MsA4P!#(A^oi#v$uc z+<6g88n5Q>6a`O_?0A{I&8L_TW2R2j&Lrv42!Fb?M`C@t3bNd6QiA}3Su0uruwJ!| z@A~N1Pw@c-z4m}#>~!^lHUsqftTT{Fo>N=~ZFd@HmU?=>c)%}S58l$(4dp6()xi!D z+fYjE@9xD8l6{PNJ~S&THLFkm2WoCHH$-`C|wdpoasX#oW49CiH}_O~+-_tBZW**T=dn zeTpDA&H53R>G(L+t=C{7<#z=#y1Avet7QIV#+8e0Qm5ErpM#vlyFjkWrS#fL}b$W;ZrVSeROx(liXh+Or} zA=2fSR)ZhcTKg&RqYwMaKP+n;jLl23l#e2Y@Gr>GpY~=zpIb2rV-##J#h^CvIQiRh zhYdg&!GNfUTo!Je7Wq{KPhHo!q3dHj+h48@=E50Iwz6ZB)Zbp9RP@sm`flLU4Y#6{ zZcutzqm+ie9d+B!PR{lUuA?I-g+VJ}`?}_=v3-|nKI^q2WE^%X7eDm8U{Ua*;zsCC z%hsm9^GYK(rlaPY0#aZ9xn$+PPmY^wk`DOA-=mS(;I-DGv!WcYWA^HZ=i`Hcmt=qW zE~~~XZ7}NL^DA?h(lq(crrRgk#HU;FC<2qhA^iZqS76VL>8#>?@5@!%wUar&ZvQ)x ziJ?z`IU$n4(DBPxIYtxXK9Rk@Apuq&EsOrAo%wuA?halLB)5(DU@Fd;5eT0gLSc6*w z$!~L{*@2cKtkGyMeTiMw|oY;MkAhvl^JoapJvVi9P#?a6a& z_Vn1paho3ka~~oD&T}=feIB1n)IkfcrPIEXHYA)gwZ)b#Iq_H?I0gfL`XEYAi5x92 zCvgEL+3~CmlP5T((NF3_rFO;O{WWNJTjmYm#WaujQ)063GkQ&sj?o)Av{)ZvU6*k` zQZOIfL=_ySD)!#}oLEQxu>1@;yk%#f-c>p;QtE<{#KR76Inzc>Il;qinHf?SEf|8$ zv8(IvgV2`d8EwlOwLKkjmvS}B=T|@eXj}Iyol)l5dtXmw*Vm*<{WLl1jU-0Wt>+n# z!Qg;3yBL75O##@#&lO*abzyUw89wXA(R0PC_Z3668RQhw0fzfz`GbZ@`#eUUW1LAP zXbb)6pEiAu{taSFoN-_OO{k8in#&d&O+f5Det6{}_fS$>;r=hYqRXPy)d{z+snY#; zZkrSF`NHW>jx`M0|8!RM)uVFaTaC5@FK9;Q0W__L0Q}d_e)h?d~417L*TF$7*n7v<|R*_X^ z-cq-eI@s{b;-)Q%v0amCL_~0Ly?WmIr*6_dH&CI9Bfre3HDh$ya*)8Q55N3sM_oJs zD5H!jJVAX8dgq~bo85{CWjdCz>po>K@MGFZ2;UMGX?xn4y-P!b6nuDiXelW5lpk+% zrW;HRRErXqJnWzK8TlX7h_4YP$XAtaK=LX0j+hc-70CZTmp1n}KMzx-3*V8ZO3(mX z8^dw%3o~=mKB2z5%8&uC{X3C-nfLa#!C{L)2W=#+z#(N!w$!Sv2M4~6Qs3;5@E4Gv zVu5SJ?OZJC6L3-O*}=O{K^wOY&ia%6+dBk3IBKCTp>o*?x)IuY4iu)qVZVGsAT^&; zF>*Tt3)JXd%;Mb5l5crh2cK{qZ>hcGibdpC7h3Tf`RHb-r++4b)W=1BT9!XhXF}(% zy8OYjiZXllK*#nUnugcW0#`HPJp?`B2oDyQ*n+?s%7zS>zlgfVez*T(GNrTA$mvH< zxGL(bM=5LRed+ghDOX31PRr@4$rz$Yfe0My&qp>ZK4yQ^@&la`_d*Ux} zd2wFI@Gn&~m-JV$$%4J^5c}^T@uwbVvWZ*J$HA{#n~M6A+{I=`anXyyi?{1i6u@kz z?;+oHsRL?8l$})zX*V^=lm}1{EykI=8=q=zRnaEof3L($Q>_^llm+5FMlx`o;q=PPMeL%;fZb-hX(1rQBZr({+Fr zTMltk>S%D_vazA?+pNwRT_^4u{F~*h4RgO$Ci>%llC?4OZ)Xe{G2e%682QXYg<$;5)jP&_S57x6EMOHDVO;UWy16#m zh<^FdnBjLmh}$xfS~e@gjmF94B848*R3CYS3tKbsrcW$ya$~)2`L{RJ_iUA0Dj*Zu zTgv-M*mB(9;YpI!T3ZgM}SRv$1V?#w<5-v@!x{cRA3(A{u zK&KK+m2V=T8z7Ez;d>+YZnwY84A`+P4pZ^}bktoax4n0Ip!t44&@M0jfmmt1Kp)A+ zO+$s%%Xr;!i+Lf0B6_2nx~~X9drhCyzfhME`1MmWb~R78*a! zU7@Y3R|M>z+J(51biT~Y{Q*1zn4-wzvo;0yq zxdzM}h~b{_t*1FK(>09QqNjy(}GikiT@Y z9`{X<>vcOvwr4IKl?OpMO{~(=p>|OR+_|qZ9yMhwP?bgJecX(HoT_{QG;PBG%>$&SYlPL*)n4UQ0=D08lUG-mvMLTKfE#mG&$3 zRsZ3M7yCSufZQQea$qdg|7)XiPiHU6=njf$biWLX@9QdjQkN2VO1j7GAVg;}yhesMZ})>ojtO+{M6Mhfelp$|?ug-N7)-4&O5Z(k zM;}&`-rE!?Q(s*eG8#IOMU%c^4A~lb+to-g9JDu+yyu|X(MnN|2}WFec>AYkuv*}6 zcQbCqT>P>;T!r;h{Eiy>w0#AgXfD#VyyMwqKxjQo3cvG%Ra97{?gna>F#$Ja&)=Mi`^_2{VEshyniC=+7@PG^E6(G>buQJ4KBgKBX-P~qw_~%~8^_N?Q>%BU zd7`*24?T)*hDHl7%9)kZxSNhCGbQQAIaB%#eK?!THR+0;^EQcmoR7@92x^>+?fN=i zlHf1=3@}3tiPrSLWky#VIsh)SD>a`p6P*~Jigf+1QPI>>AsiPtWA&;SzU7*;YW-^D z!>ybR)6R6b0Ivaw6uBn1z!W9KKDUufu&X>l9Uzx@+vS?J4m;XPSfa%04E7^uLPe9z*f zUvKkE&<{=7%yTZohZAZ=n6v8NUqH(MrQCCcv%l{hqHNk*>VH|l%$Z7#MBbP!x}BZU z@=b`$;DlOShyqoSV4h#33$$YW59x?l77aP`%*x8k9C$)DqxG$?t&wS3CT+B)rgBC) zDr&ht9ownNZub6gV4HJCtWIlX*B?HgpZKsb>c<%6HjC|%z}2S)Xh`n1gY`y|zHGe+ z%!h?`^L^HDk7%J0>K3#D(Q$$KRZ)nR zH72D#v)m+!KiXVui3Kq^b=9ZoGfRLhxdMQF{&HfH|9THSpDQ96AjCzM{D+sl-ukMp z@tsuqw;=8vzF8mOf1;xUHPMm3UX~`^vDAHZi{weObPf{uaFXT;c26`JAd7U~rrVV( z=wQ!qVGvt>&fFrtdp-G$CmKO``+z+p>|HRtz_(;umFk5b?3gvdS8kpGd#vK+%m zUqlTOR9>)Pakh1<$8<5-$qlJgG`bG*+tcNB6unAzGDtkJwPg8?Dj8rK(@fIfDm_6v z(1||KRXf#JS@Dv!`QI<>TQP8VXOH3(^jJ=&?h zk>~(ZMHdBbRx0Z95W9?8hdiO+4D8Ld>=4JPTwWU_x;Vt7DwxPTQ;};<6<~#(6ysmQ zEY6FA`7jhXmZT^fC$>Y?RcoK&z{E31Z^S$%x(Nt&42|A|oL!n#a(3MCgZ~9xtv63x z#`TX&@Qh4ms{DCeJ*hicwsqt>2j=hA+%|Z@&B%*-jXGEo(Bv2LzKRk#oFktmISrUj zrL=xmx9+V~dhhaByXx^E6%0#bU&~v$*W{5kUT)%Re}TFu>|LWmNY13BBO_xw-cen} z{5vu=v<-AJ_D}{k$bBsfoIowy`x<~N*=F^5tm4JEOxFDF(ZGu*aVx)xvQ+Qf4lJy^ zqLnX&-R~RKbG@OyxdKLl?_Zto=sGWcJ`3sgf9k$t?Hd}&xY#;mYcx_%JAE1 z+8*On2xIf*?@|f}w&amNUNwwpk6KLwZK?dl=d4ww1DDm`=Oj`kK?+_4%Ljth)HLt#+f?=_0r zgXgO@usa0rQ>R$Fy1b;YwQ*c%!#o_JLftn1IL45rLWX;f5_r?tiI2Q(|LAK2-heSE zDL@s9yf7cXqr!etf7|n6if>yN_Bue{tTXxzb9ZHwZOd!#8;Mr|%&ffhobp}^Ly*xs zC;gPxQy?m)_=gI`$+iA5MZvAIP5CmSWOi7vQPgGgdF+`89POYTH}fx=x_-yw>}8D$ zrLQ%P%O&*0aVBdCW2D#(uV#`f32X}xzn)A&-Z>W1RnCoUIxwXqL0VQsgo#Kg49wr$ zIw;q^|6^rr#^oRxQFNtqWXgA`;+*JIKH%wSVAlHqr&9c|XSx10l-@NXvC&Y^-iYx8 zUgYOO&-iWOYsnpGGKEi(oIl9nzKYsZ6uHMm!6&!ch*#X-EiIeFwEB@?e!3xlrFIx) z87$l~1%j$cTHbszoA(6>%EHtiU5GBtZCuZ|p*7xPf2`soMTd^#h}Yrjv3ZHHx6geI zuDrmcvx9J-3}R(vX~wS;)3q~+(ja@R?uF|uu=0)}TCGdt?V76PeVV4bRb2EpFdL@9 z52e34UK0Zr12%5J^X@W&H|EW$-7?B@qfNNdw0#MM9)riF1qZO{^b@WAw>jb}FnNE@U-IA@cOz zXd&4+T%hE|VF!+jT7n9SA+#dGlEcN=pmvU`fNbzV)RdRzmS0ZK7l-;a9KH`&mI(&5r@+?j3t?MgsY3k`F+c|gES zb)ZtMvTzCA8C_XulZoOOG6iXYPaXnm4(jngStE)uwB4>?5ieq`w|hQ2JlMd>7Hqz9 z3oW;AsHF^N4_~co!3ZL9c`{Wwe7YY*3uMZ|&nk9i?jCNSQ`H?VT+p~*RJP7IK0kV= zJ)@1!I0+Hl`mEBHY0*N)!98Zg?Q>w1<_+|Lu7PJa-ln}j*=RVq3<#pl7LJ>9*XCQv0rZ$xz8vr7O~o7+nrE~`A$Ek z=6Exd4lUAKi%08>PU&x)5V%hrd_s4LEqOZYB%Kx+Kpw{PDgX6$-`&gcW~pr7AJ>2P%-(8N*NyK= zIzcByHo%DEFllgc;H$~JiRo+Z5(V;n6u}2qfr(7+PA`{*664mXt$H(2U~z5OK;(te z+J{!&+d@P|gygI4glTWgtI>J0d!%k79)};+(1KCvnQ$k^zk)Dc7>mQ>{8pD{F=k1R zh%{wQ7A^Cedf@5S^Sxr@DpRJZ@#D6L=8dG8SX=M? ziWLXgwtB0E$-YjY;PyXC%%zbg`*P*z6mtoycs$Sq==9)QZh^(@5pJK>^dn-M;M9*4 z-ymH!bVoj2=|?hs8Y;u-`?Zst#E(D{^!TWaroTd|Az}r~;MJGEtCGs|t0I#csrx_r z-{_Zdky`-}8ooxv3aYQjLRJqBYZg%G>bF&(wO+b}-s&&lo?0_Y{E(Hk&C`vai3G0a z^<2nOFk(KCIeq~9)w+`;~b1wZ-n9~eKuI3wduxXJz>0tnprw31x+TQ0^dm=$-wZX0m1MDXqNP3U?pw`u+L=_CxgsK6NILhT>kW?|6Swwimthhq zaf(tUoePtqBAG3sbwf*?aNaaqH?fkdw3=GPTe+dQrYmA7n@j!mUd4+c<2Z_>T+zYq z?7}}q;1JDEa8tL}>$(U4y56-kx2AvGzUdU>x=G zgv%kKOkii!B;6931iqd+wR-CJ^qInHra}+|sE_gEsUsJIEuZR7Yq21>W-@5JRZqDt zbq`+E#cKq&EDK6=xU%n3el8}jK8aKFD^}W)9;`h5Ik~13Jf&_aOk0;eojyFxlKA-d zLNH2VgSJbO!7EiWrH)T}L%iti5!|VLJ?{^`y<3c6Ywa(GB*x1jBafDviTU`!M{*Pj zhV_evTP(C^1tZpQ6k{;eW`@U1x((HKyt@{@V{X@?sqgIxAMp@c@B!u)%cz#d27HU6n{*vxZ$J=tf|L|Bw5IzvJ$?-gk z9=77<)lRIba-0d&p)-UrZL)qlPLi2>5Qrsz-;50@RQGaw6;;|8d7>iihEn+6Ka@xm zx%x#mG2kK>Bi0Fs-mN#s90T?LC)#tUKxEbai|vp982a1?4>aDCPn9JSZHwa+It_g- zy>h&r9@74Y&Z^dFM-}Nvf0)%7>$|!HwVG{CekMSdccO*tmBq*|ac4L^Q>r;lCVR3o zyLu<09q0c&Hnp*3u&Qo1|Js?YpxVeHm5weY$-13A#?`*4Zcd8RIWt4u9}@1#z=zdl ze$t90ew}pU>ns|bhwB6Z4TK9v|)Zxe<7fMa#iq_x3ANN<6}A%kWDHIQ~{3p&$9 ztV=gsc5egO28>}f4sSOa4&(&i^~)al$s)|Hdbi=@Wy1U4sBSkVsJ;sNhn5Ey3{Q`4 zBLd$0R%kJgA@9V+Z*A3_-H^PIvAYI{&qUqy;TDJ(MS=a3GVhfd!@v7rK*z_3lUj3_ zt9Vg8{hD3^g%Bw1FJWjKKm~r;lItt4?;mRtSV|}1192=i+;k%S9lcR1Qf_@rJ!=rx zKntK_w!%WzYE$8}$I=itvaB$+DedjJsV|A2XH&TNb?JH;w=;>TG5V3p>@m*o3t31; zPq;Xz^+g%i*EJbG=rhlj_pAwjz|=l~5-S4`Gv3RFvMf(aOnJ}hnZ2}9)3?BshrJg7 z^gN~J)^7$|Ucs_2D;+qX4=TAN zf#kWIJ4g8aXQ;GDg!2E8clyGI3t#MtIlTMeoc*K1UzKlGSDG zfg_$abPA$=cfKq**)5|c4Alh*PrvsrF_FmbN_~jpXbx!7_j^&s221^BwK~e!?HRjX zY+7)yj4s(pw}DRgjdfrZCbfje&%W*Dq`3yFFhQ>1<%qquvycHUQg@u(!zh5ClSCSN zU9@irNc7K(cVN<=3Y7U9x|j!v-HbK>37&3Q!6tXKCbhk|AeUy1vnj=Je%GH^>^V>{ zM$k2OZM8??-im+=4wr^xLOke3B+&5o_lg)2X?!aPd>xlK{?zM*4%wGKz)8z?yssQR z7scG6#5fGH(oQk3=H%-{iyg`AW-DBh$H-Qcv@@s6izL5_QE??vc=v7WhQ zg=4c*!ENH{rMj1;8tIA;x{KRR75p8BC9@?0v1+t+YLy??zP9Y`JvP%HPQ3@LM(a9B zyvqQqrtJ}d1uVHGdysC=Nzb|zCq((R?z~1-;C#7^WG#}X`tXTX-R~~_g`^86NfG+2 z7H>u-t_%+$2ih2OH5it??$^h;FmeHO95`Ir-JgCe~}(?h9F^QLmqYAQvAOxT!SA(JWqE<3o@VbBhC5Zz8+p ztG@H^Vpsz6%J#K^U)aN@gvuR3=*X4GtI87?i|d)lD>|QL${#$!?!trQ9!S`>nP>}? zw2e$Sh?#a}sII|p)8jJOMKzzdc)9XqF2UzM^2|)arEFTZNr}<3D6XDSqwLX-r`{J` zAd)t(@+Fmt2NaXjJ<+uQO8@`ClItPz-kkaaR|&HFU+)~-d1`SF=+P&Y63POow~k_>>{0Tl`o=jg?6H&hQM9!*KGV@kR0? zrE$iKO3$B2+n{(f@Q5Ze1tzzb>!lnfJc6FtHh4wV zOagv}%%;%2>U3s^zUS1&(eBLuXn#B+^FV|xaf=&dZ{J2Od;^-jBZKHn9d0zIb$DM( zzTvbz%3Q6oCeWbRpPfO0FSd`ZKDN_^j|93?oK>{7IYXFzU$3lM=h!_^+cs0!>V6Sf z{DYO6z3>6Sex@7X_Sd?2GQdD%ncTq|VEMA@uj1W_@V_Qof3ntcIxR}Go{l;5Q^?8T zot-feo=qF|hUk1+82$|$Sh;Er?r5d0$A(~z)h4vX9_5EWJX?7QK*bPrc|^uwLpf9) za{mm1Rca;2I`=qFAtu(M6eXRa6uc4*WC3Ok#$-cJX2%7{7W@j1 z7AH}tR2sWtP|avmH`$}Vr;cDv7qF{g6|zgktVujK$jx)l8#8kT(6@9lp|qqrH1o z`Pu}d&SWqUl?Twyp1%8_6W%>g^dMBy4ybQ#zK4yz&Zp?lfY-t8uK?dmCys_oDh682 zT^X3mbeyIJ%mhHm9z8r+Vqtu3PeZOJZSEeyH^N-5X!wY5WMFLZ?T>i%w<~ULcRK|c zqTnOG+Y=5{kkUbUune@brrE9OPGKSUzzPOPj`P6i_Z194%l;DJ9WPJ7cU)~2McCR(Fw?n1J z)BWqxl1IUtj1*fC-MV<@;JrJN>DaSED+7ZlRsIfBH{B6$J}W4=abRHwJU@M@$>Akk|QD_wO9e}nD z+!4zJN&)TLs^B;v!Q=K7T=PbToz+1!tIHS%Q*>=k2kibl=wyxgBALane<&b3{EwT% zS%bRUWQK9(?0HtT&o@;kS%z`%%m45cG|@$`+brAg_Rv>8vNU5>uxPU4jc6s1ap2Ie z7@P_=5$F;(u~B(}B$`Z+9X0Zp%F?dZ`6xl|Gd6)ck#$TUAK)U-*c7MSslxT`gS%2y z#m@fvNQViC5l1!E%ty*qxn$g|{onxPZop4LC1EL^tdtcA{85oZHHW5B9 ztqX50$}tlb?L7KrE#YW6LG%FClBob$kBy&OQn+Y7Zn~&!++Js74 zSRC+718$R>i4CF-ipRdo!+*P(7(S#jP+PJ&Zgn=W*5E1CZ@2i}rQNVQ=$NX!81*vi zy!2BuqR{+g9N@U})Q~7zWY0%;ee|UIth>B_p6;DrfFIP~D zxKDXMX$fauyTLqF^uS2Q*0yT7dh4U1K*)Sdr*17oXbrX+%|Z)bHHH zuli**fWo2Rw*c_7q)FigOt>ZE@_yDF07mcYs#o|ozZm%suQ>fhaU|ZzJtSvBJk%&J@nY!RX@qU=aD-VhZ9O6Y;da1c1rfzhepYrIG_(Pcr6_3v?~KmSyR;`|aBE4uiH;I4*)@v60>?wp319QV{nbrUA7K2C%L*4|_D@rK`ve=i@elY{!^r?u9l9LB2W zx#c*jEf|>^pRX9^BrdD|I$JWGhNVn2gSM{#kCHG$gCz6J&lB&9TdJz7Q?qU;o)Qu@ z^uRhDLilAN3V4y3&_uvVE4;~&`h{UUJ=SXc3L<9g&q$AFr(O_UyPhIEeWie>=qr3L z{*8oi(PiPi*?G<#&TOkm%qu+E2YuAu%i!O72I$QQVrdnK`CTN%gH?_IPJTtFfgR)stBDh0{-8n2A~*oGOS( z_~Uuut!ily2+OMDy@$VyfDO&fXS9A{F01=~Gx^18JS*mU6#rC}&|Y9bcL)E!x&H%x CS>p@< diff --git a/extras/Images/velocity.png b/extras/Images/velocity.png deleted file mode 100644 index 9835970413e32bd53ab4afea93fc02fd54c2bff6..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 21237 zcmZ6z2|SeF+dqy7DQmXKl9BApSVj@XVC>6a#@=A8GiJuVFJ)h{CaqdXb`c?aRH&4Q zC`6KdDf{+6^Z9(A=lTBruh+b8GxyB7?sKkl?brKAHaFEjb>hqk8XB5Y1}LN@4Gmp3 zc>j^h%7zokAIgGL_iyQ_Tm39xPQhSpLjNV;iv!dDXBW%?DOtsTi74BIxVfm9DCwCiDEe5D%)PCUM7XLR zIWWx3&)1q_6G#ann;ZKf&~6@{X8LBXrlthbYuzOQ??tQO(i={1B^5 zA(|QlqjeQLOv6F}fApYwWK$zcMSTlfB_m54A5UEif2<+e)HcKzg*OQ?GWD?_sh!yq_#sC9t1hb2@WtxOIA0;C6pnJSoin;F@f;)vQP3f=_; z)d}?uf>Sp;7;WY0j#aQS*HLuQ$LNtLHgH=c!8X9($AYA9VTVxkP_Xp~^H4!qV@!fV z6)f~kL)4Tps=lTHL>Gi=h!Gr!n4Tdi6paOcy)c#rmVr3%Ffe)W(u3LQ;%!a*!ob!e zf-OBfgM)l^L+!%C%)IpVlyz-j+95`vXlturb1M~7cQ+Foq9w-FfE<9fQZ_L534s~o z-Gbq0INBd=ZebFJRX};7)C|#{M%H#ACOU>tcTb|NF;R~Q^&k^Gamt>`dUjsQmOgk} z3kwA_%3RydFcfZRXJryTB+2Wb6heVhFYH40iXynyBI|b%O11CIlmWBt;FW zMhH^^iy)YIn0s3W;ITv)!Bf>1OAPa|#H+ZXPzoV|zJ5R}5w2zyhL$jIpz=_PucEH2 zt)*?C4h4o)!YKKflMO5al*7WXA;F$7oU*R13rP=YYDe7$l&gyuBFIg}MG-;7V=OSL zrUC94sv=^+Mj$*I8y(ErP=A2v8VYSph>*^)t4%@PdXyk=jAQZbk++wg_E> zo{71UijEI15D{Po^Hf7&F~JIcU}yl^-zv~s*AU@iWov1u?}IVav9|Iu1?2GSxCDIsaW@HxN=YdpoH6|#!*|1QP%S}R&qD@ zfm1@Y74%h9bbM`X0$fqPE?|bHb}((5uwW!f-`zbdIDnw52W*9+2RV?U7OZEg0(CJ9 z4nW!wj6;M=o#KC-mO~5A$n*c>Tfe0K5!q(F>*q>w-gbVYv1;V0c0Pfi! zto%_3ZACQB(8|W$)GG{QMOIM^L4%=sFcl+968QZS_MFWCcOO3?|@4l@Ow z1))t0wFtEH1r`+H;%*DBU=T7i6oFH-Gr^dW6i^|duuzJXmoGF>1#1HjGr<`n6|5+5 zJGB7IAUxJrH%!gN%1B8Wj&t=?BcWlg)+&AhhA=yz{Rm$?%r8va7KKo@wj*MUO<)LM zyY!GgXmC{~p#p8qLyV}VkQ_$FnrZuZDuno9?9gZoxMcuWax)4FP^Fkc4T-9%1US~z zhG1p~rT7KdD(d=L!AUmeKqV0RDt6kY+I}!BE+9Y=W$f>xN+DCM;Uo{Nb(kS8$lurt zX|7`cHxBgo*H-d`>YG!=Oabl#wZ2@)jLwT6F1S*7C zVm&SNDcCS&5<1w;j%@CNfnf~E6f6u5cOk232ZaSwY+YRpf(?~Jah@(AR7Yg$XRQqE zr?D>-uMmjv4^dH6wW68~b8jVYWtCtrRid_+euy<%1*SysSMXHTHo^FzC@!kHB(hZy zTHl2nYGrF}6-F?$!kd68`MP4vNEEcSl7Si$OOuWs>6gO9W zK;FX;r{W$M5ENu?<>#eBQL_vsL4ATTMn;MlKe!1_5uxW|U_&AX5HW^6E(ZE=D}sSf zh&$9)0ZBA+)7Lk~+vs>;Fz_H#q`5B^g|xt;JUrcfd@wjG4A2ZL-W!Wm_NN5kbxr*B z;L3O}ynBF;x0SU*h)t+hC~$CiU7WIhkTF_~=;;9qCSqLOFqqIF;E&K0Wj(yEAw@;o zRToY+4@UZ%QH8|U9TP%Oa&f`<5LI+>+6D+L!PVT)1~^;rrN1)C#M;adgYv{0>H~36 zRyMI!^z{r40Q|M_^9%D(w$@cOharJ5=wT_Ib{JnX3e3O;j3kBz`V)1nY~Xr$EDjrF zhaXUK7K$U70g2j3It5B71Yjvx($Gmzbm+Sx_}@7VMKuI zAdOLEs42q6#@9a#YUrn=W32D*XX$5W>P`s=!KvbGOgylrZr*-Ge5j$Kw;RbwAMh27 zRRJNKD+;S(<3mJ-1u2Ir2DrdnElKDwS2bcFoNSHqRe@0ueu};XU?}u#e65Mf=HAxc zYDN}zXb;l>tc{McA08JNs1KYp0tQhkcd+C2=0J9H|74RINnx=$ZRZ_p<85uO z%`ScQ(YZTGET?lB%^iNDwfkHsUb+-*j_2lsQq}~=N*Ql$={r~PS$omrgLi+i`hR$L z_uXAL_i^?9$jR}X9!Q&;-}p{;gmcCG{JeJuk`AKve=iQ^!AF^CsI;#JG4!bac|mAT z7_icFiqQVgE4GHo9F-TJ&YMNUocTX5bClo7|NQ{oo&yBjt?RwgQ+f8j9Bi8V)lZ$pFUZu?Yn zwCxU6b(Iv~KQm{i0bACHK8#QdTEtqs3|gw``w< zqm3S9rlmsqdZcJi^ptPPjOkMOu*}XR3pv{9k4}+uY)X1D9%gh>__9O0REbRXcJ#uR z3Vc~*!&J)E8|Fvh-~n!j7X#-{%Vh5@y(suS_M)n}(x$?0{ZI7K-bDP~Q=i-+^o`*C zwKu7?{g>?tBh|4y2Eng6eO!`h?x#wkpCq+xjoYW4Q8o-IsB?dRJ2{z4qSqsMez0V! zlSMvPd8oi_zx7H7U8CUx`rm~HIc}{k!@v8Rik|$b|Cc{`%yFFA&Jk5M*6nyxbIwA{?j8-fO^*8(tScwA&b{Jt${6j!Dy_BW;kAPTRXGLsm1QO_mE-0 z@;BRWls9MNCq7lGj)%B1#$H!>yaZUo^|{zgK4QmSNWZy7m(Gw~sv~jscuDlpq4IsM zwBqrW@IK15!u$3c5v3L9YTe&+T3cJw^^4x`x#Qbp@GWeiVqLs{#a93F`G3SLHiDB$ z93q+^!t^FXSbhsR-=_KJ9ZY#sN@{_r)nQflNnBxPnfwdMR0#4y>$~P~`Hj8(Y2l+x z8(wk2p-2aw?4r15heeg6m90P5UUEKYA}45Jrf804c|$G>+mXsrHB=w#XXMGd5=WnB z$;a?z?DpMrx_+oWhp_CQ{%)F`;E^d7_mAX?*wQ_WbCZl^6#ZIZ|Kd!YRi0|(Ej!t3 zlBs9P@33b#X>G{WiOT0a!)b>u)eT25l=UH?D82>8yynmr=Yjb@jKUGs32;-`nh&pZy z8G>R<#(o$v?d0lKkkq&x8PbehlV%#+IQb-_IU&o%lrxg#63@I1~ur_{odJ;-JHuc8l}u(>lI zU+P0qsM2F(5jqx4nOmm>RAgil_m;8-3j%Lq7-~NE5tyk)qQO8UHxoIup(Ez{IxVZs z_1NXS=liA}(<{4{*!&{mO5|XTO6&8?zk8F&IlwZJgi`{)%7uF@JK>)F9v_7aP8g^P zUl6G4^p8F0Lw$Z?A{}DdzS7ih^S$XQ>+2tCo&E{4Ov9yqs{<+?9|Ucma6TRP__$!* zp*I$4_OID`NsnMLcsXRe@;#8Yl4V*XwQ$R5%q-~+Jitue;>$N9kyB&pBR>Bs)>nv@ z=&kor>2=oCHj1}6_@Hh{wzT4vPcn^9%Cc0_(0-8Tj=B3$Hv8@{XDKw*B!(v5jn2H* z26DICRbCn$O5a}D)YR0R8p_S=c9&-MW10Cp ziMe4l0$HV8b){`c@K};fB8{y7?1vj2={c5^tjgl)WLW8h_0xld+73pP1H| zIG7cgEto0ExIMF7K+i!dI$5d%qW%l9X>epn6 z`xmaO{o-S`7&>-TIx&6KrB;wj^j0p-Y#dJI+|;k)RKyIOVYFUgbeYo&i~Kl+Imx3e zCe0M{qNWLyda%^>mrgu~hrp~3CIwG41^O`SvsHQOrDDd;O-6cU_{g2`Hv87E|M6fu zRGohP8>w1-Jbb0avah|^f4I_7w=Yk2n%4eNu5K!iL3A6F)78co9{u+REWIwpb7n_9 zVqdLBK6&(hlEp-~PP>pLKh(OA2ia@xthF7!GTwsUC(N9-RU5XU<8}`6RF26T<{6&|wF&I9LB$#L7t zdDN!=L5dxN;-?oRXGPy{4OiR$rk<~J=}tjhwm!c6nBG(H8&(g`Y>u+Y3m#p`>uUaW zF{k)`m?71(l{>dNIfTyKn5yZMtF@WgTWNDPz6-Zl1P;-qJ%;vCh&5D|w}|ZQ1o2J$S5V2ESC!w5o2xXP_Qq zu=<%nIInc*3zxA}Q#-n!(}rPn@#&4Y%aOZpZ^E&ETKb=bB{+vK)je|IK-Ad3@Kq*@ zb3+xGqYVDmmf;g-^hM{q*_v#ts;7J3k0w@e(-+>>+}l{-J?uO&i~Q~VyZrEA&q&+0 z=d>Z}5yD&Y)KOyQwF@%%c=Lj8uPiG{OF_sKbI;ouJaJH7noeDwOV5(c$#P%hB;^Eq z@%~`#ByU)4uCC=$hLwDng-rH*JXF%R^jqP!xFZSE%huN~4QY`VH>i^!9Ar0X_Q_^w zec3xzb}8h?>n~?zJf;Wh7MP1$pS?@3(4T&jQ8gmD@)2QqwsdDXxJ_DD9C`2Jg~zRN ztHFz@U2VI5_Q0i#%PT5VHs*(nzD4aVamEcFWHd>X-}1J7Kl9=JRhs_YxU9e11}OzK zka%4%TUj^0t>v zE}4M_jvTMJ5ad0!GWbGHh*A+{C_wimJV~5lcwF@@n9_P2?ql6Ud6Sfau#!%{y4LQ; zgC)eD@$yjh3>IFw+^ZZ$Bi^^p6gRG&uiR8Bt63$u`m0_3yro-;9;2kPob|QbM+9H# zh3WlB1hEuDOWU(jdKSirDbbQ8UGK7N$@>>JU@g2=85vqOdrM6Vl{tqZ5@z>h$k)Xx znE&h+-E@*N3!Dg@y_c*a_B_-0IS3tEAOsPod zCF%XN<5?Zul-1A9+ZNp4{Vbvk_CIHBzI-uOW>diF0p*;4ycK0T_N0z-4-H)$Fo-kvY{0F@j@#&}RV6>$6;qtDm>q%hjIp8MP@KMyyM zYLnD_ca{vhYO+64ua)X%sd1yy&*aSwpNfMXv#4{xGdZuloH&sCRQfe3#=l4WW>THc zaLOCuX!Wf6B16=9ga~8&?GvlzCVV%R{nlY(rcpsVCDz>B=5*KRHfXrr>mKV4gg|Mq>`|E?kO7d70)}D+P@ORx;I=NO>`vIPS{jA$wvKsEZn0L3y1%nl{{yBK(0P6 z-59RneY$0OZ zNVVNL z6?WJcIW41(?h33ve~N?LdUUYDLI{2ZJ?8%1 zXUTi4f2OReRqDg#J;F1}w4U0NdeVd(gSbrYc8k>kd9o<<&o4TOC)0jwIZv42A-7(Q z&jNd?!Baf*Fuu^&`tL5q%JhX%BZDNy*f!kIrRiBRjXt+S^{>(U3NG^}e7YMt`)!!i z(W{lKFk)iGLdVK_pZtr!@X(32gC&wnPqsMS-l)~p4W`7P@u)o_$9bNHq2sH+F0r>a zbOyygi2K|LKXo=Yv-6I9^!wcU;t`PS`64!t(h$b(e8-8S5snT|7@<_8Nm&l{KN z6Y>hYjsX@jA6|bxLpwWPR+ZNpceFpNDUjM@ju`N<7<^Uz@Yve%2ZDUO0y0moN_nz3 z?KWbVcGa%PYslYE`jQZ0U|L7yr|4m)aN-qa0Tlu}@ZiBuBUXcx;%bK2qMV<5W_b>k-q^ph zD|lpj?_ym-W>>@2kT_J=iPD11xEXf;AJ4r$(=D9NjpZO88ePcE{F}nRKMq`NV;hav z?~f0mcX5*1xo>8Oq&qF5;;-UvT-)J4HsS6-!Ni$=)LELJtz3Pa84wr;v6mm4X3OfG zw41p@YL#R{@d^7jujw_az7IOcE-LswK-?0@!;d}p61(YnBc`jNQ{^HPrfnC;CRUyW zzv6o4(j_Afa@4_sbL!^O*v&{9iQLRV*-ZG^qWzSP6ODwgPz!78x>uJkS8Jkj$!qi}tm6u$2mvDQ76r7y&BY3X^6LyIMy zW!>wbgWkuzWrQt(P5r5pw6D4IyhKHY1{!MY!ep~oc|%9NihHi9o$t}37tGl`?&x!d z7EI%>y_5CcIg1VuJT6auiA7kx{d`4g98TXLbj&ueT&UnK0_xdN{KtQctMU;@t3ncH z`wN_t?k!0@WZF?*kafdsMm)WpPxQ64;C0v7 zE;q2-^u@PC&2-9cUDQl1l#_XtXO!xOwe!fdNJo81g@R{qI69m3D z26oLOlO}DhZ?3mqJ|eIO#TTU4zoD27?=(8K!FNSc@gvKszq2jJ=9)KN;qLXxy_Bih zL$s`9UyqsYgiA`$nO+c0ejVDK#+lBZI{&;r3OeSK-Zx#c^gtu~3LP%lq+_-2$)@(a zZ*+tHK)ilmIcvRyL(3+gKl~F@N65?#j3I6EEN}l-#fx#NgX(xSbq_tr=#bo6s*S&@ z-^&mE8@r94QkRE1H=;f-Br?IO^*Y0~8kzgPuG-!TkXiOy;GGS$0Lu2KjSSwb zS0#?-+G}PPnGzTJMh!iw)r;3ZZYzA77SxKuH(tg;zDIptcbuI)>&lm!cs7VnHv7rh zmA4y}8JfcjvnbVzm{Y@hCRM^R$#7%3R5vwA!19^FBFo_`V_G9j@Q3jbDPcG3LCxW| zyOTb>Bw>6}%t*5tR`h9{>NngK*WGH|E4LAevA)qOv%7J)+UQr`#sZ_9`WjhWO=ssX zwkf!_yWg+g|ErVBgioS;DmD|IyYbi{=X|oVDB*y!jD|%nHD=-9$^6#g-b!kY*=5`I za4j{-Wa=Cq4-8Mzu>PVA`OTaX!)1Uvu8f=zOOCXuZjjVI9YD;}WaFGHT^cFdtcpG` z^3&ln)T{4#{gfQp$$5KBG`;7Z1p2gI|A4ZYw4pW`?5tR){ z6AGA27-@Jtcxlwym(+2h*17kdF6XiNjOhKxY2SA~Tv|!$zr1Jcr#2aL3<=Wl?z!Ru zxv0(B0`Vq^w{_Z_R>H#)X%BYC4)5;23u`~FxyW@^J%pT|^1^4ha&lgVklH*h-RZ>Z z(OSLVjIhkOk`VGbQ8=n0E&Xip3H!E&mA>_NObz3tr^4zM5g@6{x>+}!7UQb-HN6Z| z=^)8A-Y%6~5j>tNAi4uGCIjUIkWi#JAFkgVz>G6X+!fIY7Ok+WGrY1o>5p|=RU1cL zhfgu7h7GvL0;bA5Vh;3KXNfQIJTI^>0?Eqtf$cjp;65Jl4Av-}Fqj!QwRBe5J2(Gw zWYbAWMvhRBLo;>h=qY72WTzjdmo10Nz1fJ;IhcGdxcrXna>+17n$9#gyy<@MyL`o| znVZf$8JdS7m*amPY)#0AfwGF3)->M{;Fv>AKRXwX1>b5srC(z!cM00Q5zA2@RcXeD z8^cKp@7&6I(a~>)nt#MD_ns```{Axy4dqoL+s!`=>yt-im?|EyB+h%6f_Y%>?=E1G zt3^-t#+Ajmmgg@30mp1lZ7(<i!hMJt)$&$NQdGpDa#GW`ZZsY^_M-q}O+uM0}bGLOiN zHi!N}eZP9Z4IFFMey3K%Nb~t&iIc;7@nCP?9@o?qEjj$s79A~FI10SW?D0ruK4-g@ z@U1)>^+id`DJ~;I62r;j*W?n5p3{tNZ-l~)snrO-P@nznH9Fs3YFzVXAPqjxYov=s zLFg*C1m+X1-#j&aJDn86#q5>>)iLT&*cvdBA9@=2Bpz}m0)$XKGu~L*UW0;&^<;-% zhwn*IIre>p3tW0?2X;L^Z~N2gPenzALpV0M<&cvT)@Ds@x=aQRWu333L>srp!+F1j z-TIUi6)3o0UDZsPemynfn!(NVEV-ST@oa$k(_X@Ob7SEK^!jdmDHE*Qusx_Po*%>O z96>2WDN&H^$=o&9;&Ik=Ha(z}QEdM5-3f!m|FfGcdFL?MM*9vp&LSa|?Hyal#zh^Gb1IF7Qij}dkk0#39VP1~x0MVc zRy!DN_UB)Bu=V|6;gQL7;Y6Gf9lTo4B&o8hllak($@qsydivuii`VF9%}sdQ;P%R2 zr;|Lek9g%Au+{Lg8mr%*O3=lSMEJ`QWGW^-gJgiineZ3L<}371Cq4cJ(AbFdaLaceK%xeG53%{0vYA;dh2z zr)N0a93$~Q+Uv4#x9hD|!-eoOoW1%W)41>HE=hwUa0*z0yiZ&y;sVoEpzOlH`G;i_ z879`g&1@hpBU(sk{y8#Pyfp)ASh8DBT-(lcZ9UMw=FKEJwt)^jB@G#_u$Q>GIn*ab zFUsmZRsCf2#LQXE@tPsN&TWgt7tPa#$*448{Ey8(*M;O4-${H%Q=$%b zld08s@?eEM#!f7H_j5r4!VN?agC@{yFHqX#ir(pS{+TLnc|IN@WOovJw~IB*=k+nR zve+>5)D0NxRyzZ`dWu2O_VO7C%sm)l&tE}21yESq{B;ZN~T%{H@aJ21y zoXuhnNSA^Z8(tNuZ0mAl@6P?QL~zOlkjV_;Cl`jRgn6&m)nXRHP7A; z@7>|2JHcAu_*8hF+XkiL^QAl?&^Eq9mtRWiR`7m^qcrZ_y8_MV#0t(Pj~JInpBT(& zEY$}~#R*Lh6Qs`&E`f5^V?p%T3)0Q2oIHm6tfD*nfBI8%OfO0f!rVB)LQg?+nbUr> z(7v;jgsf?~ToE}gW9qUeE?6BKjatk&X^4x5^fvC!mvzT73gwqvQ)M56C&#D%#U5{` zr6bj7;C^pN1~Sn(8$U-KPY-!)l>>U65)t?WSs?03}rsX}o?45nP zYLrctU2mQ0dHKBJ$mu$Z=x3p0ZJ-kO?K$7$1&k>;)I6`zKrtdu)8*qSLud`$P41w`KG{y^M|X6nxMuOi4hF@{V;Y*?|2S~9(*$& z8jnDemSjhk6LSqgtAI_&j&S9T0ZK6L(`Q?cd*Z@_{{0%N)eDc93>H~p;E~IXvvhqX z=;KU3slAxU^Gv=OMG}tYqub}?U(5eykMlur=D4fHiOPCbB{ZoCT-(Lpb z^u0g$g`q9faEbWWPJ$w@(ROh#{wCLfc$fRp&Ub->V9Gk+Un9BfHtWojj({sfrT0DRr#i zU{>>p!#QfFD2AkWqk4t8UuE-gqtfBP_T<>F#I<;$_J~j+J;dqn56e^j=}WsMmrwa* zS><^o88rXCU?k@BI#4v(Z|G28TxjiTC4GsXa8ZV2!t}bypw4~>X(!G z-gwcSBRc?8Dr>?*IJ)?{{7~f8jfoDu?ZuYO!+4+Hm9Zqk2SCs!rdAL3MQ#*1H+r*unQHa;S8D?doIJ7;XV)+`NDan~mp> zdvpmc*$7TihBYm%%o5=MyON1DTXUh6*%^mFU0h~NSSIUE0p>WNE1iXo#;DG~V|iFB z#M^?5%e$ynTPa>TY8!H`-r~vq+)OLyFkEc0sIW{^_5G4K@#9#IYTgY{Xn&Nc^cx9s zH|-&=w$nDeGG$^vZgsbM5c1!^e&7Cx64XPeR%;wqJESe0P2%~*i|Yb8Bu6&(!?g>q z^Jweb96|Az#~|YC&5L!BBe+Cv)*o8z+xJGl=;|O|ov+5;IjE1=@#8!mbc)x@36YP6p_)w6tj|udCVqOP*UsG6oUh9{t1d!+EwBC| z@pZZY=9PU~jf1O!kWpXM7^L${KScO$&IB-sbEmV-SCXE`h%3nG=xEJ5YrzTEj=^zs zb^2e$lEt0!{c3|oju+Sekm0uxanu?(=eC}7uwpmH<*QzSdU9HZWs333ic3$fbJ6De zdDbTfNF6BsH6!I2-U!B8!OG$O^1!bxqZ?7Lf?g;T*9(VC($3MbUzW&0f#_?j&WE>G z)$`d+fvU{s9AVt$WIq9U>yla&qT5yTm{dm3E~Dml2WuqTjqArC|en_F)rR z0`e)=e6Hxc%0);9^xd^TO_y=>FWP-s*J0D7PBTr1L~-rrq*mbdpk4Qt2Xq_XSTHV` zyDr9Fn`Nv+mXxQBe+;_7Nby+1$K>3aw-T4x_ZB|eiw>W=Vxnam@-^OwYq39Jf$y$T zch^ZDhP>wLheDN}#y6p_)*ojo2^5FEytvp<(=ASL6QI}K-l&Q`dy&p`a1+Ey2ez*| zDxM-NC#I|yubf(cP8?JDM7|A7asKwfN_2s#DE|{N{&R{ai^!oMo$0LWbdp<#xsrPO zUk0B_{A(pch(vsmhzQK5Q`UD9JYgvz&XH#_F;Q5a`8KuX{s=OI*D<$ZxyU)gK{nU%9hE(s}>y1f%|w_jgp;`npwx_pR#)UoC}B#614lEdEcraE+QS z4_y01B zVdL6D$%B@R5Sz7=2_QZM@?c&T7ZXPyR7r@Ew!}Ly9CP_-e7(e`0=O57o8{6R8%cpuVP>Da6V64 zoW5m`VdHbXcaL5F^otdPp<{>|D?VLJoZGYXL-&@(>7geF0>P13C-^@p3*(BMcJZ@k zMf4MYqAE)|v)+>A8fZE<3#_P zo*J6rB)3eMYi?gRC=lLx`0EZ3QjQNS1+R)-gtm}jj6A|hwfgD%i|c5K7egh) zNH6Fc`zwPWHF@>e9Ow+4Ho2p6<5>~M zjJQFY*G%x8d(w^t3XA5<(U^6X{$6>Bov*XSFF9kk_0n9+N4l~`+9>Ab5&Zuoq)T2& z9}`v%T#~~feZrR-zl!n4{r;I_me)F};`{A_4lQ&E)eaCo*y5axte|8^QEo6vYwi5u|q=)_~GOSzlW;| zo}!CQX%kB)fQHFeuP1#Ti;|pstI|-Ml79Al*o{__z3%93WuLs?Un=gDx26Ql++-`z z!B*M7Fb%Ue->btSS8$b z&PMnkLR;djk3F+N+RlUD*6c6IT9$nd^NE&R^t(ZLF<5hZ{B(Zl1xGT(3L( zhU>Atn04rL!`+-Z4P4i!36(w(P1x>Fj}O$Ig{pMdsy95|sm3k&?{G0^xjtO<2&BSj z)S2}gVBz~QHg)s2M<6Oo67X&47*XgAMb>d4`GS|!> zx+++2X9=REbX_=NReSE2x$aMBiGRM2eB;mTMg4lo<8)t84K*W8fn_5gY5Oak{C+az zaV$%wOSt%t%S?N+S2@?)1I=wXL60LWdmmIuV!jUXMQ?Z3-E#kMSMt~UI})=FkpEwI zBgpjDmflgvZQfiJ!iY$9p+IgXsUUJQ>#KP^SQ%5`w^Hk}&RA?jLLA=75#{2b?RGAc z33cVOWtU~Q_KPTo$NgM4+~dEUQjRhp;e#8uv1Br{S2StlY1EP|fcNqtBDW#g(s| zM&N`>rb6Fl?7w5mcO-`I;~H5H!+!XiGNWYLMD6%G2fkJo@PFTTBEFoM9A(T?-S)Aj zqBjbI87piczo=$MJ8S=gYo&ZZiLG09KU$rfv-U$Z-bs#B^gzdhdaVnq5sosO`J0MvF&Y%-tBDh-()6|-d)WyZ1g&Hd@u zEHD!-VPkSc-9DKs;r!2vgm;wZXE3za#t~qXSr4$<|qhm9o*i>)by6 z%IotJZn?6f%vlA9no_WD15*KuZO=3ahCC!j%!(W(GfKe<%gRB zOHU_oMeW$mtw5UpTgOsZ8^aLWq1c;r0f{Y$%Zjf#y`cSF$7Xp`pQ9Q1XpVFN)hD`~ z^dTeXL-LPnWOj)Eyu=7Nq51z%h%XUF1W!%A2Mq*C#k`al*VI~{t#}WCyCYEm{K;bd zST~!er=4=(>_luhCyf>^ZCYp&bmor_;g2>!i0d zmK&xEm1_Vp=XCZ(+U2a1LXT|kC|tD{BvAungQ%~+-ux@w9?vEw--aLTZb0?6K+&&N z2e7W(v0)`&(X|WIfgD^(kel^w;##8o>d0C+2(2%+3jXwXo&A4%_rbgE2MsH0b_8J4 z0Hslg_6?8E*p_3XUlDx$tynj;DSch@aQkfOt0JNtk@5Pca#J7z8IoWTv5@~-#5WT8 zR9s}X=E0mgJ4x#Jf#yzXO39Q@a8fOZ#7A|9m7x0dZZcr%Zqb zu*q}JPl)Ej-390qm3TJ}x^H6q>gs(361%=4UYdhpR55r+; z`GW-fGH4B^#Ix}BGQmR)sI?II#vodEqBT-CLrB9=W4Nr`#Jn(VWSDf&SzrG8ICWFw%Pv2W=N zMA+!Bq{roq%i7l`IR<~Xz9|318p@{8uk!0wOiE0SZXZM@3wYRc$T>wGs#5$>m#AKX znDfwnKT~qzfpv{cE`XbtbB$Evu8n{;yw0$WZoBs4oXleS>xiHq@w_RKn_ngV`qi_h zQXl#E)vGjs_dF7RU@ykaWhbt75hW5yKS^!|P^|TU^>o#7K0EU%nh&skb+Pln@S9$o zEBvdxKX&F-cRv-L^FeL)t~sO6{uwGeZjCa=a7)k%(64SfwM9if1I9TORHKuqpo3g34u^r>t-|NMa!2N{$f?^|7zO{`sWY6(jQ zVU^~`ZnKi8hrs@o|MlB`IMkDsS(?RyUi@y}*4$@(CC`sq0F@`j{j8DWQaHfh0T3Uz3uwcL z-%C%N(>`HvqDNsmE)+oXQ`q0;Xlk(1alSnl>zbiq(|oWwrhNN2Ml(cP@Nz`MbMxck zcdrO*ggtMV$+Q32aS6l4$^<~3?;ioUx2~&)e#IrK+6*eb+6NpyLp?yi$ca*oUH<;E zujM+5Jrf=<@Z1Yc0SJoJ>t`?Z9$do>*pphsMJ|+;mUe9nJIk|GH)N9)eqX<|%nl&M zxpbU;I}~y11RGv+_KC(ia6ZUB#h3*>|CrP=Ni#2|!&{ozxVF}Z_7rGVmYC#p9!uev6GWD-+_QiFz}U! zVnR@#nQ+XvQx_3u)hh!FdrvE@Mdb;~2=v*{&S9yYe8RD`R{{piC`#qdqSoW&ym z!u9iN0iCNSLu}3WslrUoR5-?*sYL+?Dg@6$GNb6K+76pM$D2bRidLU@B6l!YJ^-R9 zQ-6FaSGD*4rQphZ&FI!|iJ||C;Wdi{)tgw$k1909EabU#g2!=(BFsP*R={g%>3MS(o8kV51k%qEli1c+M;5@`?%F z4KW&tX}Aas?91Bsm8chfs;0k9N1{V}C5ut9Y1ru*te7Mup1tjHrm<&I4VLpQBRHuN z@fT)qKqnHDnY{W59=RJZ*Pvc82h0&C#xd|lfWH!eDgis=j1uJ^I%7aJOkX@=HqO&} zfFnB>KXaEeFM;657y4nXrv@bwOn(95KRiQFU}lQbZr+{(fR&Dg%9nE7$or9-wp1fDr{ekd z_ou1wiM{*f!QjwH;hzm4dB{-#1JNB>S~+5|%YJP(WKsqg1&@~r++wjv=Ju6oZj6H{ z6+WmKwI4Ev`qupy>`98KPQu%_s$%-rPq%G%%X?dKu?{>l<1GH%XYd>~aL)Ea!w+R( zUM7Go_-QT@8^P58By`47u{?s>sfH<#^N&X<=%?|CI_{nnP%&Pc=DpUvWiBoW z)6*VzDGARJoogWj$y7m@Q+&N{Ao3Zo6861?Ajph74{$8U6}<;9&=yaey%cm>BkV7` z=Kc>hv720*S2e+Lq^Tc?!g&t`Uk0zpg>5d{S_~uqRSBv8QVCklRk3P--}4gfdgxSG zaIokx;Ajq3mL5|9P}t3@oh(o{v2#mGUIR#>2Xi1P{|7zaD>v&xRbs!_r>aD0Ik)p@ z;vtE2z?87ZGO+L@0qmy3yZajU<-i);1!nb;ZLRww5bQs~y-JvRaE+A{Kzhq8PRiV& z0u=gg%JWhSfmo0thk#C07YIMZOf?SzK2U z?^M_8YI=4spnN|=q}{M*0NKJH>{Bz4OcF4I054vDpMDCm3fxI5IO_Hc&`iA-G%ESw z5tsBo0l>44?yJ<8;{xQ*$3B7>ShFG+cRD-bBJhAG!3LjcpDqFdRwAKARis_*cgHhh zOu$c6=KhR>`}JV*mZ(voYt5R>g|~q?mA=flAwkQj0FI9shHoW6y{#uNN0rK44Me#da|1X_I8bqTg@_U%(OWp;aQI@L~Gk{U5?zI)aJ zVV4Gm6ica5;1r2vrx#%d0iWaBI8r98;wVAO4h^6F8K)>I`;P zkQqps1#|uff%(76%c-BglA6~N{vJ!#QR@f_l^3omRD9* zUOypXv@>@oVbs!7pQ$y&oF64>)%v;_h<6N;u738^N)L%k=ydjT)a^83CnLH>i7R_7 zqFZORXdsygI+b6iR%p-8gb$n+rfSn1-_!;q(}zx_mEG^u-E@iAlk9H?nzgCg5UZbU zB0?KZU-LKqO2)YrW4fJlnMI-3sOHVtOy1szPLb>F059U5Csq(B76+Z}ZB?q6?>qqF z$p@(LUZp+mWJm{LkJS?Ybqe{^3uG6fAL?I(!O6#Xk)YMh+kH1Z(d(b|E1%M-4mhD! zEmNHXPNqufhVtm<0*+rkYydV8Z;akJdOD-fCP1Hkh#)`y|2nzycqrF4%%n1u7&|RvmoStpb&_Rd z#@Lr>q{U2e4$2@CT20xCG>rxw6%|f%vS*};Lqb_fIS6HGMC-In(juMje&l?=@9*#T zo4?+7-e-BA_qp%;x}N*Gc_s54o)nId%b9oa9UL-s1oz92p~ATZB* z5AM*n$Ed@T#}n9<8swsNfyx};>gUYmMN0x zsjKe+Bg*-j4ymb5E1fn%Ql|sM8Fo^*A}MD0y_W9#p-UOMCd1ZdTuTL#T$={HxY{_x zZmHF891Soa)mqj7VYbMAvaz*V!i=7o{!E}P$uSF}j!6el#*w14$xr=~oR_5ze^_pM zO1x@QhK5pDpmvt;urG@xQ18NMaf=3|5cFDVtg4W-Y~Wh5RweIp z$NO!~7*rn+L~IW8Nz#_l7aSCCI9p0cy#uluBe50;-ar_z>_v^E>xE~9&lrz{J==3$ zi5NR7J)zn4IMnQg!PdB?&12{6_7XuROoT9~`ERd{+xok@{2r(1opI_`4BlkEIW@e8 ztzp&i&P<_W;M?I=z*x-G`mAt}zI=+Gm&7b*ygkzM^c=WhVvN}t)Rp?p|LuyW%B>CR zKQvW5trtyLUh|Z$Z9g_*9}B5>Y9PfefBJOCMnS2yk*l3R9QO(YVALibEbZM&NyYgr z8_O}@1Ka+j^nYkN2!q~-^=AyrR#~mC@^IgosMeP2P?bxQjrV$-Y*vlS^6eM;>*iC$ zEWSA}xa$BQnq1i1b&l!!X50xc8A@8R)bR4kr5De&Zdz$Y$@0zJH#;%0I{5!WK8BHCr&&WKR4V<|}vmcF~m3KgZ%t zZYp?Rd$#F4ZDf$A@~^1$ImC&Cpo`X|Mgv;D1gU0DF73BQezywK^`h(XbBD-QHZXAw zdvn2~B4HB!4l-9$*j-`6$mLi6LoBLTAhey_>un#>e#Yqw-&S{_j7~eeh#u;}x3deO zv9Hq^qaU2_kUg;&3`pQH>J2HWg&b5DfIRKxFBdVot*`YRNtS)Zwd~f2NoC#nBJ#@4 zs3?BDd9T5u^%D@fRe0ek9~U6AJ!51NviAKJyw4$9T&il!g91k+wu|9wcMPg<+hWTo zSrrr(ImMb{AdO4QgDy`#k#D0A>itat=9zA-wRjudBw6j=2)Q=Xy72v)xQs)9N)!(Y zR_ZHj%`^9Cf=+dwm}W!t5{ecthM@n4=XsORt_x<%6P}&UO~s~ntd?$=XQh|}8fP^P zzi+p+;2iXbeytUDtcVUS@PiH4fGdUFl|9!x1R+!;z7s({#oafFA-6?Fqecq!<8Ov; zUWZKF{q#WXxCy@a%h#Lw`fxlDR~h!VVI{!hmJ#o45(Gka7(n#upqx=c;{DYRYhXqw z3kAijBG`KOh^bXdJUxevT;5J`eHO(@^1ykCD(GQxkn+jdfUjEvULai7fmscw)+JkS ztX|794|w=Qp4@0BO4Dn;e9GPgxQJT!SQBj@O$^<0XR1s_>5=t=Q&;TAS73p)_Fy`2+Zc?%Q`lzpy z_iRSePV2c+FTJc=2qS67K8YVYIjiO^6IF4H0S2bIcURDzKlBALj~9F7g`L+a?H`0;gIfKs|TL2a8bRtbEA>WvjlCwM`Tm#_F^OJ3d<+)9NCsSn9y&R?5HC7@rY87KxF0FpeY9y_Wa2ETsIY9^uHvi#&Ku<` z)tqKNi}p0Q1sL72I9vV&tLXZA#SBGG|K6kqXQBecrIT>x`7&Ik{RpU-3t9Au&a+4$ zs(O>agouc<9An`>15%!xs~Uk@W(qlz8Mja}@!O#OkeqGJKsFM#2*M4Jc?L*g)KHL1 zYIMPTdi_Yfx3^c7|ND;JA8zb@-u|A$b5qO!p$-RwdwX+q|8roOx!2)TvW#{u^rQ-p z=l+VqXiihAcBkTgdFO&ziI<}2>*j}i2+4A)x+~SpH~C)op;eplRWi;1m(4&KazNUK z$fcNG&9%WOde$TrF78u24mB2VCy!>R%9FcEo(7o(M7+Oi~a0Wiy@DpPLuu_2u|h zK{&6`ttFlCmoa<=hM60tXbE@%C7aZeK|JK0+c?VBT`zC0fJVVG?eWN221FeqTx z5*6KHWDjxdp?!}%?mI`B#RETaw=^cujy9GGo~+wpY!4aliQ%bn_YWyO{1q5t-v|6J zqUf4?aUwV!3}&~4OUsNSULmJ8x^cnuIjA+ji(N~zM|A;u@QLb!aBuBqe;^imhj#C# zV*PzdOZ|Ij$*xHkW05kT8K`{!hv0aJ?sTASi5Eaj?)R8gVvB`J2t~<- zd!`a1%J&QdjDr!WAaGUbh|$DzZ0Nk}Q=!3WRVWVEgp-W34>LoqNnG&ECKIOk-Xo~E z1MPJa6P;Fj)VBz^5auQ*QxhTx3uot6>jto;_W~VI0ES(My;>)*Y4Q%HqETNl1_W|K zG;xoF*ZlbmbM@tvBCv>@L_2_nds9r=z+~Uet7s28P`bo|I$Jj71meDcVS^}q_Qo0u z;s6w8VP_yV^tU@zfe?ewj(H-&>Y4z?9Ht9nE*@rVBNy~{A5}ZBZV8x@f5EO6Al%}M zIW$+C?A%l((z8WgHUpRw4z4Lt#}emmY|@bHgjn4HqY5t}(C0~=CRX41=Ueay?Wyob zQ?dY*9Cn{$z)58NoKg8F=~g*-p(y$XETg5*k)E6Cf)wLCgkF8%x~72JFKydRKp%mvD=gg&b9yp_40AuA)PJn7C)x*P>s;qL*BS3~&Mh;vA@{L!#||Aj#Emr4 zH$QZUbp*Js;5Z7r-((#TKXiyIIsjo4KxPm~J|2f8!SH{tB$bsseQ5!bV0}qtWjvLt z;7-C5{qba)0>vW$xCMMq_H`!_NFMJ0KBKIptR%0bA`b#tDyd3>bwM!TO<7F=3WeGI z`#hfLLHW;s5CtV*02v&K;_e$n11`~)z#B*jxDD0=u7EF~D*s+GpenM!9bGEb#{=i# zYC-~LH-La)3ScO3TgJr55@jl>3P}Qa%2?P4x98`T(;kOM(#qH~+&nU;@&A7zJ{(#;AelZoXzTFLMKB zGhaV9+`ofR@Bq30Fx(8_mHaj0#SSnkltuFYXS_aq)NhC=<1onZEW3LL3XO%2zW5?6x|zmv+}pq zb!FJOdO@%O2L5i|=46Z>4UTukx(2xu;kvE_S|IQg6YUp3CZi#$a3x!Bm_FHqX=M!# zGA1aa?eK0Cyt}2Bz6IXf3&}Jmso<$@hIYCt3?jlGWMN>!w821>nHXcHKPFH~kKu1% ztqM25kbyNBsMrPvczgO2+zBSo1A<6yrZA+PzioiBt1$wHbGP%h2*!Hp2if=q>cezh znVz1e`bv0zG9<_jp=+v&@}UFl)uWRGT-Asmgc~i`7T8n+gsCeX27J2fQ4E6AfD0Q- zeI=x&D!{g25FDfGYe5RIVR!<+bk(DgnFhK{OFs`=OG6~uR^Jk$WP?;ScC&_iTl%9Q zZV-P^V33`gxhdLT4P^+o0!CBCDjUPmV0V2y*xd_8K$0x=d^`-yV0v_04+A9?UrS@W zt&#;Oo;}rZh_tqAEjWNoizeW3JgG+c@qPJ&D^{oV0{K$g<^~FAnNJ6 zf?(!GswN~Kq?NG>Kpn!ArlwB|GD8^|5cGnLkf30*Ad_Ge9*1;e67`5=4^?w33Q5I+ zsb@#FG(_0YRn@3e8+xFfx3Luha==d%APIi@rsia-Zjd|J*OCT^m!1(6*alTS1BM+P z4MM^_f=qBA3ewXK<7Eng1{&JXfoD);bF{8naFCJ@6yyabVGz231ZE)G25AAI(=FUQ zDKH;TGh2p{E5#e@8AxBuV>RHUA_#7Di-V0o zdt+QxlxFkT2_Jy%l|OG6aW&&tHy1EC6`;dFgf%pt(|*5*V*BR~fjs8T^R91p{dT5dmFcKsF?)`WUJNfK-jFtPo@q1F{d& zP0uS(&yZ+HKtTL$@VbV0Gn%=s84X79r(%5YYSyp-6T4udH9(&3fx6N&BtV&1hF7qg zotYKFCOF842~2E3z!*c-5MV=9q#+LBO~Rtwy>va9bW1;7e^WiOmx?>gjpEPL!(rX< zG?E3#2kh?;j75Zd+ZmXdS$m-k)$|NiNnjr&g3R>R1-TMEj1XicQ?NCjgjF*Q3NnB| zjC{N>W(2sYJIWkGFsHie!#pSyWi`6F3Df{(3h}V{5NL!C-W*8{w)CZ1`@0!hVu#2u{fsicm2z@rNInHZVjPM1uw!Qq?TL1eyv6Foy=V1Rpf; zfmOA{sRSXdf`iFEM1qwe-3DxI6rij}HGwlJSifK!RG<&q8&8DM`~nO}L~|mANJ5yK zQD8_o$cU&*M-YvXAmDfzsJf9<0tw32AOe~SS0ms|^vP6Dsu6)|W1)mZV+^cGSU)wi zk0FGHRQ9zs0eDX$`hgGzu0g=172bz|1z9txK5FI|tTGAbXQ*PVOQC~6zHWMU2P({) zN<@2ul&w^e5HQUIY;8;i=0q{@!~@YYF~F!8Q370PR2znh8Oj9aZ3_o6(Rx^SW26a| z;e*mOG4S@JVQu})1F&c&*~A=4q64}Wjx%vLhN0Z_j4izUpl&b~1G2uAstVHE2pK@} zHzh;e@k~#w3gBxPnAnk3d}v0d7%-K2AUFDfUj8OQu12n4I*H-VG=`bujo{X5x=>w` zpRI=~)s14|hlP^8kV+mzeT=y+(_7Eo*utCaE%0}}-J zP}Tfh&By@V3?%{t55`(TK}r~JJ-ji_9gX#{q7cbJ?gR{uZfI!+VOUU2&=f;BaC8Wk zXrEv`x(Ub|Vv1*)n1cenT=9A)7^0syL04JV9|8q*hk1~VB`C-j!(avkyBRQoAO{M< z$i&M;DHv>L#UQx_7zcoT@xV8&uB=Z)61bQ1LYlI8a@#7__B%5RGE&iZb%FK?Ycx5==Y-jNul@Afq5_ zfF4(4Pk$OdfNF+E)71zTI6XI$%_ z`@ksrfH5{OQ#+KJ3enof+LsP?_jA)%1G%CCakkzdS3jyQ)7aVui6!7{ZODKk(=(y@ z&~%mI7&8b+4Xo#nH?s7$qgq-R`cUAmc-+C3Adv=c9)K~@a|QmaEnE+NW&lPVcr0cI z#tLu=f%pIM3jc8tf&c&GbAu7pfyruz4v8H?>g!rEoaWLwcW@R%AM29YA&Im0t)3@b zvoG2oN1~pw-%&pI<)Sf{z*!T^i>9){c2TRXy~a_^4<+p`lV5yyHGXzE(fsUL?~WOo z$fR~w|H4Mq#z5$1TF;kDYw9!GX;&8}pKNOmFIcBS$$b}1FY2)V->*0Py|EG+&~Bd? zHlu6*=XH`Lma4#ZLX74AykZ_7LNHqEe+qNn)!E_<*AsAMJGhl!JgJ~8=v`*bpvrz7tlnKcR-#*hL64mf%o>WjzrXt_| ze>V36z<;M|waFM@tT2gd=SehahyBpiKi{T@O>R+>AF6&y)^lot+}NJ|S(4jo$&vA& zeb>1rkv4NMeGywJs(k1Ty)UZj7B%#mz@ay(Jm80ic~qaaM7_F?Qf;;U+HNQs`o8J$ z4M(Q1D(BrpoMurpZs6l&@*(}dMfj$Z*Wb8(jD=om7)EK2Oca!9*>Lj8M2m)%ug>&f z9(1kM-wgTw68Rb}Kfkn}X?QB-`ANn%zdr{%wUkZw>{D_!m#X`<9c4 zeT1l8*%K@xcQ1eUq2(Psc~^n;P3&UPO*FsA>CgLx(sLSqHU*AV^cGx6MI;AHU?&Rp zIV&Sf4xqF&jn=N_zdiR3x9eE-uyZdhy((>{JKsWKvURY9`Z=~w(&L!HQ%r_dgIu;* ziiC!8X`bp)*6O!FqU2n?^)%iG*b=F&mGMBu=f2azT3f;WaYJTx94WP%J z7QuA>GEt5A=8fYoK=4I@-}C9;Jv}ncYUV)y>5;nm<3_!~m6^Pf*Rz+!8^z1T?}`=3 z-O4|8$=Y(f%k|ir2k5sjvrpbFt0JB*&c59rG{nq$N#t5N@@>^_WHsbjs80XdCk2>D z(#b@6YwN(+WX5@uiHt*q2|n$hN%_>3(}+SxM7eBmtIKIV-45;j5UZD};6q2~@^AY8 z9QVQZMFCrPKCm6-qxQj4_K^$r(6K7?a_NQX9>vN0NTgQJE0V}$+Q^G|m;?@r^)tLWsP zZV8(Af8AWXc_^AMS}a=WV@1(}OSqP*h1yGTr{$9>Xp^tCm)>rV-NQTt)+cxGhl&)A zf4+=X6|(8?QD`rVH$1UfDqm2>85FzdU)4|fEqBM|%i1lCIl>oGX4KoLzzA)8yg5mF zpiRnQ`&!vdq9bL`rTxCwxmODglCdlDYwA>9p%?n)9ZSxs2N8wvbKG@ z)WC6_Z?8-QE9T1jU(+kT{ESMKs7~r_bXgmz&g+l5m$myH!dvWRaWa&zv&}T;M+1Jf zewBqhd|^S7QL@(l+OoZ9^MU`p*sCc#MHZx*Uq|EFZ?5z5+>;6U2HuSr{Z%=1UumYX zF13N#a^92IAnw&Yv0no=w>n4By*-8}c4B)8iId#wLqWr#@0N{k-YHt2>o>V4g_3YS z3MRCgEeSt8`wNs$n{4-r)|eWTYy75b!Nx73VY9pY(4O+M@%H-wQTCC1lvQ=|3)Ozm zhtpwTQ9B05?~=m<;06sz?^_xrP`ABp`?1vgaIbyYvq!XdJ$PJy9&e1aUc)b$4+SjN zE45(*zKYc7UY|K9l0j`p#L-Ge22|^HY3Z0A{^+bHN)wTRK1e`&<~BamIk^Gp*Lt76 z|CsnB@%mx*maVm!Bkk%}0;f*~3BK;D+8DZeVA;$|2&k#9+()I9!7FcS87D?=t;KWS z(`n{BxkM0}xQ}S)(0GJTQE5CH!Wk|X%3D-?Zx zk=wrfCWd~_CYKC_i=r?A$rtxGJHoA>kA-F0++^N@B9?xmJ~EX$nNJyYR41Jxl1uQY?n1kadqW~U9eFfRX+PP%-riomp?i@hgZ52>wG5ki{5#s zziJ3Z8h=d9sv=ifT=&Q74xw7P-%cDf_2j4ZRmeVp>fCyjBNGveeS(i*r(zdN3y-fW zcCsypmD~yTfBriwsHjb*&Z&CJ^27+AGvik>J9N;evF-32mQ6G+*7?WElZRV1i)~Pv(Ak>l&>`Zn}1SlOP09{~>xxn>c2tc^c+>W$W&Es&8%1duS`Vl*Gw%+l}3* zs`f`fr#KqLpeFSxE3|R9?_TLYn4U%WmCGEMG`m`CA!$-3nA%E2k8gZxoUT((S zD@y9wyU`^w!x^pPG&wh&TWGykyHK|urnda)LeupJI`ZX(`%4MomO~bM%a7{x`y!3> z8GM4MOru6=$Id(Wmlu`om;=w1UnIY-JP#|Z9`YHrV`q-Av)mjzZ6WScz#I{T3Kp&% z87Bre>ZMY@81TGZn(AJm#j2ds<6#Ln|^JVr%i~FR?w?EX=fg^b$S@_q)HNh({{S)m_ol!*- zmlI(9MZJt1>D-;P-(oA~wUjAy%#nzk8+p`#72*41RbA8j+W)62Dlt zzg_nV@Z^*Ut;t4JkM!N!;uI>4YXAP`VlID{zHl}*mjia#_9=U2g5!#=TbMZ{s1bYg zI(9LqyF$R_n53iALfD0J#K!#K5s71U5YMkVJesRt6tJlUzLt^zC12oL3YtpgzZ+=QCB0InJvbv}@U={V~ z#E(Abf_T?k9o~GJS0vJ=dFuR=UM#fhpt@d?#t5~F~(Uzawyu#&J0DVa|OPo zxJVf(t=Csd6y#p~{{7a8rshqzfE<57u9t+$%zf5v)Ha~Ma=b;k~*O!oseDq zt8*5wLYS35Z#FcQ@hq1}mNCPYzd-AJYc~zb`YBb#k-v71rVhU}me%xDdYkR89I?kl zW*??^QrFJWjqTl0voYcOyBp6^Gs|PC7Ah%KF?=5~4=J}vl)5xG+@C3^Dwuwnbhh}s z!S<`!8o&U&n42lAb3#lUBWU%1zX_;hhQC z_cF5ms}AE^eu}$I;-;Q8w*;hb#)8@sAxli1kYugKTh0jGsXmy=0 zSxcUh{of`yj5Sdpdp}@&*!OGzzEaImqg zy1@s?*@xSDIR1FV>kr&}&Q&(A$5;^irzgJfP;e5yGjk~>3hU0}l$(rxmz}|C-&P8W0)XlCmmH5u}z4a1OSQ z72YTZ+z+U-;FE^zH>E6SKXd(Iy^((Xyysz0Cha+uyv zZkf5!iFig4sQN>>E}vvKMwufxT2>A^H0}**3`8l)bI5XGWNbtyu0(FItb8qE{t*-> z`E~lO#GklPM|ii!2Q94bdUQGrc~gp4Ig2zR=zbje@JOABLdC_;3ZLwKYa~}DI|O^9 zXQH?{g_j+QT&|agGEt=~KGhdl@-FRa7$4&gVKybyp!r6PCNsioU9zeMDjUCuE=Tdl zNarR(6zg{Ub@O6?0N_dy-^Rtpw|srXj8Nzb%{$l-G}y#ki#Knnij}Q?BUbwP*6Dq; zul)FFsyVOdJ34Ug?p5O1NIjct;zo{T9)sPH{9iZi~U#BMY^C zj7PXu0k_wM481E7JA3P%&i9#?1hr#6WpB9R6~Dgq?%`3%VaDb$8;%GX0dY;JX!mNV zfJhA8=*C(Bv(TwVPUO>%Hp#c2UUtWWlP*#_*E6V%oZm}`9XbL@fL7KyPnQ)|DJBr~ z%jMs{Jk2zp>s!X}F*vB2Y@=zX!_fScqjwsaQKgxsizb&u--SuG6#}tY@k+aTt|PRr zU~HiI)9|SD-LcB$(dT@W!vG#&7YG$MioH}!xU01#KLab4LXiWlH$(rdvl=VFmm71iL9+|j^yCT1{v!=CaPMUnQ zz9*?2IW?>MePu$@CV`Z5yzY1UmB3~98)os0ABm7orOq%3Z}X^V4I0wfL7Z0_(uJSo z&q?zAYo2~X7L)YNszM|}{+Y^B(>Z;rbPQSF_o3A5N;eeeR#GkZziast_KPC#L`L^=Zrpnwn>UrE==VTv^fp+-uzU4l zV`R)3hRU~*3H|`Fg8M%tHojB%p8OIl4RN6HS*y1TR+tya4|ZFBb2{4Onh~JsRFHLX z`%iV9^^(q&RLgk=4 zvoJw}NR$31txpbCax*8@+QqQHu0={w8dB>S%VVEYH!BiecMxivy5YjRpS*-@e-Ud> z{uXltjJspuaQVaquASemBU$GQ0S9&Wt32gw;f$QDUS&9kOljC|@LI@Q6jr~xbPk@h zN$hwc4_F)eodcthE|G01CIS=sbdgTEcc8bfFeA8!9^T|RFSi&v-!-FW{#a1;N<-Gv#OK#^9^4-7VJP z7r_5z!H+pEsWDaS&OJS^*uY5oh2R$nIaTh6X|U&bcQkg9%9L_U?O8MAf3j-oksAsy zCkOj1oHo&#NbAtVJ+AA^RJ!2ZSC(G3GuQtPmy+#V7baOXaloHX)jzBE_qK~eHkakK zmf!&iXFz%dmD6(9@3ubY2ucCGD4Tb2x%WRA*#Bec1s*vCPo17PRnGS$blvt;5sNGu zTjBos#M^65jFBUoy9?ok14ZY72w5&k==*D{T()nei|YCuVIL8UU)R}#KUhPZbJ7>t zMHuy6JMV4rY1OS|gWYf!9ks%1I}s@Az>aCBaLFXE*59WOh!?W5xeXe^NrgLUyAW8e zb)JoQ;Pj6~0Gp~0H*C4T+E@2gh;ZXN$IH;6uiA_dyPDv)Z)J^>6CsCn(Z~@X3V#hx z>E-@-^BK4zcG3JdqW}7f;(Hh^CfD}Iyf~_SELl|e*9hIO;xX=iKPSdGYWV6x&37R7 zWf4g8A0niZ9+h(HECFKajy-^S$! zsTT>vrgEENTfa{Ce*VyAv=AlzhHHwLI0JgRU{vncxAltd{qFu9O*REpFYP8zA$D;n zWgxpRLxq&II^AWm-sfHTI(<=9fBYKDVaqy~&L7#>3%P;u7~2EOI=v5gK18eT#}!FI zCp%Ai%nwvdm+;oss%~BkyxT?AWMj3s);K2UlQcSkGmcU}@^<}QeB#thP~Gmj#YS1+ zOtmCv1`%ut&hPEDx`R_Yj)TBzdzMI zY+L5@_}nDmWK4FKW(||KCUf)%u{U)3Cb@U}fxBJJ);UJ`<6<{X*@7P;V=5Az_qTfd zXY$`smdr;h1>(c59JwuPz0{rH9<1XxKSB7WZfrRrgMKpcg-gUpY5R;iJ+HVV8kw;7 z{nx6Vz}xKiJb%-JhH^|zS50osrQGN_k(}w^_uq(_lBIk^m^1kX? zikqEbC2PtzFRt8mR@(Agxg^=x7TyGR^u6M;a&$i-id!hgqUN5@v7nv#k8JX1D)tr6 zAFY#q!qDT<`s=cWJh!pdiP3gk9}eGFsuVQd*PG(F^hScOxw6>nt1@_t{hmetAx%7> zwr0Hu#qcIwT+P;WZtB|4dmI}QuBKSelou{ASX@}+i<2Wxj4P4L$rCb8E$p_Bi&#G9 z{5cCI*eqOA@Ba|5indm?E0wu>r~HwiT8O46fd2H!cB+ps%E7LLyIpsEewJ$ICA}IQ z3Le;L`5EQ zT41+rF#u#-o&E|N4zcj-(YU?GoaO-EFczC)uAC^_YvfWajisJ7aBnjc&ni+5;clWZ zzC4uA4W2|sU3izup&SlF{00zl5H_Q?_a$;=V!{u{c;xH%qOIj9!(F|)hS1=r9>EXulAuIuHdDG zrPMRY4&>$L=^5b_DsA-UgbfS1ICTx2V=6Ey(EhTFS)< z$+5CGjNa;xWWBxU|Fq-C{anFlh+o(tScB@E+6z~A3*Y3KhRi{8=2})bS?{Js=Hq+A z5YbZS2Q68*obQjWT5L#Xggl3;is`hZ|BOk^NaYA>)}_uzsUuYPYJtcu*#E{%^fUX% z<(q2Tv>wNxoWn~+9Unp~f)<8SZ!Nvtj@}DCHBz(@EgP>zd{wvpTdYP)d#u_}ZKk_J zzxwWx4% z0uIo*&q%3(jv>Y<_nLY9$rO%+RNl0wL4aQIDbW?IaMnFhIw+$Sw$_F7|A94>^_3p1 z47~L7B#&F;K5VvOFbRmDf)xPw{s3lW75yGCW06*;z4pUm`dLhBSE8YaZSj;!ezdv7 zfJWW*L8x|g;tTgDQeoKmPRt-9fL z0RdpdgK0(mvA(z7U6_9(D%u?v8PcB&96wLzbHLfhrC)8FNZWIb_rrJc{2pK?$OUE# z{{D7W{O5qFjC6TT^DmA{LiK%2@DSDWjGl0h*u3bU1leZsMrR;XRonrYJQJzkz1nyQ z!>m8+lvIDYL_!#Lku4_2D)-?z4s@Hk#aG1qMy6=#V78!;Pm)W<9gG=c`@=J2r-${* zL|fMfj()Fq?iU)DIFB~&eGqgG$c2LIniiz#5=$R`-M2tvc@478U^;_k4m8tB)x?Xm zB9)~$|Fp1~`5!s=u9R~0<2i&vK;RFIft>;U^36bAMV?+h#(c#jo8o@C=z~7aXrqnM ziLZ(lSsZm^NhXciEkWm1g<;`)A&`$(8t$ETO2$vTBXvp*2S#JR=5p-M`G)7F@%(z6 z{{sFZ^!>SSiuv3@1Qj0w48QtX!N?tj;U1F_Xzy#d$bIFwY>E0vj|1&aJ@=3B-JbBAXkN;% zUUHYzNk8q7)pN+#j)mSQ3+ni~{CBt3mVsQGLuh=&9PGX7Y(3S*vpdiBiN^EZ7;5jc zhT5gk1nu>{F4M85$Rq6LcZ+zIPDIw51RE-&W}e-zd3E-TT)sre&fldRN3J58=GLDV z0yD!0=_AeH)w`nMJ8xd|+C+a8rrlodNqE%w5@F{`)$=^lvj8L^^|C*QpR(Dv$TUq{ zsNF_eJr7dA_bv6hB}i)3jq{8?FI0N)9Xi5jNCDCXCkFn)LS00lE13X{)$@#p{Kc^) zsG5oC+)yr$GHpqX@3BQ!aYWm@7S3}v^!vJ_3aghN@+v-Kd~4`=)*4Gqwyv*c3760{ z)4K*wgWn!qKx%|g{XzlkhE?5D<4l|O?vDLe0 zq&jcq{YoWc#J0ZH>S0CG@}<}B>hjC_W-*2PnO|-s)|opxg*PeiXuy)IEctY)3sK?G zXE3hkAEu<5tB(+B0i7-^X6)S>*L0w?u!JzD-VTt1%PC&@2+kS+0FR;G-EP;~ALw$D7c17YvSC$y z1N+b(f>&Jn$NNMWyhuk&}8_f;hm&D+ z?=P%Z*|tj+_V^1(qfgG7s*CoOBd0O_Kwg->TXf-tfP_vBVB4l|zUKWU@#iSLZ!Jqc z9T!Kf`SNVCIqibt{%OLVaUgS(n@R2EP**#XfmXWLc%_~wEnI8ldVT^Km31SdN605_ z69_0?*SeGX(WUuh^%1L!Q_-Pmm!ErHB85=}HWr(Bb0>{*4hJANI;^Ak5>OBRrxsxJ z_+f|BZqkc@PxDAQUDER-+DC@z5b2;=9hes;_g}s`$UCm&!MXASP9{R7f_#GGfA1Z zMYm@#$;OsmT=tubzn^`8Y4tSZu?mVt-R+5n@x%g|H1>iWJ{R4Ev4>xLN*Inpx5W<6 zRu`GXy>qB8x^`BJIC@Q-=g>Fd4?I_VsumkJ7Q*-K^D6*9$~M1_OQBrH>VD?h-L70_iMKV?1&e$i?<{s6;!K3y*rWhuKLli6$RuPLSG>*R2OgWJu zl_jUN7bznU-2f|Nq?3bF^WygKzSG=5;|^Q&^Lifumv}9AER{ed4_3bQ4unESI<&U) zDs?BOT%;&R7qfV1BGvUSk3^>7mWI@XuGi1V3OI@^J}c?~nijjayfV#+_SVP7Y*T zNu`GYM&yp#F?wb?>rdInbm+*HoK&NasKvuU1zanOTy{^9wu9{)l|R zJ9ylQA}vgK%J+>jA=B&fzDKVUQoQH&oHw%S{OVdCu0MpD9_5{23f(<+K@l3TWS;Uf zof`8ANZvi-zVYOT1P0LEajdmB-roCb?r|pX<0Yi;=J#5W>N^q@4nRUUlrPLLmijKH zwL#{u;@pFb6#=?~!l|0|4sDi)w86Vq(5*XsOvZ*pN#>OFiJv)8(0~ z1&=XTFV!y;NjKyF_>DHpE+{JHN2Y^njl`EFOnDY_&V@pPT6fG>TM{G&6h~Yiu2dEz zJs*X*O6hft?%eD7lu|Y-3s`AyZuU?zqMY>5cAigaS?p*Gv#6(RfwGyw_|19U7J?|( zZPCEr3GWUwCF|v9?f&++Kl3;AbCM+M&~bJ+Y@Ld?xxI62~>Urw(es{qG!>z7)ZW%D zq;ShGH26*)N&SgAbR-)d9+TtG-sd-)9(x>c!f5ue00f^QJ=dPXhldf*v*TrSDBw4e!Ami!gXT>uOVmorTs5R=`4ac$b1Dvp?o2jf- z1M~0N(2NvBIrKpTgSvREY-Ve*_a*Y4-WvpHPV%f!?8;xmXhhR{FIw=(Nvh`^WNU5ENqn9 zEFpQeA(EX-FLHE-g(qRUXcm9cJaIGO!$5Z#Czf#CwOj@L)p;p{t@k1 zYGmoqu7Qf;%jc;tR0YLFloPb~%Bz=KE)`Qp^u{s5qy)|NyFlKZOK(KNy{1jKTlI8s z5_wVT)NQRz$&Z+R`{(Qo&W~sL8JgFxK^Gn{#6K=9Mnw#dKwbf^327eJE_`GTusccC z{7#h2Mb`t&%4j~WS}Vd)6!`#sz^8Wu{&9IuHFh;Nk4y$QH|iqF1?DpxKO_Ot-6*`? zz%H66(tMD$P41d_T_BMkEh81b6M>bi8{2$5-@fP%VlKOT6bKsp-npp@+Pm_PAhZXj zU!AX*=E79yr&9O5qoE^vKe179+3cTfiRqGz)X2dL^x)*Oi+9&k$$gWzcOu&OHYGbc zrf81+->y!boh9R8b_#xBHD;#HPhL*8$@|pIi#nWYf*%_={>T`6)sWMBqH*#5No(f- z&DHo5&~F*jCR@K_J#FkQxvqjZ{9YdAJ|`nuV|sD~UwHkw0|rm)TuXFTDn_n&50t<8 zbx&KP>Haa{q=5a1Z}OC>i<8_#reQ0o!$$pOFEFlS^N%9@*&z(w;xKM0l*!Ka|f81Mu8< zvRgdX$=vu=_65Ro)EtvDQ*lw1O?yabavF##tnNFg-u}uAJn0-d;oca-pg*P6T z%*PcvB|iHR@$+_l9L*CbcoC=0`j76nW!Dm3IyzhevVc7?)rs7HvSOF?SUUWHJyM=} zsaS9~x&#quk%fNHiB?CsSlo;ggpT~>%_!yj!7g~YGn`{AR8wEG2hc=Hn@1*tK1)7g z%f0AAVl#cL9bUWqF;8GXuW@c9;s}>J0DQ36yDXJ+{;G`1F-)4;+g^BdP#6}-(m}h( z_7f;h+J4>L1(Y``_BdT7f3Da3#GW{N+7|ptH66s67GcNEPYd=?{&MFG=y?k&8=zHp zYxdPFLeTMj%ws2=pA(c z5WedIAIhXhEF6u;Js39j1?xtxw07Ti}h2~aZ?NwCXjn*0Jf&ZYP z!Wua40r}n$0d=j7QSTS2KXr-{iv!Zwl4=#mt=Rf;0LQ>qjWF8P1*$j70SX$sb2)gu zr5!$sb9^VhD=xaIbI~zm@VQ#7ko=e7d$r}4tAu3K(X$s^czsfnjRj=B2gkT_1K{E7 zgB-Y^6XV&H)!Magdz^-jpwIow=V3s`)})Xfj8ag7XpTe)yabXLsUug$?^`%r@IE>+ zV-*$cAs`aX@zI2vKI>N&FQM^iS_XR{z+)qpdGqn=^LGJcSihpf^*Kj^EBDE%V2L^z z4z^tI)LKu0qq@gLbYc7hhtEfZBuze|#6Aalj6VN5c2H;=c;<|HJCI8(*doy}OgV-d{j#8bt%DRDoG=GZ|q&FbpJrN|edk0XY z!9aCO0!MYZS=6?hO_}9)LENXN9Gml6Sz^-y?^Oj5jFa9^jd}z&5xQbF=_KcH(gFa! zZpx>xGjo4v&)#f`G(IpvQlI3D31P(VVeUX-7$3vHw$w9G&Xk|hQRI57)Y$>gv(c`; zaQ`5Y;G>eS)ZgOeh_K_uw(@Ttd0`y3Iq`9m8(Q~|g14F$rPm5Uye=-@j)-||L`j6) z`<>QI$HxL?TWxZ_eif%jkSHDOPMJhXKae1h<{LE~-~^ccau<{126jvCGXuzD9tWSg8@9B;1tr;oRxi-$|(aO9d%o zqYU319S}K+Eq$DIw=H-(EX*V;bf|ijcRt3?i1z#aEwATti0;+})4n^i z2X588NJhx==hqPxgPiZ+O#@*Z$AzG#=f7V&L;Ob`7|b*J-zZMg7wcTWkAaBfe;Eni zuf8}N@y_R`xk%_L_LTHX2Oy{nJSEP{x;hX%lOOvS4Wz%5H)EPrL;g~2s~K-}ZiD}! z@%vs;tZOU28yVK%`G07fBn=fEj=yFO;AKHSKc#G@BNr}2rs~f|)g1uZr=D|cwBJ=b z&&GF*KGJxD71Rz?vVA!Bsk2G$m=+~4DMRR4OI_CgE_jkWB=+9B>$N1gzf4}p7F<^{ zMRu>-TPy5RU;z1U*~S`iHw75$1;hCJ?}o$d#hM=j$xEBV%&RtthHUfyl0}h8Ze2=u zp|c{@^mzYUIa(Kz~>Qj9_4K z1{|Xz5U=~yz*%oOefyS#Ml1vfwXII(8FvA!Gy1<)%N+VuTLkEQ|B1)MmMBhvW%XMk zhTXNHS9POWf%M;l%ewsY{1;2e$V1V`e--UNxjHZYM44?lq~wm zzbB#@{0V?F9sGI+I2Bu7$GD^cWixfh?799U95O9{aL`GG0=%yeO2V3NpS8$l4@h2V zoVj3{veaeul1Ve@zMbIjFQ4w$e0ExC!g+65um^1xRVCqi)1Pf|F%3#i0fhE};7I89 zx}-=3TfIV?dZJeJ2Um%fjK%Xo1L8O*=Bwq5FYcH_uJId!S1HIxGJT=k^IYNUB^fz_ z^VQNmmqP%kZ5fEL80X{=<>&QyvI)l zxAqpWOSL;YZG4wtHJWb*G76g=K;63m4YjBZi0KeCu|t%LeK8r+Oo+My|gp zW<6m9VL5LLPB@5G_J7AI=CP?t#Yt#%nLr2AngF*(76s>C&jF+-c^6a|Y;7zQR=-jLNOF&?2SCX}9-9jzaS!jDG1SSR3|4*)+n$p? z%+7Nka5A&PzFxu=+y_kA=h#!1+<~c^})-zKn=IWyq&L^&bSAG#VDJ554rguj* zjUBY3I0SZCop?x;0Low6=|{I9K(%||i8KE@tXWk53AeBlMuOMl&#PO1IClMSGs_1c z82Ta}Ei6IqE5)vVclutBQzQVr#NE;8s{U4J(~y`?XY=x{yUXITDur=C;Hl0L14wQaS!#@_#LP0u2P_ z4ezME!2p_KTtX`SC$ZRsF+5h;n%lu+OXf z$zWoYR?E`R8w(Sh;`k zkl`)^e&auKZVz-smAy~SU@O)=L?2OYWj%mIzFS?`fX`yw9I;+qY0*sQ%r?gq6dspp1lI{C2_1Uw@taLW;qrf-gj6=ZYwXdo_}WS! z(jd_I3<~kSVL&0^>ql__2;j6c8(|Se3_E*K{Th%^vNO1I?v-B8zj{s{=(DqTZN;$u zl)R?2zSzLs)66k_uWJ>k`!)v3oE}^27JQdafr6rKYxSh~qzcKqPk5T% z>@JQp{U4q5ALa2$i^cOMmtwWqjfewx4Gek;#3{N36%*&i`=~(ee=#soPFN72T_2AF z)g0X|r_&@f1UjG0qZ>(DJTkw2fd6aXcv%-`LV;6boNxE`KsU;LLZ9pWC>nk_bZZsM z4`DxkMhsxxJYg`3C&E#+y8bT`Kvm#(JWgIm-jn)#R~&B1cIm&E?#xChA35qVbbW9f z2wJrvkxdOIf7KR%q`SX*Z=tic$HsX&puZPa z@|xnzVqGYp42*!Dh;hI@xJ@onQm+8kuWb(%IrMq+b5 zMt0MISR^7*E0V*=e(2bGDY~zg{g`w-db0FwblN1sY&^cTQFgA7l0ii=qg1Yv>BTbiqVkX>3p&IBGdO8jux8)ie*tY<%Yw(&!qkG7 z4L^9C%-Ou6{&{fb6;U){0;fF%^mdJK(vyG!`;)xBZKTJK86Av95SIy@JNMlObiy^f zT$}<#)u4>lwEFEneHwHKO<(LK0!3Fi8}p>o`?0S0mXvVW;LihOIGSS^PSmw2-aPH# z6#Po_YnH(0hxsRCqyXh^Pa#y4knFVQexFj&D>?wT6rfO- zD6V=C(*!s}&Ha8$7CXE60Fwj!a?F>LGQhmZngEipl8oU02CkcI+6)B!0&!G1 zg!pk9fb#=-3om3hZ+DBn?eKe!(hxwvg3u^!Eu%RDeq8PfE<(CGodxBkABy_Lh7FDu zGu@xJq{{;H@#YudKu$=Wck;rSi5{z0;j*3vPM|8LNR0u%Q9p(a@~s9At2w#GxK>bW z1Z@ zu&g`KghB{Za|Oh0q|I63tDG?QfZVZV&0APS%mZ&#=AZ=d2c+t0DQAP1`g1NEgrZOB_B)`Er)+ z5M%*|#gc@qff$2m-O8sT7k|f^JQHFi3wqc^E@l{uqbT#!&y|PLK0kSRu;@zPV8>#aUXcbpO73eZ>rKiA(RPvizwBohZ4g(9Lny9L26zv^^gA}~>tET9I3Wj}Q0A+> z>6F*dh=J$cNdB!3Ob!C0hL)$!K=+^)wU5~jvgsue(-D_(+8q@W&>0J&g35jOM&`R( zxfe+wOcm&tAvJ~%gHxsRN?kod0UU>+Ij4uRF|)Mw4(5h~LC=np%HKV8x{?#DNW4$G$Oh1{muPC0FIO!O$atX?<^F=3z=5 zR)q1z^@1+eR9(7~&e5Hc?RwWuV#ViFXC<%JACNE#Ebl#75KIHjC}8vwuDL0{;`2(E zU0`~YH=@y;DqF9p{x`}~Z0KJxia(+9mK+ z20@4wQb)gk+0hTQbn&G9!dPabDjxRX*rY2TWumFnJ{a-%40QVa}L zjy0U$W;NTuAj85|qjM^J%VNBu{f^;PYtLuoLY>f&PetK%c#oy3=?8Ei!~(Y< z0iKeJ+laCq)VfMMWKwS!7@XCjze{YG;h;{RWPx6Yq>yzwL1YaK5}KlJ`WyjdY)X(q z9;AJyR;CGV0g#6>g>4jxE=s+uX&3Dj3XBNxOnwTtUBR(isEajwk)50 zkw^;w$(vcFaXa9N%JeA~B!sy@hx-^4bIyTPenzZPWI$+I{BI|@37T9xweiLr9yIP?;H8i|Nr*RRla4owyvazzVp|mrCVB7*L3$1d(Tdw zG4X|MUrni1|8B`Ys)kGJTBFln9#Npb9!8)TBFBo=TTq;JW%0n9)hY?q31naxNkt;(FPqZW@=rxZbF&TC>KESmf2M zw;^7!f`JjCj^(@YZc_9)@LB)4;i!*(`wt^>AnR%boRY`20hA280wxiQGh_9sQ&P|_ z=;5)5X&CRm#fsY_Xv>}bKRmi7CZzK0405f5!lu>yRz5C2>gEjd0Ft^%P;{SZDb|Ll z@uW#H^TE!ddaoU(lK8{3;#6h+lOe@ zp-89XU)K@f8Ur|U|N3agU6=D+g^q`~NEeyQtEcJU+BNw1b6Nh4H$@~K5ThLsskP>3 ztKV5kgE{1!t+GJ?(2;M0pYT_K-}fGVAN3^8;P|EIp>emh#H%|2YEC;&I^ISui3miO z4uu9Y%KWZ-SI+c2lF~J?L`GqPD<#3=KR-GRq=&QEyWwWesg42hu(cbZ4r#b;^DACiZN zFGo4rn$f7)dsr5N#uK-93{P;;Kx_rTW%E-NOPuCEcWkjeE;cMoQ8h0C>n2EQdbJl8 z1F6t2K|gvmZna`(r%G{gF(%ie`XcgZcy(4|16pfa}bL=cwH(1wYK z&XJ=m;*JM^@z|;dX$P}0vDnjtne#wvDpV8Nl2$fyL7Ag>_)09iwIOPOx4$|pY$`gc zA^H1weQAs{e+3YK>E~?oF;D6QtQ!9#uHrz@)}UmmJ`JLt?l2p_{1XJGTs$+WMfkn} z%5!V@;`%8(xJBtb-y!O3>^*C-MI)53NI0GiSm_(wp8(|*7hl&2k}YwAZJmN;#-_s3 z!#^r{b*p={C4r{1Ny@iE#v(-}9ykKcCB06{P@7d%61kGOb{S30&o$tw`9wcFs73rC zt8UutaWy`3PudN*`J>GuV(tIHCkeKw=&DMn6Nyl)5ceDSL4N?SETW-D&i%EIfK52D0x&lZ_Z#?O r1iAD^%dZr`1MH;tpS^*ocl?ivEtK&0wBzAMP98HOYs13toFo1M>=~-o diff --git a/extras/Images/voltage.png b/extras/Images/voltage.png deleted file mode 100644 index 3cd15377b0ae29b893ca3099b8bf6e6cc9c32463..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 15230 zcmcJ0i9gg|^!LmdvNN(K`&#yW$v%b|yD?_Ql6~xqZN`$yl3lWtw1}kaqOv4J)=Ef3 zDIruu5|Pkzr@p`EdH#W4ugrYr&b{Z}d+xbsd7m>Gb~fg0%tx3Z5C|IvZHk3Jpk3g3 zmXQIxUOZ_24uKq6i$W2jLSlRaf=Li5HRQi1DOF{Ea%7a0nyHkkYIJn8qECcpv|<1m zd;(vEkbMGt14usqzE)LM(NR!QR!~;Ksi;b+8LOy+7jVa&#nkw84QF6=l$@W&)nT7n*<)?J-7E{TO&N4hst=5lCK^ z0a3K^YFdhFnxI+M5{Wn5*ih(<7w>VZ*6Dn zWUCXbYOAec?Hp+3}Au)z)(Ra;GJgsKCIV(*8ujWbgRWX#M>P1IC1$wXV* zFr=L`D$d_GB2YUv80D;HV{IA}W9op^vB!~cs5qRrI$AxLY-WS2{s{Gsv(xv zSWk6pGjt?YO9$(RA(`RPL?6otbqnPTSpm`F9WihTqwHqh40+Z0bbbSs-!M`WO_vxT3zV_*zm3Em&=55^$P%&3tuK1lB{ zGb>vwD}tqiG08ewovf^*jtjA~jEW%mNBXK_&^C@(Xa88Lj=H+B7TOp~inLG;z=e7R zAT7iFf^CrDUf3XGAc^=G$2ezab26437G;T3CR;f4uk*= z4J{3IvpDBCM<;cs0CY%ru%;EoN7agIp<%5VgAcL^LIGmtUPPTZJ1szog24uQtA>In zA1!}nE3%3;Ni{k)EY_E#0x5jY70gQKhKkeJquo@qWHwh(@rfdN6pW;;b=bA028m zN>w$0MDV8i`Po{B;>Z>eBqvQGnH+-+_BR7NN5sP>@*|&Y>aihP3(QWq9W13 zXp)VcuOHdopXzN%vLT{Xyqsb+Z9|={v|}8pSYP$vU@cWEWOQhV7KZ4fjEas5itw{U zhG~$UN&a}Eg$6!aCoonUs~Qmy8wjQ&o0#BjtbAj=jRQ2jEX}d%fhcox?J$&Mm|uvt zk0v?XKNv?qIfo;|D30o?o;n(SSYu}|Wi*L|N276`QIR%Up$=5MFWH7{qh=2-bGV6C zsJgk2Cn3a_Y-vC?QID(4X&zTN^!Qgi_r{1d6U7Pwz3A* zLX8+@hp_;?os@(9uz)KjMBf;5>j-qHD&E@1EYgY?tD&N79_3)76&FS!=-@FnIEFnFSgV|aM1X}F!0FIt7*7v&qJtcEApI%p7m>{SSsL4Hm+Weq?V{Fx!C zmR=|nSe#h^+RHrLBEr$$*h$kX!ZN}<&=F||dV&9dNoL036pC7`8Y#$_V(vqTwgeN^Jqi6Pox z(;9eFKOYTsF9NWffI7IeW)_;UG2ksC)R7PinnHZM9KGT+NwG+6&}t9NrztQp;PHR# z%wMAeKL2Oh)le#fl3NgnC(tWT%hqJKHhfTri;{qv)I;rA!O zPpAEsihc5*>glA>iMZ!Kj9n|%D_B^XVfb+N&;E8&3L_^}+z6g-^pw+oRvda}e`|6+ z`tk2#?cZPT_j#rX;Z-k%wVEc-dgUI1Np|VkEvcnL5TY>CE**F+*X)lGL#6&4A-U!$ zFP8A>kd};(7YyC@7M0E-u7$Q$xk80wW)r=}EA8jECf)fy_Mbm|@)7kCr0o4%nuyz> zrN|L|8A4{@V$AmY=;t3C10%op@nxM@YelLDjP>fI*oo4X20;uSg08?B#T`s3V0q8& zx4*nH=MrU3U%o_eLtJ)0^RP(SGimSf4gFJ@2nnZo zW37iYs`iX{_h;vwHAjdxtM!B=Nmk?dC122X85;B;{`gXQ#$WD>G6R;Rs~I(6SxTV& zh|-9{?yiQ+-q!)o3l&zHt#1uO8dEYq#c#eek2*JZ!kETISryo8rm%&v z$qXBT?3Rt33B&xbheTa9DFvoc?t5P+Pr;26uA{Rme3$EDKCv})(^I`oaZP&!^* z)3Qx1iT}OY(sxKCUbIl&N!(z6)1lF;kGU~!E3h&2z3$6OdkKMi5jAzqTtEPervfU9 zdlesj7617z()P>ssXNx!O!(7&!1;$*8wZ3>;j$SW7#|!fCoqPIE8NkoYT1oLRz8&} ziN_8VsUTA?y#un+d+__4(w`a1UKb$#*p^EC~il8}t7_oZ`1-89uB4=c0 z&i*;w=+O=P{x<0D)5nOXHK%|7Eb|`7QLVq9l>+}LN8mVZ_k{v zO)ZVznM;$pQXKY#sSKIMK0hdNf!lERsq zyDBiAlzS8|DZtg@PgyR`@`wu7oscRw4c?s30&LUG;t60K> zzOwugY2OjvI@%APAYp%P-!l0;rzmSOy~wk2>2Sb7+w1SWsw-@A9WQU0KR+?Xs6KYv zlJ8}6h>K7Ie${*J-NTJe&H4_pou^WlUBwBh&6f4>^zQi@iK0eh`iK4BhV_0}g?}oJ zezth;*;J`2(#WY>!Hy#4MnBXqS$WS?*2}c{&;;ME`GcaqEIu{0b0Iaa_TsrpeU0?L z)n~)CDa*Jk5o^zt9&=wlNxjm#{)DA2;MdHlZbiC{^L0_Cq7y59K_aR;SiKeg{Pags5#$`_m@4P)=t&q=r z#)^>c3iEP>q}SQQAJ>~kh<3HBA}@YHsd=_yzDq!_8h!X+Q1I6AB?9ujYCNLj)Hao> z-IK~zU{07?eSV_VbPdj^F#C?f4Yht`d8Xsh(04wAmJAmtLyJxxo52fayO8dy&FS~r z{qKZXWx5wZdPE$W7uB}nf4T_5Fss$gGpj901eu(|FspMRwlU#tZnLP&RlB41bMl5t zckSiimH5zZy)#9P67lop7GEUH`7YjVu=6kVed5Qb6?6kdKXE)E|HPO$Q zMYZ#Xf7_-djKuwZRdOIXvc1-}qWHxh`v7*R*ixwjH+y|Oi3Nm9ojkDKK(?7{VZq%W zs&PMHsFRDM8}nI8uR|!+t5z{-^Uuw1+hI?8x^Sm;?i5?JUnBT3mbj~bEIf7&om^rO zcXWJv^d@qVPijrQs`$`5%O^RBIr(M=LL=THah&UpWFXSt7EgEnUVCJFG=9B1uIt_? zOHRYE;h*>~QgJJFEk`bOF+-0C*_(bkJ|c=g7t8DJ{-9lXJh8-C=!pPCsz_XJMLTNn zvLi#Y?S+I3aXo2=(B{e+QxO);T??3wpKo7 z;U)JPUO}RRj@I{lT@)q|F7(g><3qoZ{>+!Gi#LoDK zMS8LK@)~0?31+#~Hyu8>JvbsdI4&u7=J-0SdBC2N(>PYhk1H7Yv3BE2ZsO^3^Ddc= z#J#IpWJRTxYqE-_+1*Y{;3l2V6=fPdHxZUJo>aY>u{=$F%yTXH9;UBxs?e5YQ0i-M z^GyDfBUh70&EZcztu}WaweqSk$aOabO$L5omx3-gUpG42?5>`Se11D z@*5VVGdxwO#3vQA!+9+ZIr|yhice!s953t3Oq8YbIM|gKB~?k!xa*EY=y}r0Ef0NG;6O50ad(?dX!}?qgz4X=dS~J9crK8FoM*89p6x`={f&(DUTMRBq z6%q#ZyIU(VVHhDNUR*{22SLazn_ujk%}PYfF_Ye+lD!2P*nv=t4CQ2=DD+4?(?`}f zv$r}vzop;fbUpRv9*Jw@h1LgGF0uBE>87B|%U4tRn7{jQHm?Q_U)Py${g`tY=(2px zrZf9-m~%wL{HMT;Zp30~GCS9L*EnV3CK}x>fe|GPqh_m8zz9dLUO53yD&gnBR z?>!?w(qDh{xh$(T^ZRnm-ArJ|k+bj2c;f4NuJ|78{TgBCx5%lljYE=XSoZxj*2gkXUkJGe6|>lVrLN+wi|uu7`=P5EmbFgz&8SJM zcAvM(3v9S9=xs1EHBkNQn$8{6w{JX~`gGUzAvUha50e-I1?%1xMS-xTZ52Hc^AO9FWVXL<@n_TAEle!UahA27G z9`Y-~J}Hf(u}Avn%I=}bWxqD{W$0VUk zJgbH^^TCh(ofcc(&uE@u9G_SPb!VF__*xw)`VxIpk#-YQD%j2LVj&y{J2x zy56kM(`uLq?x&mdvWBr6nfwK)e&^}efd9&H{$XxtDNg)k%#s+RYGBZ{md%FyG<@X$|+gdczDN_un>Nd zZ2XHekG{q*Mq<)gS!RCt<`?44re_uRPrgl8NfGOk&7DQiUpVH2Ff*mkU9dg7>rfA& zIA84R%v85`I+t<5Cc`N2E3=%IcB}_I(Ncv+mjUxB~GB&o0InE%Xg`PbJLO}OjiwS11mN)G)^ zJ1BXw{d^mw6dO9(95Ov#_BorsV0SJ@-6*s2kZ_EV=%(v!6PS9X{3K0f zO^#8pd*}q`Sw(9Z%<3~<(OeF>%lC(ME!VXD!g;vN_nWSy%+B+xTtN26fF#1)WdkFvu;iXp;XH&|hfQslI=&-U$eT-~uw+F6Qi= zr`r{BUfE8YtDBu4&iu{*;ntT!BHUn?yA9vVP>9mq#|Ec&(J&)Xw_J~~8cwC@#mnxB z1nVg^LU~3VzpF+g!o%p$nF|KHl~W)LThtsJ%#$GT9+G@LZXY#Rfn@)g$NrbAKS7{4 ze)$6h$V-|}c%V1oGw{`TMt~2vf8pylIjI}Rho`Pz8t>2Ir7*;R7|Z;|BK^1LiIA80 zVxHqL)2O(w#ePgZxSFJ>+3m^42aXQ{CoH}``qnuQTx;%%V(Qf?5N2{^oI9E@fzQ%i zu#{w!3qWmwr~J@xBUqm6DogzfkE07OYhyY`zx8h9tOAjPcU-I8CXSV|L8I0b_1TB-99U<%k=8@ z@ll2|#*g?7;#-Ymk6j;_z2(`J0Ns)fo8CC)RKPWx$s@PG+b|}P&Z_uh{ivxp9+mK! zpktr%8?OofZBKbZy*)uw{`PmZ1eKhRz*yrf z&FUaL(D~!gqZVPQg-gd#4E}%ouCx0jcg0**aFJeo6aV9d6vAtM0OifMknD{y?u87_TXxp6zfsgzmg2VQL~>?)hb< z3qzB9p=oi)Zz{MR9~T+FrW1MR-3G3ncbVLNYNr85-`hf6b$(grqV;_g$&u0W;mnEf zrEPhH_q_7@>Nbe$E)9sX@XDvl7{&j3LLB$0?_&H@va3TJ!4rfcdIfQ(~37?Xt4!(j2rG1S{vMWrKoGI5!`Y7O^(*rx&DY}MyVxW?EdTWBPq2~~rWv0_TE71L;!@@7YzMJ>reMh@tj{_SQ z245HQj&{E}4t7a=v| z&7Sn0Ff}mT+L8Va&Wy04@W~*7tdP+pU-_}@Q^@^Du|7n`C z>HOlV#^IKkxF8=>_UVlYlZ2_C&@0|SP9Y(9iLO~@&H|iCYjy;GmM|iAT@$b`jJWJjuOkXn6=ecK> zSJlSO)%4;9eyw#k%=Mg>?C=&QA>7~bm;QCwy6W5zT+X2OAgOODtI(4;tWFU!BrI6o zr_Wqr@r+wUCZPVs)&8j8s$Xk0p$Zigw@?*-Q9@ zX99|$EI9gdju~sm6ZBJUeY`%`k(V;UZ`!(MKK^v$6gt5P(r+5kFW@(Ldap8n3&mn% z<+P9;B-lQ6RO3xwlh)Sn+MO%;mRl=r@plH?#}7_U3hJ2@#3YJ;Ji#bs-CLxto25&~ z>Rb5II6>1y9!3|FH1C}&*QL&zcQ5ocpMnzXoS64--f+Vo?VtD#`C<2pIF#8j2c75> zYM5_OuSq5w=K%5k^2T!(E~SB_w2Ih$muD#V^l(Fwb31`n?@Ek=CXkw^{i}^nB;U{iM}fs%E09%#2ulzG!jJsllGh z6FdgT&PaBt@NhlfQc(;l zO8mvg}~pAGiyIGO|yDNXUfaRHAo^UAm18ugi#0>8qm@)v|X*0Wy@ zmTE?2T7B1}Q_pBfB^G+ZSQ*N5+We2WW*mdD;dMN$Yp|9iRn5!#U?Duo%2x7Uj*KCxX@@mHnR>Yul_n8lB+8GA2a8H+el3$kcRo1|X7(^IcckbL_pU+C~ zrE1Plp7$K&i_Oy9-+IZ@0H7SptHaJQD_`ln6&OxWJVDKHX*(#B5>CIJsk_e7hWmI6 zs>1ImK3Ur{CgzS8m@?3Z(Re53L3J%WbOU;4vLmott?O;0<-4&hK85c_@{Z$)?xPM0 zs{*3KgfJVss?WJ2Tn}!asSW9nYN~0~JA0?Yh$4V-gX)hBS}KjI`%e%je`eutO%1Ex zKkt4`GsGvJAZeTOJgRl7a6|ybV+8<`-vFfbNpd}EKbvh!pU7@fxsdgIGjvzDRI#ZI zozQ-$((;kxZsV`AMP~RFEg7CIV9&xP};25E<<^4qe=4@kGGu5q0%C zCOrtpBuovRu3s9uB5~OFu5**c+i`%)NFkCS>ydT_xkvSkm4K@z;{PN{-VT)jW)`#H zR_y!``>B{>e{;O4e0_hmGVb*5W);g^Sp?stQ48lUY=}X8-J!el{ub`kO2%QCOsD(4 z85%*a2W=XJm>=5cev$kRpz>TuP}*x}%g-D&6|MIo7A+F%9=9gNxr9EvU7OlDA+o0z zz2+J|D3&(($Kmn7hbeYeE*iWN4Zt0=Dx>eYLy2DW{GE>jbwx_WyF?ouGk?O%*ri+8 zQcYO7JhUOr)oC1Do5h4U$tAk%`+;mU*oW?==9#J2#%%)c1hBnnA;%>*Om~h=Z;+5J z?R6n5Y=ol?W8J6!dK>VHLvyK%*K{e>uJm3q;;#A9BXy3`b386mu<<6?P%`8Sq7xs4 zelrXZ2dwL->gj$CXog7qy79{fPh_mY&2(ER$;IFkH=Z*wc!llL+13lpkCrEDE=w9T zrBvfHx_LwoIQ$ZUQ&%2U#8k*Gq}ywj{j{vG9A3G?s>}iFJwy*?c zt>k2JJm|use8fqVzwb-jd_kV?KGdD^Yc6b?5uX6;AWc z;ns8&dWQ?);RxREH`9dkXR1Nm8U{cc%^sViLnFO6{V~O@Sy_EmJr5`FU0y6ybL5vhJDs=LCye7-j#-twK|S zbDxuuLl=)ZETq?Dh;ssr7M2RO~BbmRgI-9aeJ_E>owsO?NDq>r1zGe zYIP*S!%NmTU)kQ}SLs(`yCd=f7a=OaQF_pfARA7g00Gkl!clI638tPH!csl-NU|(4wwf^I$ zw)iFww^Yr}WwsoZuyx`+pNw{8k!*ekh7Pmyh$|nqr@T25xp8$aEeFOtAf|Uty{mN9 zcyO6)t9|A|{_czCT$=_1ejRg}@L{N}{uVCL=K)FSWLp#>eNQ!JeHJZ?PGC^z{lxb| zG?;SoFMhXp^Om?lPjtuJy}b;X8?yC}*4p9_-kFs(@~S;5pA!!W=hi&7NP!p8&lNRy z0*>A+_&4s#Yg_x@O35>2;{Du??oEUHV53=@A#WMWZ7K50Ec0^Huw9-@<=*V_%3mLI6_l8VB+ z(VW~rX<5aI=QkbRldhmCUP~tKq%jw5uWXi`YlYCNJF`1U>b}h-EFBQYVMAIiKzItA zKP|W7v3cqj!@W6<`Db!>FK&Ai$0QOmaP$+_AFe6{i$RJXw%;!m!dq=aCX^q!AxJ$b9iX%yO_ zddZ`g-+kabw>|Ju&$oXg1Pn7@zXjsvCbRq7A1=>ztgn@cPRC-!aR_ga8LKyOD;$v8rX|LF zW6~cj+gVphc9~p>*Yup*((&kmg#UP6<;7E*pT(RX_=|;tFw&%#9ThwR@SseP3(d-tFvoW++%Qd+?2?p? zb*`}5zNzOZmgX1%|M@=JUFGb-UYzXgGrIa%RsmJhdd82;dS2wm`_yny_Hd#Y12|8_^Q#KmzNs7G-fVwvz>9cQE-V*7^s&-uSPOVt^f$$k4LhUwForik@$|W!T9pFe z`Ng<5BQ?;?-Icp6oO1y8>;pMbDIrVOV_{Pd0Ul)vY6hgfqezrWM?9BD-C*o!4*YW> zm(Dq?M1orThl8Ij`Fp_Y6G`L|8{Q67aHz1kG<|bWA?6L~^3x%%X6E5-5RFS=gr;xI z`84Y;h(ni+8cR>-LRhM`Gp#|*z&a?l$fDJS%*wBWv*QD~^H%NE2d`Agq$if#Inp$E zu4{s+oF{O)xi0+Or{Q9`{tF^Xchx=QTi>xO+0ry1^BdTvB}_gcUsfDZnFP^$)bch^ zPGAa_69R;@UXs1`Mg#rTrgo5Ghq>f(816L?TSAMqfe&k%#xB&GXD(dT=Y4cT!sYk> zZfEEF@3Mj2)0RRIqDS4Y4oflnO(Osw2RnLd}jAcKC${X z%p!}k-R$Ldwt!kMs4iL5`S^d!1a9+v`8iEiViK6FHS!g;cD?W1=#{bqTu^wscKB)U z?j-v8rb)Mgvm)WWh%!(m5OKT0VMg+!1XSAi=__4HBU_&5o|lB7*Xf>w!+q$zRPC2u zT$7pA`vHh%aTx3v$vfRMjoQXszQsn1oKX0e!?-o*gt{ICr)HxJOH7o#M<-}ad1Hcc~3XZSH@ zsl*gKkrW)hPX}!*NKKP~?t1ZPWGBOkbpF96aOQK6HR$jaHFLf1y@$(yYfGQ6=Zp*9 zKKSZqSl|u3wDYW=?=r)nqDRknAyN?f?Lz@_wIIG_0*B=0JBgRBlo`y(*pupQw+)ff6_E0ECji0)LW2&>jjpA$XWHr-3tEW zF;FvoB7b(wV+ou!MlrX<)6ZVLZ#W^*V#MMH+l5O*mwWQ{5s77@31NO9+`Pf6l=?0K zC42VI?+>K@Bd#Szvuj}V05yvFl)|S*4U7)qDsW-OyS_!Y#(xnVCL5cX{A$ z9e>3<2YZyY2rfpUaU0^8@8{8*^R@Sft7W7Wmp&d<#=Op|{2osKx$Jdheg?eg@Mt_M zB8(ea&iABH9Pjw)dSs3o_Q_NFZT`Gl+yuc~dXvQy}0OeuVlfA$|?4);vSGh za6nJF(L{Q7P{%~eDlpv0uYC?c*5^O;IX6H-jNFJEu)`O8&IeTj-v+Agel-_z`laN6 zG5nrH*nm*<;BN|}+51P)R^$`DW%##)g0T%zkGMfw!9&L*+++M5fJtnxwmjg{{;qd`r{ZPe~9y}SOvf2(@E zpMyzQTS@2Qf(kO$f=H)+aP9G*GrxA+_m>G9Z%vg~Ocf%;Uaq~eHB>;}7gK$)_UN0U zkV_k7<&IPb*7*uLApr5C(tv4Hf)pWZ+QkV&XP$`N@VRoA#k;Azz2tadsKtW0prxZ@yH`P-5h{A{NZcRcgJdV0aDg z?*xt4L&);O{_IXZ?xneaZl|{#uP`tf{`qA12LVvvyDZK7t1TZgUuaHS=}yoJ%A}j$ z`<0wtSf;_gl)zp|ql)poyULPX@!ywTr6-IqifU_&Av8kYf!gY+22P|Dl-I=C_naj3 zYWJlME~vO2D;%BBH(G!=2FegTNEM(ijT;W-@-XHmnOJd^GU49H0Gop{PJk1+tp#!m z;QkOC6$1+RJUK<7yk?HO^q_=b;G#Z_)KMC#mzSs*Ou}0+QW}jEBOsM{@wN+&t2ET~ zjR+tWE1popmo69wH2iax-2fIQWd$$c2^nZyxfOc~<3&y|fay|w(4eHzN%TDtQ1_KD zz79k3GY4$TGk-1_>)A)8;t z#DZ;OdAjB9o)A_I9F;jN;3_YOKM7=7>C@vwDnOaU(tZCU>aeFc)d{pzUS%#sNR#(f zSsuh%V(0)=%~hsC@W}we%9S(ZMx_pNeW#fvkYcoeT~`mtC$@&&l+@y`{kk5R3juWW zo0c8qp3w}pD}6r1GPp#ti%YHqDFZ9ygft4B*_or*4iqk(V>-MrB5Hyn8pBLeV=ijL zSbt{iR+Bjcabi$sRT!VJB`nIAk(OxYB$_@?Fs7zb@QVGb&wz(I@1rLy@5GEj;@Y>HkaTk z6^UDrO*gv1=u@n9QA@@rwdIrC-FESB-@6~)9%JT|)16?SDc<=pL2!56f}Ni}=>367 zh;`2K9(fixn8TJf&k5=|>0r&D&Ns*e6p9rM5#uN8>>F6YZhVQkI*+c-+HRFl7En;Oi2oN5cF8KjLOEzXy>fjQ(+)9XSo5L9UH z%kh&Dwq?p(9$Xjo>I%}tPB9Cmq2Lx-314FA*p<|Lhbpsnu}uEwbV0#Hc2`GlIp2q# z(|Hifp#C#LzL$yTkLn@@d7uSw{-%2@GlHxiR~V5hz4920GV|A7qb9`;Sd{Nu>Zn!Ox`G9`-gwd^YV0f?Ev>hM&80&qx+F)W&83 z+kA_w;TSF#yUdSgFJ_E6pYSwR!Yb_ea+XCdi%0V1Sxkc4wX1Ksuc-Un&%YlHu1c_& zN5l-{U5Ih|eZP@H9jK$;sE3;oSE+*B`s_n#wl{P!+HlZKoRhX3CIxf?NE_EbhmWWk zUG?>aTOEn;otuIJj@yXS=$uNd-o(7RV_hI1s@SoK1?JdxypHh;{c?E*H&V7B)s+=4 zD+PK7Ae8mVy*f{1WABHaEfdl0E}!T$-?A3GXKoiR3zR^xk?4h3iBQr2T3LNyh;hMl z@Jfo$A@GHE3hkr_2{u>oolkar27ieUR3H*J#Ajc%8^h%93Z1$%S<@T10K~MOF&7e< za*aa`j7SY;miTE2G|*{y{8g=1n0zDUx6hyyULwr~9)aqrh)sqU)qH8)QZ8YAqu_Il z4YAG#Em>mYDt$~nazeF)RfpP8YXnbE;H3=*wF6dVMa5w9zH!KHX;>ffF9D+7?^n`| zwyCvj+*DIAmE*s@Qkv8f)`$PIq#boKSe1rQi||r`*rOEr+hVYTe{0{IwDC3vjRWk3 zJU~oGlm1GiT^5G>{$W6%=t$|fX=x1OUjkWvXWvTxe45*o_#_APEj`Q{(sdRn(u0*E z2}xKRVm)AHmf5a_!d+Gk75=+2v|IP?rV< zhl*JSq$fQ7x5WLXS5tYQu`!uM59WCw`j_Om7gyicUO?augRBNZR`?%*`8Oq+8K+f! zLP{GXK;P>B4zscGfBTFe#UB222NJ-eb{{w@h8R8nPqy0XZW--^wbLgRmvJSUNc@wn z2giI5&j4F$y z%is~vk})xO^Khao?Sw?3OM$wf`a?2EDvOf^62A9O4nN;5?#}^@IYRPsKm(T2|0Bs; zAnPjw2&iZnRb?1`=ln~6cjVv!=4*ji5M7E80vJ=C|IXdwQJ_lZJ!d)=@O)MswlaB_kM`?;9grZtUZ_?T_Ah221CN>)B*uAYZd%%{ zkGZs)dcJEw;aKlP+H_!2Ri|TEcNdDg)`DoFT*eg8pl^L|J;8nv_@{ zcd*R>$z>;>!Ji|As?C zw)YAZPaanm8M?0HkS${9Mk~GBUn*U^dvG%Wpf{yT*46G2-Xk_xzIyfs)7>08P zIOo0ng5>Mv)mjvE!c1j89S}9}^N~b#U@=~m_O;PI04ZRDNg9!HPZPnj5zyyHfPxJe z^*TxW070xX0O8lFUNHJg)l?L8?o#(}R0LCi;W5b&rcpu12+@C}azSU0BM*p|X>^U? c?Z&fzAd2+N6?A1ODG=}vgR(KLH}OdNKjq5XSpWb4 diff --git a/keywords.txt b/keywords.txt deleted file mode 100644 index c79a2e98..00000000 --- a/keywords.txt +++ /dev/null @@ -1,60 +0,0 @@ -ArduinoFOC KEYWORD1 -BLDCMotor KEYWORD1 -Encoder KEYWORD1 - -initFOC KEYWORD2 -loopFOC KEYWORD2 -disable KEYWORD2 - -PI_velocity KEYWIORD2 -PI_velocity_ultra_slow KEYWIORD2 -P_angle KEYWIORD2 - -ControlType LITERAL1 -DriverType LITERAL1 -Pullup LITERAL1 - -linkEncoder KEYWIORD2 -handleA KEYWIORD2 -handleB KEYWIORD2 -getVelocity KEYWIORD2 -getAngle KEYWIORD2 -setCounterZero KEYWIORD2 - -voltage_q KEYWIORD2 -shaft_angle_sp KEYWIORD2 -shaft_velocity_sp KEYWIORD2 -shaft_angle KEYWIORD2 -shaft_velocity KEYWIORD2 -controller KEYWIORD2 -driver KEYWIORD2 -pullup KEYWIORD2 - - -voltage KEYWIORD2 -velocity KEYWIORD2 -velocity_ultra_slow KEYWIORD2 -angle KEYWIORD2 - -K KEYWIORD2 -Ti KEYWIORD2 -u_limit KEYWIORD2 -velocity_limit KEYWIORD2 - -pinA LITERAL1 -pinB LITERAL1 -index LITERAL1 - -INTERN KEYWORD2 -EXTERN KEYWORD2 - -unipolar KEYWIORD2 -bipolar KEYWIORD2 - -pwmA LITERAL1 -pwmB LITERAL1 -pwmC LITERAL1 -enable_pin LITERAL1 -pole_pairs LITERAL1 - -power_supply_voltage LITERAL1 \ No newline at end of file diff --git a/library.properties b/library.properties deleted file mode 100644 index 075e71bf..00000000 --- a/library.properties +++ /dev/null @@ -1,10 +0,0 @@ -name=Arduino FOC -version=1.1.0 -author=Antun Skuric -maintainer=Antun Skuric -sentence=A library demistifying FOC for BLDC motors -paragraph=Simple library intended for hobby comunity to run the gimbal motor using FOC algorithm -category=Device Control -url=http://github.com/askuric/Arduino-FOC/ -architectures=* -includes=ArduinoFOC.h \ No newline at end of file diff --git a/src/ArduinoFOC.h b/minimal_example/ArduinoFOC.h similarity index 100% rename from src/ArduinoFOC.h rename to minimal_example/ArduinoFOC.h diff --git a/src/BLDCMotor.cpp b/minimal_example/BLDCMotor.cpp similarity index 100% rename from src/BLDCMotor.cpp rename to minimal_example/BLDCMotor.cpp diff --git a/src/BLDCMotor.h b/minimal_example/BLDCMotor.h similarity index 100% rename from src/BLDCMotor.h rename to minimal_example/BLDCMotor.h diff --git a/src/Encoder.cpp b/minimal_example/Encoder.cpp similarity index 100% rename from src/Encoder.cpp rename to minimal_example/Encoder.cpp diff --git a/src/Encoder.h b/minimal_example/Encoder.h similarity index 100% rename from src/Encoder.h rename to minimal_example/Encoder.h diff --git a/examples/change_direction/change_direction.ino b/minimal_example/minimal_example.ino similarity index 99% rename from examples/change_direction/change_direction.ino rename to minimal_example/minimal_example.ino index e5ab1d57..568cb0ff 100644 --- a/examples/change_direction/change_direction.ino +++ b/minimal_example/minimal_example.ino @@ -1,4 +1,4 @@ -#include +#include "ArduinoFOC.h" // Only pins 2 and 3 are supported #define arduinoInt1 2 // Arduino UNO interrupt 0 From b3fa5311f8aa9bd773c91c8bb712986b1d7f93f9 Mon Sep 17 00:00:00 2001 From: askuric Date: Sat, 11 Apr 2020 15:57:03 +0200 Subject: [PATCH 02/65] created minimal example --- {minimal_example => arduino_foc_minimal}/ArduinoFOC.h | 0 {minimal_example => arduino_foc_minimal}/BLDCMotor.cpp | 0 {minimal_example => arduino_foc_minimal}/BLDCMotor.h | 0 {minimal_example => arduino_foc_minimal}/Encoder.cpp | 0 {minimal_example => arduino_foc_minimal}/Encoder.h | 0 .../arduino_foc_minimal.ino | 0 6 files changed, 0 insertions(+), 0 deletions(-) rename {minimal_example => arduino_foc_minimal}/ArduinoFOC.h (100%) rename {minimal_example => arduino_foc_minimal}/BLDCMotor.cpp (100%) rename {minimal_example => arduino_foc_minimal}/BLDCMotor.h (100%) rename {minimal_example => arduino_foc_minimal}/Encoder.cpp (100%) rename {minimal_example => arduino_foc_minimal}/Encoder.h (100%) rename minimal_example/minimal_example.ino => arduino_foc_minimal/arduino_foc_minimal.ino (100%) diff --git a/minimal_example/ArduinoFOC.h b/arduino_foc_minimal/ArduinoFOC.h similarity index 100% rename from minimal_example/ArduinoFOC.h rename to arduino_foc_minimal/ArduinoFOC.h diff --git a/minimal_example/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp similarity index 100% rename from minimal_example/BLDCMotor.cpp rename to arduino_foc_minimal/BLDCMotor.cpp diff --git a/minimal_example/BLDCMotor.h b/arduino_foc_minimal/BLDCMotor.h similarity index 100% rename from minimal_example/BLDCMotor.h rename to arduino_foc_minimal/BLDCMotor.h diff --git a/minimal_example/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp similarity index 100% rename from minimal_example/Encoder.cpp rename to arduino_foc_minimal/Encoder.cpp diff --git a/minimal_example/Encoder.h b/arduino_foc_minimal/Encoder.h similarity index 100% rename from minimal_example/Encoder.h rename to arduino_foc_minimal/Encoder.h diff --git a/minimal_example/minimal_example.ino b/arduino_foc_minimal/arduino_foc_minimal.ino similarity index 100% rename from minimal_example/minimal_example.ino rename to arduino_foc_minimal/arduino_foc_minimal.ino From e4c18e5406b3274a202d65b44577f535e7d7b5d1 Mon Sep 17 00:00:00 2001 From: askuric Date: Sat, 11 Apr 2020 18:16:03 +0200 Subject: [PATCH 03/65] Renaming arduino library --- arduino_foc_minimal/ArduinoFOC.h | 7 ------- arduino_foc_minimal/arduino_foc_minimal.ino | 3 ++- 2 files changed, 2 insertions(+), 8 deletions(-) delete mode 100644 arduino_foc_minimal/ArduinoFOC.h diff --git a/arduino_foc_minimal/ArduinoFOC.h b/arduino_foc_minimal/ArduinoFOC.h deleted file mode 100644 index ecb06bd6..00000000 --- a/arduino_foc_minimal/ArduinoFOC.h +++ /dev/null @@ -1,7 +0,0 @@ -#ifndef ArduinoFOC_h -#define ArduinoFOC_h - -#include "BLDCMotor.h" -#include "Encoder.h" - -#endif \ No newline at end of file diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index 568cb0ff..6ee7118e 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -1,4 +1,5 @@ -#include "ArduinoFOC.h" +#include "BLDCMotor.h" +#include "Encoder.h" // Only pins 2 and 3 are supported #define arduinoInt1 2 // Arduino UNO interrupt 0 From de693fdfd11bd47154daccdfd593b2b949b675cb Mon Sep 17 00:00:00 2001 From: askuric Date: Tue, 14 Apr 2020 06:16:36 +0200 Subject: [PATCH 04/65] renaming unipolar/bipolar to half/full bridge and testing for L6234 --- arduino_foc_minimal/BLDCMotor.cpp | 133 ++++++++------------ arduino_foc_minimal/BLDCMotor.h | 8 +- arduino_foc_minimal/Encoder.cpp | 3 +- arduino_foc_minimal/arduino_foc_minimal.ino | 91 +++++++++++--- 4 files changed, 134 insertions(+), 101 deletions(-) diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index f683d3de..1ef8b197 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -29,6 +29,8 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) PI_velocity.Ti = DEF_PI_VEL_TI; PI_velocity.timestamp = micros(); PI_velocity.u_limit = -1; + PI_velocity.uk_1 = 0; + PI_velocity.ek_1 = 0; // Ultra slow velocity // PI contoroller @@ -36,6 +38,8 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) PI_velocity_ultra_slow.Ti = DEF_PI_VEL_US_TI; PI_velocity_ultra_slow.timestamp = micros(); PI_velocity_ultra_slow.u_limit = -1; + PI_velocity_ultra_slow.uk_1 = 0; + PI_velocity_ultra_slow.ek_1 = 0; // position loop config // P controller constant @@ -44,7 +48,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) P_angle.velocity_limit = DEF_P_ANGLE_VEL_LIM; // driver deafault type - driver = DriverType::bipolar; + driver = DriverType::half_bridge; } // init hardware pins @@ -118,11 +122,13 @@ void BLDCMotor::linkEncoder(Encoder* enc) { Encoder alignment to electrical 0 angle */ void BLDCMotor::alignEncoder() { - setPhaseVoltage(12, -M_PI/2); - delay(1000); + //setPhaseVoltage(12, M_PI/2); + setPwm(pwmA,12); + setPwm(pwmB,0); + setPwm(pwmC,0); + delay(1500); encoder->setCounterZero(); - - + delay(500); setPhaseVoltage(0, 0); } @@ -191,84 +197,53 @@ void BLDCMotor::move(float target) { /** FOC methods */ -/* - Method using FOC to set Uq to the motor at the optimal angle - - for unipolar drivers - only positive values -*/ -void BLDCMotor::setPhaseVoltageUnipolar(double Uq, double angle_el) { - - // Uq sign compensation - float angle = Uq > 0 ? angle_el : normalizeAngle( angle_el + M_PI ); - // Park transform - Ualpha = abs(Uq) * cos(angle); - Ubeta = abs(Uq) * sin(angle); - - // determine the segment I, II, III - if ((angle >= 0) && (angle <= _120_D2R)) { - // section I - Ua = Ualpha + _1_SQRT3 * Ubeta; - Ub = _2_SQRT3 * Ubeta; - Uc = 0; - - } else if ((angle > _120_D2R) && (angle <= (2 * _120_D2R))) { - // section III - Ua = 0; - Ub = _1_SQRT3 * Ubeta - Ualpha; - Uc = -_1_SQRT3 * Ubeta - Ualpha; - - } else if ((angle > (2 * _120_D2R)) && (angle <= (3 * _120_D2R))) { - // section II - Ua = Ualpha - _1_SQRT3 * Ubeta; - Ub = 0; - Uc = - _2_SQRT3 * Ubeta; - } - - // set phase voltages - setPwm(pwmA, Ua); - setPwm(pwmB, Ub); - setPwm(pwmC, Uc); -} /* Method using FOC to set Uq to the motor at the optimal angle - - for bipolar drivers - posiitve and negative voltages */ -void BLDCMotor::setPhaseVoltageBipolar(double Uq, double angle_el) { - - // q component angle - float angle = angle_el + M_PI/2; +void BLDCMotor::setPhaseVoltage(double Uq, double angle_el) { + // Uq sign compensation - angle = Uq > 0 ? angle : normalizeAngle( angle + M_PI ); - + float angle = angle_el + M_PI/2.0; + // Uq sign compensation + angle = normalizeAngle(Uq > 0 ? angle : angle + M_PI ); // Park transform Ualpha = abs(Uq) * cos(angle); Ubeta = abs(Uq) * sin(angle); - - // determine the segment I, II, III - // section I - Ua = Ualpha; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta; - - // set phase voltages - setPwm(pwmA, Ua); - setPwm(pwmB, Ub); - setPwm(pwmC, Uc); -} - -/* - Method using FOC to set Uq to the motor at the optimal angle -*/ -void BLDCMotor::setPhaseVoltage(double Uq, double angle_el) { + switch (driver) { - case DriverType::bipolar : - // L6234 - setPhaseVoltageBipolar(Uq, angle_el); + case DriverType::full_bridge : + // full Clarke transform + Ua = Ualpha; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta; break; - case DriverType::unipolar : - // HMBGC - setPhaseVoltageUnipolar(Uq, angle_el); + case DriverType::half_bridge : + // HMBGC & L6234 + // Unipolar Clarke transform + // determine the segment I, II, III + if ((angle >= 0) && (angle <= _120_D2R)) { + // section I + Ua = Ualpha + _1_SQRT3 * Ubeta; + Ub = _2_SQRT3 * Ubeta; + Uc = 0; + } else if ((angle > _120_D2R) && (angle <= (2 * _120_D2R))) { + // section III + Ua = 0; + Ub = _1_SQRT3 * Ubeta - Ualpha; + Uc = -_1_SQRT3 * Ubeta - Ualpha; + } else if ((angle > (2 * _120_D2R)) && (angle <= (3 * _120_D2R))) { + // section II + Ua = Ualpha - _1_SQRT3 * Ubeta; + Ub = 0; + Uc = - _2_SQRT3 * Ubeta; + } break; } + + // set phase voltages + setPwm(pwmA, Ua); + setPwm(pwmB, Ub); + setPwm(pwmC, Uc); } @@ -280,23 +255,21 @@ void BLDCMotor::setPwm(int pinPwm, float U) { int U_max = power_supply_voltage; // uniploar or bipolar FOC switch (driver) { - case DriverType::bipolar : + case DriverType::full_bridge : // sets the voltage [-U_max,U_max] to pwm [0,255] - // - U_max you can set in header file - default 12V - // - support for L6234 drive U_pwm = ((float)U + (float)U_max) / (2.0 * (float)U_max) * 255.0; break; - case DriverType::unipolar : + case DriverType::half_bridge : // HMBGC // sets the voltage [0,12V(U_max)] to pwm [0,255] - // - U_max you can set in header file - default 12V // - support for HMBGC controller - U_pwm = 255.0 * (float)U / (float)U_max; + // - support for L6234 drive + U_pwm = (int)(255.0 * (float)U / (float)U_max); break; } // limit the values between 0 and 255; U_pwm = U_pwm < 0 ? 0 : U_pwm; - U_pwm = U_pwm > 255 ? 255 : U_pwm; + U_pwm = U_pwm >= 255 ? 255 : U_pwm; // write hardware pwm analogWrite(pinPwm, U_pwm); @@ -325,7 +298,7 @@ float BLDCMotor::velocityPI(float ek) { // u(s) = Kr(1 + 1/(Ti.s)) float uk = PI_velocity.uk_1; - uk += PI_velocity.K * (Ts / (2 * PI_velocity.Ti) + 1) * ek + PI_velocity.K * (Ts / (2 * PI_velocity.Ti) - 1) * PI_velocity.ek_1; + uk += PI_velocity.K * (Ts / (2.0 * PI_velocity.Ti) + 1.0) * ek + PI_velocity.K * (Ts / (2.0 * PI_velocity.Ti) - 1.0) * PI_velocity.ek_1; if (abs(uk) > PI_velocity.u_limit) uk = uk > 0 ? PI_velocity.u_limit : -PI_velocity.u_limit; PI_velocity.uk_1 = uk; diff --git a/arduino_foc_minimal/BLDCMotor.h b/arduino_foc_minimal/BLDCMotor.h index 8279a1e1..2c17ed05 100644 --- a/arduino_foc_minimal/BLDCMotor.h +++ b/arduino_foc_minimal/BLDCMotor.h @@ -37,8 +37,8 @@ enum ControlType{ // driver type configuration enum enum DriverType{ - bipolar, // L6234 - unipolar // HMBGC + full_bridge, + half_bridge // HMBGC & L6234 }; // P/PI controller strucutre @@ -107,6 +107,7 @@ class BLDCMotor // encoder link Encoder* encoder; + float Ua,Ub,Uc; private: //Encoder alignment to electrical 0 angle @@ -125,8 +126,6 @@ class BLDCMotor /** FOC methods */ //Method using FOC to set Uq to the motor at the optimal angle void setPhaseVoltage(double Uq, double angle_el); - void setPhaseVoltageUnipolar(double Uq, double angle_el); - void setPhaseVoltageBipolar(double Uq, double angle_el); /** Utility funcitons */ //normalizing radian angle to [0,2PI] @@ -139,7 +138,6 @@ class BLDCMotor float velocityUltraSlowPI(float ek); float positionP(float ek); - float Ua,Ub,Uc; float Ualpha,Ubeta; }; diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index e67a0960..34887bf0 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -100,13 +100,14 @@ float Encoder::getVelocity(){ // intialise counter to zero void Encoder::setCounterZero(){ pulse_counter = 0; + pulse_timestamp = micros(); } void Encoder::init(void (*doA)(), void(*doB)()){ // Encoder - check if pullup needed for your encoder - if(pullup == INTERN){ + if(pullup == Pullup::INTERN){ pinMode(pinA, INPUT_PULLUP); pinMode(pinB, INPUT_PULLUP); }else{ diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index 6ee7118e..d37f074d 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -32,9 +32,9 @@ void setup() { encoder.init(doA, doB); // set driver type - // DriverType::unipolar - // DriverType::bipolar - default - motor.driver = DriverType::bipolar; + // DriverType::half_bridge - default + // DriverType::full_bridge + motor.driver = DriverType::half_bridge; // power supply voltage // default 12V @@ -47,10 +47,36 @@ void setup() { // ControlType::angle motor.controller = ControlType::velocity; - // velocity PI controller parameters - // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 1; - motor.PI_velocity.Ti = 0.003; + // contoller configuration based on the controll type + if(motor.controller == ControlType::velocity){ + // velocity PI controller parameters + // default K=1.0 Ti = 0.003 + motor.PI_velocity.K = 0.5; + motor.PI_velocity.Ti = 0.015; + motor.PI_velocity.u_limit = 12; + }else if(motor.controller == ControlType::angle){ + // contooler settings for angle + // angle P controller + // default 20 + motor.P_angle.K = 10; + // make sure you dont exit the range of the arduino + // it depends of the range or the enocoder + // default 20 rad/s + motor.P_angle.velocity_limit = 7; + + // change the velocity PI controller + // parameters as well to get better performance + // default K=1.0 Ti = 0.003 + motor.PI_velocity.K = 0.1; + motor.PI_velocity.Ti = 0.015; + motor.PI_velocity.u_limit = 12; + }else if(motor.controller == ControlType::velocity_ultra_slow){ + // ultra slow velocity PI controller parameters + // default K=120.0 Ti = 100 + motor.PI_velocity_ultra_slow.K = 120; + motor.PI_velocity_ultra_slow.Ti = 0.01; + motor.PI_velocity_ultra_slow.u_limit = 12; + } // link the motor to the sensor motor.linkEncoder(&encoder); @@ -65,7 +91,7 @@ void setup() { } // target velocity variable -float target_velocity = 3; +float target = 0; int t = 0; void loop() { @@ -76,23 +102,23 @@ void loop() { // the best would be to be in ~10kHz range motor.loopFOC(); - // direction chnaging logic - // change direction each 1000 loop passes - target_velocity *= (t >= 1000) ? -1 : 1; - // loop passes counter - t = (t >= 1000) ? 0 : t+1; + // direction chnaging logic (comment out if you dont need it) + // // change direction each 1000 loop passes + // target *= (t >= 1000) ? -1 : 1; + // // loop passes counter + // t = (t >= 1000) ? 0 : t+1; // iterative function setting the outter loop target // velocity, position or voltage // this funciton can be run at much lower frequency than loopFOC funciton // it can go as low as ~50Hz - motor.move(target_velocity); + motor.move(target); // function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! - //motor_monitor(); + // motor_monitor(); } // utility function intended to be used with serial plotter to monitor motor variables @@ -106,6 +132,12 @@ void motor_monitor() { Serial.print(motor.shaft_velocity_sp); Serial.print("\t"); Serial.println(motor.shaft_velocity); +// Serial.print("\t"); +// Serial.print(motor.Ua); +// Serial.print("\t"); +// Serial.print(motor.Ub); +// Serial.print("\t"); +// Serial.println(motor.Uc); break; case ControlType::angle: Serial.print(motor.voltage_q); @@ -117,8 +149,37 @@ void motor_monitor() { case ControlType::voltage: Serial.print(motor.voltage_q); Serial.print("\t"); + Serial.print(motor.shaft_angle); + Serial.print("\t"); Serial.println(motor.shaft_velocity); +// Serial.print("\t"); +// Serial.print(motor.Ua); +// Serial.print("\t"); +// Serial.print(motor.Ub); +// Serial.print("\t"); +// Serial.println(motor.Uc); break; } } +// Serial communication callback +void serialEvent() { + // a string to hold incoming data + static String inputString; + while (Serial.available()) { + // get the new byte: + char inChar = (char)Serial.read(); + // add it to the inputString: + inputString += inChar; + // if the incoming character is a newline + // end of input + if (inChar == '\n') { + target = inputString.toFloat(); + Serial.print("Tagret: "); + Serial.println(target); + inputString = ""; + } + } +} + + From e0236f6cf8635e40e172c3257e19a2f041834639 Mon Sep 17 00:00:00 2001 From: askuric Date: Tue, 14 Apr 2020 06:29:51 +0200 Subject: [PATCH 05/65] added serial output to querry the target --- arduino_foc_minimal/arduino_foc_minimal.ino | 1 + 1 file changed, 1 insertion(+) diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index d37f074d..8767e394 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -87,6 +87,7 @@ void setup() { Serial.println("Motor ready."); + Serial.println("Input the new target value:"); delay(1000); } From 734d01765423d980dc98896750e781a1b93b01c7 Mon Sep 17 00:00:00 2001 From: askuric Date: Tue, 14 Apr 2020 14:28:26 +0200 Subject: [PATCH 06/65] ecnoder index init added --- arduino_foc_minimal/BLDCMotor.cpp | 31 ++++++- arduino_foc_minimal/BLDCMotor.h | 2 + arduino_foc_minimal/Encoder.cpp | 94 +++++++++++++++++---- arduino_foc_minimal/Encoder.h | 26 ++++-- arduino_foc_minimal/arduino_foc_minimal.ino | 25 +++--- 5 files changed, 142 insertions(+), 36 deletions(-) diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index 1ef8b197..b108dc38 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -49,6 +49,11 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // driver deafault type driver = DriverType::half_bridge; + + + // electric angle og the zero angle + // electric angle of the index for encoder + zero_electric_angle = 0; } // init hardware pins @@ -122,14 +127,32 @@ void BLDCMotor::linkEncoder(Encoder* enc) { Encoder alignment to electrical 0 angle */ void BLDCMotor::alignEncoder() { - //setPhaseVoltage(12, M_PI/2); setPwm(pwmA,12); setPwm(pwmB,0); setPwm(pwmC,0); - delay(1500); + delay(1000); encoder->setCounterZero(); delay(500); - setPhaseVoltage(0, 0); + setPhaseVoltage(0,0); + delay(200); + indexSearch(); + delay(500); +} +/* + Encoder alignment to electrical 0 angle +*/ +void BLDCMotor::indexSearch() { + // if no index return + if(!encoder->hasIndex()) return; + // search the index with small speed + while(!encoder->indexFound() && shaft_angle < 2 * M_PI){ + voltage_q = 3; + loopFOC(); + } + setPhaseVoltage(0,0); + + encoder->setIndexZero(); + zero_electric_angle = electricAngle(encoder->getIndexAngle()); } /** @@ -203,7 +226,7 @@ void BLDCMotor::move(float target) { void BLDCMotor::setPhaseVoltage(double Uq, double angle_el) { // Uq sign compensation - float angle = angle_el + M_PI/2.0; + float angle = angle_el + M_PI/2.0 + zero_electric_angle; // Uq sign compensation angle = normalizeAngle(Uq > 0 ? angle : angle + M_PI ); // Park transform diff --git a/arduino_foc_minimal/BLDCMotor.h b/arduino_foc_minimal/BLDCMotor.h index 2c17ed05..d30726d4 100644 --- a/arduino_foc_minimal/BLDCMotor.h +++ b/arduino_foc_minimal/BLDCMotor.h @@ -112,6 +112,7 @@ class BLDCMotor private: //Encoder alignment to electrical 0 angle void alignEncoder(); + void indexSearch(); /** State calculation methods */ //Shaft angle calculation float shaftAngle(); @@ -139,6 +140,7 @@ class BLDCMotor float positionP(float ek); float Ualpha,Ubeta; + float zero_electric_angle; }; diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index 34887bf0..9d7b9328 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -17,12 +17,13 @@ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ // counter setup pulse_counter = 0; pulse_timestamp = 0; - cpr = 4.0*_ppr; + + cpr = _ppr; A_active = 0; B_active = 0; I_active = 0; // index pin - index = _index; // its 0 if not used + index_pin = _index; // its 0 if not used // velocity calculation varibles prev_Th = 0; @@ -32,6 +33,8 @@ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ // extern pullup as default pullup = Pullup::EXTERN; + // enable quadrature encoder by default + quadrature = Quadrature::ENABLE; } // Encoder interrupt callback functions @@ -39,20 +42,50 @@ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ // A channel void Encoder::handleA() { int A = digitalRead(pinA); - if ( A != A_active ) { - pulse_counter += (A_active == B_active) ? 1 : -1; - pulse_timestamp = micros(); - A_active = A; + int I = hasIndex() ? digitalRead(index_pin) : 0; + switch (quadrature){ + case Quadrature::ENABLE: + // CPR = 4xPPR + if ( A != A_active ) { + pulse_counter += (A_active == B_active) ? 1 : -1; + pulse_timestamp = micros(); + A_active = A; + } + break; + case Quadrature::DISABLE: + // CPR = PPR + if(A && !digitalRead(pinB)){ + pulse_counter++; + pulse_timestamp = micros(); + } + break; } + if(I && !I_active) index_pulse_counter = pulse_counter; + I_active = I; } // B channel void Encoder::handleB() { int B = digitalRead(pinB); - if ( B != B_active ) { - pulse_counter += (A_active != B_active) ? 1 : -1; - pulse_timestamp = micros(); - B_active = B; + int I = hasIndex() ? digitalRead(index_pin) : 0; + switch (quadrature){ + case Quadrature::ENABLE: + // CPR = 4xPPR + if ( B != B_active ) { + pulse_counter += (A_active != B_active) ? 1 : -1; + pulse_timestamp = micros(); + B_active = B; + } + break; + case Quadrature::DISABLE: + // CPR = PPR + if(B && !digitalRead(pinA)){ + pulse_counter--; + pulse_timestamp = micros(); + } + break; } + if(I && !I_active) index_pulse_counter = pulse_counter; + I_active = I; } /* @@ -84,7 +117,7 @@ float Encoder::getVelocity(){ pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second; // if more than 0.3 passed in between impulses - if ( Th > 0.1) pulse_per_second = 0; + if ( Th > 0.15) pulse_per_second = 0; // velocity calculation float velocity = pulse_per_second / ((float)cpr) * (2.0 * M_PI); @@ -97,11 +130,31 @@ float Encoder::getVelocity(){ return (velocity); } +// getter for index pin +// return -1 if no index +int Encoder::indexFound(){ + return index_pulse_counter != 0; +} +// getter for index pin +int Encoder::hasIndex(){ + return index_pin != 0; +} +// getter for Index angle +float Encoder::getIndexAngle(){ + return (index_pulse_counter) / ((float)cpr) * (2.0 * M_PI); +} + + // intialise counter to zero void Encoder::setCounterZero(){ pulse_counter = 0; pulse_timestamp = micros(); } +// intialise index to zero +void Encoder::setIndexZero(){ + pulse_counter -= index_pulse_counter; +} + void Encoder::init(void (*doA)(), void(*doB)()){ @@ -115,7 +168,7 @@ void Encoder::init(void (*doA)(), void(*doB)()){ pinMode(pinB, INPUT); } // if index used intialise it - if(index) pinMode(index,INPUT); + if(hasIndex()) pinMode(index_pin,INPUT); // counter setup pulse_counter = 0; @@ -129,8 +182,19 @@ void Encoder::init(void (*doA)(), void(*doB)()){ // attach interrupt if functions provided if(doA != nullptr){ - // A callback and B callback - attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); - attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); + switch(quadrature){ + case Quadrature::ENABLE: + cpr = 4*cpr; + // CPR = 4xPPR + attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); + attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); + break; + case Quadrature::DISABLE: + // CPR = PPR + attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING); + attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); + break; + } + // // A callback and B callback } } diff --git a/arduino_foc_minimal/Encoder.h b/arduino_foc_minimal/Encoder.h index 07dfa273..4f5b0a7f 100644 --- a/arduino_foc_minimal/Encoder.h +++ b/arduino_foc_minimal/Encoder.h @@ -10,6 +10,11 @@ enum Pullup{ EXTERN }; +enum Quadrature{ + ENABLE, // CPR = 4xPPR + DISABLE // CPR = PPR +}; + class Encoder{ public: /* @@ -34,24 +39,31 @@ class Encoder{ // shaft velocity getter float getVelocity(); float getAngle(); + // getter for index pin + int indexFound(); + int hasIndex(); + float getIndexAngle(); // setter for counter to zero void setCounterZero(); + void setIndexZero(); // pins A and B int pinA, pinB; // encoder hardware pins // index pin - int index; + int index_pin; // encoder pullup type Pullup pullup; - + // use 4xppr or not + Quadrature quadrature; private: - long pulse_counter; // current pulse counter - long pulse_timestamp; // last impulse timestamp in us - float cpr; // impulse cpr - int A_active, B_active; // current active states of A and B line - int I_active; // index active + long pulse_counter; // current pulse counter + long pulse_timestamp; // last impulse timestamp in us + float cpr; // impulse cpr + int A_active, B_active; // current active states of A and B line + int I_active; // index active + long index_pulse_counter; // pulse counter of the index // velocity calculation varibles float prev_Th, pulse_per_second; diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index 8767e394..b20b1348 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -19,10 +19,15 @@ Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 4); void doA(){encoder.handleA();} void doB(){encoder.handleB();} -void setup() { +void setup() { // debugging port Serial.begin(115200); + // check if you need internal pullups + // Quadrature::ENABLE - CPR = 4xPPR - default + // Quadrature::DISABLE - CPR = PPR + encoder.quadrature = Quadrature::ENABLE; + // check if you need internal pullups // Pullup::EXTERN - external pullup added - dafault // Pullup::INTERN - needs internal arduino pullup @@ -51,7 +56,7 @@ void setup() { if(motor.controller == ControlType::velocity){ // velocity PI controller parameters // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 0.5; + motor.PI_velocity.K = 0.1; motor.PI_velocity.Ti = 0.015; motor.PI_velocity.u_limit = 12; }else if(motor.controller == ControlType::angle){ @@ -67,14 +72,14 @@ void setup() { // change the velocity PI controller // parameters as well to get better performance // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 0.1; - motor.PI_velocity.Ti = 0.015; + motor.PI_velocity.K = 0.4; + motor.PI_velocity.Ti = 0.01; motor.PI_velocity.u_limit = 12; }else if(motor.controller == ControlType::velocity_ultra_slow){ // ultra slow velocity PI controller parameters // default K=120.0 Ti = 100 - motor.PI_velocity_ultra_slow.K = 120; - motor.PI_velocity_ultra_slow.Ti = 0.01; + motor.PI_velocity_ultra_slow.K = 100; + motor.PI_velocity_ultra_slow.Ti = 1; motor.PI_velocity_ultra_slow.u_limit = 12; } @@ -104,10 +109,10 @@ void loop() { motor.loopFOC(); // direction chnaging logic (comment out if you dont need it) - // // change direction each 1000 loop passes - // target *= (t >= 1000) ? -1 : 1; - // // loop passes counter - // t = (t >= 1000) ? 0 : t+1; + // change direction each 1000 loop passes + target *= (t >= 1000) ? -1 : 1; + // loop passes counter + t = (t >= 1000) ? 0 : t+1; // iterative function setting the outter loop target From 47b80489a33d7064d12e6124c58e8fafdbf920a9 Mon Sep 17 00:00:00 2001 From: askuric Date: Tue, 14 Apr 2020 17:57:36 +0200 Subject: [PATCH 07/65] added support for pins 5 and 6 --- arduino_foc_minimal/BLDCMotor.cpp | 16 +++---- arduino_foc_minimal/Encoder.cpp | 49 ++++++++++++++------- arduino_foc_minimal/Encoder.h | 3 ++ arduino_foc_minimal/arduino_foc_minimal.ino | 20 ++++----- 4 files changed, 53 insertions(+), 35 deletions(-) diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index b108dc38..5bb6f74e 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -27,7 +27,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // PI contoroller constant PI_velocity.K = DEF_PI_VEL_K; PI_velocity.Ti = DEF_PI_VEL_TI; - PI_velocity.timestamp = micros(); + PI_velocity.timestamp = _micros(); PI_velocity.u_limit = -1; PI_velocity.uk_1 = 0; PI_velocity.ek_1 = 0; @@ -36,7 +36,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // PI contoroller PI_velocity_ultra_slow.K = DEF_PI_VEL_US_K; PI_velocity_ultra_slow.Ti = DEF_PI_VEL_US_TI; - PI_velocity_ultra_slow.timestamp = micros(); + PI_velocity_ultra_slow.timestamp = _micros(); PI_velocity_ultra_slow.u_limit = -1; PI_velocity_ultra_slow.uk_1 = 0; PI_velocity_ultra_slow.ek_1 = 0; @@ -317,7 +317,7 @@ double BLDCMotor::normalizeAngle(double angle) Motor control functions */ float BLDCMotor::velocityPI(float ek) { - float Ts = (micros() - PI_velocity.timestamp) * 1e-6; + float Ts = (_micros() - PI_velocity.timestamp) * 1e-6; // u(s) = Kr(1 + 1/(Ti.s)) float uk = PI_velocity.uk_1; @@ -326,13 +326,13 @@ float BLDCMotor::velocityPI(float ek) { PI_velocity.uk_1 = uk; PI_velocity.ek_1 = ek; - PI_velocity.timestamp = micros(); + PI_velocity.timestamp = _micros(); return uk; } // PI controller for ultra slow velocity control float BLDCMotor::velocityUltraSlowPI(float vel) { - float Ts = (micros() - PI_velocity_ultra_slow.timestamp) * 1e-6; + float Ts = (_micros() - PI_velocity_ultra_slow.timestamp) * 1e-6; static float angle; angle += vel * Ts; @@ -345,7 +345,7 @@ float BLDCMotor::velocityUltraSlowPI(float vel) { PI_velocity_ultra_slow.uk_1 = uk; PI_velocity_ultra_slow.ek_1 = ek; - PI_velocity_ultra_slow.timestamp = micros(); + PI_velocity_ultra_slow.timestamp = _micros(); return uk; } // P controller for position control loop @@ -372,7 +372,3 @@ void setPwmFrequency(int pin) { } } - - - - diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index 9d7b9328..9b2d9b40 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -29,7 +29,7 @@ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ prev_Th = 0; pulse_per_second = 0; prev_pulse_counter = 0; - prev_timestamp_us = micros(); + prev_timestamp_us = _micros(); // extern pullup as default pullup = Pullup::EXTERN; @@ -42,13 +42,12 @@ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ // A channel void Encoder::handleA() { int A = digitalRead(pinA); - int I = hasIndex() ? digitalRead(index_pin) : 0; switch (quadrature){ case Quadrature::ENABLE: // CPR = 4xPPR if ( A != A_active ) { pulse_counter += (A_active == B_active) ? 1 : -1; - pulse_timestamp = micros(); + pulse_timestamp = _micros(); A_active = A; } break; @@ -56,23 +55,29 @@ void Encoder::handleA() { // CPR = PPR if(A && !digitalRead(pinB)){ pulse_counter++; - pulse_timestamp = micros(); + pulse_timestamp = _micros(); } break; } - if(I && !I_active) index_pulse_counter = pulse_counter; - I_active = I; + if(hasIndex()){ + int I = digitalRead(index_pin); + if(I && !I_active){ + index_pulse_counter = pulse_counter; + // aling encoder on each index + pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; + } + I_active = I; + } } // B channel void Encoder::handleB() { int B = digitalRead(pinB); - int I = hasIndex() ? digitalRead(index_pin) : 0; switch (quadrature){ case Quadrature::ENABLE: // CPR = 4xPPR if ( B != B_active ) { pulse_counter += (A_active != B_active) ? 1 : -1; - pulse_timestamp = micros(); + pulse_timestamp = _micros(); B_active = B; } break; @@ -80,12 +85,20 @@ void Encoder::handleB() { // CPR = PPR if(B && !digitalRead(pinA)){ pulse_counter--; - pulse_timestamp = micros(); + pulse_timestamp = _micros(); } break; } - if(I && !I_active) index_pulse_counter = pulse_counter; - I_active = I; + if(hasIndex()){ + int I = digitalRead(index_pin); + if(I && !I_active){ + index_pulse_counter = pulse_counter; + // aling encoder on each index + pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; + prev_pulse_counter = pulse_counter; + } + I_active = I; + } } /* @@ -100,7 +113,7 @@ float Encoder::getAngle(){ */ float Encoder::getVelocity(){ // timestamp - long timestamp_us = micros(); + long timestamp_us = _micros(); // sampling time calculation float Ts = (timestamp_us - prev_timestamp_us) * 1e-6; // time from last impulse @@ -148,11 +161,12 @@ float Encoder::getIndexAngle(){ // intialise counter to zero void Encoder::setCounterZero(){ pulse_counter = 0; - pulse_timestamp = micros(); + pulse_timestamp = _micros(); } // intialise index to zero void Encoder::setIndexZero(){ pulse_counter -= index_pulse_counter; + prev_pulse_counter = pulse_counter; } @@ -172,12 +186,12 @@ void Encoder::init(void (*doA)(), void(*doB)()){ // counter setup pulse_counter = 0; - pulse_timestamp = micros(); + pulse_timestamp = _micros(); // velocity calculation varibles prev_Th = 0; pulse_per_second = 0; prev_pulse_counter = 0; - prev_timestamp_us = micros(); + prev_timestamp_us = _micros(); // attach interrupt if functions provided @@ -198,3 +212,8 @@ void Encoder::init(void (*doA)(), void(*doB)()){ // // A callback and B callback } } + + +long _micros(){ + return micros()/64.0; +} diff --git a/arduino_foc_minimal/Encoder.h b/arduino_foc_minimal/Encoder.h index 4f5b0a7f..84180911 100644 --- a/arduino_foc_minimal/Encoder.h +++ b/arduino_foc_minimal/Encoder.h @@ -72,4 +72,7 @@ class Encoder{ }; +long _micros(); + + #endif diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index b20b1348..5d5d4f2b 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -9,12 +9,12 @@ // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); +BLDCMotor motor = BLDCMotor(9, 10, 6, 11, 8); // Encoder(int encA, int encB , int cpr, int index) // - encA, encB - encoder A and B pins // - ppr - impulses per rotation (cpr=ppr*4) // - index pin - (optional input) -Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 4); +Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192); // interrupt ruotine intialisation void doA(){encoder.handleA();} void doB(){encoder.handleB();} @@ -56,8 +56,8 @@ void setup() { if(motor.controller == ControlType::velocity){ // velocity PI controller parameters // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 0.1; - motor.PI_velocity.Ti = 0.015; + motor.PI_velocity.K = 0.5; + motor.PI_velocity.Ti = 0.007; motor.PI_velocity.u_limit = 12; }else if(motor.controller == ControlType::angle){ // contooler settings for angle @@ -72,7 +72,7 @@ void setup() { // change the velocity PI controller // parameters as well to get better performance // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 0.4; + motor.PI_velocity.K = 0.1; motor.PI_velocity.Ti = 0.01; motor.PI_velocity.u_limit = 12; }else if(motor.controller == ControlType::velocity_ultra_slow){ @@ -108,11 +108,11 @@ void loop() { // the best would be to be in ~10kHz range motor.loopFOC(); - // direction chnaging logic (comment out if you dont need it) - // change direction each 1000 loop passes - target *= (t >= 1000) ? -1 : 1; - // loop passes counter - t = (t >= 1000) ? 0 : t+1; + // // direction chnaging logic (comment out if you dont need it) + // // change direction each 1000 loop passes + // target *= (t >= 1000) ? -1 : 1; + // // loop passes counter + // t = (t >= 1000) ? 0 : t+1; // iterative function setting the outter loop target From 20314b356e612a7a34694c4270309fb37713c1ba Mon Sep 17 00:00:00 2001 From: askuric Date: Wed, 15 Apr 2020 11:19:29 +0200 Subject: [PATCH 08/65] - --- arduino_foc_minimal/Encoder.cpp | 2 +- arduino_foc_minimal/arduino_foc_minimal.ino | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index 9b2d9b40..2465a2d3 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -215,5 +215,5 @@ void Encoder::init(void (*doA)(), void(*doB)()){ long _micros(){ - return micros()/64.0; + return micros(); } diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index 5d5d4f2b..3f2968ca 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -9,7 +9,7 @@ // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 6, 11, 8); +BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); // Encoder(int encA, int encB , int cpr, int index) // - encA, encB - encoder A and B pins // - ppr - impulses per rotation (cpr=ppr*4) @@ -56,9 +56,9 @@ void setup() { if(motor.controller == ControlType::velocity){ // velocity PI controller parameters // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 0.5; + motor.PI_velocity.K = 0.9; motor.PI_velocity.Ti = 0.007; - motor.PI_velocity.u_limit = 12; + motor.PI_velocity.u_limit = 7; }else if(motor.controller == ControlType::angle){ // contooler settings for angle // angle P controller @@ -124,7 +124,7 @@ void loop() { // function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! - // motor_monitor(); + //motor_monitor(); } // utility function intended to be used with serial plotter to monitor motor variables From d67e130bd4e6fde2975855592f10027967859444 Mon Sep 17 00:00:00 2001 From: askuric Date: Fri, 17 Apr 2020 15:54:12 +0200 Subject: [PATCH 09/65] FEATURE Encoder index added --- arduino_foc_minimal/BLDCMotor.cpp | 26 ++++++++--- arduino_foc_minimal/BLDCMotor.h | 12 +++-- arduino_foc_minimal/Encoder.cpp | 20 ++++++-- arduino_foc_minimal/Encoder.h | 12 ++--- arduino_foc_minimal/arduino_foc_minimal.ino | 52 ++++++++------------- 5 files changed, 69 insertions(+), 53 deletions(-) diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index 5bb6f74e..aaf0d32c 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -53,7 +53,9 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // electric angle og the zero angle // electric angle of the index for encoder - zero_electric_angle = 0; + index_electric_angle = 0; + // index search voltage + index_search_voltage = DEF_INDEX_SEARCH_VOLTAGE; } // init hardware pins @@ -127,17 +129,23 @@ void BLDCMotor::linkEncoder(Encoder* enc) { Encoder alignment to electrical 0 angle */ void BLDCMotor::alignEncoder() { + // align the electircal phases of the motor and encoder setPwm(pwmA,12); setPwm(pwmB,0); setPwm(pwmC,0); delay(1000); + // set encoder to zero encoder->setCounterZero(); delay(500); setPhaseVoltage(0,0); delay(200); + + // find the index if available indexSearch(); delay(500); } + + /* Encoder alignment to electrical 0 angle */ @@ -146,13 +154,19 @@ void BLDCMotor::indexSearch() { if(!encoder->hasIndex()) return; // search the index with small speed while(!encoder->indexFound() && shaft_angle < 2 * M_PI){ - voltage_q = 3; + voltage_q = index_search_voltage; loopFOC(); } - setPhaseVoltage(0,0); - encoder->setIndexZero(); - zero_electric_angle = electricAngle(encoder->getIndexAngle()); + // set index to zero if it has been found + if(encoder->indexFound()){ + encoder->setIndexZero(); + // remember index electric angle + index_electric_angle = electricAngle(encoder->getIndexAngle()); + } + + // disable motor + setPhaseVoltage(0,0); } /** @@ -226,7 +240,7 @@ void BLDCMotor::move(float target) { void BLDCMotor::setPhaseVoltage(double Uq, double angle_el) { // Uq sign compensation - float angle = angle_el + M_PI/2.0 + zero_electric_angle; + float angle = angle_el + M_PI/2.0 + index_electric_angle; // Uq sign compensation angle = normalizeAngle(Uq > 0 ? angle : angle + M_PI ); // Park transform diff --git a/arduino_foc_minimal/BLDCMotor.h b/arduino_foc_minimal/BLDCMotor.h index d30726d4..03048acf 100644 --- a/arduino_foc_minimal/BLDCMotor.h +++ b/arduino_foc_minimal/BLDCMotor.h @@ -17,6 +17,9 @@ #define DEF_P_ANGLE_K 20 // angle velocity limit default #define DEF_P_ANGLE_VEL_LIM 20 +// index search voltage +#define DEF_INDEX_SEARCH_VOLTAGE 3 + // sign funciton #define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) @@ -106,8 +109,11 @@ class BLDCMotor // encoder link Encoder* encoder; - - float Ua,Ub,Uc; + + // index electric angle - if available + float index_electric_angle; + // index search voltage + float index_search_voltage; private: //Encoder alignment to electrical 0 angle @@ -140,7 +146,7 @@ class BLDCMotor float positionP(float ek); float Ualpha,Ubeta; - float zero_electric_angle; + float Ua,Ub,Uc; }; diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index 2465a2d3..d3f6a6c8 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -24,6 +24,7 @@ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ I_active = 0; // index pin index_pin = _index; // its 0 if not used + index_pulse_counter = 0; // velocity calculation varibles prev_Th = 0; @@ -62,9 +63,14 @@ void Encoder::handleA() { if(hasIndex()){ int I = digitalRead(index_pin); if(I && !I_active){ - index_pulse_counter = pulse_counter; // aling encoder on each index - pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; + if(index_pulse_counter){ + long tmp = pulse_counter; + pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; + prev_pulse_counter = pulse_counter + (tmp-prev_pulse_counter); + } + // initial offset + if(!index_pulse_counter) index_pulse_counter = pulse_counter; } I_active = I; } @@ -92,10 +98,14 @@ void Encoder::handleB() { if(hasIndex()){ int I = digitalRead(index_pin); if(I && !I_active){ - index_pulse_counter = pulse_counter; // aling encoder on each index - pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; - prev_pulse_counter = pulse_counter; + if(index_pulse_counter){ + long tmp = pulse_counter; + pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; + prev_pulse_counter = pulse_counter + (tmp-prev_pulse_counter); + } + // initial offset + if(!index_pulse_counter) index_pulse_counter = pulse_counter; } I_active = I; } diff --git a/arduino_foc_minimal/Encoder.h b/arduino_foc_minimal/Encoder.h index 84180911..6e9a5f34 100644 --- a/arduino_foc_minimal/Encoder.h +++ b/arduino_foc_minimal/Encoder.h @@ -58,16 +58,16 @@ class Encoder{ Quadrature quadrature; private: - long pulse_counter; // current pulse counter - long pulse_timestamp; // last impulse timestamp in us + volatile long pulse_counter; // current pulse counter + volatile long pulse_timestamp; // last impulse timestamp in us float cpr; // impulse cpr - int A_active, B_active; // current active states of A and B line - int I_active; // index active - long index_pulse_counter; // pulse counter of the index + volatile int A_active, B_active; // current active states of A and B line + volatile int I_active; // index active + volatile long index_pulse_counter; // pulse counter of the index // velocity calculation varibles float prev_Th, pulse_per_second; - long prev_pulse_counter, prev_timestamp_us; + volatile long prev_pulse_counter, prev_timestamp_us; }; diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index 3f2968ca..d62506c6 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -14,7 +14,7 @@ BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); // - encA, encB - encoder A and B pins // - ppr - impulses per rotation (cpr=ppr*4) // - index pin - (optional input) -Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192); +Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 4); // interrupt ruotine intialisation void doA(){encoder.handleA();} void doB(){encoder.handleB();} @@ -39,7 +39,7 @@ void setup() { // set driver type // DriverType::half_bridge - default // DriverType::full_bridge - motor.driver = DriverType::half_bridge; + motor.driver = DriverType::full_bridge; // power supply voltage // default 12V @@ -50,38 +50,22 @@ void setup() { // ControlType::velocity // ControlType::velocity_ultra_slow // ControlType::angle - motor.controller = ControlType::velocity; + motor.controller = ControlType::angle; // contoller configuration based on the controll type - if(motor.controller == ControlType::velocity){ - // velocity PI controller parameters - // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 0.9; - motor.PI_velocity.Ti = 0.007; - motor.PI_velocity.u_limit = 7; - }else if(motor.controller == ControlType::angle){ - // contooler settings for angle - // angle P controller - // default 20 - motor.P_angle.K = 10; - // make sure you dont exit the range of the arduino - // it depends of the range or the enocoder - // default 20 rad/s - motor.P_angle.velocity_limit = 7; - - // change the velocity PI controller - // parameters as well to get better performance - // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 0.1; - motor.PI_velocity.Ti = 0.01; - motor.PI_velocity.u_limit = 12; - }else if(motor.controller == ControlType::velocity_ultra_slow){ - // ultra slow velocity PI controller parameters - // default K=120.0 Ti = 100 - motor.PI_velocity_ultra_slow.K = 100; - motor.PI_velocity_ultra_slow.Ti = 1; - motor.PI_velocity_ultra_slow.u_limit = 12; - } + // velocity PI controller parameters + // default K=1.0 Ti = 0.003 + motor.PI_velocity.K = 0.9; + motor.PI_velocity.Ti = 0.007; + motor.PI_velocity.u_limit = 4; + + // angle loop setting + motor.P_angle.K = 20; + motor.P_angle.velocity_limit = 5; + + + // index search - default 3V + motor.index_search_voltage = 4; // link the motor to the sensor motor.linkEncoder(&encoder); @@ -137,7 +121,9 @@ void motor_monitor() { Serial.print("\t"); Serial.print(motor.shaft_velocity_sp); Serial.print("\t"); - Serial.println(motor.shaft_velocity); + Serial.print(motor.shaft_velocity); + Serial.print("\t"); + Serial.println(motor.shaft_angle); // Serial.print("\t"); // Serial.print(motor.Ua); // Serial.print("\t"); From 6a5b3f47c47c4b423923a6b537c23d87fabe37e5 Mon Sep 17 00:00:00 2001 From: askuric Date: Sat, 18 Apr 2020 17:38:24 +0200 Subject: [PATCH 10/65] Added index usage and the debugging --- arduino_foc_minimal/.vscode/arduino.json | 5 + .../.vscode/c_cpp_properties.json | 19 +++ arduino_foc_minimal/BLDCMotor.cpp | 109 ++++++++---------- arduino_foc_minimal/BLDCMotor.h | 28 +++-- arduino_foc_minimal/Encoder.cpp | 4 +- arduino_foc_minimal/arduino_foc_minimal.ino | 49 ++------ 6 files changed, 96 insertions(+), 118 deletions(-) create mode 100644 arduino_foc_minimal/.vscode/arduino.json create mode 100644 arduino_foc_minimal/.vscode/c_cpp_properties.json diff --git a/arduino_foc_minimal/.vscode/arduino.json b/arduino_foc_minimal/.vscode/arduino.json new file mode 100644 index 00000000..5b873481 --- /dev/null +++ b/arduino_foc_minimal/.vscode/arduino.json @@ -0,0 +1,5 @@ +{ + "board": "arduino:avr:uno", + "port": "COM56", + "sketch": "arduino_foc_minimal.ino" +} \ No newline at end of file diff --git a/arduino_foc_minimal/.vscode/c_cpp_properties.json b/arduino_foc_minimal/.vscode/c_cpp_properties.json new file mode 100644 index 00000000..933d05b7 --- /dev/null +++ b/arduino_foc_minimal/.vscode/c_cpp_properties.json @@ -0,0 +1,19 @@ +{ + "configurations": [ + { + "name": "Win32", + "includePath": [ + "C:\\Users\\Gospar\\AppData\\Local\\Arduino15\\packages\\arduino\\tools\\**", + "C:\\Users\\Gospar\\AppData\\Local\\Arduino15\\packages\\arduino\\hardware\\avr\\1.6.23\\**" + ], + "forcedInclude": [ + "C:\\Users\\Gospar\\AppData\\Local\\Arduino15\\packages\\arduino\\hardware\\avr\\1.6.23\\cores\\arduino\\Arduino.h" + ], + "intelliSenseMode": "msvc-x64", + "compilerPath": "C:/Program Files (x86)/Microsoft Visual Studio/2019/BuildTools/VC/Tools/MSVC/14.24.28314/bin/Hostx64/x64/cl.exe", + "cStandard": "c11", + "cppStandard": "c++17" + } + ], + "version": 4 +} \ No newline at end of file diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index aaf0d32c..c0f9eedd 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -46,26 +46,27 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) P_angle.K = DEF_P_ANGLE_K; // maximum angular velocity to be used for positioning P_angle.velocity_limit = DEF_P_ANGLE_VEL_LIM; - - // driver deafault type - driver = DriverType::half_bridge; - // electric angle og the zero angle // electric angle of the index for encoder index_electric_angle = 0; - // index search voltage - index_search_voltage = DEF_INDEX_SEARCH_VOLTAGE; + // index search velocity + index_search_velocity = DEF_INDEX_SEARCH_VELOCITY; + + //debugger + debugger = nullptr; } -// init hardware pins +// init hardware pins void BLDCMotor::init() { + if(debugger) debugger->println("DEBUG: Initilaise the motor pins."); // PWM pins pinMode(pwmA, OUTPUT); pinMode(pwmB, OUTPUT); pinMode(pwmC, OUTPUT); pinMode(enable_pin, OUTPUT); + if(debugger) debugger->println("DEBUG: Set high frequency PWM."); // Increase PWM frequency to 32 kHz // make silent setPwmFrequency(pwmA); @@ -74,8 +75,9 @@ void BLDCMotor::init() { // check if u_limit configuration has been done. // if not set it to the power_supply_voltage - if(PI_velocity.u_limit == -1) PI_velocity.u_limit = power_supply_voltage; - if(PI_velocity_ultra_slow.u_limit == -1) PI_velocity_ultra_slow.u_limit = power_supply_voltage; + // or if set too high + if(PI_velocity.u_limit == -1 || PI_velocity.u_limit > power_supply_voltage/2) PI_velocity.u_limit = power_supply_voltage; + if(PI_velocity_ultra_slow.u_limit == -1 || PI_velocity.u_limit > power_supply_voltage/2) PI_velocity_ultra_slow.u_limit = power_supply_voltage; delay(500); // enable motor @@ -87,11 +89,12 @@ void BLDCMotor::init() { /* initialization function */ -void BLDCMotor::initFOC() { +int BLDCMotor::initFOC() { // encoder alignment delay(500); - alignEncoder(); + int exit_flag = alignEncoder(); delay(500); + return exit_flag; } /* @@ -128,7 +131,8 @@ void BLDCMotor::linkEncoder(Encoder* enc) { /* Encoder alignment to electrical 0 angle */ -void BLDCMotor::alignEncoder() { +int BLDCMotor::alignEncoder() { + if(debugger) debugger->println("DEBUG: Align the encoder and motor electrical 0 angle."); // align the electircal phases of the motor and encoder setPwm(pwmA,12); setPwm(pwmB,0); @@ -140,21 +144,27 @@ void BLDCMotor::alignEncoder() { setPhaseVoltage(0,0); delay(200); + if(debugger) debugger->println("DEBUG: Search for the encoder index - if available."); // find the index if available - indexSearch(); + int exit_flag = indexSearch(); delay(500); + if(debugger){ + if(exit_flag< 0 ) debugger->println("DEBUG: Error: Index not found!"); + if(exit_flag> 0 ) debugger->println("DEBUG: Success: Index found!"); + } + return exit_flag; } /* Encoder alignment to electrical 0 angle */ -void BLDCMotor::indexSearch() { +int BLDCMotor::indexSearch() { // if no index return - if(!encoder->hasIndex()) return; + if(!encoder->hasIndex()) return 0; // search the index with small speed while(!encoder->indexFound() && shaft_angle < 2 * M_PI){ - voltage_q = index_search_voltage; + voltage_q = velocityPI(index_search_velocity - shaftVelocity()); loopFOC(); } @@ -167,6 +177,8 @@ void BLDCMotor::indexSearch() { // disable motor setPhaseVoltage(0,0); + + return encoder->indexFound() ? 1 : -1; } /** @@ -240,42 +252,17 @@ void BLDCMotor::move(float target) { void BLDCMotor::setPhaseVoltage(double Uq, double angle_el) { // Uq sign compensation - float angle = angle_el + M_PI/2.0 + index_electric_angle; + float angle = angle_el + index_electric_angle; // Uq sign compensation angle = normalizeAngle(Uq > 0 ? angle : angle + M_PI ); - // Park transform - Ualpha = abs(Uq) * cos(angle); - Ubeta = abs(Uq) * sin(angle); + // Inverse park transform + Ualpha = -sin(angle) * abs(Uq); + Ubeta = cos(angle) * abs(Uq); - switch (driver) { - case DriverType::full_bridge : - // full Clarke transform - Ua = Ualpha; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta; - break; - case DriverType::half_bridge : - // HMBGC & L6234 - // Unipolar Clarke transform - // determine the segment I, II, III - if ((angle >= 0) && (angle <= _120_D2R)) { - // section I - Ua = Ualpha + _1_SQRT3 * Ubeta; - Ub = _2_SQRT3 * Ubeta; - Uc = 0; - } else if ((angle > _120_D2R) && (angle <= (2 * _120_D2R))) { - // section III - Ua = 0; - Ub = _1_SQRT3 * Ubeta - Ualpha; - Uc = -_1_SQRT3 * Ubeta - Ualpha; - } else if ((angle > (2 * _120_D2R)) && (angle <= (3 * _120_D2R))) { - // section II - Ua = Ualpha - _1_SQRT3 * Ubeta; - Ub = 0; - Uc = - _2_SQRT3 * Ubeta; - } - break; - } + // Clarke transform + Ua = Ualpha; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta; // set phase voltages setPwm(pwmA, Ua); @@ -289,21 +276,11 @@ void BLDCMotor::setPhaseVoltage(double Uq, double angle_el) { */ void BLDCMotor::setPwm(int pinPwm, float U) { int U_pwm = 0; - int U_max = power_supply_voltage; - // uniploar or bipolar FOC - switch (driver) { - case DriverType::full_bridge : - // sets the voltage [-U_max,U_max] to pwm [0,255] - U_pwm = ((float)U + (float)U_max) / (2.0 * (float)U_max) * 255.0; - break; - case DriverType::half_bridge : - // HMBGC - // sets the voltage [0,12V(U_max)] to pwm [0,255] - // - support for HMBGC controller - // - support for L6234 drive - U_pwm = (int)(255.0 * (float)U / (float)U_max); - break; - } + float U_max = power_supply_voltage/2.0; + + // sets the voltage [-U_max,U_max] to pwm [0,255] + U_pwm = ((float)U + (float)U_max) / (2.0 * (float)U_max) * 255.0; + // limit the values between 0 and 255; U_pwm = U_pwm < 0 ? 0 : U_pwm; U_pwm = U_pwm >= 255 ? 255 : U_pwm; @@ -369,6 +346,10 @@ float BLDCMotor::positionP(float ek) { return velk; } +void BLDCMotor::useDebugging(Print &print){ + debugger = &print; //operate on the adress of print +} + /* High PWM frequency diff --git a/arduino_foc_minimal/BLDCMotor.h b/arduino_foc_minimal/BLDCMotor.h index 03048acf..7bed9798 100644 --- a/arduino_foc_minimal/BLDCMotor.h +++ b/arduino_foc_minimal/BLDCMotor.h @@ -17,8 +17,8 @@ #define DEF_P_ANGLE_K 20 // angle velocity limit default #define DEF_P_ANGLE_VEL_LIM 20 -// index search voltage -#define DEF_INDEX_SEARCH_VOLTAGE 3 +// index search velocity +#define DEF_INDEX_SEARCH_VELOCITY 1 // sign funciton @@ -38,12 +38,6 @@ enum ControlType{ angle }; -// driver type configuration enum -enum DriverType{ - full_bridge, - half_bridge // HMBGC & L6234 -}; - // P/PI controller strucutre struct PI_s{ float K; @@ -69,7 +63,7 @@ class BLDCMotor void linkEncoder(Encoder* enc); // initilise FOC - void initFOC(); + int initFOC(); // iterative method updating motor angles and velocity measurement void loopFOC(); // iterative control loop defined by controller @@ -101,7 +95,6 @@ class BLDCMotor float power_supply_voltage; // configuraion structures - DriverType driver; ControlType controller; PI_s PI_velocity; PI_s PI_velocity_ultra_slow; @@ -109,16 +102,21 @@ class BLDCMotor // encoder link Encoder* encoder; - // index electric angle - if available float index_electric_angle; - // index search voltage - float index_search_voltage; + // index search velocity + float index_search_velocity; + + + + // debugging + void useDebugging(Print &print); + Print* debugger; private: //Encoder alignment to electrical 0 angle - void alignEncoder(); - void indexSearch(); + int alignEncoder(); + int indexSearch(); /** State calculation methods */ //Shaft angle calculation float shaftAngle(); diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index d3f6a6c8..a53e32cd 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -67,7 +67,7 @@ void Encoder::handleA() { if(index_pulse_counter){ long tmp = pulse_counter; pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; - prev_pulse_counter = pulse_counter + (tmp-prev_pulse_counter); + prev_pulse_counter = pulse_counter - (tmp-prev_pulse_counter); } // initial offset if(!index_pulse_counter) index_pulse_counter = pulse_counter; @@ -102,7 +102,7 @@ void Encoder::handleB() { if(index_pulse_counter){ long tmp = pulse_counter; pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; - prev_pulse_counter = pulse_counter + (tmp-prev_pulse_counter); + prev_pulse_counter = pulse_counter - (tmp-prev_pulse_counter); } // initial offset if(!index_pulse_counter) index_pulse_counter = pulse_counter; diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index d62506c6..32031d3b 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -36,11 +36,6 @@ void setup() { // initialise encoder hardware encoder.init(doA, doB); - // set driver type - // DriverType::half_bridge - default - // DriverType::full_bridge - motor.driver = DriverType::full_bridge; - // power supply voltage // default 12V motor.power_supply_voltage = 12; @@ -50,31 +45,31 @@ void setup() { // ControlType::velocity // ControlType::velocity_ultra_slow // ControlType::angle - motor.controller = ControlType::angle; + motor.controller = ControlType::velocity; // contoller configuration based on the controll type // velocity PI controller parameters // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 0.9; - motor.PI_velocity.Ti = 0.007; + motor.PI_velocity.K = 0.3; + motor.PI_velocity.Ti = 0.003; + //defualt power_supply_voltage/2 motor.PI_velocity.u_limit = 4; - // angle loop setting - motor.P_angle.K = 20; - motor.P_angle.velocity_limit = 5; - - - // index search - default 3V - motor.index_search_voltage = 4; + // index search velocity - default 1 rad/s + motor.index_search_velocity = 2; // link the motor to the sensor motor.linkEncoder(&encoder); + + // use debugging with serial for motor init + // comment out if not needed + motor.useDebugging(Serial); + // intialise motor motor.init(); // align encoder and start FOC motor.initFOC(); - Serial.println("Motor ready."); Serial.println("Input the new target value:"); delay(1000); @@ -82,7 +77,6 @@ void setup() { // target velocity variable float target = 0; -int t = 0; void loop() { // iterative state calculation calculating angle @@ -92,13 +86,6 @@ void loop() { // the best would be to be in ~10kHz range motor.loopFOC(); - // // direction chnaging logic (comment out if you dont need it) - // // change direction each 1000 loop passes - // target *= (t >= 1000) ? -1 : 1; - // // loop passes counter - // t = (t >= 1000) ? 0 : t+1; - - // iterative function setting the outter loop target // velocity, position or voltage // this funciton can be run at much lower frequency than loopFOC funciton @@ -108,7 +95,7 @@ void loop() { // function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! - //motor_monitor(); + // motor_monitor(); } // utility function intended to be used with serial plotter to monitor motor variables @@ -124,12 +111,6 @@ void motor_monitor() { Serial.print(motor.shaft_velocity); Serial.print("\t"); Serial.println(motor.shaft_angle); -// Serial.print("\t"); -// Serial.print(motor.Ua); -// Serial.print("\t"); -// Serial.print(motor.Ub); -// Serial.print("\t"); -// Serial.println(motor.Uc); break; case ControlType::angle: Serial.print(motor.voltage_q); @@ -144,12 +125,6 @@ void motor_monitor() { Serial.print(motor.shaft_angle); Serial.print("\t"); Serial.println(motor.shaft_velocity); -// Serial.print("\t"); -// Serial.print(motor.Ua); -// Serial.print("\t"); -// Serial.print(motor.Ub); -// Serial.print("\t"); -// Serial.println(motor.Uc); break; } } From 3e12822e8493666db94404459ff74519460fa721 Mon Sep 17 00:00:00 2001 From: askuric Date: Sat, 18 Apr 2020 17:46:49 +0200 Subject: [PATCH 11/65] removed micros buffering funciton --- arduino_foc_minimal/.vscode/arduino.json | 2 +- arduino_foc_minimal/BLDCMotor.cpp | 12 ++++++------ arduino_foc_minimal/Encoder.cpp | 23 +++++++++-------------- arduino_foc_minimal/Encoder.h | 4 ---- 4 files changed, 16 insertions(+), 25 deletions(-) diff --git a/arduino_foc_minimal/.vscode/arduino.json b/arduino_foc_minimal/.vscode/arduino.json index 5b873481..60b455d8 100644 --- a/arduino_foc_minimal/.vscode/arduino.json +++ b/arduino_foc_minimal/.vscode/arduino.json @@ -1,5 +1,5 @@ { "board": "arduino:avr:uno", - "port": "COM56", + "port": "COM57", "sketch": "arduino_foc_minimal.ino" } \ No newline at end of file diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index c0f9eedd..29d76a04 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -27,7 +27,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // PI contoroller constant PI_velocity.K = DEF_PI_VEL_K; PI_velocity.Ti = DEF_PI_VEL_TI; - PI_velocity.timestamp = _micros(); + PI_velocity.timestamp = micros(); PI_velocity.u_limit = -1; PI_velocity.uk_1 = 0; PI_velocity.ek_1 = 0; @@ -36,7 +36,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // PI contoroller PI_velocity_ultra_slow.K = DEF_PI_VEL_US_K; PI_velocity_ultra_slow.Ti = DEF_PI_VEL_US_TI; - PI_velocity_ultra_slow.timestamp = _micros(); + PI_velocity_ultra_slow.timestamp = micros(); PI_velocity_ultra_slow.u_limit = -1; PI_velocity_ultra_slow.uk_1 = 0; PI_velocity_ultra_slow.ek_1 = 0; @@ -308,7 +308,7 @@ double BLDCMotor::normalizeAngle(double angle) Motor control functions */ float BLDCMotor::velocityPI(float ek) { - float Ts = (_micros() - PI_velocity.timestamp) * 1e-6; + float Ts = (micros() - PI_velocity.timestamp) * 1e-6; // u(s) = Kr(1 + 1/(Ti.s)) float uk = PI_velocity.uk_1; @@ -317,13 +317,13 @@ float BLDCMotor::velocityPI(float ek) { PI_velocity.uk_1 = uk; PI_velocity.ek_1 = ek; - PI_velocity.timestamp = _micros(); + PI_velocity.timestamp = micros(); return uk; } // PI controller for ultra slow velocity control float BLDCMotor::velocityUltraSlowPI(float vel) { - float Ts = (_micros() - PI_velocity_ultra_slow.timestamp) * 1e-6; + float Ts = (micros() - PI_velocity_ultra_slow.timestamp) * 1e-6; static float angle; angle += vel * Ts; @@ -336,7 +336,7 @@ float BLDCMotor::velocityUltraSlowPI(float vel) { PI_velocity_ultra_slow.uk_1 = uk; PI_velocity_ultra_slow.ek_1 = ek; - PI_velocity_ultra_slow.timestamp = _micros(); + PI_velocity_ultra_slow.timestamp = micros(); return uk; } // P controller for position control loop diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index a53e32cd..16a9767a 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -30,7 +30,7 @@ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ prev_Th = 0; pulse_per_second = 0; prev_pulse_counter = 0; - prev_timestamp_us = _micros(); + prev_timestamp_us = micros(); // extern pullup as default pullup = Pullup::EXTERN; @@ -48,7 +48,7 @@ void Encoder::handleA() { // CPR = 4xPPR if ( A != A_active ) { pulse_counter += (A_active == B_active) ? 1 : -1; - pulse_timestamp = _micros(); + pulse_timestamp = micros(); A_active = A; } break; @@ -56,7 +56,7 @@ void Encoder::handleA() { // CPR = PPR if(A && !digitalRead(pinB)){ pulse_counter++; - pulse_timestamp = _micros(); + pulse_timestamp = micros(); } break; } @@ -83,7 +83,7 @@ void Encoder::handleB() { // CPR = 4xPPR if ( B != B_active ) { pulse_counter += (A_active != B_active) ? 1 : -1; - pulse_timestamp = _micros(); + pulse_timestamp = micros(); B_active = B; } break; @@ -91,7 +91,7 @@ void Encoder::handleB() { // CPR = PPR if(B && !digitalRead(pinA)){ pulse_counter--; - pulse_timestamp = _micros(); + pulse_timestamp = micros(); } break; } @@ -123,7 +123,7 @@ float Encoder::getAngle(){ */ float Encoder::getVelocity(){ // timestamp - long timestamp_us = _micros(); + long timestamp_us = micros(); // sampling time calculation float Ts = (timestamp_us - prev_timestamp_us) * 1e-6; // time from last impulse @@ -171,7 +171,7 @@ float Encoder::getIndexAngle(){ // intialise counter to zero void Encoder::setCounterZero(){ pulse_counter = 0; - pulse_timestamp = _micros(); + pulse_timestamp = micros(); } // intialise index to zero void Encoder::setIndexZero(){ @@ -196,12 +196,12 @@ void Encoder::init(void (*doA)(), void(*doB)()){ // counter setup pulse_counter = 0; - pulse_timestamp = _micros(); + pulse_timestamp = micros(); // velocity calculation varibles prev_Th = 0; pulse_per_second = 0; prev_pulse_counter = 0; - prev_timestamp_us = _micros(); + prev_timestamp_us = micros(); // attach interrupt if functions provided @@ -222,8 +222,3 @@ void Encoder::init(void (*doA)(), void(*doB)()){ // // A callback and B callback } } - - -long _micros(){ - return micros(); -} diff --git a/arduino_foc_minimal/Encoder.h b/arduino_foc_minimal/Encoder.h index 6e9a5f34..a7e475d0 100644 --- a/arduino_foc_minimal/Encoder.h +++ b/arduino_foc_minimal/Encoder.h @@ -71,8 +71,4 @@ class Encoder{ }; - -long _micros(); - - #endif From 075b38b6ae3b1828eb06118afd7a05266ff6aa68 Mon Sep 17 00:00:00 2001 From: askuric Date: Sun, 19 Apr 2020 19:05:46 +0200 Subject: [PATCH 12/65] added updated libraries --- arduino_foc_minimal/BLDCMotor.cpp | 113 +++++++++++++------- arduino_foc_minimal/BLDCMotor.h | 44 +++++--- arduino_foc_minimal/Encoder.cpp | 31 +++--- arduino_foc_minimal/arduino_foc_minimal.ino | 11 +- 4 files changed, 131 insertions(+), 68 deletions(-) diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index 29d76a04..8a367675 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -40,6 +40,8 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) PI_velocity_ultra_slow.u_limit = -1; PI_velocity_ultra_slow.uk_1 = 0; PI_velocity_ultra_slow.ek_1 = 0; + // current estimated angle + ultraslow_estimated_angle = 0; // position loop config // P controller constant @@ -47,11 +49,19 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // maximum angular velocity to be used for positioning P_angle.velocity_limit = DEF_P_ANGLE_VEL_LIM; + // index search PI controller + PI_velocity_index_search.K = DEF_PI_VEL_INDEX_K; + PI_velocity_index_search.Ti = DEF_PI_VEL_INDEX_TI; + PI_velocity_index_search.u_limit = -1; + PI_velocity_index_search.timestamp = micros(); + PI_velocity_index_search.uk_1 = 0; + PI_velocity_index_search.ek_1 = 0; + // index search velocity + index_search_velocity = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // electric angle og the zero angle // electric angle of the index for encoder index_electric_angle = 0; - // index search velocity - index_search_velocity = DEF_INDEX_SEARCH_VELOCITY; //debugger debugger = nullptr; @@ -76,13 +86,15 @@ void BLDCMotor::init() { // check if u_limit configuration has been done. // if not set it to the power_supply_voltage // or if set too high - if(PI_velocity.u_limit == -1 || PI_velocity.u_limit > power_supply_voltage/2) PI_velocity.u_limit = power_supply_voltage; - if(PI_velocity_ultra_slow.u_limit == -1 || PI_velocity.u_limit > power_supply_voltage/2) PI_velocity_ultra_slow.u_limit = power_supply_voltage; + if(PI_velocity.u_limit == -1 || PI_velocity.u_limit > power_supply_voltage/2) PI_velocity.u_limit = power_supply_voltage/2; + if(PI_velocity_ultra_slow.u_limit == -1 || PI_velocity.u_limit > power_supply_voltage/2) PI_velocity_ultra_slow.u_limit = power_supply_voltage/2; + if(PI_velocity_index_search.u_limit == -1 || PI_velocity_index_search.u_limit > power_supply_voltage/2) PI_velocity_index_search.u_limit = power_supply_voltage/2; - delay(500); + _delay(500); // enable motor + if(debugger) debugger->println("DEBUG: Enabling motor."); enable(); - delay(500); + _delay(500); } @@ -91,9 +103,9 @@ void BLDCMotor::init() { */ int BLDCMotor::initFOC() { // encoder alignment - delay(500); + _delay(500); int exit_flag = alignEncoder(); - delay(500); + _delay(500); return exit_flag; } @@ -134,20 +146,19 @@ void BLDCMotor::linkEncoder(Encoder* enc) { int BLDCMotor::alignEncoder() { if(debugger) debugger->println("DEBUG: Align the encoder and motor electrical 0 angle."); // align the electircal phases of the motor and encoder - setPwm(pwmA,12); + setPwm(pwmA, power_supply_voltage/2.0); setPwm(pwmB,0); setPwm(pwmC,0); - delay(1000); + _delay(1000); // set encoder to zero encoder->setCounterZero(); - delay(500); + _delay(500); setPhaseVoltage(0,0); - delay(200); + _delay(200); - if(debugger) debugger->println("DEBUG: Search for the encoder index - if available."); // find the index if available int exit_flag = indexSearch(); - delay(500); + _delay(500); if(debugger){ if(exit_flag< 0 ) debugger->println("DEBUG: Error: Index not found!"); if(exit_flag> 0 ) debugger->println("DEBUG: Success: Index found!"); @@ -162,11 +173,17 @@ int BLDCMotor::alignEncoder() { int BLDCMotor::indexSearch() { // if no index return if(!encoder->hasIndex()) return 0; + + if(debugger) debugger->println("DEBUG: Search for the encoder index."); + // search the index with small speed while(!encoder->indexFound() && shaft_angle < 2 * M_PI){ - voltage_q = velocityPI(index_search_velocity - shaftVelocity()); - loopFOC(); + voltage_q = velocityIndexSearchPI(index_search_velocity - shaftVelocity()); + loopFOC(); } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); // set index to zero if it has been found if(encoder->indexFound()){ @@ -175,8 +192,6 @@ int BLDCMotor::indexSearch() { index_electric_angle = electricAngle(encoder->getIndexAngle()); } - // disable motor - setPhaseVoltage(0,0); return encoder->indexFound() ? 1 : -1; } @@ -277,11 +292,14 @@ void BLDCMotor::setPhaseVoltage(double Uq, double angle_el) { void BLDCMotor::setPwm(int pinPwm, float U) { int U_pwm = 0; float U_max = power_supply_voltage/2.0; + + // limit the voltage + if(abs(U) > U_max) U = U > 0 ? U_max : -U_max; // sets the voltage [-U_max,U_max] to pwm [0,255] U_pwm = ((float)U + (float)U_max) / (2.0 * (float)U_max) * 255.0; - // limit the values between 0 and 255; + // limit the values between 0 and 255 (just in case) U_pwm = U_pwm < 0 ? 0 : U_pwm; U_pwm = U_pwm >= 255 ? 255 : U_pwm; @@ -307,38 +325,42 @@ double BLDCMotor::normalizeAngle(double angle) /** Motor control functions */ -float BLDCMotor::velocityPI(float ek) { - float Ts = (micros() - PI_velocity.timestamp) * 1e-6; +// PI controller function +float BLDCMotor::controllerPI(float ek, PI_s& cont){ + float Ts = (micros() - cont.timestamp) * 1e-6; + // u(s) = Kr(1 + 1/(Ti.s)) - float uk = PI_velocity.uk_1; - uk += PI_velocity.K * (Ts / (2.0 * PI_velocity.Ti) + 1.0) * ek + PI_velocity.K * (Ts / (2.0 * PI_velocity.Ti) - 1.0) * PI_velocity.ek_1; - if (abs(uk) > PI_velocity.u_limit) uk = uk > 0 ? PI_velocity.u_limit : -PI_velocity.u_limit; - - PI_velocity.uk_1 = uk; - PI_velocity.ek_1 = ek; - PI_velocity.timestamp = micros(); + float uk = cont.uk_1; + uk += cont.K * (Ts / (2.0 * cont.Ti) + 1.0) * ek + cont.K * (Ts / (2.0 * cont.Ti) - 1.0) * cont.ek_1; + // antiwindup - limit the output voltage + if (abs(uk) > cont.u_limit) uk = uk > 0 ? cont.u_limit : -cont.u_limit; + + cont.uk_1 = uk; + cont.ek_1 = ek; + cont.timestamp = micros(); return uk; } - +// velocity control loop PI controller +float BLDCMotor::velocityPI(float ek) { + return controllerPI(ek, PI_velocity); +} +// index search PI contoller +float BLDCMotor::velocityIndexSearchPI(float ek) { + return controllerPI(ek, PI_velocity_index_search); +} // PI controller for ultra slow velocity control float BLDCMotor::velocityUltraSlowPI(float vel) { float Ts = (micros() - PI_velocity_ultra_slow.timestamp) * 1e-6; - static float angle; - - angle += vel * Ts; - float ek = angle - shaft_angle; - // u(s) = Kr(1 + 1/(Ti.s)) - float uk = PI_velocity_ultra_slow.uk_1; - uk += PI_velocity_ultra_slow.K * (Ts / (2 * PI_velocity_ultra_slow.Ti) + 1) * ek + PI_velocity_ultra_slow.K * (Ts / (2 * PI_velocity_ultra_slow.Ti) - 1) * PI_velocity_ultra_slow.ek_1; - if (abs(uk) > PI_velocity_ultra_slow.u_limit) uk = uk > 0 ? PI_velocity_ultra_slow.u_limit : -PI_velocity_ultra_slow.u_limit; + // integrate the velocity to get the necessary angle + ultraslow_estimated_angle += vel * Ts; + // error of positioning + float ek = ultraslow_estimated_angle - shaft_angle; - PI_velocity_ultra_slow.uk_1 = uk; - PI_velocity_ultra_slow.ek_1 = ek; - PI_velocity_ultra_slow.timestamp = micros(); - return uk; + return controllerPI(ek, PI_velocity_ultra_slow); } + // P controller for position control loop float BLDCMotor::positionP(float ek) { float velk = P_angle.K * ek; @@ -346,8 +368,11 @@ float BLDCMotor::positionP(float ek) { return velk; } + + void BLDCMotor::useDebugging(Print &print){ debugger = &print; //operate on the adress of print + if(debugger )debugger->println("DEBUG: Serial debugger enabled!"); } @@ -367,3 +392,9 @@ void setPwmFrequency(int pin) { } } +// funciton buffering _delays +// arduino funciton doesn't work well with interrupts +void _delay(uint64_t ms){ + long t = micros(); + while((micros() - t)/1000 < ms){}; +} \ No newline at end of file diff --git a/arduino_foc_minimal/BLDCMotor.h b/arduino_foc_minimal/BLDCMotor.h index 7bed9798..201f3cda 100644 --- a/arduino_foc_minimal/BLDCMotor.h +++ b/arduino_foc_minimal/BLDCMotor.h @@ -8,17 +8,20 @@ // power supply voltage #define DEF_POWER_SUPPLY 12.0 // velocity PI controller params -#define DEF_PI_VEL_K 1.0 -#define DEF_PI_VEL_TI 0.003 +#define DEF_PI_VEL_K 0.5 +#define DEF_PI_VEL_TI 0.01 // ultra slow velocity PI params -#define DEF_PI_VEL_US_K 120.0 +#define DEF_PI_VEL_US_K 60.0 #define DEF_PI_VEL_US_TI 100.0 // angle P params #define DEF_P_ANGLE_K 20 // angle velocity limit default #define DEF_P_ANGLE_VEL_LIM 20 // index search velocity -#define DEF_INDEX_SEARCH_VELOCITY 1 +#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 +// velocity PI controller params for index search +#define DEF_PI_VEL_INDEX_K 0.5 +#define DEF_PI_VEL_INDEX_TI 0.01 // sign funciton @@ -38,13 +41,20 @@ enum ControlType{ angle }; -// P/PI controller strucutre +// PI controller strucutre struct PI_s{ float K; float Ti; long timestamp; float uk_1, ek_1; float u_limit; +}; + +// P controller structure +struct P_s{ + float K; + long timestamp; + float uk_1, ek_1; float velocity_limit; }; @@ -98,7 +108,8 @@ class BLDCMotor ControlType controller; PI_s PI_velocity; PI_s PI_velocity_ultra_slow; - PI_s P_angle; + P_s P_angle; + PI_s PI_velocity_index_search; // encoder link Encoder* encoder; @@ -107,6 +118,9 @@ class BLDCMotor // index search velocity float index_search_velocity; + /** FOC methods */ + //Method using FOC to set Uq to the motor at the optimal angle + void setPhaseVoltage(double Uq, double angle_el); // debugging @@ -127,11 +141,7 @@ class BLDCMotor float electricAngle(float shaftAngle); //Set phase voltaget to pwm output void setPwm(int pinPwm, float U); - - /** FOC methods */ - //Method using FOC to set Uq to the motor at the optimal angle - void setPhaseVoltage(double Uq, double angle_el); - + /** Utility funcitons */ //normalizing radian angle to [0,2PI] double normalizeAngle(double angle); @@ -139,12 +149,19 @@ class BLDCMotor float filterLP(float u); /** Motor control functions */ + float controllerPI(float ek, PI_s &controller); float velocityPI(float ek); - float velocityUltraSlowPI(float ek); + float velocityUltraSlowPI(float vel); + float velocityIndexSearchPI(float ek); float positionP(float ek); + // phase voltages float Ualpha,Ubeta; float Ua,Ub,Uc; + + // velocity ultra slow angle + float ultraslow_estimated_angle; + }; @@ -152,5 +169,8 @@ class BLDCMotor High PWM frequency */ void setPwmFrequency(int pin); +// funciton implementing arduino blocking delay funciton +// regular delay funciton doesn't work with interrupts +void _delay(uint64_t ms); #endif diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index 16a9767a..af435528 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -66,8 +66,10 @@ void Encoder::handleA() { // aling encoder on each index if(index_pulse_counter){ long tmp = pulse_counter; + // corrent the counter value pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; - prev_pulse_counter = pulse_counter - (tmp-prev_pulse_counter); + // preserve relative speed + prev_pulse_counter += pulse_counter - tmp; } // initial offset if(!index_pulse_counter) index_pulse_counter = pulse_counter; @@ -101,8 +103,10 @@ void Encoder::handleB() { // aling encoder on each index if(index_pulse_counter){ long tmp = pulse_counter; + // corrent the counter value pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; - prev_pulse_counter = pulse_counter - (tmp-prev_pulse_counter); + // preserve relative speed + prev_pulse_counter += pulse_counter - tmp; } // initial offset if(!index_pulse_counter) index_pulse_counter = pulse_counter; @@ -205,20 +209,23 @@ void Encoder::init(void (*doA)(), void(*doB)()){ // attach interrupt if functions provided - if(doA != nullptr){ switch(quadrature){ case Quadrature::ENABLE: cpr = 4*cpr; - // CPR = 4xPPR - attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); - attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); + // A callback and B callback + if(doA != nullptr){ + // CPR = 4xPPR + attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); + attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); + } break; case Quadrature::DISABLE: - // CPR = PPR - attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING); - attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); + // A callback and B callback + if(doA != nullptr){ + // CPR = PPR + attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING); + attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); + } break; - } - // // A callback and B callback - } + } } diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index 32031d3b..89f1b0b8 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -40,6 +40,14 @@ void setup() { // default 12V motor.power_supply_voltage = 12; + // index search velocity - default 1rad/s + motor.index_search_velocity = 1; + // index search PI contoller parameters + // default K=0.5 Ti = 0.01 + motor.PI_velocity_index_search.K = 0.1; + motor.PI_velocity_index_search.Ti = 0.01; + motor.PI_velocity_index_search.u_limit = 3; + // set FOC loop to be used // ControlType::voltage // ControlType::velocity @@ -55,9 +63,6 @@ void setup() { //defualt power_supply_voltage/2 motor.PI_velocity.u_limit = 4; - // index search velocity - default 1 rad/s - motor.index_search_velocity = 2; - // link the motor to the sensor motor.linkEncoder(&encoder); From 618e238f92dec0ae17706605738995dcb964ecb4 Mon Sep 17 00:00:00 2001 From: askuric Date: Mon, 20 Apr 2020 09:22:17 +0200 Subject: [PATCH 13/65] Enabled support for all arduino UNO Pwms --- arduino_foc_minimal/.vscode/arduino.json | 5 - .../.vscode/c_cpp_properties.json | 19 ---- arduino_foc_minimal/BLDCMotor.cpp | 92 +++++++------------ arduino_foc_minimal/BLDCMotor.h | 32 ++----- arduino_foc_minimal/Encoder.cpp | 36 ++++---- arduino_foc_minimal/Encoder.h | 1 + arduino_foc_minimal/FOCutils.cpp | 38 ++++++++ arduino_foc_minimal/FOCutils.h | 28 ++++++ arduino_foc_minimal/arduino_foc_minimal.ino | 12 ++- 9 files changed, 132 insertions(+), 131 deletions(-) delete mode 100644 arduino_foc_minimal/.vscode/arduino.json delete mode 100644 arduino_foc_minimal/.vscode/c_cpp_properties.json create mode 100644 arduino_foc_minimal/FOCutils.cpp create mode 100644 arduino_foc_minimal/FOCutils.h diff --git a/arduino_foc_minimal/.vscode/arduino.json b/arduino_foc_minimal/.vscode/arduino.json deleted file mode 100644 index 60b455d8..00000000 --- a/arduino_foc_minimal/.vscode/arduino.json +++ /dev/null @@ -1,5 +0,0 @@ -{ - "board": "arduino:avr:uno", - "port": "COM57", - "sketch": "arduino_foc_minimal.ino" -} \ No newline at end of file diff --git a/arduino_foc_minimal/.vscode/c_cpp_properties.json b/arduino_foc_minimal/.vscode/c_cpp_properties.json deleted file mode 100644 index 933d05b7..00000000 --- a/arduino_foc_minimal/.vscode/c_cpp_properties.json +++ /dev/null @@ -1,19 +0,0 @@ -{ - "configurations": [ - { - "name": "Win32", - "includePath": [ - "C:\\Users\\Gospar\\AppData\\Local\\Arduino15\\packages\\arduino\\tools\\**", - "C:\\Users\\Gospar\\AppData\\Local\\Arduino15\\packages\\arduino\\hardware\\avr\\1.6.23\\**" - ], - "forcedInclude": [ - "C:\\Users\\Gospar\\AppData\\Local\\Arduino15\\packages\\arduino\\hardware\\avr\\1.6.23\\cores\\arduino\\Arduino.h" - ], - "intelliSenseMode": "msvc-x64", - "compilerPath": "C:/Program Files (x86)/Microsoft Visual Studio/2019/BuildTools/VC/Tools/MSVC/14.24.28314/bin/Hostx64/x64/cl.exe", - "cStandard": "c11", - "cppStandard": "c++17" - } - ], - "version": 4 -} \ No newline at end of file diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index 8a367675..d4c0e4c3 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -27,7 +27,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // PI contoroller constant PI_velocity.K = DEF_PI_VEL_K; PI_velocity.Ti = DEF_PI_VEL_TI; - PI_velocity.timestamp = micros(); + PI_velocity.timestamp = _micros(); PI_velocity.u_limit = -1; PI_velocity.uk_1 = 0; PI_velocity.ek_1 = 0; @@ -36,7 +36,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // PI contoroller PI_velocity_ultra_slow.K = DEF_PI_VEL_US_K; PI_velocity_ultra_slow.Ti = DEF_PI_VEL_US_TI; - PI_velocity_ultra_slow.timestamp = micros(); + PI_velocity_ultra_slow.timestamp = _micros(); PI_velocity_ultra_slow.u_limit = -1; PI_velocity_ultra_slow.uk_1 = 0; PI_velocity_ultra_slow.ek_1 = 0; @@ -53,7 +53,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) PI_velocity_index_search.K = DEF_PI_VEL_INDEX_K; PI_velocity_index_search.Ti = DEF_PI_VEL_INDEX_TI; PI_velocity_index_search.u_limit = -1; - PI_velocity_index_search.timestamp = micros(); + PI_velocity_index_search.timestamp = _micros(); PI_velocity_index_search.uk_1 = 0; PI_velocity_index_search.ek_1 = 0; // index search velocity @@ -177,7 +177,7 @@ int BLDCMotor::indexSearch() { if(debugger) debugger->println("DEBUG: Search for the encoder index."); // search the index with small speed - while(!encoder->indexFound() && shaft_angle < 2 * M_PI){ + while(!encoder->indexFound() && shaft_angle < _2PI){ voltage_q = velocityIndexSearchPI(index_search_velocity - shaftVelocity()); loopFOC(); } @@ -191,8 +191,7 @@ int BLDCMotor::indexSearch() { // remember index electric angle index_electric_angle = electricAngle(encoder->getIndexAngle()); } - - + // return bool is index found return encoder->indexFound() ? 1 : -1; } @@ -211,7 +210,8 @@ float BLDCMotor::shaftVelocity() { Electrical angle calculation */ float BLDCMotor::electricAngle(float shaftAngle) { - return normalizeAngle(shaftAngle * pole_pairs); + //return normalizeAngle(shaftAngle * pole_pairs); + return (shaftAngle * pole_pairs); } /* Iterative function looping FOC algorithm, setting Uq on the Motor @@ -233,10 +233,8 @@ void BLDCMotor::move(float target) { // get angular velocity shaft_velocity = shaftVelocity(); switch (controller) { - case ControlType::velocity_ultra_slow: - // velocity set point - shaft_velocity_sp = target; - voltage_q = velocityUltraSlowPI(shaft_velocity_sp); + case ControlType::voltage: + voltage_q = target; break; case ControlType::angle: // angle set point @@ -251,8 +249,10 @@ void BLDCMotor::move(float target) { shaft_velocity_sp = target; voltage_q = velocityPI(shaft_velocity_sp - shaft_velocity); break; - case ControlType::voltage: - voltage_q = target; + case ControlType::velocity_ultra_slow: + // velocity set point + shaft_velocity_sp = target; + voltage_q = velocityUltraSlowPI(shaft_velocity_sp); break; } } @@ -266,13 +266,9 @@ void BLDCMotor::move(float target) { */ void BLDCMotor::setPhaseVoltage(double Uq, double angle_el) { - // Uq sign compensation - float angle = angle_el + index_electric_angle; - // Uq sign compensation - angle = normalizeAngle(Uq > 0 ? angle : angle + M_PI ); // Inverse park transform - Ualpha = -sin(angle) * abs(Uq); - Ubeta = cos(angle) * abs(Uq); + Ualpha = -sin(angle_el + index_electric_angle) * Uq; + Ubeta = cos(angle_el + index_electric_angle) * Uq; // Clarke transform Ua = Ualpha; @@ -288,22 +284,19 @@ void BLDCMotor::setPhaseVoltage(double Uq, double angle_el) { /* Set voltage to the pwm pin + - function a bit optimised to get better performance */ void BLDCMotor::setPwm(int pinPwm, float U) { - int U_pwm = 0; + // max value float U_max = power_supply_voltage/2.0; - // limit the voltage - if(abs(U) > U_max) U = U > 0 ? U_max : -U_max; - // sets the voltage [-U_max,U_max] to pwm [0,255] - U_pwm = ((float)U + (float)U_max) / (2.0 * (float)U_max) * 255.0; + // u_pwm = 255 * (U + U_max)/(2*U_max) + int U_pwm = 127.5 * (U/U_max + 1); - // limit the values between 0 and 255 (just in case) - U_pwm = U_pwm < 0 ? 0 : U_pwm; - U_pwm = U_pwm >= 255 ? 255 : U_pwm; + // limit the values between 0 and 255 + U_pwm = (U_pwm < 0) ? 0 : (U_pwm >= 255) ? 255 : U_pwm; - // write hardware pwm analogWrite(pinPwm, U_pwm); } @@ -313,10 +306,9 @@ void BLDCMotor::setPwm(int pinPwm, float U) { /* normalizing radian angle to [0,2PI] */ -double BLDCMotor::normalizeAngle(double angle) -{ - double a = fmod(angle, 2 * M_PI); - return a >= 0 ? a : (a + 2 * M_PI); +double BLDCMotor::normalizeAngle(double angle){ + double a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); } @@ -328,7 +320,7 @@ double BLDCMotor::normalizeAngle(double angle) // PI controller function float BLDCMotor::controllerPI(float ek, PI_s& cont){ - float Ts = (micros() - cont.timestamp) * 1e-6; + float Ts = (_micros() - cont.timestamp) * 1e-6; // u(s) = Kr(1 + 1/(Ti.s)) float uk = cont.uk_1; @@ -338,7 +330,7 @@ float BLDCMotor::controllerPI(float ek, PI_s& cont){ cont.uk_1 = uk; cont.ek_1 = ek; - cont.timestamp = micros(); + cont.timestamp = _micros(); return uk; } // velocity control loop PI controller @@ -351,7 +343,7 @@ float BLDCMotor::velocityIndexSearchPI(float ek) { } // PI controller for ultra slow velocity control float BLDCMotor::velocityUltraSlowPI(float vel) { - float Ts = (micros() - PI_velocity_ultra_slow.timestamp) * 1e-6; + float Ts = (_micros() - PI_velocity_ultra_slow.timestamp) * 1e-6; // integrate the velocity to get the necessary angle ultraslow_estimated_angle += vel * Ts; @@ -368,33 +360,11 @@ float BLDCMotor::positionP(float ek) { return velk; } - - +/** + * Debugger functions + */ +// funciton implementing the debugger setter void BLDCMotor::useDebugging(Print &print){ debugger = &print; //operate on the adress of print if(debugger )debugger->println("DEBUG: Serial debugger enabled!"); -} - - -/* - High PWM frequency -*/ -void setPwmFrequency(int pin) { - if (pin == 5 || pin == 6 || pin == 9 || pin == 10) { - if (pin == 5 || pin == 6) { - TCCR0B = ((TCCR0B & 0b11111000) | 0x01); - } else { - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); - } - } - else if (pin == 3 || pin == 11) { - TCCR2B = ((TCCR2B & 0b11111000) | 0x01); - } -} - -// funciton buffering _delays -// arduino funciton doesn't work well with interrupts -void _delay(uint64_t ms){ - long t = micros(); - while((micros() - t)/1000 < ms){}; } \ No newline at end of file diff --git a/arduino_foc_minimal/BLDCMotor.h b/arduino_foc_minimal/BLDCMotor.h index 201f3cda..8ec8beb4 100644 --- a/arduino_foc_minimal/BLDCMotor.h +++ b/arduino_foc_minimal/BLDCMotor.h @@ -3,6 +3,7 @@ #include "Arduino.h" #include "Encoder.h" +#include "FOCutils.h" // default configuration values // power supply voltage @@ -23,16 +24,6 @@ #define DEF_PI_VEL_INDEX_K 0.5 #define DEF_PI_VEL_INDEX_TI 0.01 - -// sign funciton -#define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) -// utility defines -#define _2_SQRT3 1.15470053838 -#define _1_SQRT3 0.57735026919 -#define _SQRT3_2 0.86602540378 -#define _SQRT2 1.41421356237 -#define _120_D2R 2.09439510239 - // controller type configuration enum enum ControlType{ voltage, @@ -87,6 +78,14 @@ class BLDCMotor int enable_pin; int pole_pairs; + + + /** State calculation methods */ + //Shaft angle calculation + float shaftAngle(); + //Shaft velocity calculation + float shaftVelocity(); + // state variables // current elelctrical angle float elctric_angle; @@ -131,11 +130,6 @@ class BLDCMotor //Encoder alignment to electrical 0 angle int alignEncoder(); int indexSearch(); - /** State calculation methods */ - //Shaft angle calculation - float shaftAngle(); - //Shaft velocity calculation - float shaftVelocity(); //Electrical angle calculation float electricAngle(float shaftAngle); @@ -165,12 +159,4 @@ class BLDCMotor }; -/* - High PWM frequency -*/ -void setPwmFrequency(int pin); -// funciton implementing arduino blocking delay funciton -// regular delay funciton doesn't work with interrupts -void _delay(uint64_t ms); - #endif diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index af435528..dba916de 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -30,7 +30,7 @@ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ prev_Th = 0; pulse_per_second = 0; prev_pulse_counter = 0; - prev_timestamp_us = micros(); + prev_timestamp_us = _micros(); // extern pullup as default pullup = Pullup::EXTERN; @@ -39,7 +39,6 @@ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ } // Encoder interrupt callback functions -// enabling CPR=4xPPR behaviour // A channel void Encoder::handleA() { int A = digitalRead(pinA); @@ -48,7 +47,7 @@ void Encoder::handleA() { // CPR = 4xPPR if ( A != A_active ) { pulse_counter += (A_active == B_active) ? 1 : -1; - pulse_timestamp = micros(); + pulse_timestamp = _micros(); A_active = A; } break; @@ -56,11 +55,11 @@ void Encoder::handleA() { // CPR = PPR if(A && !digitalRead(pinB)){ pulse_counter++; - pulse_timestamp = micros(); + pulse_timestamp = _micros(); } break; } - if(hasIndex()){ + if(hasIndex()){ int I = digitalRead(index_pin); if(I && !I_active){ // aling encoder on each index @@ -85,7 +84,7 @@ void Encoder::handleB() { // CPR = 4xPPR if ( B != B_active ) { pulse_counter += (A_active != B_active) ? 1 : -1; - pulse_timestamp = micros(); + pulse_timestamp = _micros(); B_active = B; } break; @@ -93,11 +92,11 @@ void Encoder::handleB() { // CPR = PPR if(B && !digitalRead(pinA)){ pulse_counter--; - pulse_timestamp = micros(); + pulse_timestamp = _micros(); } break; } - if(hasIndex()){ + if(hasIndex()){ int I = digitalRead(index_pin); if(I && !I_active){ // aling encoder on each index @@ -107,9 +106,10 @@ void Encoder::handleB() { pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; // preserve relative speed prev_pulse_counter += pulse_counter - tmp; - } - // initial offset - if(!index_pulse_counter) index_pulse_counter = pulse_counter; + } else { + // initial offset + index_pulse_counter = pulse_counter; + } } I_active = I; } @@ -119,7 +119,7 @@ void Encoder::handleB() { Shaft angle calculation */ float Encoder::getAngle(){ - return (pulse_counter) / ((float)cpr) * (2.0 * M_PI); + return _2PI * (pulse_counter) / ((float)cpr); } /* Shaft velocity calculation @@ -127,7 +127,7 @@ float Encoder::getAngle(){ */ float Encoder::getVelocity(){ // timestamp - long timestamp_us = micros(); + long timestamp_us = _micros(); // sampling time calculation float Ts = (timestamp_us - prev_timestamp_us) * 1e-6; // time from last impulse @@ -147,7 +147,7 @@ float Encoder::getVelocity(){ if ( Th > 0.15) pulse_per_second = 0; // velocity calculation - float velocity = pulse_per_second / ((float)cpr) * (2.0 * M_PI); + float velocity = pulse_per_second / ((float)cpr) * (_2PI); // save variables for next pass prev_timestamp_us = timestamp_us; @@ -168,14 +168,14 @@ int Encoder::hasIndex(){ } // getter for Index angle float Encoder::getIndexAngle(){ - return (index_pulse_counter) / ((float)cpr) * (2.0 * M_PI); + return (index_pulse_counter) / ((float)cpr) * (_2PI); } // intialise counter to zero void Encoder::setCounterZero(){ pulse_counter = 0; - pulse_timestamp = micros(); + pulse_timestamp = _micros(); } // intialise index to zero void Encoder::setIndexZero(){ @@ -200,12 +200,12 @@ void Encoder::init(void (*doA)(), void(*doB)()){ // counter setup pulse_counter = 0; - pulse_timestamp = micros(); + pulse_timestamp = _micros(); // velocity calculation varibles prev_Th = 0; pulse_per_second = 0; prev_pulse_counter = 0; - prev_timestamp_us = micros(); + prev_timestamp_us = _micros(); // attach interrupt if functions provided diff --git a/arduino_foc_minimal/Encoder.h b/arduino_foc_minimal/Encoder.h index a7e475d0..8f551b7a 100644 --- a/arduino_foc_minimal/Encoder.h +++ b/arduino_foc_minimal/Encoder.h @@ -2,6 +2,7 @@ #define ENCODER_LIB_H #include "Arduino.h" +#include "FOCutils.h" // Pullup configuation structure diff --git a/arduino_foc_minimal/FOCutils.cpp b/arduino_foc_minimal/FOCutils.cpp new file mode 100644 index 00000000..47f88cab --- /dev/null +++ b/arduino_foc_minimal/FOCutils.cpp @@ -0,0 +1,38 @@ +#include "FOCutils.h" + +/* + High PWM frequency +*/ +void setPwmFrequency(int pin) { + if (pin == 5 || pin == 6 || pin == 9 || pin == 10) { + if (pin == 5 || pin == 6) { + // configure the pwm phase-corrected mode + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); + // set prescaler to 1 + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); + } else { + // set prescaler to 1 + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); + } + } + else if (pin == 3 || pin == 11) { + // set prescaler to 1 + TCCR2B = ((TCCR2B & 0b11111000) | 0x01); + } +} + +// funciton buffering delay() +// arduino funciton doesn't work well with interrupts +void _delay(unsigned long ms){ + long t = _micros(); + while((_micros() - t)/1000 < ms){}; +} + + +// funciton buffering _micros() +// arduino funciton doesn't work well with interrupts +unsigned long _micros(){ + // return teh value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +} \ No newline at end of file diff --git a/arduino_foc_minimal/FOCutils.h b/arduino_foc_minimal/FOCutils.h new file mode 100644 index 00000000..0d464f03 --- /dev/null +++ b/arduino_foc_minimal/FOCutils.h @@ -0,0 +1,28 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + +// sign funciton +#define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +// utility defines +#define _2_SQRT3 1.15470053838 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI_2 1.57079632679 +#define _2PI 6.28318530718 + +// High PWM frequency +void setPwmFrequency(int pin); + +// funciton buffering delay() +// arduino funciton doesn't work well with interrupts +void _delay(unsigned long ms); + +// funciton buffering _micros() +// arduino funciton doesn't work well with interrupts +unsigned long _micros(); + +#endif \ No newline at end of file diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index 89f1b0b8..77c2c1c6 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -9,12 +9,12 @@ // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); +BLDCMotor motor = BLDCMotor(9, 5, 6, 11, 8); // Encoder(int encA, int encB , int cpr, int index) // - encA, encB - encoder A and B pins // - ppr - impulses per rotation (cpr=ppr*4) // - index pin - (optional input) -Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 4); +Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192,4); // interrupt ruotine intialisation void doA(){encoder.handleA();} void doB(){encoder.handleB();} @@ -61,7 +61,7 @@ void setup() { motor.PI_velocity.K = 0.3; motor.PI_velocity.Ti = 0.003; //defualt power_supply_voltage/2 - motor.PI_velocity.u_limit = 4; + motor.PI_velocity.u_limit = 3; // link the motor to the sensor motor.linkEncoder(&encoder); @@ -77,11 +77,12 @@ void setup() { Serial.println("Motor ready."); Serial.println("Input the new target value:"); - delay(1000); + _delay(1000); } // target velocity variable float target = 0; +int t =0; void loop() { // iterative state calculation calculating angle @@ -97,7 +98,8 @@ void loop() { // it can go as low as ~50Hz motor.move(target); - + t = t> 1000 ? 0 : t + 1; + if(!t) Serial.print(_micros()); // function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! // motor_monitor(); From 0c16f3bb3adffee214f83735eda7469b7a6adf3a Mon Sep 17 00:00:00 2001 From: askuric Date: Mon, 20 Apr 2020 09:29:35 +0200 Subject: [PATCH 14/65] typo --- arduino_foc_minimal/arduino_foc_minimal.ino | 2 -- 1 file changed, 2 deletions(-) diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index 77c2c1c6..ba8329e3 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -98,8 +98,6 @@ void loop() { // it can go as low as ~50Hz motor.move(target); - t = t> 1000 ? 0 : t + 1; - if(!t) Serial.print(_micros()); // function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! // motor_monitor(); From 16ad6604cf6b5d13a821d10af43ae7971f0e958e Mon Sep 17 00:00:00 2001 From: askuric Date: Mon, 20 Apr 2020 17:21:37 +0200 Subject: [PATCH 15/65] added ramping --- arduino_foc_minimal/BLDCMotor.cpp | 76 ++++++++++++--------- arduino_foc_minimal/BLDCMotor.h | 16 +++-- arduino_foc_minimal/Encoder.h | 1 + arduino_foc_minimal/FOCutils.cpp | 2 +- arduino_foc_minimal/arduino_foc_minimal.ino | 18 +++-- 5 files changed, 65 insertions(+), 48 deletions(-) diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index d4c0e4c3..171d4b58 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -28,18 +28,20 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) PI_velocity.K = DEF_PI_VEL_K; PI_velocity.Ti = DEF_PI_VEL_TI; PI_velocity.timestamp = _micros(); - PI_velocity.u_limit = -1; - PI_velocity.uk_1 = 0; - PI_velocity.ek_1 = 0; + PI_velocity.voltage_limit = power_supply_voltage/2; + PI_velocity.voltage_ramp = DEF_PI_VEL_U_RAMP; + PI_velocity.voltage_prev = 0; + PI_velocity.tracking_error_prev = 0; // Ultra slow velocity // PI contoroller PI_velocity_ultra_slow.K = DEF_PI_VEL_US_K; PI_velocity_ultra_slow.Ti = DEF_PI_VEL_US_TI; PI_velocity_ultra_slow.timestamp = _micros(); - PI_velocity_ultra_slow.u_limit = -1; - PI_velocity_ultra_slow.uk_1 = 0; - PI_velocity_ultra_slow.ek_1 = 0; + PI_velocity_ultra_slow.voltage_limit = power_supply_voltage/2; + PI_velocity_ultra_slow.voltage_ramp = DEF_PI_VEL_US_U_RAMP; + PI_velocity_ultra_slow.voltage_prev = 0; + PI_velocity_ultra_slow.tracking_error_prev = 0; // current estimated angle ultraslow_estimated_angle = 0; @@ -52,10 +54,12 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // index search PI controller PI_velocity_index_search.K = DEF_PI_VEL_INDEX_K; PI_velocity_index_search.Ti = DEF_PI_VEL_INDEX_TI; - PI_velocity_index_search.u_limit = -1; + PI_velocity_index_search.voltage_limit = power_supply_voltage/2; + PI_velocity_index_search.voltage_ramp = DEF_PI_VEL_INDEX_U_RAMP; PI_velocity_index_search.timestamp = _micros(); - PI_velocity_index_search.uk_1 = 0; - PI_velocity_index_search.ek_1 = 0; + PI_velocity_index_search.voltage_prev = 0; + PI_velocity_index_search.tracking_error_prev = 0; + // index search velocity index_search_velocity = DEF_INDEX_SEARCH_TARGET_VELOCITY; @@ -83,12 +87,10 @@ void BLDCMotor::init() { setPwmFrequency(pwmB); setPwmFrequency(pwmC); - // check if u_limit configuration has been done. - // if not set it to the power_supply_voltage - // or if set too high - if(PI_velocity.u_limit == -1 || PI_velocity.u_limit > power_supply_voltage/2) PI_velocity.u_limit = power_supply_voltage/2; - if(PI_velocity_ultra_slow.u_limit == -1 || PI_velocity.u_limit > power_supply_voltage/2) PI_velocity_ultra_slow.u_limit = power_supply_voltage/2; - if(PI_velocity_index_search.u_limit == -1 || PI_velocity_index_search.u_limit > power_supply_voltage/2) PI_velocity_index_search.u_limit = power_supply_voltage/2; + // sanity check for the voltage limit configuration + if(PI_velocity.voltage_limit > power_supply_voltage/2) PI_velocity.voltage_limit = PI_velocity.voltage_limit > power_supply_voltage/2; + if(PI_velocity.voltage_limit > power_supply_voltage/2) PI_velocity_ultra_slow.voltage_limit = power_supply_voltage/2; + if(PI_velocity_index_search.voltage_limit > power_supply_voltage/2) PI_velocity_index_search.voltage_limit = power_supply_voltage/2; _delay(500); // enable motor @@ -178,8 +180,8 @@ int BLDCMotor::indexSearch() { // search the index with small speed while(!encoder->indexFound() && shaft_angle < _2PI){ - voltage_q = velocityIndexSearchPI(index_search_velocity - shaftVelocity()); loopFOC(); + voltage_q = velocityIndexSearchPI(index_search_velocity - shaftVelocity()); } voltage_q = 0; // disable motor @@ -204,7 +206,7 @@ float BLDCMotor::shaftAngle() { } // shaft velocity calculation float BLDCMotor::shaftVelocity() { - return encoder->getVelocity(); + return vk1; } /* Electrical angle calculation @@ -318,28 +320,34 @@ double BLDCMotor::normalizeAngle(double angle){ Motor control functions */ // PI controller function -float BLDCMotor::controllerPI(float ek, PI_s& cont){ - +float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){ float Ts = (_micros() - cont.timestamp) * 1e-6; - - // u(s) = Kr(1 + 1/(Ti.s)) - float uk = cont.uk_1; - uk += cont.K * (Ts / (2.0 * cont.Ti) + 1.0) * ek + cont.K * (Ts / (2.0 * cont.Ti) - 1.0) * cont.ek_1; - // antiwindup - limit the output voltage - if (abs(uk) > cont.u_limit) uk = uk > 0 ? cont.u_limit : -cont.u_limit; + if(Ts > 0.5) Ts = 1e-3; - cont.uk_1 = uk; - cont.ek_1 = ek; + // u(s) = Kr(1 + 1/(Ti.s)) + // tustin discretisation of the PI controller ( a bit optimised ) + // uk = uk_1 + K*(Ts/(2*Ti) + 1)*ek + K*(Ts/(2*Ti)-1)*ek_1 + float tmp = 0.5 * Ts / cont.Ti; + float voltage = cont.voltage_prev + cont.K * ((tmp + 1.0) * tracking_error + (tmp - 1.0) * cont.tracking_error_prev); + + // antiwindup - limit the output voltage_q + if (abs(voltage) > cont.voltage_limit) voltage = voltage > 0 ? cont.voltage_limit : -cont.voltage_limit; + // limit the acceleration by ramping the the voltage + float d_voltage = voltage - cont.voltage_prev; + if (abs(d_voltage)/Ts > cont.voltage_ramp) voltage = d_voltage > 0 ? cont.voltage_prev + cont.voltage_ramp*Ts : cont.voltage_prev - cont.voltage_ramp*Ts; + + cont.voltage_prev = voltage; + cont.tracking_error_prev = tracking_error; cont.timestamp = _micros(); - return uk; + return voltage; } // velocity control loop PI controller -float BLDCMotor::velocityPI(float ek) { - return controllerPI(ek, PI_velocity); +float BLDCMotor::velocityPI(float tracking_error) { + return controllerPI(tracking_error, PI_velocity); } // index search PI contoller -float BLDCMotor::velocityIndexSearchPI(float ek) { - return controllerPI(ek, PI_velocity_index_search); +float BLDCMotor::velocityIndexSearchPI(float tracking_error) { + return controllerPI(tracking_error, PI_velocity_index_search); } // PI controller for ultra slow velocity control float BLDCMotor::velocityUltraSlowPI(float vel) { @@ -348,9 +356,9 @@ float BLDCMotor::velocityUltraSlowPI(float vel) { // integrate the velocity to get the necessary angle ultraslow_estimated_angle += vel * Ts; // error of positioning - float ek = ultraslow_estimated_angle - shaft_angle; + float tracking_error = ultraslow_estimated_angle - shaft_angle; - return controllerPI(ek, PI_velocity_ultra_slow); + return controllerPI(tracking_error, PI_velocity_ultra_slow); } // P controller for position control loop diff --git a/arduino_foc_minimal/BLDCMotor.h b/arduino_foc_minimal/BLDCMotor.h index 8ec8beb4..ee3ff444 100644 --- a/arduino_foc_minimal/BLDCMotor.h +++ b/arduino_foc_minimal/BLDCMotor.h @@ -11,9 +11,11 @@ // velocity PI controller params #define DEF_PI_VEL_K 0.5 #define DEF_PI_VEL_TI 0.01 +#define DEF_PI_VEL_U_RAMP 1000 // ultra slow velocity PI params #define DEF_PI_VEL_US_K 60.0 #define DEF_PI_VEL_US_TI 100.0 +#define DEF_PI_VEL_US_U_RAMP 1000 // angle P params #define DEF_P_ANGLE_K 20 // angle velocity limit default @@ -23,6 +25,7 @@ // velocity PI controller params for index search #define DEF_PI_VEL_INDEX_K 0.5 #define DEF_PI_VEL_INDEX_TI 0.01 +#define DEF_PI_VEL_INDEX_U_RAMP 500 // controller type configuration enum enum ControlType{ @@ -37,15 +40,16 @@ struct PI_s{ float K; float Ti; long timestamp; - float uk_1, ek_1; - float u_limit; + float voltage_prev, tracking_error_prev; + float voltage_limit; + float voltage_ramp; }; // P controller structure struct P_s{ float K; long timestamp; - float uk_1, ek_1; + float voltage_prev, tracking_error_prev; float velocity_limit; }; @@ -143,10 +147,10 @@ class BLDCMotor float filterLP(float u); /** Motor control functions */ - float controllerPI(float ek, PI_s &controller); - float velocityPI(float ek); + float controllerPI(float tracking_error, PI_s &controller); + float velocityPI(float tracking_error); float velocityUltraSlowPI(float vel); - float velocityIndexSearchPI(float ek); + float velocityIndexSearchPI(float tracking_error); float positionP(float ek); // phase voltages diff --git a/arduino_foc_minimal/Encoder.h b/arduino_foc_minimal/Encoder.h index 8f551b7a..7dd06c66 100644 --- a/arduino_foc_minimal/Encoder.h +++ b/arduino_foc_minimal/Encoder.h @@ -72,4 +72,5 @@ class Encoder{ }; + #endif diff --git a/arduino_foc_minimal/FOCutils.cpp b/arduino_foc_minimal/FOCutils.cpp index 47f88cab..d23ab09b 100644 --- a/arduino_foc_minimal/FOCutils.cpp +++ b/arduino_foc_minimal/FOCutils.cpp @@ -32,7 +32,7 @@ void _delay(unsigned long ms){ // funciton buffering _micros() // arduino funciton doesn't work well with interrupts unsigned long _micros(){ - // return teh value based on the prescaler + // return the value based on the prescaler if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); else return (micros()); } \ No newline at end of file diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index 77c2c1c6..abe8bc5c 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -14,7 +14,7 @@ BLDCMotor motor = BLDCMotor(9, 5, 6, 11, 8); // - encA, encB - encoder A and B pins // - ppr - impulses per rotation (cpr=ppr*4) // - index pin - (optional input) -Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192,4); +Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 4); // interrupt ruotine intialisation void doA(){encoder.handleA();} void doB(){encoder.handleB();} @@ -46,7 +46,10 @@ void setup() { // default K=0.5 Ti = 0.01 motor.PI_velocity_index_search.K = 0.1; motor.PI_velocity_index_search.Ti = 0.01; - motor.PI_velocity_index_search.u_limit = 3; + //motor.PI_velocity_index_search.voltage_limit = 3; + // jerk control using voltage voltage ramp + // default value is 100 + motor.PI_velocity_index_search.voltage_ramp = 100; // set FOC loop to be used // ControlType::voltage @@ -58,10 +61,13 @@ void setup() { // contoller configuration based on the controll type // velocity PI controller parameters // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 0.3; + motor.PI_velocity.K = 0.1; motor.PI_velocity.Ti = 0.003; //defualt power_supply_voltage/2 - motor.PI_velocity.u_limit = 3; + motor.PI_velocity.voltage_limit = 6; + // jerk control using voltage voltage ramp + // default value is 1000 volts per sec ~ 1V per millisecond + motor.PI_velocity.voltage_ramp = 500; // link the motor to the sensor motor.linkEncoder(&encoder); @@ -82,7 +88,7 @@ void setup() { // target velocity variable float target = 0; -int t =0; +int t = 0; void loop() { // iterative state calculation calculating angle @@ -98,8 +104,6 @@ void loop() { // it can go as low as ~50Hz motor.move(target); - t = t> 1000 ? 0 : t + 1; - if(!t) Serial.print(_micros()); // function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! // motor_monitor(); From 6aedb36ba3f852ca5f127dd2bcc754134f9d3035 Mon Sep 17 00:00:00 2001 From: askuric Date: Mon, 20 Apr 2020 17:27:20 +0200 Subject: [PATCH 16/65] typos --- arduino_foc_minimal/BLDCMotor.cpp | 2 +- arduino_foc_minimal/Encoder.cpp | 44 ++++++++++----------- arduino_foc_minimal/arduino_foc_minimal.ino | 4 +- 3 files changed, 25 insertions(+), 25 deletions(-) diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index 171d4b58..f9ecb532 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -206,7 +206,7 @@ float BLDCMotor::shaftAngle() { } // shaft velocity calculation float BLDCMotor::shaftVelocity() { - return vk1; + return encoder->getVelocity(); } /* Electrical angle calculation diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index dba916de..77fc21a7 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -42,23 +42,23 @@ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ // A channel void Encoder::handleA() { int A = digitalRead(pinA); - switch (quadrature){ - case Quadrature::ENABLE: + // switch (quadrature){ + // case Quadrature::ENABLE: // CPR = 4xPPR if ( A != A_active ) { pulse_counter += (A_active == B_active) ? 1 : -1; pulse_timestamp = _micros(); A_active = A; } - break; - case Quadrature::DISABLE: - // CPR = PPR - if(A && !digitalRead(pinB)){ - pulse_counter++; - pulse_timestamp = _micros(); - } - break; - } + // break; + // case Quadrature::DISABLE: + // // CPR = PPR + // if(A && !digitalRead(pinB)){ + // pulse_counter++; + // pulse_timestamp = _micros(); + // } + // break; + // } if(hasIndex()){ int I = digitalRead(index_pin); if(I && !I_active){ @@ -79,23 +79,23 @@ void Encoder::handleA() { // B channel void Encoder::handleB() { int B = digitalRead(pinB); - switch (quadrature){ - case Quadrature::ENABLE: + // switch (quadrature){ + // case Quadrature::ENABLE: // CPR = 4xPPR if ( B != B_active ) { pulse_counter += (A_active != B_active) ? 1 : -1; pulse_timestamp = _micros(); B_active = B; } - break; - case Quadrature::DISABLE: - // CPR = PPR - if(B && !digitalRead(pinA)){ - pulse_counter--; - pulse_timestamp = _micros(); - } - break; - } + // break; + // case Quadrature::DISABLE: + // // CPR = PPR + // if(B && !digitalRead(pinA)){ + // pulse_counter--; + // pulse_timestamp = _micros(); + // } + // break; + // } if(hasIndex()){ int I = digitalRead(index_pin); if(I && !I_active){ diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index abe8bc5c..c86f68e0 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -61,13 +61,13 @@ void setup() { // contoller configuration based on the controll type // velocity PI controller parameters // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 0.1; + motor.PI_velocity.K = 0.3; motor.PI_velocity.Ti = 0.003; //defualt power_supply_voltage/2 motor.PI_velocity.voltage_limit = 6; // jerk control using voltage voltage ramp // default value is 1000 volts per sec ~ 1V per millisecond - motor.PI_velocity.voltage_ramp = 500; + motor.PI_velocity.voltage_ramp = 300; // link the motor to the sensor motor.linkEncoder(&encoder); From 33354536c571c9e7555f6f58eefa6d44378132d1 Mon Sep 17 00:00:00 2001 From: askuric Date: Mon, 20 Apr 2020 17:30:35 +0200 Subject: [PATCH 17/65] tested ultra_slow velocity and uncommented the encoder callback --- arduino_foc_minimal/BLDCMotor.h | 6 +-- arduino_foc_minimal/Encoder.cpp | 44 ++++++++++----------- arduino_foc_minimal/arduino_foc_minimal.ino | 2 +- 3 files changed, 26 insertions(+), 26 deletions(-) diff --git a/arduino_foc_minimal/BLDCMotor.h b/arduino_foc_minimal/BLDCMotor.h index ee3ff444..a1b01b03 100644 --- a/arduino_foc_minimal/BLDCMotor.h +++ b/arduino_foc_minimal/BLDCMotor.h @@ -11,11 +11,11 @@ // velocity PI controller params #define DEF_PI_VEL_K 0.5 #define DEF_PI_VEL_TI 0.01 -#define DEF_PI_VEL_U_RAMP 1000 +#define DEF_PI_VEL_U_RAMP 300 // ultra slow velocity PI params #define DEF_PI_VEL_US_K 60.0 #define DEF_PI_VEL_US_TI 100.0 -#define DEF_PI_VEL_US_U_RAMP 1000 +#define DEF_PI_VEL_US_U_RAMP 100 // angle P params #define DEF_P_ANGLE_K 20 // angle velocity limit default @@ -25,7 +25,7 @@ // velocity PI controller params for index search #define DEF_PI_VEL_INDEX_K 0.5 #define DEF_PI_VEL_INDEX_TI 0.01 -#define DEF_PI_VEL_INDEX_U_RAMP 500 +#define DEF_PI_VEL_INDEX_U_RAMP 100 // controller type configuration enum enum ControlType{ diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index 77fc21a7..dba916de 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -42,23 +42,23 @@ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ // A channel void Encoder::handleA() { int A = digitalRead(pinA); - // switch (quadrature){ - // case Quadrature::ENABLE: + switch (quadrature){ + case Quadrature::ENABLE: // CPR = 4xPPR if ( A != A_active ) { pulse_counter += (A_active == B_active) ? 1 : -1; pulse_timestamp = _micros(); A_active = A; } - // break; - // case Quadrature::DISABLE: - // // CPR = PPR - // if(A && !digitalRead(pinB)){ - // pulse_counter++; - // pulse_timestamp = _micros(); - // } - // break; - // } + break; + case Quadrature::DISABLE: + // CPR = PPR + if(A && !digitalRead(pinB)){ + pulse_counter++; + pulse_timestamp = _micros(); + } + break; + } if(hasIndex()){ int I = digitalRead(index_pin); if(I && !I_active){ @@ -79,23 +79,23 @@ void Encoder::handleA() { // B channel void Encoder::handleB() { int B = digitalRead(pinB); - // switch (quadrature){ - // case Quadrature::ENABLE: + switch (quadrature){ + case Quadrature::ENABLE: // CPR = 4xPPR if ( B != B_active ) { pulse_counter += (A_active != B_active) ? 1 : -1; pulse_timestamp = _micros(); B_active = B; } - // break; - // case Quadrature::DISABLE: - // // CPR = PPR - // if(B && !digitalRead(pinA)){ - // pulse_counter--; - // pulse_timestamp = _micros(); - // } - // break; - // } + break; + case Quadrature::DISABLE: + // CPR = PPR + if(B && !digitalRead(pinA)){ + pulse_counter--; + pulse_timestamp = _micros(); + } + break; + } if(hasIndex()){ int I = digitalRead(index_pin); if(I && !I_active){ diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index c86f68e0..9ce99c44 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -66,7 +66,7 @@ void setup() { //defualt power_supply_voltage/2 motor.PI_velocity.voltage_limit = 6; // jerk control using voltage voltage ramp - // default value is 1000 volts per sec ~ 1V per millisecond + // default value is 100 volts per sec ~ 0.1V per millisecond motor.PI_velocity.voltage_ramp = 300; // link the motor to the sensor From 9aee1d522f28c7b0997f70e1d1574a1fa341bcfa Mon Sep 17 00:00:00 2001 From: askuric Date: Wed, 22 Apr 2020 16:35:21 +0200 Subject: [PATCH 18/65] interrupt index --- arduino_foc_minimal/BLDCMotor.cpp | 31 +++++++++------- arduino_foc_minimal/BLDCMotor.h | 4 +-- arduino_foc_minimal/Encoder.cpp | 40 ++++++++++----------- arduino_foc_minimal/Encoder.h | 3 ++ arduino_foc_minimal/FOCutils.cpp | 37 ++++++++++++++++++- arduino_foc_minimal/FOCutils.h | 10 ++++++ arduino_foc_minimal/arduino_foc_minimal.ino | 38 ++++++++++++-------- 7 files changed, 112 insertions(+), 51 deletions(-) diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index f9ecb532..98dceb30 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -21,14 +21,14 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) enable_pin = en; // Power supply woltage - power_supply_voltage = DEF_POWER_SUPPLY; + voltage_power_supply = DEF_POWER_SUPPLY; // Velocity loop config // PI contoroller constant PI_velocity.K = DEF_PI_VEL_K; PI_velocity.Ti = DEF_PI_VEL_TI; PI_velocity.timestamp = _micros(); - PI_velocity.voltage_limit = power_supply_voltage/2; + PI_velocity.voltage_limit = voltage_power_supply/2; PI_velocity.voltage_ramp = DEF_PI_VEL_U_RAMP; PI_velocity.voltage_prev = 0; PI_velocity.tracking_error_prev = 0; @@ -38,7 +38,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) PI_velocity_ultra_slow.K = DEF_PI_VEL_US_K; PI_velocity_ultra_slow.Ti = DEF_PI_VEL_US_TI; PI_velocity_ultra_slow.timestamp = _micros(); - PI_velocity_ultra_slow.voltage_limit = power_supply_voltage/2; + PI_velocity_ultra_slow.voltage_limit = voltage_power_supply/2; PI_velocity_ultra_slow.voltage_ramp = DEF_PI_VEL_US_U_RAMP; PI_velocity_ultra_slow.voltage_prev = 0; PI_velocity_ultra_slow.tracking_error_prev = 0; @@ -54,7 +54,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // index search PI controller PI_velocity_index_search.K = DEF_PI_VEL_INDEX_K; PI_velocity_index_search.Ti = DEF_PI_VEL_INDEX_TI; - PI_velocity_index_search.voltage_limit = power_supply_voltage/2; + PI_velocity_index_search.voltage_limit = voltage_power_supply/2; PI_velocity_index_search.voltage_ramp = DEF_PI_VEL_INDEX_U_RAMP; PI_velocity_index_search.timestamp = _micros(); PI_velocity_index_search.voltage_prev = 0; @@ -88,9 +88,9 @@ void BLDCMotor::init() { setPwmFrequency(pwmC); // sanity check for the voltage limit configuration - if(PI_velocity.voltage_limit > power_supply_voltage/2) PI_velocity.voltage_limit = PI_velocity.voltage_limit > power_supply_voltage/2; - if(PI_velocity.voltage_limit > power_supply_voltage/2) PI_velocity_ultra_slow.voltage_limit = power_supply_voltage/2; - if(PI_velocity_index_search.voltage_limit > power_supply_voltage/2) PI_velocity_index_search.voltage_limit = power_supply_voltage/2; + if(PI_velocity.voltage_limit > voltage_power_supply/2) PI_velocity.voltage_limit = PI_velocity.voltage_limit > voltage_power_supply/2; + if(PI_velocity.voltage_limit > voltage_power_supply/2) PI_velocity_ultra_slow.voltage_limit = voltage_power_supply/2; + if(PI_velocity_index_search.voltage_limit > voltage_power_supply/2) PI_velocity_index_search.voltage_limit = voltage_power_supply/2; _delay(500); // enable motor @@ -148,7 +148,7 @@ void BLDCMotor::linkEncoder(Encoder* enc) { int BLDCMotor::alignEncoder() { if(debugger) debugger->println("DEBUG: Align the encoder and motor electrical 0 angle."); // align the electircal phases of the motor and encoder - setPwm(pwmA, power_supply_voltage/2.0); + setPwm(pwmA, voltage_power_supply/2.0); setPwm(pwmB,0); setPwm(pwmC,0); _delay(1000); @@ -267,10 +267,15 @@ void BLDCMotor::move(float target) { Method using FOC to set Uq to the motor at the optimal angle */ void BLDCMotor::setPhaseVoltage(double Uq, double angle_el) { - + + // angle normalisation in between 0 and 2pi + // only necessary if using _sin and _cos - approximation funcitons + float angle = normalizeAngle(angle_el + index_electric_angle); // Inverse park transform - Ualpha = -sin(angle_el + index_electric_angle) * Uq; - Ubeta = cos(angle_el + index_electric_angle) * Uq; + // regular sin + cos ~300us + // approx _sin + _cos ~90us + Ualpha = -_sin(angle) * Uq; + Ubeta = _cos(angle) * Uq; // Clarke transform Ua = Ualpha; @@ -290,10 +295,12 @@ void BLDCMotor::setPhaseVoltage(double Uq, double angle_el) { */ void BLDCMotor::setPwm(int pinPwm, float U) { // max value - float U_max = power_supply_voltage/2.0; + float U_max = voltage_power_supply/2.0; // sets the voltage [-U_max,U_max] to pwm [0,255] // u_pwm = 255 * (U + U_max)/(2*U_max) + // it can be further optimised + // (example U_max = 6 > U_pwm = 127.5 + 21.25*U) int U_pwm = 127.5 * (U/U_max + 1); // limit the values between 0 and 255 diff --git a/arduino_foc_minimal/BLDCMotor.h b/arduino_foc_minimal/BLDCMotor.h index a1b01b03..b26cabd0 100644 --- a/arduino_foc_minimal/BLDCMotor.h +++ b/arduino_foc_minimal/BLDCMotor.h @@ -15,7 +15,7 @@ // ultra slow velocity PI params #define DEF_PI_VEL_US_K 60.0 #define DEF_PI_VEL_US_TI 100.0 -#define DEF_PI_VEL_US_U_RAMP 100 +#define DEF_PI_VEL_US_U_RAMP 300 // angle P params #define DEF_P_ANGLE_K 20 // angle velocity limit default @@ -105,7 +105,7 @@ class BLDCMotor float voltage_q; // Power supply woltage - float power_supply_voltage; + float voltage_power_supply; // configuraion structures ControlType controller; diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index dba916de..0077abf4 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -59,29 +59,13 @@ void Encoder::handleA() { } break; } - if(hasIndex()){ - int I = digitalRead(index_pin); - if(I && !I_active){ - // aling encoder on each index - if(index_pulse_counter){ - long tmp = pulse_counter; - // corrent the counter value - pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; - // preserve relative speed - prev_pulse_counter += pulse_counter - tmp; - } - // initial offset - if(!index_pulse_counter) index_pulse_counter = pulse_counter; - } - I_active = I; - } } // B channel void Encoder::handleB() { int B = digitalRead(pinB); switch (quadrature){ case Quadrature::ENABLE: - // CPR = 4xPPR + // // CPR = 4xPPR if ( B != B_active ) { pulse_counter += (A_active != B_active) ? 1 : -1; pulse_timestamp = _micros(); @@ -96,6 +80,10 @@ void Encoder::handleB() { } break; } +} + +// Index channel +void Encoder::handleIndex() { if(hasIndex()){ int I = digitalRead(index_pin); if(I && !I_active){ @@ -191,14 +179,13 @@ void Encoder::init(void (*doA)(), void(*doB)()){ if(pullup == Pullup::INTERN){ pinMode(pinA, INPUT_PULLUP); pinMode(pinB, INPUT_PULLUP); + if(hasIndex()) pinMode(index_pin,INPUT_PULLUP); }else{ pinMode(pinA, INPUT); pinMode(pinB, INPUT); + if(hasIndex()) pinMode(index_pin,INPUT); } - // if index used intialise it - if(hasIndex()) pinMode(index_pin,INPUT); - - // counter setup + // counter setup pulse_counter = 0; pulse_timestamp = _micros(); // velocity calculation varibles @@ -211,6 +198,8 @@ void Encoder::init(void (*doA)(), void(*doB)()){ // attach interrupt if functions provided switch(quadrature){ case Quadrature::ENABLE: + // initial cpr = PPR + // change it if the mode is quadrature cpr = 4*cpr; // A callback and B callback if(doA != nullptr){ @@ -227,5 +216,12 @@ void Encoder::init(void (*doA)(), void(*doB)()){ attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); } break; - } + } + + // if index used intialise the index interrupt + if(hasIndex()) { + *digitalPinToPCMSK(index_pin) |= bit (digitalPinToPCMSKbit(index_pin)); // enable pin + PCIFR |= bit (digitalPinToPCICRbit(index_pin)); // clear any outstanding interrupt + PCICR |= bit (digitalPinToPCICRbit(index_pin)); // enable interrupt for the group + } } diff --git a/arduino_foc_minimal/Encoder.h b/arduino_foc_minimal/Encoder.h index 7dd06c66..21da1a80 100644 --- a/arduino_foc_minimal/Encoder.h +++ b/arduino_foc_minimal/Encoder.h @@ -35,6 +35,8 @@ class Encoder{ void handleA(); // B channel void handleB(); + // index handle + void handleIndex(); // encoder getters // shaft velocity getter @@ -58,6 +60,7 @@ class Encoder{ // use 4xppr or not Quadrature quadrature; + private: volatile long pulse_counter; // current pulse counter volatile long pulse_timestamp; // last impulse timestamp in us diff --git a/arduino_foc_minimal/FOCutils.cpp b/arduino_foc_minimal/FOCutils.cpp index d23ab09b..b183e6fc 100644 --- a/arduino_foc_minimal/FOCutils.cpp +++ b/arduino_foc_minimal/FOCutils.cpp @@ -2,6 +2,7 @@ /* High PWM frequency + https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 */ void setPwmFrequency(int pin) { if (pin == 5 || pin == 6 || pin == 9 || pin == 10) { @@ -35,4 +36,38 @@ unsigned long _micros(){ // return the value based on the prescaler if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); else return (micros()); -} \ No newline at end of file +} + + +// lookup table for sine calculation in between 0 and 90 degrees +float sine_array[200] = {0.0000,0.0079,0.0158,0.0237,0.0316,0.0395,0.0473,0.0552,0.0631,0.0710,0.0789,0.0867,0.0946,0.1024,0.1103,0.1181,0.1260,0.1338,0.1416,0.1494,0.1572,0.1650,0.1728,0.1806,0.1883,0.1961,0.2038,0.2115,0.2192,0.2269,0.2346,0.2423,0.2499,0.2575,0.2652,0.2728,0.2804,0.2879,0.2955,0.3030,0.3105,0.3180,0.3255,0.3329,0.3404,0.3478,0.3552,0.3625,0.3699,0.3772,0.3845,0.3918,0.3990,0.4063,0.4135,0.4206,0.4278,0.4349,0.4420,0.4491,0.4561,0.4631,0.4701,0.4770,0.4840,0.4909,0.4977,0.5046,0.5113,0.5181,0.5249,0.5316,0.5382,0.5449,0.5515,0.5580,0.5646,0.5711,0.5775,0.5839,0.5903,0.5967,0.6030,0.6093,0.6155,0.6217,0.6279,0.6340,0.6401,0.6461,0.6521,0.6581,0.6640,0.6699,0.6758,0.6815,0.6873,0.6930,0.6987,0.7043,0.7099,0.7154,0.7209,0.7264,0.7318,0.7371,0.7424,0.7477,0.7529,0.7581,0.7632,0.7683,0.7733,0.7783,0.7832,0.7881,0.7930,0.7977,0.8025,0.8072,0.8118,0.8164,0.8209,0.8254,0.8298,0.8342,0.8385,0.8428,0.8470,0.8512,0.8553,0.8594,0.8634,0.8673,0.8712,0.8751,0.8789,0.8826,0.8863,0.8899,0.8935,0.8970,0.9005,0.9039,0.9072,0.9105,0.9138,0.9169,0.9201,0.9231,0.9261,0.9291,0.9320,0.9348,0.9376,0.9403,0.9429,0.9455,0.9481,0.9506,0.9530,0.9554,0.9577,0.9599,0.9621,0.9642,0.9663,0.9683,0.9702,0.9721,0.9739,0.9757,0.9774,0.9790,0.9806,0.9821,0.9836,0.9850,0.9863,0.9876,0.9888,0.9899,0.9910,0.9920,0.9930,0.9939,0.9947,0.9955,0.9962,0.9969,0.9975,0.9980,0.9985,0.9989,0.9992,0.9995,0.9997,0.9999,1.0000,1.0000}; + +// function approximating the sine calculation by using fixed size array +// ~40us +// precision +-0.005 +// it has to receive an angle in between 0 and 2PI +float _sin(float a){ + if(a < _PI_2){ + //return sine_array[(int)(199.0*( a / (M_PI/2.0)))]; + return sine_array[(int)(126.6873* a)]; + }else if(a < M_PI){ + // return sine_array[(int)(199.0*(1.0 - (a-M_PI/2.0) / (M_PI/2.0)))]; + return sine_array[398 - (int)(126.6873*a)]; + }else if(a < _3PI_2){ + // return -sine_array[(int)(199.0*((a - M_PI) / (M_PI/2.0)))]; + return -sine_array[-398 + (int)(126.6873*a)]; + } else { + // return -sine_array[(int)(199.0*(1.0 - (a - 3*M_PI/2) / (M_PI/2.0)))]; + return -sine_array[796 - (int)(126.6873*a)]; + } +} + +// function approfimating cosine calculaiton by using fixed size array +// ~50us +// precision +-0.005 +// it has to receive an angle in between 0 and 2PI +float _cos(float a){ + float a_sin = a + _PI_2; + a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} diff --git a/arduino_foc_minimal/FOCutils.h b/arduino_foc_minimal/FOCutils.h index 0d464f03..d6177497 100644 --- a/arduino_foc_minimal/FOCutils.h +++ b/arduino_foc_minimal/FOCutils.h @@ -13,6 +13,7 @@ #define _120_D2R 2.09439510239 #define _PI_2 1.57079632679 #define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 // High PWM frequency void setPwmFrequency(int pin); @@ -25,4 +26,13 @@ void _delay(unsigned long ms); // arduino funciton doesn't work well with interrupts unsigned long _micros(); +// function approximating the sine calculation by using fixed size array +// ~40us +// it has to receive an angle in between 0 and 2PI +float _sin(float a); +// function approfimating cosine calculaiton by using fixed size array +// ~50us +// it has to receive an angle in between 0 and 2PI +float _cos(float a); + #endif \ No newline at end of file diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index 9ce99c44..eedcbd05 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -13,11 +13,20 @@ BLDCMotor motor = BLDCMotor(9, 5, 6, 11, 8); // Encoder(int encA, int encB , int cpr, int index) // - encA, encB - encoder A and B pins // - ppr - impulses per rotation (cpr=ppr*4) -// - index pin - (optional input) -Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 4); -// interrupt ruotine intialisation +// - index pin - (optional input) +Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, A0); + +// Interrupt rutine intialisation +// channel A and B callbacks void doA(){encoder.handleA();} void doB(){encoder.handleB();} +// index calback interrupt code +// please set the right PCINT(0,1,2)_vect parameter +// PCINT0_vect - index pin in between D8 and D13 +// PCINT1_vect - index pin in between A0 and A5 (recommended) +// PCINT2_vect - index pin in between D0 and D7 +ISR (PCINT1_vect) { encoder.handleIndex(); } + void setup() { // debugging port @@ -38,7 +47,7 @@ void setup() { // power supply voltage // default 12V - motor.power_supply_voltage = 12; + motor.voltage_power_supply = 12; // index search velocity - default 1rad/s motor.index_search_velocity = 1; @@ -51,7 +60,7 @@ void setup() { // default value is 100 motor.PI_velocity_index_search.voltage_ramp = 100; - // set FOC loop to be used + // set control loop type to be used // ControlType::voltage // ControlType::velocity // ControlType::velocity_ultra_slow @@ -63,12 +72,13 @@ void setup() { // default K=1.0 Ti = 0.003 motor.PI_velocity.K = 0.3; motor.PI_velocity.Ti = 0.003; - //defualt power_supply_voltage/2 + //defualt voltage_power_supply/2 motor.PI_velocity.voltage_limit = 6; // jerk control using voltage voltage ramp - // default value is 100 volts per sec ~ 0.1V per millisecond + // default value is 300 volts per sec ~ 0.3V per millisecond motor.PI_velocity.voltage_ramp = 300; + // link the motor to the sensor motor.linkEncoder(&encoder); @@ -82,13 +92,13 @@ void setup() { motor.initFOC(); Serial.println("Motor ready."); - Serial.println("Input the new target value:"); + Serial.println("Input the new target velocity:"); _delay(1000); + } // target velocity variable -float target = 0; -int t = 0; +float target_velocity = 0; void loop() { // iterative state calculation calculating angle @@ -102,7 +112,7 @@ void loop() { // velocity, position or voltage // this funciton can be run at much lower frequency than loopFOC funciton // it can go as low as ~50Hz - motor.move(target); + motor.move(target_velocity); // function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! @@ -152,9 +162,9 @@ void serialEvent() { // if the incoming character is a newline // end of input if (inChar == '\n') { - target = inputString.toFloat(); - Serial.print("Tagret: "); - Serial.println(target); + target_velocity = inputString.toFloat(); + Serial.print("Tagret Velocity: "); + Serial.println(target_velocity); inputString = ""; } } From 9dee9f81507e584d5b696b9e6c1ad8a6662bc9d1 Mon Sep 17 00:00:00 2001 From: askuric Date: Wed, 22 Apr 2020 18:35:40 +0200 Subject: [PATCH 19/65] Readme addapted for the minimal branch --- README.md | 456 +++++++++++++++++++++++++++++++++++++++++------------- 1 file changed, 345 insertions(+), 111 deletions(-) diff --git a/README.md b/README.md index f8974bcc..dcce0616 100644 --- a/README.md +++ b/README.md @@ -1,36 +1,64 @@ -# Arduino Field Oriented Control (FOC) library - +# Arduino Simple FOC library minimal example ![Library Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Compile/badge.svg) [![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT) +[![arduino-library-badge](https://www.ardu-badge.com/badge/Simple%20FOC.svg?)](https://www.ardu-badge.com/badge/Simple%20FOC.svg) + +This is the minimal Arduino example of the [Simple FOC](https://github.com/askuric/Arduino-FOC) arduino library intended for mostly for easier experiemtation and modification! + + # Contents + - [Installation](#arduino-simple-foc-instalation) + - [Installing the full library](#installing-simple-foc-full-library) + - [Installing the minimal Arduino example](#download-minimal-simple-foc-arduino-example) +- [Electrical connecitons and schematic](#electrical-connections) + - [Minimal setup](#all-you-need-for-this-project-is-an-exaple-in-brackets) + - [Arduino Simple FOC Shield V1.2](#arduino-simple-foc-shield-v12) + - [Arduino UNO + L6234 driver](#arduino-uno--l6234-breakout-broad) + - [HMBGC gimbal contorller example](#hmbgc-v22) +- [Code explanation and examples](#arduino-simple-foc-library-code) + - [Encoder setup](#encoder-setup) + - [BLDC motor setup](#motor-setup) + - [Control loop setup](#control-loop-setup) + - [Voltage control loop](#voltage-control-loop) + - [Velcoity control loop](#velocity-control-loop) + - [Angle control loop](#angle-control-loop) + - [Utra Slow Velocity control loop](#ultra-slow-velocity-control-loop) + - [Debugging practice](#debugging) + - [Future work and work in progress](#future-work-roadmap) +- [Contact](#contact) + + +# Arduino Simple FOC instalation +Depending on if you want to use this library as the plug and play Arduino library or you want to get insight in the algorithm and make changes simply there are two ways to install this code. + +## Installing Simple FOC full library +### Arduino IDE - Library manager +The simplest way to get hold of the library is direclty by using Arduino IDE and its integrated Library Manager. Just serarch for `Simple FOC` library and install the lates version. + +### Download library directly +If you don't want to use the Arduino IDE and Library manager you can direclty download the library from this website. +- Simplest way to do it is to download the `zip` aerchieve directly on the top of this webiste. Click first on `Clone or Download` and then on `Download ZIP`. Once you have the zip ardhieve downloaded, unzip it and place it in your Arduino Libraries forlder. On Windows it is usually in `Documents > Arduino > libraries`. + - Now reopen your Arduino IDE and you should have the library examples in `File > Examples > Simple FOC`. + +- If you are more experienced with the terminal you can open your terminal in the Arduino libraries folder direclty and clone the Arduino FOC git repsitory: +```bash +git clone https://github.com/askuric/Arduino-FOC.git +``` + - Now reopen your Arduino IDE and you should have the library examples in `File > Examples > Simple FOC`. +## Download minimal Simple FOC Arduino example +To download the minmial verison of Simple FOC intended for those willing to experiment and extend the code I suggest using this version over the full library. +This code is completely indepenedet and you can run it as any other Arduino Schetch without the need for any libraries. +The code is place in the [minimal branch](https://github.com/askuric/Arduino-FOC/tree/minimal). -Proper low cost FOC supporting boards are very hard to find these days and even may not exist. The reason may be that the hobby community has not yet dug into it properly. Therefore this is the attempt to demistify the Field Oriented Control (FOC) algorithm and make a robust but simple implementation for usage with Arduino hadrware. - -### This project aims to close the gap in the areas: -- Low cost applications <50$ -- Low current operation < 5A -- Simple usage and scalability (Arduino) - and demistify FOC control in a simple way. - - -#### The closest you can get to FOC support and low cost (I was able to find) is: - -Odroid | Trinamic ------------- | ------------- - | -:heavy_check_mark: Open Source | :x: Open Source -:heavy_check_mark:Simple to use | :heavy_check_mark: Simple to use -:x: Low cost ($100) | :x: Low cost ($100) -:x: Low power (>50A) | :heavy_check_mark: Low power +- You can download it directly form the [minimal branch](https://github.com/askuric/Arduino-FOC/tree/minimal) by clicking on the `Clone or Download > Download ZIP`. + - Then you just unzip it and open the schetch in Arduino IDE. -Infineon | FOC-Arduino-Brushless ------------- | ------------- -| -:x: Open Source | :heavy_check_mark: Open Source -:heavy_check_mark:Simple to use | :x: Simple to use -:heavy_check_mark:Low cost ($40) | :heavy_check_mark: Low cost -:heavy_check_mark: Low power | :heavy_check_mark: Low power +- You can also clone it using the terminal: + ```bash + git clone -b minimal https://github.com/askuric/Arduino-FOC.git + ``` + - Then you just open it with the Arduino IDE and run it. @@ -38,42 +66,43 @@ Proper low cost FOC supporting boards are very hard to find these days and even ### All you need for this project is (an exaple in brackets): - Brushless DC motor - 3 pahse (IPower GBM4198H-120T [Ebay](https://www.ebay.com/itm/iPower-Gimbal-Brushless-Motor-GBM4108H-120T-for-5N-7N-GH2-ILDC-Aerial-photo-FPV/252025852824?hash=item3aade95398:g:q94AAOSwPcVVo571:rk:2:pf:1&frcectupt=true)) - - Encoder - ( Incremental 2400cpr [Ebay](https://www.ebay.com/itm/600P-R-Photoelectric-Incremental-Rotary-Encoder-5V-24V-AB-2-Phases-Shaft-6mm-New/173145939999?epid=19011022356&hash=item28504d601f:g:PZsAAOSwdx1aKQU-:rk:1:pf:1)) -- Arduino + BLDC motor driver ( L6234 driver [Drotek](https://store-drotek.com/212-brushless-gimbal-controller-l6234.html), [Ebay](https://www.ebay.fr/itm/L6234-Breakout-Board-/153204519965)) + - Encoder + - Incremental 2400cpr [Ebay](https://www.ebay.com/itm/600P-R-Photoelectric-Incremental-Rotary-Encoder-5V-24V-AB-2-Phases-Shaft-6mm-New/173145939999?epid=19011022356&hash=item28504d601f:g:PZsAAOSwdx1aKQU-:rk:1:pf:1) + - Magnetic 14bit [Aliexpress](https://fr.aliexpress.com/item/4000034013999.html?spm=a2g0o.productlist.0.0.4a7f5c25mYwpN3&algo_pvid=8f452506-7081-4d0a-8f66-d0b725d6de66&algo_expid=8f452506-7081-4d0a-8f66-d0b725d6de66-0&btsid=0b0a0ad815873142372227604ed134&ws_ab_test=searchweb0_0,searchweb201602_,searchweb201603_) +- BLDC motor driver + - L6234 driver [Drotek](https://store-drotek.com/212-brushless-gimbal-controller-l6234.html), [Ebay](https://www.ebay.fr/itm/L6234-Breakout-Board-/153204519965) + - Alternatively the library supports the arduino based gimbal controllers such as: HMBGC V2.2 ([Ebay](https://www.ebay.com/itm/HMBGC-V2-0-3-Axle-Gimbal-Controller-Control-Plate-Board-Module-with-Sensor/351497840990?hash=item51d6e7695e:g:BAsAAOSw0QFXBxrZ:rk:1:pf:1)) -Alternatively the library supports the arduino based gimbal controllers such as: -- HMBGC V2.2 ([Ebay](https://www.ebay.com/itm/HMBGC-V2-0-3-Axle-Gimbal-Controller-Control-Plate-Board-Module-with-Sensor/351497840990?hash=item51d6e7695e:g:BAsAAOSw0QFXBxrZ:rk:1:pf:1)) - -## Arduino FOC Shield V1.2 +## Arduino Simple FOC Shield V1.2 At this moment we are developing an open source version of Arduin shiled specifically for FOC motor control. We already have prototypes of the board and we are in the testing phase. We will be coming out with the details very soon! ### Features -- Plug and play capability with the Arduino FOC library +- Plug and play capability with the Arduino Simple FOC library - Price in the range of \$20-\$40 - Gerber files and BOM available Open Source ***Let me know if you are interested! antun.skuric@outlook.com*** -You can explore the [3D model of the board in the PDF form](extras/ArduinoFOCShieldV12.pdf). +You can explore the [3D model of the board in the PDF form](https://raw.githubusercontent.com/askuric/Arduino-FOC/master/extras/ArduinoFOCShieldV12.pdf). - + ## Arduino UNO + L6234 breakout broad The code is simple enough to be run on Arudino Uno board.

- +

### Encoder - Encoder channels `A` and `B` are connected to the Arduino's external intrrupt pins `2` and `3`. -- Optionally if your encoder has `index` signal you can connect it to any available pin, figure shows pin `4`. - - The library doesnt support the Index pin for now (version v1.1.0) +- Optionally if your encoder has `index` signal you can connect it to any available pin, figure shows pin `4`. + - If you can choose preferably connect it to an `A0-A5` due to the interrupt rutine, it will have better performance (but any other pin will work as well). ### L6234 breakout board -- Connected to the arduino pins `9`,`10` and `11`. +- Connected to the arduino pins `9`,`10` and `11` (you can use also pins `5` and `6`). - Additionally you can connect the `enable` pin to the any digital pin of the arduino the picture shows pin `8` but this is optional. You can connect the driver enable directly to 5v. - Make sure you connect the common ground of the power supply and your Arduino ### Motor @@ -86,8 +115,8 @@ Motor phases `a`,`b`,`c` and encoder channels `A` and `B` have to be oriented ri To use HMBGC controller for vector control (FOC) you need to connect motor to one of the motor terminals and connect the Encoder. The shema of connection is shown on the figures above, I also took a (very bad) picture of my setup.

- - + +

@@ -96,7 +125,6 @@ Since HMBGC doesn't have acces to the arduinos external interrupt pins `2` and ` - Encoder channels `A` and `B` are connected to the pins `A0` and `A1`. - Optionally if your encoder has `index` signal you can connect it to any available pin, figure shows pin `A2`. - - The library doesnt support the Index pin for now (version v1.1.0) ### Motor - Motor phases `a`,`b` and `c` are connected directly to the driver outputs @@ -104,9 +132,8 @@ Motor phases `a`,`b`,`c` and encoder channels `A` and `B` have to be oriented ri - -# Arduino FOC library code -The code is organised into a librarie. The library contains two classes `BLDCmotor` and `Endcoder`. `BLDCmotor` contains all the necessary FOC algorithm funcitons as well as PI controllers for the velocity and angle control. `Encoder` deals with the encoder interupt funcitons, calcualtes motor angle and velocity( using the [Mixed Time Frequency Method](https://github.com/askuric/Arduino-Mixed-Time-Frequency-Method)). +# Arduino Simple FOC library code +The code is organised into a library. The library contains two classes `BLDCmotor` and `Endcoder`. `BLDCmotor` contains all the necessary FOC algorithm funcitons as well as PI controllers for the velocity and angle control. `Encoder` deals with the encoder interupt funcitons, calcualtes motor angle and velocity ( using the [Mixed Time Frequency Method](https://github.com/askuric/Arduino-Mixed-Time-Frequency-Method)). The `Encoder` class will support any type of otpical and magnetic encoder. ## Encoder setup To initialise the encoder you need to provide the encoder `A` and `B` channel pins, encoder `PPR` and optionally `index` pin. @@ -115,7 +142,14 @@ To initialise the encoder you need to provide the encoder `A` and `B` channel pi // - encA, encB - encoder A and B pins // - ppr - impulses per rotation (cpr=ppr*4) // - index pin - (optional input) -Encoder encoder = Encoder(2, 3, 8192, 4); +Encoder encoder = Encoder(2, 3, 8192, A0); +``` +Next important feature of the encoder is enabling or disabling the `Quadrature` more. If the Encoder is run in the quadratue more its number of impulses per rotation(`PPR`) is quadrupled by detecting each `CHANGE` of the signals `A` and `B` - `CPR = 4xPPR`. In some applicaitons, when the encoder `PPR` is high it can be too much for the Arudino to handle so it is preferable not to use `Quadrature` mode. By default all the encoders use `Quadrature` mode. If you would like to enable or disable this paramter do it in the Arduino setup funciton by running: +```cpp +// check if you need internal pullups +// Quadrature::ENABLE - CPR = 4xPPR - default +// Quadrature::DISABLE - CPR = PPR +encoder.quadrature = Quadrature::ENABLE; ``` Additionally the encoder has one more important parameters which is whether you want to use Arduino's internal pullup or you have external one. That is set by changing the value of the `encoder.pullup` variuable. The default value is set to `Pullup::EXTERN` ```cpp @@ -124,25 +158,36 @@ Additionally the encoder has one more important parameters which is whether you // Pullup::INTERN - needs internal arduino pullup encoder.pullup = Pullup::EXTERN; ``` -Finally to start the encoder counter and intialise all the periphery pins you need the call of `encoder.init()` is made. -```cpp -// initialise encoder hardware -encoder.init(doA, doB); -``` -Where the functions `doA()` and `doB()` are buffering functions of encoder callback funcitons `encoder.handleA()` and `encoder.handleB()`. +### Encoder interrupt configuration +There are two ways you can run encoders with Simple FOC libtrary. +- Using Arduino hardware external interrupt - for Arduino UNO pins `2` and `3` +- Using software pin chnage interrupt by using a library such as [PciManager library](https://github.com/prampec/arduino-pcimanager) + +> Using the hardware external interrupts usualy results in a bit better and more realible performance but software interrupts will work very good as well. + +#### Arduino Hardware external interrupt +Arduino hadrware external interrupt pins are pin `2` and `3`. And in order to use its functionallities the encoder channels `A` and `B` will have to be connected exacly on these pins. + +Simple FOC `Encoder` class already has implemented initialisation and encoder `A` and `B` channel callbacks. +All you need to do is define two funcitons `doA()` and `doB()`, the buffering functions of encoder callback funcitons `encoder.handleA()` and `encoder.handleB()`. ```cpp // interrupt ruotine intialisation void doA(){encoder.handleA();} void doB(){encoder.handleB();} ``` -You can name the funcitons as you wish. It is just important to supply them to the `encoder.init()` funciton. This procedure is a tradeoff in between scalability and simplicity. This allows you to have more than one encoder connected to the same arduino. All you need to do is to instantiate new `Encoder` class and create new buffer functions. For example: +And supply those functions to the encoder initialiasation fucntion `encoder.init()` +```cpp +// initialise encoder hardware +encoder.init(doA, doB); +``` +You can name the buffering funcitons as you wish. It is just important to supply them to the `encoder.init()` funciton. This procedure is a tradeoff in between scalability and simplicity. This allows you to have more than one encoder connected to the same arduino. All you need to do is to instantiate new `Encoder` class and create new buffer functions. For example: ```cpp // encoder 1 -Encoder enc1 = Encoder(2, 3, 8192, 4); +Encoder enc1 = Encoder(...); void doA1(){enc1.handleA();} void doB1(){enc1.handleB();} // encoder 2 -Encoder enc2 = Encoder(5, 6, 8192, 7); +Encoder enc2 = Encoder(...); void doA2(){enc2.handleA();} void doB2(){enc2.handleB();} @@ -154,8 +199,150 @@ void setup(){ } ``` +##### Index pin configuration +In order to read index pin efficienlty Simple FOC algorithm uses Arduino interrupt routine as well. +Simple FOC has implemented the index pin callback `encoder.handleIndex()`. In order to enable the index pin utilisation just add the index pin in the encoder constructor: +```cpp +Encoder encoder = Encoder(pinA, pinB, cpr, index_pin); +``` +The library make sure to enable the propper interrupts and initialise the `pinMode` based on your [pullup configuration](#encoder-setup). + +The last peace of the index pin enabling puzzle is the Arduino's `ISR` funciton call: +```cpp +// index calback interrupt code +// please set the right PCINT(0,1,2)_vect parameter +// PCINT0_vect - index pin in between D8 and D13 +// PCINT1_vect - index pin in between A0 and A5 (recommended) +// PCINT2_vect - index pin in between D0 and D7 +ISR (PCINT1_vect) { encoder.handleIndex(); } +``` +Make sure you use the right `PCINT(1,2,3)_vect` paramereter of the `ISR` function. +`ISR` Parameter | Arduino pin +-----| ----- +PCINT0_vect | D8 - D13 +PCINT1_vect | A0 - A5 +PCINT2_vect | D0 - D7 + +The `ISR` with the vector `PCINT0_vect` will be called each time one of the pins `D8-D13` changes. Each time one of the pins `A0-A5` chenges the Arduino interrupt `ISR` function with the `PCINT1_vect` will be called and finally if any one of the `D0-D7` pins changes the `ISR` function with the parameter `PCINT2_vect` will be called. So therefore it is important to use the index callback `encoder.handleIndex()` funciton in the rigth `ISR` function. +Here is an eaxmple of the setup od two encoders with different `index` locations: +```cpp +Encoder encoder = Encoder(2,3,600,A0); +// A and B interrupt rutine +void doA1(){encoder.handleA();} +void doB1(){encoder.handleB();} +// index interrupt rutine +ISR (PCINT1_vect) { encoder.handleIndex(); } + +void setup(){...} +void loop(){...} +``` +Or for example: +```cpp +Encoder encoder = Encoder(2,3,600,13); +// A and B interrupt rutine +void doA1(){encoder.handleA();} +void doB1(){encoder.handleB();} +// index interrupt rutine +ISR (PCINT0_vect) { encoder.handleIndex(); } + +void setup(){...} +void loop(){...} +``` To explore better the encoder algorithm an example is provided `encoder_example.ino`. +#### Arduino software pin change interrupt +If you are not able to access your pins `2` and `3` of your Arduino or if you want to use more than none encoder you will have to use the software interrupt approach. +I suggest using the [PciManager library](https://github.com/prampec/arduino-pcimanager). + +The stps of using this library in code are very similar to [harware interrupt](#arduino-hardware-external-interrupt). +The SimpleFOC `Encoder` class still provides you with all the callbacks `A`, `B` and `Index` channels but the Simple FOC library will not initialise the interrupts for you. + +In order to use the `PCIManager` library you will need to include it in your code: +```cpp +#include +#include +``` +Next step is the same as before, you will just intialise the new `Encoder` instance. +```cpp +Encoder encoder = Encoder(10, 11, 8192); +// A and B interrupt callback buffers +void doA(){encoder.handleA();} +void doB(){encoder.handleB();} +``` +Then you declare listeners `PciListenerImp `: +```cpp +// encoder interrupt init +PciListenerImp listenerA(encoder.pinA, doA); +PciListenerImp listenerB(encoder.pinB, doB); +``` +And finally instead of supplying the functions `doA` and `doB` to the `encoder.init()` you call the init without parameters and use `PCIManager` library to register the interrupts +```cpp +// initialise encoder hardware +encoder.init(); +// interrupt intitialisation +PciManager.registerListener(&listenerA); +PciManager.registerListener(&listenerB); +``` +And that is it, it is very simple. It if you wnat more than one encoder, you just initialise the new class instance, create the new `A` and `B` callbacks, intialise the new listeners. Here is a quick example: +```cpp +// encoder 1 +Encoder enc1 = Encoder(9, 10, 8192); +void doA1(){enc1.handleA();} +void doB1(){enc1.handleB();} +PciListenerImp listA1(enc1.pinA, doA1); +PciListenerImp listB1(enc1.pinB, doB1); + +// encoder 2 +Encoder enc2 = Encoder(13, 12, 8192); +void doA2(){enc2.handleA();} +void doB2(){enc2.handleB();} +PciListenerImp listA2(enc2.pinA, doA2); +PciListenerImp listB2(enc2.pinB, doB2); + +void setup(){ +... + // encoder 1 + enc1.init(); + PciManager.registerListener(&listA1); + PciManager.registerListener(&listB1); + // encoder 2 + enc2.init(); + PciManager.registerListener(&listA2); + PciManager.registerListener(&listB2); +... +} +``` +You can look into the `HMBGC_example.ino` ecxample to see this code in action. +##### Index pin configuration +Enabling index pin in the case of the software interrupt is very simple. You just need to provide it to the `Encoder` class intialisation as additional parameter. +```cpp +Encoder encoder = Encoder(pinA, pinB, cpr, index_pin); +``` +Afterward you create the same type of callback buffering function as for `A` and `B` channels and using the `PCIManager` tools initialise and register the listener for the `index` channel as for the `A` and `B`. Here is a quick example: +xample: +```cpp +// class init +Encoder encoder = Encoder(9, 10, 8192,11); +void doA(){encoder.handleA();} +void doB(){encoder.handleB();} +void doIndex(){encoder.handleIndex();} +// listeners init +PciListenerImp listenerA(encoder.pinA, doA); +PciListenerImp listenerB(encoder.pinB, doB); +PciListenerImp listenerIndex(encoder.index_pin, doIndex); + +void setup(){ +... + // enable the hardware + enc1.init(); + // enable interrupt + PciManager.registerListener(&listenerA); + PciManager.registerListener(&listenerB); + PciManager.registerListener(&listenerIndex); +... +} +``` + ## Motor setup To intialise the motor you need to input the `pwm` pins, number of `pole pairs` and optionally driver `enable` pin. ```cpp @@ -165,6 +352,8 @@ To intialise the motor you need to input the `pwm` pins, number of `pole pairs` // - enable pin - (optional input) BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); ``` +If you are not sure what your `pole_paris` number is I included an example code to estimate your `pole_paris` number in the examples `find_pole_pairs_number.ino`. I hope it helps. + To finalise the motor setup the encoder is added to the motor and the `init` function is called. ```cpp // link the motor to the sensor @@ -174,21 +363,24 @@ motor.init(); ``` -## BLDC Driver parameters -First thing you can configure is your `power_supply_voltage` value. The default value is set to `12V`. If you set your power supply to some other vlaue, chnage it here for the control loops to adapt. +### Power supply voltage +The default `voltage_power_supply` value is set to `12V`. If you set your power supply to some other vlaue, chnage it here for the control loops to adapt. ```cpp // power supply voltage -motor.power_supply_voltage = 12; -``` -You can also change driver type by changing the value of the variable `motor.driver`. It tells the algorithm to generate unipolar of bipolar FOC voltages. This basically means if your BLDC driver can only output voltages in range `[0,power_supply_voltage]` your driver is `DriverType::unipolar` and if it can output voltage in range `[-power_supply_voltage, power_supply_voltage]` than you driver is `DriverType::bipolar` what is case in most of the drivers and what is default value as well. -```cpp -// set driver type -// DriverType::unipolar // HMBGC -// DriverType::bipolar // L6234 (default) -motor.driver = DriverType::bipolar; +motor.voltage_power_supply = 12; ``` +The `voltage_power_supply` value tells the FOC algorithm what is the maximum voltage it can output. Additioanlly since the FOC algotihm implemented in the Simple FOC library uses sinusoidal voltages the magnitudes of the sine waves exiting the Drvier circuit is going to be `[-voltage_power_supply/2, voltage_power_supply/2]`. + + + ## Control loop setup -First parameter you can change is the variable you want to control. You set it by changing the `motor.controller` variable. If you want to control the motor angle you will set the `controller` to `ControlType::angle`, if youy seek the DC motor behavior behaviour by controlling the voltage use `ControlType::voltage`, if you wish to control motor angular velocity `ControlType::velocity`. If you wish to control velocities which are very very slow, typically around ~0.01 rad/s you can use the `ControlType::velocity_ultra_slow` controller. +The SimpleFOC library gives you the choice of using 4 different plug and play control loops: +- voltage control loop +- velocity control loop +- angle control loop +- ultra slow velocity control loop + +You set it by changing the `motor.controller` variable. If you want to control the motor angle you will set the `controller` to `ControlType::angle`, if you seek the DC motor behavior behaviour by controlling the voltage use `ControlType::voltage`, if you wish to control motor angular velocity `ControlType::velocity`. If you wish to control velocities which are very very slow, typically around ~0.01 rad/s you can use the `ControlType::velocity_ultra_slow` controller. ```cpp // set FOC loop to be used // ControlType::voltage @@ -203,10 +395,10 @@ This control loop allows you to run the BLDC motor as it is simple DC motor usin // voltage control loop motor.controller = ControlType::voltage; ``` - + You rcan test this algoithm by running the example `voltage_control.ino`. -The FOC algorithm reads the angle $\textsf{a}$ from the motor and sets appropriate $\textsf{u}_a$, $\textsf{u}_b$ and $\textsf{u}_c$ voltages such to always have $90\degree$ angle in between the magnetic fields of the permanent magents in rotor and the stator. What is exaclty the principle of the DC motor. +The FOC algorithm reads the angle a from the motor and sets appropriate ua, ub and uc voltages such to always have 90 degree angle in between the magnetic fields of the permanent magents in rotor and the stator. What is exaclty the principle of the DC motor. > This control loop will give you the motor which spins freely with the velocity depending on the voltage $U_q$ you set and the disturbance it is facing. *It will turn slower if you try to hold it*. @@ -217,23 +409,28 @@ This control loop allows you to spin your BLDC motor with desired velocity. Thi motor.controller = ControlType::velocity; ``` - + -You can test this algorithm by running the example `velocity_control.ino` and `velocity_control_serial.ino` . -The velocity control is created by adding a PI velocity controller. This controller reads the motor velocity $\textsf{v}$ and sets the $\textsf{u}_q$ voltage to the motor in a such maner that it reaches and maintains the target velocity $\textsf{v}_d$, set by the user. +You can test this algorithm by running the example `velocity_control.ino`. +The velocity control is created by adding a PI velocity controller. This controller reads the motor velocity v and sets the uq voltage to the motor in a such maner that it reaches and maintains the target velocity vd, set by the user. #### PI controller parameters To change the parameters of your PI controller to reach desired behaiour you can change `motor.PI_velocity` structure: ```cpp // velocity PI controller parameters -// default K=1.0 Ti = 0.003 -motor.PI_velocity.K = 1; -motor.PI_velocity.Ti = 0.003; -motor.PI_velocity.u_limit = 12; +// default K=0.5 Ti = 0.01 +motor.PI_velocity.K = 0.2; +motor.PI_velocity.Ti = 0.01; +motor.PI_velocity.voltage_limit = 6; +// jerk control using voltage voltage ramp +// default value is 300 volts per sec ~ 0.3V per millisecond +motor.PI_velocity.voltage_ramp = 6; ``` -The parameters of the PI controller are proportional gain `K`, integral time constant `Ti` and voltage limit `u_limit` which is by default set to the `power_supply_voltage`. -- The `u_limit` parameter is intended if some reason you wish to limit the voltage that can be sent to your motor. +The parameters of the PI controller are proportional gain `K`, integral time constant `Ti`, voltage limit `voltage_limit` and `voltage_ramp`. +- The `voltage_limit` parameter is intended if, for some reason, you wish to limit the voltage that can be sent to your motor. - In general by raising the proportional constant `K` your motor controller will be more reactive, but too much will make it unstable. - The same goes for integral time constant `Ti` the smaller it is the faster motors reaction to disturbance will be, but too small value will make it unstable. +- The `voltage_ramp` value it intended to reduce the maximal change of the voltage value which is sent to the motor. The higher the value the PI controller will be able to change faster the Uq value. The lower the value the smaller the possible change and the less responsive your controller becomes. The value of this parameter is set to be `Volts per second[V/s` or in other words how many volts can your controller raise the voltage in one time unit. If you set your `voltage_ramp` value to `10 V/s`, and on average your contol loop will run each `1ms`. Your controller will be able to chnage the Uq value each time `10[V/s]*0.001[s] = 0.01V` waht is not a lot. + So in order to get optimal performance you will have to fiddle a bit with with the parameters. :) @@ -244,10 +441,10 @@ This control loop allows you to move your BLDC motor to the desired angle in rea motor.controller = ControlType::angle; ``` - + -You can test this algorithm by running the example `angle_control.ino` and `angle_control_serial.ino` . -The angle control loop is done by adding one more control loop in cascade on the velocity control loop like showed on the figure above. The loop is closed by using simple P controller. The controller reads the angle $\textsf{a}$ from the motor and determins which velocity $\textsf{v}_d$ the motor should move to reach desire angle $\textsf{a}_d$ set by the user. And then the velocity controller reads the current velocity from the motor $\textsf{v}$ and sets the voltage $\textsf{u}_q$ that is neaded to reach the velocity $\textsf{v}_d$, set by the angle loop. +You can test this algorithm by running the example `angle_control.ino`. +The angle control loop is done by adding one more control loop in cascade on the velocity control loop like showed on the figure above. The loop is closed by using simple P controller. The controller reads the angle a from the motor and determins which velocity vd the motor should move to reach desire angle ad set by the user. And then the velocity controller reads the current velocity from the motor v and sets the voltage uq that is neaded to reach the velocity vd, set by the angle loop. #### Controller parameters To tune this control loop you can set the parameters to both angle P controller and velocity PI controller. @@ -256,7 +453,10 @@ To tune this control loop you can set the parameters to both angle P controller // default K=1.0 Ti = 0.003 motor.PI_velocity.K = 0.5; motor.PI_velocity.Ti = 0.01; -motor.PI_velocity.u_limit = 12; +motor.PI_velocity.voltage_limit = 6; +// jerk control using voltage voltage ramp +// default value is 300 volts per sec ~ 0.3V per millisecond +motor.PI_velocity.voltage_ramp = 6; // angle P controller // default K=70 motor.P_angle.K = 20; @@ -284,11 +484,11 @@ This control loop allows you to spin your BLDC motor with desired velocity as we motor.controller = ControlType::velocity_ultra_slow; ``` - + You can test this algorithm by running the example `velocity_ultrasloaw_control_serial.ino` . This type of the velocity control is nothing more but motor angle control. It works particularly well for the purposes of very slow movements because regular velocity calculation techniques are not vel suited for this application and regular [velocity control loop](#velocity-control-loop) would not work well. -The behavior is achieved by integrating the user set target velocity $\textsf{v}_d$ to get the necessary angle $\textsf{a}_d$. And then controlling the motor angle $\textsf{a}$ with high-gain PI controller. This controller reads the motor angle $\textsf{a}$ and sets the $\textsf{u}_q$ voltage to the motor in a such maner that it closely follows the target angle $\textsf{a}_d$, to achieve the velocity profile $\textsf{v}_d$, set by the user. +The behavior is achieved by integrating the user set target velocity vd to get the necessary angle ad. And then controlling the motor angle v with high-gain PI controller. This controller reads the motor angle v and sets the uq voltage to the motor in a such maner that it closely follows the target angle ad, to achieve the velocity profile vd, set by the user. #### PI controller parameters To change the parameters of your PI controller to reach desired behaiour you can change `motor.PI_velocity` structure: ```cpp @@ -296,15 +496,40 @@ To change the parameters of your PI controller to reach desired behaiour you can // default K=120.0 Ti = 100.0 motor.PI_velocity_ultra_slow.K = 120; motor.PI_velocity_ultra_slow.Ti = 100; -motor.PI_velocity_ultra_slow.u_limit = 12; +motor.PI_velocity_ultra_slow.voltage_limit = 12; +// jerk control using voltage voltage ramp +// default value is 300 volts per sec ~ 0.3V per millisecond +motor.PI_velocity_ultra_slow.voltage_ramp = 6; ``` -The parameters of the PI controller are proportional gain `K`, integral time constant `Ti` and voltage limit `u_limit` which is by default set to the `power_supply_voltage`. -- The `u_limit` parameter is intended if some reason you wish to limit the voltage that can be sent to your motor. +The parameters of the PI controller are proportional gain `K`, integral time constant `Ti` and voltage limit `voltage_limit` which is by default set to the `voltage_power_supply/2` and `voltage_ramp`. +- The `voltage_limit` parameter is intended if some reason you wish to limit the voltage that can be sent to your motor. - In general by raising the proportional constant `K` your motor controller will be more reactive, but too much will make it unstable. - The same goes for integral time constant `Ti` the smaller it is the faster motors reaction to disturbance will be, but too small value will make it unstable. By defaualt the integral time constant `Ti` is set `100s`. Which means that it is extreamply slow, meaning that it is not effecting the behvior of the controlle, making it basically a P controller. +- The `voltage_ramp` value it intended to reduce the maximal change of the voltage value which is sent to the motor. The higher the value the PI controller will be able to change faster the Uq value. The lower the value the smaller the possible change and the less responsive your controller becomes. The value of this parameter is set to be `Volts per second[V/s` or in other words how many volts can your controller raise the voltage in one time unit. If you set your `voltage_ramp` value to `10 V/s`, and on average your contol loop will run each `1ms`. Your controller will be able to chnage the Uq value each time `10[V/s]*0.001[s] = 0.01V` waht is not a lot. From the PI controller parameters you can see that the values are much higher than in the [velocity control loop](#velocity-control-loop). The reason is because the angle control loop is not the main loop and we need it to follow the profile as good as possible as fast as possible. Therefore we need much higher gain than before. +### Index search routine +Finding the encoder index is performed only if the constructor of the `Encoder` class has been provided with the `index` pin. The search is performed by setting a constant velocity of the motor until it reaches the index pin. To set the desired searching velocity alter the paramterer: +```cpp +// index search velocity - default 1rad/s +motor.index_search_velocity = 2; +``` + +This velocity control loop is implemented exaclty the same as [velocity control loop](#velocity-control-loop) but it has different contorller paramters which can be set by: +```cpp +// index search PI contoller parameters +// default K=0.5 Ti = 0.01 +motor.PI_velocity_index_search.K = 0.1; +motor.PI_velocity_index_search.Ti = 0.01; +motor.PI_velocity_index_search.voltage_limit = 3; +// jerk control using voltage voltage ramp +// default value is 300 volts per sec ~ 0.3V per millisecond +motor.PI_velocity_index_search.voltage_ramp = 6; +``` +If you are having problems during the finding procedure, try tuning the PI controller constants. The same parameters as the `PI_velocity` should work well, but you can put it a bit more conservative to avoid high jumps. + + ## FOC routine ### Intialisation - `setup()` After the motor and encoder are intialised and the driver and control loops are configured you intialise the FOC algorithm. @@ -316,16 +541,15 @@ This function aligns encoder and motor zero positions and intialises FOC variabl ### Real-time execution `loop()` -The real time execution of the Arduino FOC library is govenred by two funcitons `motor.loopFOC()` and `motor.move(float target)`. +The real time execution of the Arduino Simple FOC library is govenred by two funcitons `motor.loopFOC()` and `motor.move(float target)`. ```cpp -// iterative state calculation calculating angle -// and setting FOC pahse voltage +// iterative setting FOC pahse voltage // the faster you run this funciton the better // in arduino loop it should have ~1kHz // the best would be to be in ~10kHz range motor.loopFOC(); ``` -The funciton `loopFOC()` gets the current motor angle from the encoder, turns in into the electrical angle and computes Clarke transfrom to set the desired $U_q$ voltage to the motor. Basically it implements the funcitonality of the [velocity control loop](#voltage-control-loop). +The funciton `loopFOC()` gets the current motor angle from the encoder, turns in into the electrical angle and computes Clarke transfrom to set the desired Uq voltage to the motor. Basically it implements the funcitonality of the [voltage control loop](#voltage-control-loop). - The faster you can run this funciton the better - In the empty arduino loop it runs at ~1kHz but idealy it would be around ~10kHz @@ -340,9 +564,9 @@ motor.move(target); The `move()` method executes the control loops of the algorihtm. If is governed by the `motor.controller` variable. It executes eigther pure voltage loop, velocity loop, angle loop or ultra slow velocity loop. It receives one parameter `BLDCMotor::move(float target)` which is current user define target value. -- If the user runs [velocity loop](#velocity-control-loop), `move` funciton will interpret `target` as the target velocity $\textsf{v}_d$. -- If the user runs [angle loop](#angle-control-loop), `move` will interpret `target` parameter as the target angle $\textsf{a}_d$. -- If the user runs the [voltage loop](#voltage-control-loop), `move` funciton will interpret the `target` parameter as voltage $\textbf{u}_q$. +- If the user runs [velocity loop](#velocity-control-loop), `move` funciton will interpret `target` as the target velocity vd. +- If the user runs [angle loop](#angle-control-loop), `move` will interpret `target` parameter as the target anglead. +- If the user runs the [voltage loop](#voltage-control-loop), `move` funciton will interpret the `target` parameter as voltage ud. > At this point because we are oriented to simplicity we did not implement synchornious version of this code. Uing timer interrupt. The main reason for the moment is that Arduino UNO doesn't have enough timers to run it. @@ -354,13 +578,12 @@ Examples folder structure ├───examples │ ├───voltage_control # example of the voltage control loop with configuraiton │ ├───angle_control # example of angle control loop with configuraiton -│ ├───angle_control_serial # example of angle control using serial port with configuraiton │ ├───velocity_control # example of velocity control loop with configuraiton -│ ├───velocity_control_serial # example of velocity control using serial port with configuraiton -│ ├───velocity_ultraslow_control_serial # example of ultra slow velocity control using serial port with configuraiton +│ ├───velocity_ultraslow_control # example of ultra slow velocity control using with configuraiton │ ├───encoder_example # simple example of encoder usage │ ├───minimal_example # example of code without using configuration -│ └───HMBGC_example # example of code to be used with HMBGC controller with configuraiton +│ ├───HMBGC_example # example of code to be used with HMBGC controller with +│ └───find_pole_pairs_number # simple code example estimating pole pair number of the motor ``` @@ -428,19 +651,30 @@ class Encoder{ float getAngle(); } ``` +### BLDCMotor debugging +Additonally a `BLDCMotor` calss now supports debugging using `Serial` port which is enabled by: +```cpp +motor.useDebugging(Serial); +``` +before running `motor.init()`. - -# Future Work Roadmap -#### Library maintenance +# Work Roadmap +## Future work - [ ] Proper introduction of the **Arudino FOC Shield V1.2** -- [ ] Make the library accesible in the Arduino Library Manager -- [ ] Publish a video utilising the library and the samples -- [ ] Make minimal version of the arduino code - all in one arduino file - -#### Code developement -- [ ] Encoder index proper implementation -- [ ] Enable more dirver types -- [ ] Timer interrupt execution rather than in the `loop()` -- [ ] Make support for magnetic encoder AS5048 and similar - +- [ ] Publish a video tutorial fir using the library and the samples + +## Work in progress +- [x] Make the library accesible in the Arduino Library Manager +- [x] Make minimal version of the arduino code - all in one arduino file +- [x] Encoder index proper implementation +- [x] Enable more dirver types +- [x] Make support for magnetic encoder AS5048 and similar +- [x] Add support for acceleration ramping +- [x] Timer interrupt execution rather than in the `loop()` + - FAIL: Perfromance not improved + +# Contact +Please do not hesitate to leave an issue or contact me direclty by email. +I will be very happy to hear your experiences. +antun.skuric@outlook.com \ No newline at end of file From 035c66acd49a56262f3823f9e75900fd15c0cab6 Mon Sep 17 00:00:00 2001 From: Antun Skuric <36178713+askuric@users.noreply.github.com> Date: Thu, 23 Apr 2020 09:11:31 +0200 Subject: [PATCH 20/65] Create ccpp.yml --- .github/workflows/ccpp.yml | 14 ++++++++++++++ 1 file changed, 14 insertions(+) create mode 100644 .github/workflows/ccpp.yml diff --git a/.github/workflows/ccpp.yml b/.github/workflows/ccpp.yml new file mode 100644 index 00000000..795e8be2 --- /dev/null +++ b/.github/workflows/ccpp.yml @@ -0,0 +1,14 @@ + +name: MinimalBuild +on: + push: + branches: [minimal] +jobs: + build: + name: Test compiling examples for UNO + runs-on: ubuntu-latest + steps: + - name: Checkout + uses: actions/checkout@master + - name: Compile all examples + uses: ArminJo/arduino-test-compile@v2.1.0 From e72d66b64cbb5d70bc85ffd0100f7791ac1059b3 Mon Sep 17 00:00:00 2001 From: askuric Date: Thu, 23 Apr 2020 09:23:20 +0200 Subject: [PATCH 21/65] FEAT added repository table --- README.md | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index dcce0616..f5e0ce1a 100644 --- a/README.md +++ b/README.md @@ -1,11 +1,18 @@ # Arduino Simple FOC library minimal example -![Library Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Compile/badge.svg) +![MinimalBuild](https://github.com/askuric/Arduino-FOC/workflows/MinimalBuild/badge.svg?branch=minimal) [![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT) [![arduino-library-badge](https://www.ardu-badge.com/badge/Simple%20FOC.svg?)](https://www.ardu-badge.com/badge/Simple%20FOC.svg) This is the minimal Arduino example of the [Simple FOC](https://github.com/askuric/Arduino-FOC) arduino library intended for mostly for easier experiemtation and modification! +# Repositoty structure +Branch | Description | Status +------------ | ------------- | ------------ +[master](https://github.com/askuric/Arduino-FOC) | Stable and tested library version | ![Library Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Compile/badge.svg) +[dev](https://github.com/askuric/Arduino-FOC/tree/dev) | Developement library version | ![Library Dev Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Dev%20Compile/badge.svg?branch=dev) +[minimal](https://github.com/askuric/Arduino-FOC/tree/minimal) | Minimal Arduino example with integrated library | ![MinimalBuild](https://github.com/askuric/Arduino-FOC/workflows/MinimalBuild/badge.svg?branch=minimal) + # Contents - [Installation](#arduino-simple-foc-instalation) - [Installing the full library](#installing-simple-foc-full-library) From 753c28f2e93d53e5e1c67d6ac7c6ff4138b8919f Mon Sep 17 00:00:00 2001 From: askuric Date: Thu, 23 Apr 2020 09:24:12 +0200 Subject: [PATCH 22/65] UPDATE fix style --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index f5e0ce1a..ec079424 100644 --- a/README.md +++ b/README.md @@ -6,7 +6,7 @@ This is the minimal Arduino example of the [Simple FOC](https://github.com/askuric/Arduino-FOC) arduino library intended for mostly for easier experiemtation and modification! -# Repositoty structure +## Arduino FOC repo structure Branch | Description | Status ------------ | ------------- | ------------ [master](https://github.com/askuric/Arduino-FOC) | Stable and tested library version | ![Library Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Compile/badge.svg) From 54d5a5cf94af76fd38e3fdfac33ddc41f8fb7e16 Mon Sep 17 00:00:00 2001 From: askuric Date: Thu, 23 Apr 2020 09:35:22 +0200 Subject: [PATCH 23/65] FIX readme style adjestment --- README.md | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/README.md b/README.md index ec079424..75be84d4 100644 --- a/README.md +++ b/README.md @@ -14,7 +14,7 @@ Branch | Description | Status [minimal](https://github.com/askuric/Arduino-FOC/tree/minimal) | Minimal Arduino example with integrated library | ![MinimalBuild](https://github.com/askuric/Arduino-FOC/workflows/MinimalBuild/badge.svg?branch=minimal) # Contents - - [Installation](#arduino-simple-foc-instalation) +- [Installation](#arduino-simple-foc-instalation) - [Installing the full library](#installing-simple-foc-full-library) - [Installing the minimal Arduino example](#download-minimal-simple-foc-arduino-example) - [Electrical connecitons and schematic](#electrical-connections) @@ -45,13 +45,13 @@ The simplest way to get hold of the library is direclty by using Arduino IDE and ### Download library directly If you don't want to use the Arduino IDE and Library manager you can direclty download the library from this website. - Simplest way to do it is to download the `zip` aerchieve directly on the top of this webiste. Click first on `Clone or Download` and then on `Download ZIP`. Once you have the zip ardhieve downloaded, unzip it and place it in your Arduino Libraries forlder. On Windows it is usually in `Documents > Arduino > libraries`. - - Now reopen your Arduino IDE and you should have the library examples in `File > Examples > Simple FOC`. + Now reopen your Arduino IDE and you should have the library examples in `File > Examples > Simple FOC`. - If you are more experienced with the terminal you can open your terminal in the Arduino libraries folder direclty and clone the Arduino FOC git repsitory: -```bash -git clone https://github.com/askuric/Arduino-FOC.git -``` - - Now reopen your Arduino IDE and you should have the library examples in `File > Examples > Simple FOC`. + ```bash + git clone https://github.com/askuric/Arduino-FOC.git + ``` + Now reopen your Arduino IDE and you should have the library examples in `File > Examples > Simple FOC`. ## Download minimal Simple FOC Arduino example To download the minmial verison of Simple FOC intended for those willing to experiment and extend the code I suggest using this version over the full library. @@ -59,13 +59,13 @@ This code is completely indepenedet and you can run it as any other Arduino Sche The code is place in the [minimal branch](https://github.com/askuric/Arduino-FOC/tree/minimal). - You can download it directly form the [minimal branch](https://github.com/askuric/Arduino-FOC/tree/minimal) by clicking on the `Clone or Download > Download ZIP`. - - Then you just unzip it and open the schetch in Arduino IDE. + Then you just unzip it and open the schetch in Arduino IDE. - You can also clone it using the terminal: ```bash git clone -b minimal https://github.com/askuric/Arduino-FOC.git ``` - - Then you just open it with the Arduino IDE and run it. + Then you just open it with the Arduino IDE and run it. From e965e2026bdeb19f44473e92791e84b85c7867dc Mon Sep 17 00:00:00 2001 From: askuric Date: Thu, 23 Apr 2020 11:54:21 +0200 Subject: [PATCH 24/65] FEATURE added sine int array to reduce memory usage --- arduino_foc_minimal/BLDCMotor.cpp | 14 +++++++------- arduino_foc_minimal/BLDCMotor.h | 4 ++-- arduino_foc_minimal/Encoder.cpp | 2 +- arduino_foc_minimal/FOCutils.cpp | 25 ++++++++++++++++++------- 4 files changed, 28 insertions(+), 17 deletions(-) diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index 98dceb30..446448b9 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -266,16 +266,16 @@ void BLDCMotor::move(float target) { /* Method using FOC to set Uq to the motor at the optimal angle */ -void BLDCMotor::setPhaseVoltage(double Uq, double angle_el) { +void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // angle normalisation in between 0 and 2pi // only necessary if using _sin and _cos - approximation funcitons float angle = normalizeAngle(angle_el + index_electric_angle); // Inverse park transform - // regular sin + cos ~300us - // approx _sin + _cos ~90us - Ualpha = -_sin(angle) * Uq; - Ubeta = _cos(angle) * Uq; + // regular sin + cos ~300us (no memeory usaage) + // approx _sin + _cos ~110us (400Byte ~ 20% of memory) + Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; // Clarke transform Ua = Ualpha; @@ -315,8 +315,8 @@ void BLDCMotor::setPwm(int pinPwm, float U) { /* normalizing radian angle to [0,2PI] */ -double BLDCMotor::normalizeAngle(double angle){ - double a = fmod(angle, _2PI); +float BLDCMotor::normalizeAngle(float angle){ + float a = fmod(angle, _2PI); return a >= 0 ? a : (a + _2PI); } diff --git a/arduino_foc_minimal/BLDCMotor.h b/arduino_foc_minimal/BLDCMotor.h index b26cabd0..1f144f25 100644 --- a/arduino_foc_minimal/BLDCMotor.h +++ b/arduino_foc_minimal/BLDCMotor.h @@ -123,7 +123,7 @@ class BLDCMotor /** FOC methods */ //Method using FOC to set Uq to the motor at the optimal angle - void setPhaseVoltage(double Uq, double angle_el); + void setPhaseVoltage(float Uq, float angle_el); // debugging @@ -142,7 +142,7 @@ class BLDCMotor /** Utility funcitons */ //normalizing radian angle to [0,2PI] - double normalizeAngle(double angle); + float normalizeAngle(float angle); //Reference low pass filter float filterLP(float u); diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index 0077abf4..66bc2231 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -219,7 +219,7 @@ void Encoder::init(void (*doA)(), void(*doB)()){ } // if index used intialise the index interrupt - if(hasIndex()) { + if(hasIndex() || doA != nullptr) { *digitalPinToPCMSK(index_pin) |= bit (digitalPinToPCMSKbit(index_pin)); // enable pin PCIFR |= bit (digitalPinToPCICRbit(index_pin)); // clear any outstanding interrupt PCICR |= bit (digitalPinToPCICRbit(index_pin)); // enable interrupt for the group diff --git a/arduino_foc_minimal/FOCutils.cpp b/arduino_foc_minimal/FOCutils.cpp index b183e6fc..cc94cd53 100644 --- a/arduino_foc_minimal/FOCutils.cpp +++ b/arduino_foc_minimal/FOCutils.cpp @@ -40,30 +40,41 @@ unsigned long _micros(){ // lookup table for sine calculation in between 0 and 90 degrees -float sine_array[200] = {0.0000,0.0079,0.0158,0.0237,0.0316,0.0395,0.0473,0.0552,0.0631,0.0710,0.0789,0.0867,0.0946,0.1024,0.1103,0.1181,0.1260,0.1338,0.1416,0.1494,0.1572,0.1650,0.1728,0.1806,0.1883,0.1961,0.2038,0.2115,0.2192,0.2269,0.2346,0.2423,0.2499,0.2575,0.2652,0.2728,0.2804,0.2879,0.2955,0.3030,0.3105,0.3180,0.3255,0.3329,0.3404,0.3478,0.3552,0.3625,0.3699,0.3772,0.3845,0.3918,0.3990,0.4063,0.4135,0.4206,0.4278,0.4349,0.4420,0.4491,0.4561,0.4631,0.4701,0.4770,0.4840,0.4909,0.4977,0.5046,0.5113,0.5181,0.5249,0.5316,0.5382,0.5449,0.5515,0.5580,0.5646,0.5711,0.5775,0.5839,0.5903,0.5967,0.6030,0.6093,0.6155,0.6217,0.6279,0.6340,0.6401,0.6461,0.6521,0.6581,0.6640,0.6699,0.6758,0.6815,0.6873,0.6930,0.6987,0.7043,0.7099,0.7154,0.7209,0.7264,0.7318,0.7371,0.7424,0.7477,0.7529,0.7581,0.7632,0.7683,0.7733,0.7783,0.7832,0.7881,0.7930,0.7977,0.8025,0.8072,0.8118,0.8164,0.8209,0.8254,0.8298,0.8342,0.8385,0.8428,0.8470,0.8512,0.8553,0.8594,0.8634,0.8673,0.8712,0.8751,0.8789,0.8826,0.8863,0.8899,0.8935,0.8970,0.9005,0.9039,0.9072,0.9105,0.9138,0.9169,0.9201,0.9231,0.9261,0.9291,0.9320,0.9348,0.9376,0.9403,0.9429,0.9455,0.9481,0.9506,0.9530,0.9554,0.9577,0.9599,0.9621,0.9642,0.9663,0.9683,0.9702,0.9721,0.9739,0.9757,0.9774,0.9790,0.9806,0.9821,0.9836,0.9850,0.9863,0.9876,0.9888,0.9899,0.9910,0.9920,0.9930,0.9939,0.9947,0.9955,0.9962,0.9969,0.9975,0.9980,0.9985,0.9989,0.9992,0.9995,0.9997,0.9999,1.0000,1.0000}; +//float sine_array[200] = {0.0000,0.0079,0.0158,0.0237,0.0316,0.0395,0.0473,0.0552,0.0631,0.0710,0.0789,0.0867,0.0946,0.1024,0.1103,0.1181,0.1260,0.1338,0.1416,0.1494,0.1572,0.1650,0.1728,0.1806,0.1883,0.1961,0.2038,0.2115,0.2192,0.2269,0.2346,0.2423,0.2499,0.2575,0.2652,0.2728,0.2804,0.2879,0.2955,0.3030,0.3105,0.3180,0.3255,0.3329,0.3404,0.3478,0.3552,0.3625,0.3699,0.3772,0.3845,0.3918,0.3990,0.4063,0.4135,0.4206,0.4278,0.4349,0.4420,0.4491,0.4561,0.4631,0.4701,0.4770,0.4840,0.4909,0.4977,0.5046,0.5113,0.5181,0.5249,0.5316,0.5382,0.5449,0.5515,0.5580,0.5646,0.5711,0.5775,0.5839,0.5903,0.5967,0.6030,0.6093,0.6155,0.6217,0.6279,0.6340,0.6401,0.6461,0.6521,0.6581,0.6640,0.6699,0.6758,0.6815,0.6873,0.6930,0.6987,0.7043,0.7099,0.7154,0.7209,0.7264,0.7318,0.7371,0.7424,0.7477,0.7529,0.7581,0.7632,0.7683,0.7733,0.7783,0.7832,0.7881,0.7930,0.7977,0.8025,0.8072,0.8118,0.8164,0.8209,0.8254,0.8298,0.8342,0.8385,0.8428,0.8470,0.8512,0.8553,0.8594,0.8634,0.8673,0.8712,0.8751,0.8789,0.8826,0.8863,0.8899,0.8935,0.8970,0.9005,0.9039,0.9072,0.9105,0.9138,0.9169,0.9201,0.9231,0.9261,0.9291,0.9320,0.9348,0.9376,0.9403,0.9429,0.9455,0.9481,0.9506,0.9530,0.9554,0.9577,0.9599,0.9621,0.9642,0.9663,0.9683,0.9702,0.9721,0.9739,0.9757,0.9774,0.9790,0.9806,0.9821,0.9836,0.9850,0.9863,0.9876,0.9888,0.9899,0.9910,0.9920,0.9930,0.9939,0.9947,0.9955,0.9962,0.9969,0.9975,0.9980,0.9985,0.9989,0.9992,0.9995,0.9997,0.9999,1.0000,1.0000}; + +// int array instead of float array +// 2x storage save (int 2Byte float 4 Byte ) +// sin*10000 +int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,1103,1181,1260,1338,1416,1494,1572,1650,1728,1806,1883,1961,2038,2115,2192,2269,2346,2423,2499,2575,2652,2728,2804,2879,2955,3030,3105,3180,3255,3329,3404,3478,3552,3625,3699,3772,3845,3918,3990,4063,4135,4206,4278,4349,4420,4491,4561,4631,4701,4770,4840,4909,4977,5046,5113,5181,5249,5316,5382,5449,5515,5580,5646,5711,5775,5839,5903,5967,6030,6093,6155,6217,6279,6340,6401,6461,6521,6581,6640,6699,6758,6815,6873,6930,6987,7043,7099,7154,7209,7264,7318,7371,7424,7477,7529,7581,7632,7683,7733,7783,7832,7881,7930,7977,8025,8072,8118,8164,8209,8254,8298,8342,8385,8428,8470,8512,8553,8594,8634,8673,8712,8751,8789,8826,8863,8899,8935,8970,9005,9039,9072,9105,9138,9169,9201,9231,9261,9291,9320,9348,9376,9403,9429,9455,9481,9506,9530,9554,9577,9599,9621,9642,9663,9683,9702,9721,9739,9757,9774,9790,9806,9821,9836,9850,9863,9876,9888,9899,9910,9920,9930,9939,9947,9955,9962,9969,9975,9980,9985,9989,9992,9995,9997,9999,10000,10000}; // function approximating the sine calculation by using fixed size array -// ~40us +// ~40us (float array) +// ~50us (int array) // precision +-0.005 // it has to receive an angle in between 0 and 2PI float _sin(float a){ if(a < _PI_2){ //return sine_array[(int)(199.0*( a / (M_PI/2.0)))]; - return sine_array[(int)(126.6873* a)]; + //return sine_array[(int)(126.6873* a)]; // float array optimised + return 0.0001*sine_array[(int)(126.6873* a)]; // int array optimised }else if(a < M_PI){ // return sine_array[(int)(199.0*(1.0 - (a-M_PI/2.0) / (M_PI/2.0)))]; - return sine_array[398 - (int)(126.6873*a)]; + //return sine_array[398 - (int)(126.6873*a)]; // float array optimised + return 0.0001*sine_array[398 - (int)(126.6873*a)]; // int array optimised }else if(a < _3PI_2){ // return -sine_array[(int)(199.0*((a - M_PI) / (M_PI/2.0)))]; - return -sine_array[-398 + (int)(126.6873*a)]; + //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimised + return -0.0001*sine_array[-398 + (int)(126.6873*a)]; // int array optimised } else { // return -sine_array[(int)(199.0*(1.0 - (a - 3*M_PI/2) / (M_PI/2.0)))]; - return -sine_array[796 - (int)(126.6873*a)]; + //return -sine_array[796 - (int)(126.6873*a)]; // float array optimised + return -0.0001*sine_array[796 - (int)(126.6873*a)]; // int array optimised } } // function approfimating cosine calculaiton by using fixed size array -// ~50us +// ~55us (float array) +// ~56us (int array) // precision +-0.005 // it has to receive an angle in between 0 and 2PI float _cos(float a){ From a78b82b5ce25efd0002305efd04173d58010c6a9 Mon Sep 17 00:00:00 2001 From: askuric Date: Thu, 23 Apr 2020 15:54:29 +0200 Subject: [PATCH 25/65] BUGFIX interrupt for index --- arduino_foc_minimal/Encoder.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index 66bc2231..14de9ddc 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -217,11 +217,12 @@ void Encoder::init(void (*doA)(), void(*doB)()){ } break; } - + // if index used intialise the index interrupt - if(hasIndex() || doA != nullptr) { + if(hasIndex() && doA != nullptr) { *digitalPinToPCMSK(index_pin) |= bit (digitalPinToPCMSKbit(index_pin)); // enable pin PCIFR |= bit (digitalPinToPCICRbit(index_pin)); // clear any outstanding interrupt PCICR |= bit (digitalPinToPCICRbit(index_pin)); // enable interrupt for the group } } + From c89ee30d7bf4cb8f990a8f929da4dee6139358b9 Mon Sep 17 00:00:00 2001 From: askuric Date: Mon, 27 Apr 2020 15:30:02 +0200 Subject: [PATCH 26/65] FEAT added abstract sensor class, added magentic sensro and addpater encoder and BLDCMotor. not tested (Only Encoder tested). --- arduino_foc_minimal/BLDCMotor.cpp | 67 ++++---- arduino_foc_minimal/BLDCMotor.h | 30 ++-- arduino_foc_minimal/Encoder.cpp | 21 +-- arduino_foc_minimal/Encoder.h | 36 +++-- arduino_foc_minimal/MagneticSensor.cpp | 165 ++++++++++++++++++++ arduino_foc_minimal/MagneticSensor.h | 68 ++++++++ arduino_foc_minimal/Sensor.h | 29 ++++ arduino_foc_minimal/SimpleFOC.h | 10 ++ arduino_foc_minimal/arduino_foc_minimal.ino | 43 ++--- 9 files changed, 370 insertions(+), 99 deletions(-) create mode 100644 arduino_foc_minimal/MagneticSensor.cpp create mode 100644 arduino_foc_minimal/MagneticSensor.h create mode 100644 arduino_foc_minimal/Sensor.h create mode 100644 arduino_foc_minimal/SimpleFOC.h diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index 446448b9..548b250d 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -1,13 +1,11 @@ #include "BLDCMotor.h" - /* - BLDCMotor( int phA, int phB, int phC, int pp, int encA, int encB , int cpr, int en) + BLDCMotor( int phA, int phB, int phC, int pp , int cpr, int en) - phA, phB, phC - motor A,B,C phase pwm pins - pp - pole pair number - - encA, encB - encoder A and B pins - cpr - counts per rotation number (cpm=ppm*4) - - enable pin - (optional input) + - enable pin - (optionl input) */ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) { @@ -65,7 +63,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // electric angle og the zero angle // electric angle of the index for encoder - index_electric_angle = 0; + zero_electric_angle = 0; //debugger debugger = nullptr; @@ -104,9 +102,9 @@ void BLDCMotor::init() { initialization function */ int BLDCMotor::initFOC() { - // encoder alignment + // sensor and motor alignment _delay(500); - int exit_flag = alignEncoder(); + int exit_flag = alignSensor(); _delay(500); return exit_flag; } @@ -137,33 +135,34 @@ void BLDCMotor::enable() } -void BLDCMotor::linkEncoder(Encoder* enc) { - encoder = enc; +void BLDCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; } /* Encoder alignment to electrical 0 angle */ -int BLDCMotor::alignEncoder() { - if(debugger) debugger->println("DEBUG: Align the encoder and motor electrical 0 angle."); - // align the electircal phases of the motor and encoder +int BLDCMotor::alignSensor() { + if(debugger) debugger->println("DEBUG: Align the sensor's and motor electrical 0 angle."); + // align the electircal phases of the motor and sensor setPwm(pwmA, voltage_power_supply/2.0); setPwm(pwmB,0); setPwm(pwmC,0); _delay(1000); - // set encoder to zero - encoder->setCounterZero(); + // set sensor to zero + sensor->initRelativeZero(); _delay(500); setPhaseVoltage(0,0); _delay(200); // find the index if available - int exit_flag = indexSearch(); + int exit_flag = absoluteZeroAlign(); _delay(500); if(debugger){ - if(exit_flag< 0 ) debugger->println("DEBUG: Error: Index not found!"); - if(exit_flag> 0 ) debugger->println("DEBUG: Success: Index found!"); + if(exit_flag< 0 ) debugger->println("DEBUG: Error: Absolute zero not found!"); + if(exit_flag> 0 ) debugger->println("DEBUG: Success: Absolute zero found!"); + else debugger->println("DEBUG: Success: Absolute zero not availabe!"); } return exit_flag; } @@ -172,14 +171,15 @@ int BLDCMotor::alignEncoder() { /* Encoder alignment to electrical 0 angle */ -int BLDCMotor::indexSearch() { - // if no index return - if(!encoder->hasIndex()) return 0; +int BLDCMotor::absoluteZeroAlign() { + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; - if(debugger) debugger->println("DEBUG: Search for the encoder index."); + if(debugger) debugger->println("DEBUG: Aligning the absolute zero."); - // search the index with small speed - while(!encoder->indexFound() && shaft_angle < _2PI){ + if(debugger && sensor->needsAbsoluteZeroSearch()) debugger->println("DEBUG: Searching for absolute zero."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ loopFOC(); voltage_q = velocityIndexSearchPI(index_search_velocity - shaftVelocity()); } @@ -187,14 +187,15 @@ int BLDCMotor::indexSearch() { // disable motor setPhaseVoltage(0,0); - // set index to zero if it has been found - if(encoder->indexFound()){ - encoder->setIndexZero(); - // remember index electric angle - index_electric_angle = electricAngle(encoder->getIndexAngle()); + // align absoulute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = electricAngle(zero_offset); } - // return bool is index found - return encoder->indexFound() ? 1 : -1; + // return bool is zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; } /** @@ -202,11 +203,11 @@ int BLDCMotor::indexSearch() { */ // shaft angle calculation float BLDCMotor::shaftAngle() { - return encoder->getAngle(); + return sensor->getAngle(); } // shaft velocity calculation float BLDCMotor::shaftVelocity() { - return encoder->getVelocity(); + return sensor->getVelocity(); } /* Electrical angle calculation @@ -270,7 +271,7 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // angle normalisation in between 0 and 2pi // only necessary if using _sin and _cos - approximation funcitons - float angle = normalizeAngle(angle_el + index_electric_angle); + float angle = normalizeAngle(angle_el + zero_electric_angle); // Inverse park transform // regular sin + cos ~300us (no memeory usaage) // approx _sin + _cos ~110us (400Byte ~ 20% of memory) diff --git a/arduino_foc_minimal/BLDCMotor.h b/arduino_foc_minimal/BLDCMotor.h index 1f144f25..a85bf724 100644 --- a/arduino_foc_minimal/BLDCMotor.h +++ b/arduino_foc_minimal/BLDCMotor.h @@ -2,8 +2,10 @@ #define BLDCMotor_h #include "Arduino.h" +#include "MagneticSensor.h" #include "Encoder.h" #include "FOCutils.h" +#include "Sensor.h" // default configuration values // power supply voltage @@ -59,13 +61,20 @@ struct P_s{ class BLDCMotor { public: + /* + BLDCMotor( int phA, int phB, int phC, int pp , int cpr, int en) + - phA, phB, phC - motor A,B,C phase pwm pins + - pp - pole pair number + - cpr - counts per rotation number (cpm=ppm*4) + - enable pin - (optionl input) + */ BLDCMotor(int phA,int phB,int phC,int pp, int en = 0); // change driver state void init(); void disable(); void enable(); // connect encoder - void linkEncoder(Encoder* enc); + void linkSensor(Sensor* _sensor); // initilise FOC int initFOC(); @@ -114,10 +123,12 @@ class BLDCMotor P_s P_angle; PI_s PI_velocity_index_search; - // encoder link - Encoder* encoder; - // index electric angle - if available - float index_electric_angle; + // sensor link: + // - Encoder + // - MagneticSensor + Sensor* sensor; + // absolute zero electric angle - if available + float zero_electric_angle; // index search velocity float index_search_velocity; @@ -131,9 +142,10 @@ class BLDCMotor Print* debugger; private: - //Encoder alignment to electrical 0 angle - int alignEncoder(); - int indexSearch(); + //Sensor alignment to electrical 0 angle + int alignSensor(); + //Motor and sensor alignement to the sensors absolute 0 angle + int absoluteZeroAlign(); //Electrical angle calculation float electricAngle(float shaftAngle); @@ -143,8 +155,6 @@ class BLDCMotor /** Utility funcitons */ //normalizing radian angle to [0,2PI] float normalizeAngle(float angle); - //Reference low pass filter - float filterLP(float u); /** Motor control functions */ float controllerPI(float tracking_error, PI_s &controller); diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index 14de9ddc..5cb02a51 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -147,28 +147,31 @@ float Encoder::getVelocity(){ // getter for index pin // return -1 if no index -int Encoder::indexFound(){ - return index_pulse_counter != 0; +int Encoder::needsAbsoluteZeroSearch(){ + return index_pulse_counter == 0; } // getter for index pin +int Encoder::hasAbsoluteZero(){ + return hasIndex(); +} + + int Encoder::hasIndex(){ return index_pin != 0; } -// getter for Index angle -float Encoder::getIndexAngle(){ - return (index_pulse_counter) / ((float)cpr) * (_2PI); -} - // intialise counter to zero -void Encoder::setCounterZero(){ +float Encoder::initRelativeZero(){ + long angle_offset = -pulse_counter; pulse_counter = 0; pulse_timestamp = _micros(); + return _2PI * (angle_offset) / ((float)cpr); } // intialise index to zero -void Encoder::setIndexZero(){ +float Encoder::initAbsoluteZero(){ pulse_counter -= index_pulse_counter; prev_pulse_counter = pulse_counter; + return (index_pulse_counter) / ((float)cpr) * (_2PI); } diff --git a/arduino_foc_minimal/Encoder.h b/arduino_foc_minimal/Encoder.h index 21da1a80..69426ee5 100644 --- a/arduino_foc_minimal/Encoder.h +++ b/arduino_foc_minimal/Encoder.h @@ -3,6 +3,7 @@ #include "Arduino.h" #include "FOCutils.h" +#include "Sensor.h" // Pullup configuation structure @@ -16,7 +17,7 @@ enum Quadrature{ DISABLE // CPR = PPR }; -class Encoder{ +class Encoder: public Sensor{ public: /* Encoder(int encA, int encB , int cpr, int index) @@ -38,18 +39,6 @@ class Encoder{ // index handle void handleIndex(); - // encoder getters - // shaft velocity getter - float getVelocity(); - float getAngle(); - // getter for index pin - int indexFound(); - int hasIndex(); - float getIndexAngle(); - - // setter for counter to zero - void setCounterZero(); - void setIndexZero(); // pins A and B int pinA, pinB; // encoder hardware pins @@ -60,8 +49,29 @@ class Encoder{ // use 4xppr or not Quadrature quadrature; + // implementation of abstract functions of the Sensor class + // get current angle (rad) + float getAngle(); + // get current angular velocity (rad/s) + float getVelocity(); + // set current agle as zero angle + // return the angle [rad] difference + float initRelativeZero(); + // set index angle as zero angle + // return the angle [rad] difference + float initAbsoluteZero(); + // returns 0 if it has no index + // 0 - encoder without index + // 1 - encoder with index + int hasAbsoluteZero(); + // returns 0 if it does need search for absolute zero + // 0 - encoder without index + // 1 - ecoder with index + int needsAbsoluteZeroSearch(); private: + int hasIndex(); + volatile long pulse_counter; // current pulse counter volatile long pulse_timestamp; // last impulse timestamp in us float cpr; // impulse cpr diff --git a/arduino_foc_minimal/MagneticSensor.cpp b/arduino_foc_minimal/MagneticSensor.cpp new file mode 100644 index 00000000..39d27369 --- /dev/null +++ b/arduino_foc_minimal/MagneticSensor.cpp @@ -0,0 +1,165 @@ +#include "MagneticSensor.h" + + +// MagneticSensor(int cs, float _cpr, int _angle_register) +// cs - SPI chip select pin +// _cpr - counts per revolution +// _angle_register - (optional) angle read register - default 0x3FFF +MagneticSensor::MagneticSensor(int cs, float _cpr, int _angle_register){ + // chip select pin + chip_select_pin = cs; + // angle read register of the magnetic sensor + angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTAR; + // register maximum value (counts per revolution) + cpr = _cpr; +} + + +void MagneticSensor::init(){ + // 1MHz clock (AMS should be able to accept up to 10MHz) + settings = SPISettings(1000000, MSBFIRST, SPI_MODE1); + + //setup pins + pinMode(chip_select_pin, OUTPUT); + + //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices + SPI.begin(); + + // velocity calculation init + angle_prev = 0; + velocity_calc_timestamp = _micros(); +} + + +// Shaft angle calculation +float MagneticSensor::getAngle(){ + float rotation; + rotation = getRawCount() - (int)zero_offset; + if(rotation > 8191) rotation = -((0x3FFF)-rotation); //more than -180 + return rotation / (float)cpr * _2PI; +} + +// Shaft velocity calculation +float MagneticSensor::getVelocity(){ + // calculate sample time + float Ts = (_micros() - velocity_calc_timestamp)*1e-6; + if(Ts > 0.5) Ts = 0.01; // debounce + // current angle + float angle_c = getAngle(); + // velocity calculation + float vel = (angle_c - angle_prev)/Ts; + // save variables for future pass + angle_prev = angle_c; + velocity_calc_timestamp = _micros(); + return vel; +} + +// set current agle as zero angle +// return the angle [rad] difference +float MagneticSensor::initRelativeZero(){ + float angle_offset = -getAngle(); + zero_offset = getRawCount(); + return angle_offset; +} +// set absoule zero angle as zero angle +// return the angle [rad] difference +float MagneticSensor::initAbsoluteZero(){ + float rotation; + rotation = -(int)zero_offset; + if(rotation > 8191) rotation = -((0x3FFF)-rotation); // more than -180 + // init absolute zero + zero_offset = 0; + // return offset in radians + return rotation / (float)cpr * _2PI; +} +// returns 0 if it has no absolute 0 measurement +// 0 - incremental encoder without index +// 1 - encoder with index & magnetic sensors +int MagneticSensor::hasAbsoluteZero(){ + return 1; +} +// returns 0 if it does need search for absolute zero +// 0 - magnetic sensor +// 1 - ecoder with index +int MagneticSensor::needsAbsoluteZeroSearch(){ + return 0; +} + + +// function reading the raw counter of the magnetic sensor +int MagneticSensor::getRawCount(){ + return (int)MagneticSensor::read(angle_register); +} + +// SPI finctions +/** + * Utility function used to calculate even parity of word + */ +byte MagneticSensor::spiCalcEvenParity(word value){ + byte cnt = 0; + byte i; + + for (i = 0; i < 16; i++) + { + if (value & 0x1) + { + cnt++; + } + value >>= 1; + } + return cnt & 0x1; +} + + /* + * Read a register from the sensor + * Takes the address of the register as a 16 bit word + * Returns the value of the register + */ +word MagneticSensor::read(word angle_register){ + word command = 0b0100000000000000; // PAR=0 R/W=R + command = command | angle_register; + + //Add a parity bit on the the MSB + command |= ((word)spiCalcEvenParity(command)<<15); + + //Split the command into two bytes + byte right_byte = command & 0xFF; + byte left_byte = ( command >> 8 ) & 0xFF; + + //SPI - begin transaction + SPI.beginTransaction(settings); + + //Send the command + digitalWrite(chip_select_pin, LOW); + SPI.transfer(left_byte); + SPI.transfer(right_byte); + digitalWrite(chip_select_pin,HIGH); + + //Now read the response + digitalWrite(chip_select_pin, LOW); + left_byte = SPI.transfer(0x00); + right_byte = SPI.transfer(0x00); + digitalWrite(chip_select_pin, HIGH); + + //SPI - end transaction + SPI.endTransaction(); + + //Check if the error bit is set + if (left_byte & 0x40) { + errorFlag = true; + } + else { + errorFlag = false; + } + + //Return the data, stripping the parity and error bits + return (( ( left_byte & 0xFF ) << 8 ) | ( right_byte & 0xFF )) & ~0xC000; +} + +/** + * Closes the SPI connection + * SPI has an internal SPI-device counter, for each init()-call the close() function must be called exactly 1 time + */ +void MagneticSensor::close(){ + SPI.end(); +} diff --git a/arduino_foc_minimal/MagneticSensor.h b/arduino_foc_minimal/MagneticSensor.h new file mode 100644 index 00000000..532bd628 --- /dev/null +++ b/arduino_foc_minimal/MagneticSensor.h @@ -0,0 +1,68 @@ +#ifndef MAGNETICSENSOR_LIB_H +#define MAGNETICSENSOR_LIB_H + +#include "Arduino.h" +#include +#include "FOCutils.h" +#include "Sensor.h" + +#define DEF_ANGLE_REGISTAR 0x3FFF + +class MagneticSensor: public Sensor{ + public: + + + // MagneticSensor(int cs, float _cpr, int _angle_register) + // cs - SPI chip select pin + // _cpr - counts per revolution + // _angle_register - (optional) angle read register - default 0x3FFF + MagneticSensor(int cs, float _cpr, int angle_register = 0); + + // SPI angle register to read + int angle_register; + // encoder initialise pins + void init(); + + // implementation of abstract functions of the Sensor class + // get current angle (rad) + float getAngle(); + // get current angular velocity (rad/s) + float getVelocity(); + // set current agle as zero angle + // return the angle [rad] difference + float initRelativeZero(); + // set absoule zero angle as zero angle + // return the angle [rad] difference + float initAbsoluteZero(); + // returns 1 because it is the absolute sensor + int hasAbsoluteZero(); + // returns 0 maning it doesn't need search for absolute zero + int needsAbsoluteZeroSearch(); + + + private: + // spi variables + int chip_select_pin; + bool errorFlag; + SPISettings settings; + // spi funcitons + void close(); + word read(word angle_register); + byte spiCalcEvenParity(word value); + + + // zero offset + word zero_offset; + // funciton getting current register value + int getRawCount(); + + // impulse cpr + float cpr; + // velocity calculation variables + float angle_prev; + long velocity_calc_timestamp; + +}; + + +#endif diff --git a/arduino_foc_minimal/Sensor.h b/arduino_foc_minimal/Sensor.h new file mode 100644 index 00000000..79e05684 --- /dev/null +++ b/arduino_foc_minimal/Sensor.h @@ -0,0 +1,29 @@ +#ifndef SENSOR_H +#define SENSOR_H + +// Sensor abstract class defintion +// Each sensor needs to have these functions implemented +class Sensor{ + public: + // get current angle (rad) + virtual float getAngle(); + // get current angular velocity (rad/s) + virtual float getVelocity(); + // set current agle as zero angle + // return the angle [rad] difference + virtual float initRelativeZero(); + // set absoule zero angle as zero angle + // return the angle [rad] difference + virtual float initAbsoluteZero(); + + // returns 0 if it has no absolute 0 measurement + // 0 - incremental encoder without index + // 1 - encoder with index & magnetic sensors + virtual int hasAbsoluteZero(); + // returns 0 if it does need search for absolute zero + // 0 - magnetic sensor + // 1 - ecoder with index + virtual int needsAbsoluteZeroSearch(); +}; + +#endif \ No newline at end of file diff --git a/arduino_foc_minimal/SimpleFOC.h b/arduino_foc_minimal/SimpleFOC.h new file mode 100644 index 00000000..887ae8df --- /dev/null +++ b/arduino_foc_minimal/SimpleFOC.h @@ -0,0 +1,10 @@ +#ifndef SIMPLEFOC_H +#define SIMPLEFOC_H + +#include "FOCutils.h" +#include "Sensor.h" +#include "Encoder.h" +#include "MagneticSensor.h" +#include "BLDCMotor.h" + +#endif diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index eedcbd05..89958009 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -1,49 +1,24 @@ -#include "BLDCMotor.h" -#include "Encoder.h" - -// Only pins 2 and 3 are supported -#define arduinoInt1 2 // Arduino UNO interrupt 0 -#define arduinoInt2 3 // Arduino UNO interrupt 1 +#include "SimpleFOC.h" // BLDCMotor( int phA, int phB, int phC, int pp, int en) // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - enable pin - (optional input) BLDCMotor motor = BLDCMotor(9, 5, 6, 11, 8); -// Encoder(int encA, int encB , int cpr, int index) -// - encA, encB - encoder A and B pins -// - ppr - impulses per rotation (cpr=ppr*4) -// - index pin - (optional input) -Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, A0); - -// Interrupt rutine intialisation -// channel A and B callbacks -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} -// index calback interrupt code -// please set the right PCINT(0,1,2)_vect parameter -// PCINT0_vect - index pin in between D8 and D13 -// PCINT1_vect - index pin in between A0 and A5 (recommended) -// PCINT2_vect - index pin in between D0 and D7 -ISR (PCINT1_vect) { encoder.handleIndex(); } + +// MagneticSensor(int cs, float _cpr, int _angle_register) +// cs - SPI chip select pin +// _cpr - counts per revolution +// _angle_register - (optional) angle read register - default 0x3FFF +MagneticSensor AS5x4x = MagneticSensor(10, 16384, 0x3FFF); void setup() { // debugging port Serial.begin(115200); - // check if you need internal pullups - // Quadrature::ENABLE - CPR = 4xPPR - default - // Quadrature::DISABLE - CPR = PPR - encoder.quadrature = Quadrature::ENABLE; - - // check if you need internal pullups - // Pullup::EXTERN - external pullup added - dafault - // Pullup::INTERN - needs internal arduino pullup - encoder.pullup = Pullup::EXTERN; - // initialise encoder hardware - encoder.init(doA, doB); + AS5x4x.init(); // power supply voltage // default 12V @@ -80,7 +55,7 @@ void setup() { // link the motor to the sensor - motor.linkEncoder(&encoder); + motor.linkSensor(&AS5x4x); // use debugging with serial for motor init // comment out if not needed From fee62befcab3521943cad66825caaeb858113f9e Mon Sep 17 00:00:00 2001 From: askuric Date: Tue, 28 Apr 2020 07:38:01 +0200 Subject: [PATCH 27/65] FIX overlow fix first version --- arduino_foc_minimal/BLDCMotor.cpp | 3 +-- arduino_foc_minimal/MagneticSensor.cpp | 17 ++++++++++++----- arduino_foc_minimal/arduino_foc_minimal.ino | 15 ++------------- 3 files changed, 15 insertions(+), 20 deletions(-) diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index 548b250d..00b453d4 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -61,8 +61,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // index search velocity index_search_velocity = DEF_INDEX_SEARCH_TARGET_VELOCITY; - // electric angle og the zero angle - // electric angle of the index for encoder + // electric angle of the zero angle zero_electric_angle = 0; //debugger diff --git a/arduino_foc_minimal/MagneticSensor.cpp b/arduino_foc_minimal/MagneticSensor.cpp index 39d27369..90d2a4a7 100644 --- a/arduino_foc_minimal/MagneticSensor.cpp +++ b/arduino_foc_minimal/MagneticSensor.cpp @@ -30,12 +30,11 @@ void MagneticSensor::init(){ velocity_calc_timestamp = _micros(); } - // Shaft angle calculation +// angle is in range [0,2*PI] float MagneticSensor::getAngle(){ float rotation; - rotation = getRawCount() - (int)zero_offset; - if(rotation > 8191) rotation = -((0x3FFF)-rotation); //more than -180 + rotation = getRawCount() - (int)zero_offset; return rotation / (float)cpr * _2PI; } @@ -45,9 +44,17 @@ float MagneticSensor::getVelocity(){ float Ts = (_micros() - velocity_calc_timestamp)*1e-6; if(Ts > 0.5) Ts = 0.01; // debounce // current angle - float angle_c = getAngle(); + float angle_c = getAngle(); + + // overflow compensation + float d_angle = angle_c - angle_prev; + // if angle changed more than 3PI/2 = 270 degrees + // consider it as overflow + if( abs(d_angle) > _3PI_2 ) d_angle += d_angle < 0 ? _2PI : -_2PI; + // velocity calculation - float vel = (angle_c - angle_prev)/Ts; + float vel = d_angle/Ts; + // save variables for future pass angle_prev = angle_c; velocity_calc_timestamp = _micros(); diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index 89958009..93867b97 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -17,23 +17,12 @@ void setup() { // debugging port Serial.begin(115200); - // initialise encoder hardware + // initialise magnetic sensor hardware AS5x4x.init(); // power supply voltage // default 12V motor.voltage_power_supply = 12; - - // index search velocity - default 1rad/s - motor.index_search_velocity = 1; - // index search PI contoller parameters - // default K=0.5 Ti = 0.01 - motor.PI_velocity_index_search.K = 0.1; - motor.PI_velocity_index_search.Ti = 0.01; - //motor.PI_velocity_index_search.voltage_limit = 3; - // jerk control using voltage voltage ramp - // default value is 100 - motor.PI_velocity_index_search.voltage_ramp = 100; // set control loop type to be used // ControlType::voltage @@ -91,7 +80,7 @@ void loop() { // function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! - // motor_monitor(); + motor_monitor(); } // utility function intended to be used with serial plotter to monitor motor variables From ca3f2c547e8dbffa740f056dae961e270b282a20 Mon Sep 17 00:00:00 2001 From: askuric Date: Tue, 28 Apr 2020 09:13:58 +0200 Subject: [PATCH 28/65] bugfix initAbsoluteAngle --- arduino_foc_minimal/MagneticSensor.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/arduino_foc_minimal/MagneticSensor.cpp b/arduino_foc_minimal/MagneticSensor.cpp index 90d2a4a7..0eaf1532 100644 --- a/arduino_foc_minimal/MagneticSensor.cpp +++ b/arduino_foc_minimal/MagneticSensor.cpp @@ -71,9 +71,7 @@ float MagneticSensor::initRelativeZero(){ // set absoule zero angle as zero angle // return the angle [rad] difference float MagneticSensor::initAbsoluteZero(){ - float rotation; - rotation = -(int)zero_offset; - if(rotation > 8191) rotation = -((0x3FFF)-rotation); // more than -180 + float rotation = -(int)zero_offset; // init absolute zero zero_offset = 0; // return offset in radians From 5707764296b90b249acaa88852dc4db643789f18 Mon Sep 17 00:00:00 2001 From: askuric Date: Tue, 28 Apr 2020 14:36:29 +0200 Subject: [PATCH 29/65] FEAT refactoring and simplification + added simpler interrupt support --- arduino_foc_minimal/BLDCMotor.cpp | 103 +++++++++----------- arduino_foc_minimal/BLDCMotor.h | 6 +- arduino_foc_minimal/Encoder.cpp | 49 +++++----- arduino_foc_minimal/Encoder.h | 7 +- arduino_foc_minimal/MagneticSensor.cpp | 17 ++-- arduino_foc_minimal/Sensor.h | 4 +- arduino_foc_minimal/arduino_foc_minimal.ino | 41 ++++++-- 7 files changed, 113 insertions(+), 114 deletions(-) diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index 00b453d4..e325d3db 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -1,12 +1,10 @@ #include "BLDCMotor.h" -/* - BLDCMotor( int phA, int phB, int phC, int pp , int cpr, int en) - - phA, phB, phC - motor A,B,C phase pwm pins - - pp - pole pair number - - cpr - counts per rotation number (cpm=ppm*4) - - enable pin - (optionl input) -*/ +// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - phA, phB, phC - motor A,B,C phase pwm pins +// - pp - pole pair number +// - cpr - counts per rotation number (cpm=ppm*4) +// - enable pin - (optionl input) BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) { // Pin intialization @@ -75,7 +73,7 @@ void BLDCMotor::init() { pinMode(pwmA, OUTPUT); pinMode(pwmB, OUTPUT); pinMode(pwmC, OUTPUT); - pinMode(enable_pin, OUTPUT); + if(hasEnable()) pinMode(enable_pin, OUTPUT); if(debugger) debugger->println("DEBUG: Set high frequency PWM."); // Increase PWM frequency to 32 kHz @@ -97,32 +95,18 @@ void BLDCMotor::init() { } -/* - initialization function -*/ -int BLDCMotor::initFOC() { - // sensor and motor alignment - _delay(500); - int exit_flag = alignSensor(); - _delay(500); - return exit_flag; -} -/* - disable motor -*/ +// disable motor driver void BLDCMotor::disable() { // disable the driver - if enable_pin pin available - if (enable_pin) digitalWrite(enable_pin, LOW); + if (hasEnable()) digitalWrite(enable_pin, LOW); // set zero to PWM setPwm(pwmA, 0); setPwm(pwmB, 0); setPwm(pwmC, 0); } -/* - disable motor -*/ +// enable motor driver void BLDCMotor::enable() { // set zero to PWM @@ -130,7 +114,7 @@ void BLDCMotor::enable() setPwm(pwmB, 0); setPwm(pwmC, 0); // enable_pin the driver - if enable_pin pin available - if (enable_pin) digitalWrite(enable_pin, HIGH); + if (hasEnable()) digitalWrite(enable_pin, HIGH); } @@ -139,9 +123,7 @@ void BLDCMotor::linkSensor(Sensor* _sensor) { } -/* - Encoder alignment to electrical 0 angle -*/ +// Encoder alignment to electrical 0 angle int BLDCMotor::alignSensor() { if(debugger) debugger->println("DEBUG: Align the sensor's and motor electrical 0 angle."); // align the electircal phases of the motor and sensor @@ -161,15 +143,14 @@ int BLDCMotor::alignSensor() { if(debugger){ if(exit_flag< 0 ) debugger->println("DEBUG: Error: Absolute zero not found!"); if(exit_flag> 0 ) debugger->println("DEBUG: Success: Absolute zero found!"); - else debugger->println("DEBUG: Success: Absolute zero not availabe!"); + else debugger->println("DEBUG: Absolute zero not availabe!"); } return exit_flag; } -/* - Encoder alignment to electrical 0 angle -*/ +// Encoder alignment the absolute zero angle +// - to the index int BLDCMotor::absoluteZeroAlign() { // if no absolute zero return if(!sensor->hasAbsoluteZero()) return 0; @@ -208,29 +189,38 @@ float BLDCMotor::shaftAngle() { float BLDCMotor::shaftVelocity() { return sensor->getVelocity(); } -/* - Electrical angle calculation -*/ +// Electrical angle calculation float BLDCMotor::electricAngle(float shaftAngle) { //return normalizeAngle(shaftAngle * pole_pairs); return (shaftAngle * pole_pairs); } -/* - Iterative function looping FOC algorithm, setting Uq on the Motor - The faster it can be run the better + +/** + FOC funcitons */ + +// FOC initialization function +int BLDCMotor::initFOC() { + // sensor and motor alignment + _delay(500); + int exit_flag = alignSensor(); + _delay(500); + return exit_flag; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better void BLDCMotor::loopFOC() { - // voltage open loop loop + // shaft angle shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart funciton :) setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); } -/* - Iterative funciton running outer loop of the FOC algorithm - Bahvior of this funciton is determined by the motor.controller variable - It runs either angle, veloctiy, velocity ultra slow or voltage loop - - needs to be called iteratively it is asynchronious function -*/ +// Iterative funciton running outer loop of the FOC algorithm +// Bahvior of this funciton is determined by the motor.controller variable +// It runs either angle, veloctiy, velocity ultra slow or voltage loop +// - needs to be called iteratively it is asynchronious function void BLDCMotor::move(float target) { // get angular velocity shaft_velocity = shaftVelocity(); @@ -260,12 +250,7 @@ void BLDCMotor::move(float target) { } -/** - FOC methods -*/ -/* - Method using FOC to set Uq to the motor at the optimal angle -*/ +// Method using FOC to set Uq to the motor at the optimal angle void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // angle normalisation in between 0 and 2pi @@ -289,10 +274,8 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { } -/* - Set voltage to the pwm pin - - function a bit optimised to get better performance -*/ +// Set voltage to the pwm pin +// - function a bit optimised to get better performance void BLDCMotor::setPwm(int pinPwm, float U) { // max value float U_max = voltage_power_supply/2.0; @@ -312,13 +295,15 @@ void BLDCMotor::setPwm(int pinPwm, float U) { /** Utility funcitons */ -/* - normalizing radian angle to [0,2PI] -*/ +// normalizing radian angle to [0,2PI] float BLDCMotor::normalizeAngle(float angle){ float a = fmod(angle, _2PI); return a >= 0 ? a : (a + _2PI); } +// determining if the enable pin has been provided +int BLDCMotor::hasEnable(){ + return enable_pin != 0; +} diff --git a/arduino_foc_minimal/BLDCMotor.h b/arduino_foc_minimal/BLDCMotor.h index a85bf724..29e61ac4 100644 --- a/arduino_foc_minimal/BLDCMotor.h +++ b/arduino_foc_minimal/BLDCMotor.h @@ -92,7 +92,6 @@ class BLDCMotor int pole_pairs; - /** State calculation methods */ //Shaft angle calculation float shaftAngle(); @@ -100,8 +99,6 @@ class BLDCMotor float shaftVelocity(); // state variables - // current elelctrical angle - float elctric_angle; // current motor angle float shaft_angle; // current motor velocity @@ -136,7 +133,6 @@ class BLDCMotor //Method using FOC to set Uq to the motor at the optimal angle void setPhaseVoltage(float Uq, float angle_el); - // debugging void useDebugging(Print &print); Print* debugger; @@ -155,6 +151,8 @@ class BLDCMotor /** Utility funcitons */ //normalizing radian angle to [0,2PI] float normalizeAngle(float angle); + // determining if the enable pin has been provided + int hasEnable(); /** Motor control functions */ float controllerPI(float tracking_error, PI_s &controller); diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index 5cb02a51..4f02e222 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -154,12 +154,6 @@ int Encoder::needsAbsoluteZeroSearch(){ int Encoder::hasAbsoluteZero(){ return hasIndex(); } - - -int Encoder::hasIndex(){ - return index_pin != 0; -} - // intialise counter to zero float Encoder::initRelativeZero(){ long angle_offset = -pulse_counter; @@ -173,10 +167,15 @@ float Encoder::initAbsoluteZero(){ prev_pulse_counter = pulse_counter; return (index_pulse_counter) / ((float)cpr) * (_2PI); } +// private funciton used to determine if encoder has index +int Encoder::hasIndex(){ + return index_pin != 0; +} - -void Encoder::init(void (*doA)(), void(*doB)()){ +// encoder initialisation of the hardware pins +// and calculation variables +void Encoder::init(){ // Encoder - check if pullup needed for your encoder if(pullup == Pullup::INTERN){ @@ -188,7 +187,8 @@ void Encoder::init(void (*doA)(), void(*doB)()){ pinMode(pinB, INPUT); if(hasIndex()) pinMode(index_pin,INPUT); } - // counter setup + + // counter setup pulse_counter = 0; pulse_timestamp = _micros(); // velocity calculation varibles @@ -197,35 +197,30 @@ void Encoder::init(void (*doA)(), void(*doB)()){ prev_pulse_counter = 0; prev_timestamp_us = _micros(); + // initial cpr = PPR + // change it if the mode is quadrature + if(quadrature == Quadrature::ENABLE) cpr = 4*cpr; + +} +// funciton enabling hardware interrupts of the for the callback provided +// if callback is not provided then the interrupt is not enabled +void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){ // attach interrupt if functions provided switch(quadrature){ case Quadrature::ENABLE: - // initial cpr = PPR - // change it if the mode is quadrature - cpr = 4*cpr; // A callback and B callback - if(doA != nullptr){ - // CPR = 4xPPR - attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); - attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); - } + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); break; case Quadrature::DISABLE: // A callback and B callback - if(doA != nullptr){ - // CPR = PPR - attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING); - attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); - } + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); break; } // if index used intialise the index interrupt - if(hasIndex() && doA != nullptr) { - *digitalPinToPCMSK(index_pin) |= bit (digitalPinToPCMSKbit(index_pin)); // enable pin - PCIFR |= bit (digitalPinToPCICRbit(index_pin)); // clear any outstanding interrupt - PCICR |= bit (digitalPinToPCICRbit(index_pin)); // enable interrupt for the group - } + if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE); } diff --git a/arduino_foc_minimal/Encoder.h b/arduino_foc_minimal/Encoder.h index 69426ee5..084fe16f 100644 --- a/arduino_foc_minimal/Encoder.h +++ b/arduino_foc_minimal/Encoder.h @@ -28,8 +28,11 @@ class Encoder: public Sensor{ Encoder(int encA, int encB , float ppr, int index = 0); // encoder initialise pins - void init(void (*doA)() = nullptr, void(*doB)() = nullptr); - + void init(); + // funciton enabling hardware interrupts of the for the callback provided + // if callback is not provided then the interrupt is not enabled + void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr); + // Encoder interrupt callback functions // enabling CPR=4xPPR behaviour // A channel diff --git a/arduino_foc_minimal/MagneticSensor.cpp b/arduino_foc_minimal/MagneticSensor.cpp index 0eaf1532..1e0a86a3 100644 --- a/arduino_foc_minimal/MagneticSensor.cpp +++ b/arduino_foc_minimal/MagneticSensor.cpp @@ -16,18 +16,18 @@ MagneticSensor::MagneticSensor(int cs, float _cpr, int _angle_register){ void MagneticSensor::init(){ - // 1MHz clock (AMS should be able to accept up to 10MHz) + // 1MHz clock (AMS should be able to accept up to 10MHz) settings = SPISettings(1000000, MSBFIRST, SPI_MODE1); - + //setup pins pinMode(chip_select_pin, OUTPUT); //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices SPI.begin(); - // velocity calculation init - angle_prev = 0; - velocity_calc_timestamp = _micros(); + // velocity calculation init + angle_prev = 0; + velocity_calc_timestamp = _micros(); } // Shaft angle calculation @@ -96,7 +96,7 @@ int MagneticSensor::getRawCount(){ return (int)MagneticSensor::read(angle_register); } -// SPI finctions +// SPI functions /** * Utility function used to calculate even parity of word */ @@ -106,10 +106,7 @@ byte MagneticSensor::spiCalcEvenParity(word value){ for (i = 0; i < 16; i++) { - if (value & 0x1) - { - cnt++; - } + if (value & 0x1) cnt++; value >>= 1; } return cnt & 0x1; diff --git a/arduino_foc_minimal/Sensor.h b/arduino_foc_minimal/Sensor.h index 79e05684..3555941a 100644 --- a/arduino_foc_minimal/Sensor.h +++ b/arduino_foc_minimal/Sensor.h @@ -21,8 +21,8 @@ class Sensor{ // 1 - encoder with index & magnetic sensors virtual int hasAbsoluteZero(); // returns 0 if it does need search for absolute zero - // 0 - magnetic sensor - // 1 - ecoder with index + // 0 - magnetic sensor (& encoder with index which is found) + // 1 - ecoder with index (with index not found yet) virtual int needsAbsoluteZeroSearch(); }; diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index 93867b97..3dbbee30 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -1,24 +1,45 @@ #include "SimpleFOC.h" +#include +#include + // BLDCMotor( int phA, int phB, int phC, int pp, int en) // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 5, 6, 11, 8); +BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); + +// // MagneticSensor(int cs, float _cpr, int _angle_register) +// // cs - SPI chip select pin +// // _cpr - counts per revolution +// // _angle_register - (optional) angle read register - default 0x3FFF +// MagneticSensor AS5x4x = MagneticSensor(10, 16384, 0x3FFF); + -// MagneticSensor(int cs, float _cpr, int _angle_register) -// cs - SPI chip select pin -// _cpr - counts per revolution -// _angle_register - (optional) angle read register - default 0x3FFF -MagneticSensor AS5x4x = MagneticSensor(10, 16384, 0x3FFF); +Encoder encoder = Encoder(2, 3, 8192, 4); +void doA(){encoder.handleA();} +void doB(){encoder.handleB();} +void doIndex(){encoder.handleIndex();} +// software interrupt init +PciListenerImp listenerIndex(encoder.index_pin, doIndex); void setup() { // debugging port Serial.begin(115200); - // initialise magnetic sensor hardware - AS5x4x.init(); + // // initialise magnetic sensor hardware + // AS5x4x.init(); + + encoder.quadrature = Quadrature::ENABLE; + encoder.pullup = Pullup::EXTERN; + + // init encoder + encoder.init(); + // enable hardware interrupts + encoder.enableInterrupts(doA, doB); + // enable software interrupts + PciManager.registerListener(&listenerIndex); // power supply voltage // default 12V @@ -44,7 +65,7 @@ void setup() { // link the motor to the sensor - motor.linkSensor(&AS5x4x); + motor.linkSensor(&encoder); // use debugging with serial for motor init // comment out if not needed @@ -80,7 +101,7 @@ void loop() { // function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! - motor_monitor(); + //motor_monitor(); } // utility function intended to be used with serial plotter to monitor motor variables From 9e65d78ccfe5e7e03580aa716124e8728551e23b Mon Sep 17 00:00:00 2001 From: askuric Date: Fri, 1 May 2020 17:21:20 +0200 Subject: [PATCH 30/65] FEAT removed magnetic sensor angle limit --- arduino_foc_minimal/BLDCMotor.cpp | 77 +++++++++++--------------- arduino_foc_minimal/BLDCMotor.h | 45 +++++++-------- arduino_foc_minimal/Encoder.cpp | 3 + arduino_foc_minimal/FOCutils.cpp | 8 +-- arduino_foc_minimal/MagneticSensor.cpp | 52 ++++++++++++----- arduino_foc_minimal/MagneticSensor.h | 3 + 6 files changed, 101 insertions(+), 87 deletions(-) diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index e325d3db..e563439c 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -21,35 +21,28 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // Velocity loop config // PI contoroller constant - PI_velocity.K = DEF_PI_VEL_K; - PI_velocity.Ti = DEF_PI_VEL_TI; + PI_velocity.P = DEF_PI_VEL_P; + PI_velocity.I = DEF_PI_VEL_I; PI_velocity.timestamp = _micros(); PI_velocity.voltage_limit = voltage_power_supply/2; PI_velocity.voltage_ramp = DEF_PI_VEL_U_RAMP; PI_velocity.voltage_prev = 0; PI_velocity.tracking_error_prev = 0; - // Ultra slow velocity - // PI contoroller - PI_velocity_ultra_slow.K = DEF_PI_VEL_US_K; - PI_velocity_ultra_slow.Ti = DEF_PI_VEL_US_TI; - PI_velocity_ultra_slow.timestamp = _micros(); - PI_velocity_ultra_slow.voltage_limit = voltage_power_supply/2; - PI_velocity_ultra_slow.voltage_ramp = DEF_PI_VEL_US_U_RAMP; - PI_velocity_ultra_slow.voltage_prev = 0; - PI_velocity_ultra_slow.tracking_error_prev = 0; - // current estimated angle - ultraslow_estimated_angle = 0; + // velocity low pass filter + LPF_velocity.Tf = DEF_VEL_FILTER_Tf; + LPF_velocity.timestamp = _micros(); + LPF_velocity.prev = 0; // position loop config // P controller constant - P_angle.K = DEF_P_ANGLE_K; + P_angle.P = DEF_P_ANGLE_P; // maximum angular velocity to be used for positioning P_angle.velocity_limit = DEF_P_ANGLE_VEL_LIM; // index search PI controller - PI_velocity_index_search.K = DEF_PI_VEL_INDEX_K; - PI_velocity_index_search.Ti = DEF_PI_VEL_INDEX_TI; + PI_velocity_index_search.P = DEF_PI_VEL_INDEX_P; + PI_velocity_index_search.I = DEF_PI_VEL_INDEX_I; PI_velocity_index_search.voltage_limit = voltage_power_supply/2; PI_velocity_index_search.voltage_ramp = DEF_PI_VEL_INDEX_U_RAMP; PI_velocity_index_search.timestamp = _micros(); @@ -83,8 +76,7 @@ void BLDCMotor::init() { setPwmFrequency(pwmC); // sanity check for the voltage limit configuration - if(PI_velocity.voltage_limit > voltage_power_supply/2) PI_velocity.voltage_limit = PI_velocity.voltage_limit > voltage_power_supply/2; - if(PI_velocity.voltage_limit > voltage_power_supply/2) PI_velocity_ultra_slow.voltage_limit = voltage_power_supply/2; + if(PI_velocity.voltage_limit > voltage_power_supply/2) PI_velocity.voltage_limit = voltage_power_supply/2; if(PI_velocity_index_search.voltage_limit > voltage_power_supply/2) PI_velocity_index_search.voltage_limit = voltage_power_supply/2; _delay(500); @@ -130,7 +122,7 @@ int BLDCMotor::alignSensor() { setPwm(pwmA, voltage_power_supply/2.0); setPwm(pwmB,0); setPwm(pwmC,0); - _delay(1000); + _delay(3000); // set sensor to zero sensor->initRelativeZero(); _delay(500); @@ -187,7 +179,16 @@ float BLDCMotor::shaftAngle() { } // shaft velocity calculation float BLDCMotor::shaftVelocity() { - return sensor->getVelocity(); + float Ts = (_micros() - LPF_velocity.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + // calculate the fitering + float alpha = LPF_velocity.Tf/(LPF_velocity.Tf + Ts); + float vel = alpha*LPF_velocity.prev + (1-alpha)*sensor->getVelocity(); + // save the variables + LPF_velocity.prev = vel; + LPF_velocity.timestamp = _micros(); + return vel; } // Electrical angle calculation float BLDCMotor::electricAngle(float shaftAngle) { @@ -219,7 +220,7 @@ void BLDCMotor::loopFOC() { // Iterative funciton running outer loop of the FOC algorithm // Bahvior of this funciton is determined by the motor.controller variable -// It runs either angle, veloctiy, velocity ultra slow or voltage loop +// It runs either angle, veloctiy or voltage loop // - needs to be called iteratively it is asynchronious function void BLDCMotor::move(float target) { // get angular velocity @@ -241,11 +242,6 @@ void BLDCMotor::move(float target) { shaft_velocity_sp = target; voltage_q = velocityPI(shaft_velocity_sp - shaft_velocity); break; - case ControlType::velocity_ultra_slow: - // velocity set point - shaft_velocity_sp = target; - voltage_q = velocityUltraSlowPI(shaft_velocity_sp); - break; } } @@ -259,6 +255,8 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // Inverse park transform // regular sin + cos ~300us (no memeory usaage) // approx _sin + _cos ~110us (400Byte ~ 20% of memory) + // Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; + // Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; @@ -306,21 +304,20 @@ int BLDCMotor::hasEnable(){ } - - /** Motor control functions */ // PI controller function float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){ float Ts = (_micros() - cont.timestamp) * 1e-6; - if(Ts > 0.5) Ts = 1e-3; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - // u(s) = Kr(1 + 1/(Ti.s)) + // u(s) = (P + I/s)e(s) // tustin discretisation of the PI controller ( a bit optimised ) - // uk = uk_1 + K*(Ts/(2*Ti) + 1)*ek + K*(Ts/(2*Ti)-1)*ek_1 - float tmp = 0.5 * Ts / cont.Ti; - float voltage = cont.voltage_prev + cont.K * ((tmp + 1.0) * tracking_error + (tmp - 1.0) * cont.tracking_error_prev); + // uk = uk_1 + (I*Ts/2 + P)*ek + (I*Ts/2 - P)*ek_1 + float tmp = cont.I*Ts*0.5; + float voltage = cont.voltage_prev + (tmp + cont.P) * tracking_error + (tmp - cont.P) * cont.tracking_error_prev; // antiwindup - limit the output voltage_q if (abs(voltage) > cont.voltage_limit) voltage = voltage > 0 ? cont.voltage_limit : -cont.voltage_limit; @@ -341,21 +338,9 @@ float BLDCMotor::velocityPI(float tracking_error) { float BLDCMotor::velocityIndexSearchPI(float tracking_error) { return controllerPI(tracking_error, PI_velocity_index_search); } -// PI controller for ultra slow velocity control -float BLDCMotor::velocityUltraSlowPI(float vel) { - float Ts = (_micros() - PI_velocity_ultra_slow.timestamp) * 1e-6; - - // integrate the velocity to get the necessary angle - ultraslow_estimated_angle += vel * Ts; - // error of positioning - float tracking_error = ultraslow_estimated_angle - shaft_angle; - - return controllerPI(tracking_error, PI_velocity_ultra_slow); -} - // P controller for position control loop float BLDCMotor::positionP(float ek) { - float velk = P_angle.K * ek; + float velk = P_angle.P * ek; if (abs(velk) > P_angle.velocity_limit) velk = velk > 0 ? P_angle.velocity_limit : -P_angle.velocity_limit; return velk; } diff --git a/arduino_foc_minimal/BLDCMotor.h b/arduino_foc_minimal/BLDCMotor.h index 29e61ac4..60061fc5 100644 --- a/arduino_foc_minimal/BLDCMotor.h +++ b/arduino_foc_minimal/BLDCMotor.h @@ -11,36 +11,33 @@ // power supply voltage #define DEF_POWER_SUPPLY 12.0 // velocity PI controller params -#define DEF_PI_VEL_K 0.5 -#define DEF_PI_VEL_TI 0.01 +#define DEF_PI_VEL_P 0.5 +#define DEF_PI_VEL_I 10 #define DEF_PI_VEL_U_RAMP 300 -// ultra slow velocity PI params -#define DEF_PI_VEL_US_K 60.0 -#define DEF_PI_VEL_US_TI 100.0 -#define DEF_PI_VEL_US_U_RAMP 300 // angle P params -#define DEF_P_ANGLE_K 20 +#define DEF_P_ANGLE_P 20 // angle velocity limit default #define DEF_P_ANGLE_VEL_LIM 20 // index search velocity #define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 // velocity PI controller params for index search -#define DEF_PI_VEL_INDEX_K 0.5 -#define DEF_PI_VEL_INDEX_TI 0.01 +#define DEF_PI_VEL_INDEX_P 1 +#define DEF_PI_VEL_INDEX_I 10 #define DEF_PI_VEL_INDEX_U_RAMP 100 +// velocity filter time constant +#define DEF_VEL_FILTER_Tf 0.005 // controller type configuration enum enum ControlType{ voltage, velocity, - velocity_ultra_slow, angle }; // PI controller strucutre struct PI_s{ - float K; - float Ti; + float P; + float I; long timestamp; float voltage_prev, tracking_error_prev; float voltage_limit; @@ -49,12 +46,19 @@ struct PI_s{ // P controller structure struct P_s{ - float K; + float P; long timestamp; float voltage_prev, tracking_error_prev; float velocity_limit; }; +// flow pass filter structure +struct LPF_s{ + float Tf; + long timestamp; + float prev; +}; + /** BLDC motor class */ @@ -116,10 +120,10 @@ class BLDCMotor // configuraion structures ControlType controller; PI_s PI_velocity; - PI_s PI_velocity_ultra_slow; - P_s P_angle; - PI_s PI_velocity_index_search; - + PI_s PI_velocity_index_search; + P_s P_angle; + LPF_s LPF_velocity; + // sensor link: // - Encoder // - MagneticSensor @@ -136,6 +140,8 @@ class BLDCMotor // debugging void useDebugging(Print &print); Print* debugger; + + float Ua,Ub,Uc; private: //Sensor alignment to electrical 0 angle @@ -157,16 +163,11 @@ class BLDCMotor /** Motor control functions */ float controllerPI(float tracking_error, PI_s &controller); float velocityPI(float tracking_error); - float velocityUltraSlowPI(float vel); float velocityIndexSearchPI(float tracking_error); float positionP(float ek); // phase voltages float Ualpha,Ubeta; - float Ua,Ub,Uc; - - // velocity ultra slow angle - float ultraslow_estimated_angle; }; diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal/Encoder.cpp index 4f02e222..85cb8142 100644 --- a/arduino_foc_minimal/Encoder.cpp +++ b/arduino_foc_minimal/Encoder.cpp @@ -118,6 +118,9 @@ float Encoder::getVelocity(){ long timestamp_us = _micros(); // sampling time calculation float Ts = (timestamp_us - prev_timestamp_us) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + // time from last impulse float Th = (timestamp_us - pulse_timestamp) * 1e-6; long dN = pulse_counter - prev_pulse_counter; diff --git a/arduino_foc_minimal/FOCutils.cpp b/arduino_foc_minimal/FOCutils.cpp index cc94cd53..5a383f3d 100644 --- a/arduino_foc_minimal/FOCutils.cpp +++ b/arduino_foc_minimal/FOCutils.cpp @@ -56,19 +56,19 @@ float _sin(float a){ if(a < _PI_2){ //return sine_array[(int)(199.0*( a / (M_PI/2.0)))]; //return sine_array[(int)(126.6873* a)]; // float array optimised - return 0.0001*sine_array[(int)(126.6873* a)]; // int array optimised + return 0.0001*sine_array[round(126.6873* a)]; // int array optimised }else if(a < M_PI){ // return sine_array[(int)(199.0*(1.0 - (a-M_PI/2.0) / (M_PI/2.0)))]; //return sine_array[398 - (int)(126.6873*a)]; // float array optimised - return 0.0001*sine_array[398 - (int)(126.6873*a)]; // int array optimised + return 0.0001*sine_array[398 - round(126.6873*a)]; // int array optimised }else if(a < _3PI_2){ // return -sine_array[(int)(199.0*((a - M_PI) / (M_PI/2.0)))]; //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimised - return -0.0001*sine_array[-398 + (int)(126.6873*a)]; // int array optimised + return -0.0001*sine_array[-398 + round(126.6873*a)]; // int array optimised } else { // return -sine_array[(int)(199.0*(1.0 - (a - 3*M_PI/2) / (M_PI/2.0)))]; //return -sine_array[796 - (int)(126.6873*a)]; // float array optimised - return -0.0001*sine_array[796 - (int)(126.6873*a)]; // int array optimised + return -0.0001*sine_array[796 - round(126.6873*a)]; // int array optimised } } diff --git a/arduino_foc_minimal/MagneticSensor.cpp b/arduino_foc_minimal/MagneticSensor.cpp index 1e0a86a3..66dc85ac 100644 --- a/arduino_foc_minimal/MagneticSensor.cpp +++ b/arduino_foc_minimal/MagneticSensor.cpp @@ -3,7 +3,7 @@ // MagneticSensor(int cs, float _cpr, int _angle_register) // cs - SPI chip select pin -// _cpr - counts per revolution +// _cpr - counF per revolution // _angle_register - (optional) angle read register - default 0x3FFF MagneticSensor::MagneticSensor(int cs, float _cpr, int _angle_register){ // chip select pin @@ -12,6 +12,7 @@ MagneticSensor::MagneticSensor(int cs, float _cpr, int _angle_register){ angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTAR; // register maximum value (counts per revolution) cpr = _cpr; + } @@ -27,33 +28,48 @@ void MagneticSensor::init(){ // velocity calculation init angle_prev = 0; - velocity_calc_timestamp = _micros(); + velocity_calc_timestamp = _micros(); + + // full rotations tracking number + full_rotation_offset = 0; + angle_data_prev = getRawCount(); + zero_offset = 0; } // Shaft angle calculation -// angle is in range [0,2*PI] +// angle is in radians [rad] float MagneticSensor::getAngle(){ - float rotation; - rotation = getRawCount() - (int)zero_offset; - return rotation / (float)cpr * _2PI; + // raw data from the sensor + float angle_data = getRawCount(); + + // tracking the number of rotations + // in order to expand angle range form [0,2PI] + // to basically infinity + float d_angle = angle_data - angle_data_prev; + // if overflow happened track it as full rotation + if(abs(d_angle) > (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; + // save the current angle value for the next steps + // in order to know if overflow happened + angle_data_prev = angle_data; + + // zero offset adding + angle_data -= (int)zero_offset; + // return the full angle + // (number of full rotations)*2PI + current sensor angle + return full_rotation_offset + ( angle_data / (float)cpr) * _2PI; } // Shaft velocity calculation float MagneticSensor::getVelocity(){ // calculate sample time float Ts = (_micros() - velocity_calc_timestamp)*1e-6; - if(Ts > 0.5) Ts = 0.01; // debounce + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + // current angle float angle_c = getAngle(); - - // overflow compensation - float d_angle = angle_c - angle_prev; - // if angle changed more than 3PI/2 = 270 degrees - // consider it as overflow - if( abs(d_angle) > _3PI_2 ) d_angle += d_angle < 0 ? _2PI : -_2PI; - // velocity calculation - float vel = d_angle/Ts; + float vel = (angle_c - angle_prev)/Ts; // save variables for future pass angle_prev = angle_c; @@ -66,6 +82,9 @@ float MagneticSensor::getVelocity(){ float MagneticSensor::initRelativeZero(){ float angle_offset = -getAngle(); zero_offset = getRawCount(); + + // angle tracking variables + full_rotation_offset = 0; return angle_offset; } // set absoule zero angle as zero angle @@ -74,6 +93,9 @@ float MagneticSensor::initAbsoluteZero(){ float rotation = -(int)zero_offset; // init absolute zero zero_offset = 0; + + // angle tracking variables + full_rotation_offset = 0; // return offset in radians return rotation / (float)cpr * _2PI; } diff --git a/arduino_foc_minimal/MagneticSensor.h b/arduino_foc_minimal/MagneticSensor.h index 532bd628..600c0880 100644 --- a/arduino_foc_minimal/MagneticSensor.h +++ b/arduino_foc_minimal/MagneticSensor.h @@ -56,6 +56,9 @@ class MagneticSensor: public Sensor{ // funciton getting current register value int getRawCount(); + // total angle tracking variables + float full_rotation_offset; + float angle_data_prev; // impulse cpr float cpr; // velocity calculation variables From 97aa77d7a7f135784bdcbcebad665fa54f131ca9 Mon Sep 17 00:00:00 2001 From: askuric Date: Fri, 1 May 2020 17:24:52 +0200 Subject: [PATCH 31/65] addapted ino file --- arduino_foc_minimal/arduino_foc_minimal.ino | 136 +++++++++++++------- 1 file changed, 93 insertions(+), 43 deletions(-) diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index 3dbbee30..b733c32a 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -1,5 +1,5 @@ #include "SimpleFOC.h" - +// software interrupt library #include #include @@ -7,7 +7,7 @@ // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); +BLDCMotor motor = BLDCMotor(9, 10, 11, 14); // // MagneticSensor(int cs, float _cpr, int _angle_register) // // cs - SPI chip select pin @@ -16,30 +16,27 @@ BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); // MagneticSensor AS5x4x = MagneticSensor(10, 16384, 0x3FFF); -Encoder encoder = Encoder(2, 3, 8192, 4); +Encoder encoder = Encoder(A0, A1, 2048); +// interrupt ruotine intialisation void doA(){encoder.handleA();} void doB(){encoder.handleB();} -void doIndex(){encoder.handleIndex();} -// software interrupt init -PciListenerImp listenerIndex(encoder.index_pin, doIndex); +// encoder interrupt init +PciListenerImp listenerA(encoder.pinA, doA); +PciListenerImp listenerB(encoder.pinB, doB); void setup() { // debugging port Serial.begin(115200); - // // initialise magnetic sensor hardware + // initialise magnetic sensor hardware // AS5x4x.init(); - - encoder.quadrature = Quadrature::ENABLE; - encoder.pullup = Pullup::EXTERN; - - // init encoder encoder.init(); - // enable hardware interrupts - encoder.enableInterrupts(doA, doB); - // enable software interrupts - PciManager.registerListener(&listenerIndex); + // encoder.enableInterrupts(doA,doB); + + // interrupt intitialisation + PciManager.registerListener(&listenerA); + PciManager.registerListener(&listenerB); // power supply voltage // default 12V @@ -48,23 +45,31 @@ void setup() { // set control loop type to be used // ControlType::voltage // ControlType::velocity - // ControlType::velocity_ultra_slow // ControlType::angle - motor.controller = ControlType::velocity; + motor.controller = ControlType::angle; // contoller configuration based on the controll type // velocity PI controller parameters - // default K=1.0 Ti = 0.003 - motor.PI_velocity.K = 0.3; - motor.PI_velocity.Ti = 0.003; + motor.PI_velocity.P = 0.2; + motor.PI_velocity.I = 20; //defualt voltage_power_supply/2 motor.PI_velocity.voltage_limit = 6; // jerk control using voltage voltage ramp // default value is 300 volts per sec ~ 0.3V per millisecond - motor.PI_velocity.voltage_ramp = 300; + motor.PI_velocity.voltage_ramp = 1000; + + // velocity low pass filtering + // default 10ms - try different values to see what is the best. + // the lower the less filtered + motor.LPF_velocity.Tf = 0.0; + + // angle loop controller + motor.P_angle.P = 3; + motor.P_angle.velocity_limit = 10; // link the motor to the sensor + // motor.linkSensor(&AS5x4x); motor.linkSensor(&encoder); // use debugging with serial for motor init @@ -76,47 +81,46 @@ void setup() { // align encoder and start FOC motor.initFOC(); - Serial.println("Motor ready."); - Serial.println("Input the new target velocity:"); + Serial.println("Motor ready.\n"); + Serial.println("Update all the PI contorller paramters from the serial temrinal:"); + Serial.println("- Type P100.2 to you the PI_velocity.P in 100.2"); + Serial.println("- Type I72.32 to you the PI_velocity.I in 72.32\n"); + Serial.println("Update the time constant of the velocity filter:"); + Serial.println("- Type F0.03 to you the LPF_velocity.Tf in 0.03\n"); + Serial.println("Check the loop executoion time (average):"); + Serial.println("- Type T\n"); _delay(1000); } // target velocity variable float target_velocity = 0; +// loop stats variables +unsigned long t = 0; +long timestamp = _micros(); void loop() { - // iterative state calculation calculating angle - // and setting FOC pahse voltage - // the faster you run this funciton the better - // in arduino loop it should have ~1kHz - // the best would be to be in ~10kHz range + // iterative setting FOC pahse voltage motor.loopFOC(); // iterative function setting the outter loop target // velocity, position or voltage - // this funciton can be run at much lower frequency than loopFOC funciton - // it can go as low as ~50Hz motor.move(target_velocity); - // function intended to be used with serial plotter to monitor motor variables - // significantly slowing the execution down!!!! - //motor_monitor(); + // keep track of loop number + t++; } // utility function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! void motor_monitor() { switch (motor.controller) { - case ControlType::velocity_ultra_slow: case ControlType::velocity: Serial.print(motor.voltage_q); Serial.print("\t"); Serial.print(motor.shaft_velocity_sp); Serial.print("\t"); - Serial.print(motor.shaft_velocity); - Serial.print("\t"); - Serial.println(motor.shaft_angle); + Serial.println(motor.shaft_velocity); break; case ControlType::angle: Serial.print(motor.voltage_q); @@ -147,12 +151,58 @@ void serialEvent() { // if the incoming character is a newline // end of input if (inChar == '\n') { - target_velocity = inputString.toFloat(); - Serial.print("Tagret Velocity: "); - Serial.println(target_velocity); + if(inputString.charAt(0) == 'P'){ + motor.PI_velocity.P = inputString.substring(1).toFloat(); + Serial.print("PI velocity P: "); + Serial.print(motor.PI_velocity.P); + Serial.print(",\t I: "); + Serial.print(motor.PI_velocity.I); + Serial.print(",\t Low passs filter Tf: "); + Serial.println(motor.LPF_velocity.Tf); + }else if(inputString.charAt(0) == 'I'){ + motor.PI_velocity.I = inputString.substring(1).toFloat(); + Serial.print("PI velocity P: "); + Serial.print(motor.PI_velocity.P); + Serial.print(",\t I: "); + Serial.print(motor.PI_velocity.I); + Serial.print(",\t Low passs filter Tf: "); + Serial.println(motor.LPF_velocity.Tf); + }else if(inputString.charAt(0) == 'F'){ + motor.LPF_velocity.Tf = inputString.substring(1).toFloat(); + Serial.print("PI velocity P: "); + Serial.print(motor.PI_velocity.P); + Serial.print(",\t I: "); + Serial.print(motor.PI_velocity.I); + Serial.print(",\t Low passs filter Tf: "); + Serial.println(motor.LPF_velocity.Tf); + }else if(inputString.charAt(0) == 'T'){ + Serial.print("Average loop time is (microseconds): "); + Serial.println((_micros() - timestamp)/t); + t = 0; + timestamp = _micros(); + }else if(inputString.charAt(0) == 'C'){ + Serial.print("Contoller type: "); + int cnt = inputString.substring(1).toFloat(); + if(cnt == 0){ + Serial.println("angle!"); + motor.controller = ControlType::angle; + }else if(cnt == 1){ + Serial.println("velocity!"); + motor.controller = ControlType::velocity; + }else if(cnt == 2){ + Serial.println("volatge!"); + motor.controller = ControlType::voltage; + } + Serial.println(); + t = 0; + timestamp = _micros(); + }else{ + target_velocity = inputString.toFloat(); + Serial.print("Tagret Velocity: "); + Serial.println(target_velocity); + inputString = ""; + } inputString = ""; } } } - - From ebeea8da6a652d2a3ddde66004a9ec26d389dee1 Mon Sep 17 00:00:00 2001 From: askuric Date: Fri, 1 May 2020 18:55:36 +0200 Subject: [PATCH 32/65] FIX better explanation of the usage in the serial terminal --- arduino_foc_minimal/arduino_foc_minimal.ino | 36 ++++++++++++++------- 1 file changed, 24 insertions(+), 12 deletions(-) diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index b733c32a..43fa21dd 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -7,7 +7,7 @@ // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 14); +BLDCMotor motor = BLDCMotor(9, 10, 11, 11); // // MagneticSensor(int cs, float _cpr, int _angle_register) // // cs - SPI chip select pin @@ -16,14 +16,14 @@ BLDCMotor motor = BLDCMotor(9, 10, 11, 14); // MagneticSensor AS5x4x = MagneticSensor(10, 16384, 0x3FFF); -Encoder encoder = Encoder(A0, A1, 2048); +Encoder encoder = Encoder(2, 3, 8192); // interrupt ruotine intialisation void doA(){encoder.handleA();} void doB(){encoder.handleB();} -// encoder interrupt init -PciListenerImp listenerA(encoder.pinA, doA); -PciListenerImp listenerB(encoder.pinB, doB); +// // encoder interrupt init +// PciListenerImp listenerA(encoder.pinA, doA); +// PciListenerImp listenerB(encoder.pinB, doB); void setup() { // debugging port @@ -32,11 +32,11 @@ void setup() { // initialise magnetic sensor hardware // AS5x4x.init(); encoder.init(); - // encoder.enableInterrupts(doA,doB); + encoder.enableInterrupts(doA,doB); - // interrupt intitialisation - PciManager.registerListener(&listenerA); - PciManager.registerListener(&listenerB); + // // interrupt intitialisation + // PciManager.registerListener(&listenerA); + // PciManager.registerListener(&listenerB); // power supply voltage // default 12V @@ -89,6 +89,18 @@ void setup() { Serial.println("- Type F0.03 to you the LPF_velocity.Tf in 0.03\n"); Serial.println("Check the loop executoion time (average):"); Serial.println("- Type T\n"); + Serial.println("Change control loop type by typing:"); + Serial.println("- C0 - angle contro"); + Serial.println("- C1 - velocity control"); + Serial.println("- C2 - voltage control\n"); + Serial.println("Initial parameters:"); + Serial.print("PI velocity P: "); + Serial.print(motor.PI_velocity.P); + Serial.print(",\t I: "); + Serial.print(motor.PI_velocity.I); + Serial.print(",\t Low passs filter Tf: "); + Serial.println(motor.LPF_velocity.Tf,4); + _delay(1000); } @@ -158,7 +170,7 @@ void serialEvent() { Serial.print(",\t I: "); Serial.print(motor.PI_velocity.I); Serial.print(",\t Low passs filter Tf: "); - Serial.println(motor.LPF_velocity.Tf); + Serial.println(motor.LPF_velocity.Tf,4); }else if(inputString.charAt(0) == 'I'){ motor.PI_velocity.I = inputString.substring(1).toFloat(); Serial.print("PI velocity P: "); @@ -166,7 +178,7 @@ void serialEvent() { Serial.print(",\t I: "); Serial.print(motor.PI_velocity.I); Serial.print(",\t Low passs filter Tf: "); - Serial.println(motor.LPF_velocity.Tf); + Serial.println(motor.LPF_velocity.Tf,4); }else if(inputString.charAt(0) == 'F'){ motor.LPF_velocity.Tf = inputString.substring(1).toFloat(); Serial.print("PI velocity P: "); @@ -174,7 +186,7 @@ void serialEvent() { Serial.print(",\t I: "); Serial.print(motor.PI_velocity.I); Serial.print(",\t Low passs filter Tf: "); - Serial.println(motor.LPF_velocity.Tf); + Serial.println(motor.LPF_velocity.Tf,4); }else if(inputString.charAt(0) == 'T'){ Serial.print("Average loop time is (microseconds): "); Serial.println((_micros() - timestamp)/t); From a24cbe0d638028615c38fe9ceeaf8fa1009fb0b6 Mon Sep 17 00:00:00 2001 From: askuric Date: Fri, 1 May 2020 19:47:45 +0200 Subject: [PATCH 33/65] typos and SPI freq to 10Mhz --- arduino_foc_minimal/MagneticSensor.cpp | 4 +- arduino_foc_minimal/arduino_foc_minimal.ino | 44 ++++++++++----------- 2 files changed, 24 insertions(+), 24 deletions(-) diff --git a/arduino_foc_minimal/MagneticSensor.cpp b/arduino_foc_minimal/MagneticSensor.cpp index 66dc85ac..1812b369 100644 --- a/arduino_foc_minimal/MagneticSensor.cpp +++ b/arduino_foc_minimal/MagneticSensor.cpp @@ -17,8 +17,8 @@ MagneticSensor::MagneticSensor(int cs, float _cpr, int _angle_register){ void MagneticSensor::init(){ - // 1MHz clock (AMS should be able to accept up to 10MHz) - settings = SPISettings(1000000, MSBFIRST, SPI_MODE1); + // 10MHz clock (AMS should be able to accept up to 10MHz) + settings = SPISettings(10000000, MSBFIRST, SPI_MODE1); //setup pins pinMode(chip_select_pin, OUTPUT); diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index 43fa21dd..8f63261f 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -9,17 +9,17 @@ // - enable pin - (optional input) BLDCMotor motor = BLDCMotor(9, 10, 11, 11); -// // MagneticSensor(int cs, float _cpr, int _angle_register) -// // cs - SPI chip select pin -// // _cpr - counts per revolution -// // _angle_register - (optional) angle read register - default 0x3FFF -// MagneticSensor AS5x4x = MagneticSensor(10, 16384, 0x3FFF); +// MagneticSensor(int cs, float _cpr, int _angle_register) +// cs - SPI chip select pin +// _cpr - counts per revolution +// _angle_register - (optional) angle read register - default 0x3FFF +MagneticSensor AS5x4x = MagneticSensor(10, 16384, 0x3FFF); -Encoder encoder = Encoder(2, 3, 8192); -// interrupt ruotine intialisation -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} +// Encoder encoder = Encoder(2, 3, 8192); +// // interrupt ruotine intialisation +// void doA(){encoder.handleA();} +// void doB(){encoder.handleB();} // // encoder interrupt init // PciListenerImp listenerA(encoder.pinA, doA); @@ -30,9 +30,9 @@ void setup() { Serial.begin(115200); // initialise magnetic sensor hardware - // AS5x4x.init(); - encoder.init(); - encoder.enableInterrupts(doA,doB); + AS5x4x.init(); + // encoder.init(); + // encoder.enableInterrupts(doA,doB); // // interrupt intitialisation // PciManager.registerListener(&listenerA); @@ -69,8 +69,8 @@ void setup() { // link the motor to the sensor - // motor.linkSensor(&AS5x4x); - motor.linkSensor(&encoder); + motor.linkSensor(&AS5x4x); + // motor.linkSensor(&encoder); // use debugging with serial for motor init // comment out if not needed @@ -82,15 +82,15 @@ void setup() { motor.initFOC(); Serial.println("Motor ready.\n"); - Serial.println("Update all the PI contorller paramters from the serial temrinal:"); + Serial.println("Update all the PI controller parameters from the serial terminal:"); Serial.println("- Type P100.2 to you the PI_velocity.P in 100.2"); Serial.println("- Type I72.32 to you the PI_velocity.I in 72.32\n"); Serial.println("Update the time constant of the velocity filter:"); Serial.println("- Type F0.03 to you the LPF_velocity.Tf in 0.03\n"); - Serial.println("Check the loop executoion time (average):"); + Serial.println("Check the loop execution time (average):"); Serial.println("- Type T\n"); Serial.println("Change control loop type by typing:"); - Serial.println("- C0 - angle contro"); + Serial.println("- C0 - angle control"); Serial.println("- C1 - velocity control"); Serial.println("- C2 - voltage control\n"); Serial.println("Initial parameters:"); @@ -106,7 +106,7 @@ void setup() { } // target velocity variable -float target_velocity = 0; +float target = 0; // loop stats variables unsigned long t = 0; long timestamp = _micros(); @@ -117,7 +117,7 @@ void loop() { // iterative function setting the outter loop target // velocity, position or voltage - motor.move(target_velocity); + motor.move(target); // keep track of loop number t++; @@ -209,9 +209,9 @@ void serialEvent() { t = 0; timestamp = _micros(); }else{ - target_velocity = inputString.toFloat(); - Serial.print("Tagret Velocity: "); - Serial.println(target_velocity); + target = inputString.toFloat(); + Serial.print("Target : "); + Serial.println(target); inputString = ""; } inputString = ""; From 9410e1e661b149f7037a6fb8028e6c56821a9317 Mon Sep 17 00:00:00 2001 From: askuric Date: Sat, 2 May 2020 12:54:54 +0200 Subject: [PATCH 34/65] FIX too much memory for strings --- arduino_foc_minimal/BLDCMotor.cpp | 31 +++++++- arduino_foc_minimal/arduino_foc_minimal.ino | 79 +++++++-------------- 2 files changed, 53 insertions(+), 57 deletions(-) diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal/BLDCMotor.cpp index e563439c..711b0b57 100644 --- a/arduino_foc_minimal/BLDCMotor.cpp +++ b/arduino_foc_minimal/BLDCMotor.cpp @@ -259,7 +259,27 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; - + + // // determine the segment I, II, III + // if ((angle >= 0) && (angle <= _120_D2R)) { + // // section I + // Ua = Ualpha + _1_SQRT3 * Ubeta; + // Ub = _2_SQRT3 * Ubeta; + // Uc = 0; + + // } else if ((angle > _120_D2R) && (angle <= (2 * _120_D2R))) { + // // section III + // Ua = 0; + // Ub = _1_SQRT3 * Ubeta - Ualpha; + // Uc = -_1_SQRT3 * Ubeta - Ualpha; + + // } else if ((angle > (2 * _120_D2R)) && (angle <= (3 * _120_D2R))) { + // // section II + // Ua = Ualpha - _1_SQRT3 * Ubeta; + // Ub = 0; + // Uc = - _2_SQRT3 * Ubeta; + // } + // Clarke transform Ua = Ualpha; Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta; @@ -283,7 +303,14 @@ void BLDCMotor::setPwm(int pinPwm, float U) { // it can be further optimised // (example U_max = 6 > U_pwm = 127.5 + 21.25*U) int U_pwm = 127.5 * (U/U_max + 1); - + + + // float U_max = voltage_power_supply; + // // sets the voltage [0,12V(U_max)] to pwm [0,255] + // // - U_max you can set in header file - default 12V + // // - support for HMBGC controller + // int U_pwm = 255.0 * (float)U / (float)U_max; + // limit the values between 0 and 255 U_pwm = (U_pwm < 0) ? 0 : (U_pwm >= 255) ? 255 : U_pwm; diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal/arduino_foc_minimal.ino index 8f63261f..98cfbb23 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal/arduino_foc_minimal.ino @@ -1,7 +1,7 @@ #include "SimpleFOC.h" -// software interrupt library -#include -#include +// // software interrupt library +// #include +// #include // BLDCMotor( int phA, int phB, int phC, int pp, int en) // - phA, phB, phC - motor A,B,C phase pwm pins @@ -9,30 +9,27 @@ // - enable pin - (optional input) BLDCMotor motor = BLDCMotor(9, 10, 11, 11); -// MagneticSensor(int cs, float _cpr, int _angle_register) -// cs - SPI chip select pin -// _cpr - counts per revolution -// _angle_register - (optional) angle read register - default 0x3FFF -MagneticSensor AS5x4x = MagneticSensor(10, 16384, 0x3FFF); - - -// Encoder encoder = Encoder(2, 3, 8192); -// // interrupt ruotine intialisation +//Encoder sensor = Encoder(2, 3, 2048); +// interrupt ruotine intialisation // void doA(){encoder.handleA();} // void doB(){encoder.handleB();} -// // encoder interrupt init +// encoder interrupt init // PciListenerImp listenerA(encoder.pinA, doA); // PciListenerImp listenerB(encoder.pinB, doB); + +MagneticSensor sensor = MagneticSensor(10,16384); + void setup() { // debugging port Serial.begin(115200); + //as5047.init(); + // initialise magnetic sensor hardware - AS5x4x.init(); - // encoder.init(); - // encoder.enableInterrupts(doA,doB); + sensor.init(); + //encoder.enableInterrupts(doA,doB); // // interrupt intitialisation // PciManager.registerListener(&listenerA); @@ -69,8 +66,9 @@ void setup() { // link the motor to the sensor - motor.linkSensor(&AS5x4x); - // motor.linkSensor(&encoder); + motor.linkSensor(&sensor); + // motor.linkSensor(&as5047); + // use debugging with serial for motor init // comment out if not needed @@ -81,15 +79,15 @@ void setup() { // align encoder and start FOC motor.initFOC(); - Serial.println("Motor ready.\n"); - Serial.println("Update all the PI controller parameters from the serial terminal:"); - Serial.println("- Type P100.2 to you the PI_velocity.P in 100.2"); - Serial.println("- Type I72.32 to you the PI_velocity.I in 72.32\n"); - Serial.println("Update the time constant of the velocity filter:"); - Serial.println("- Type F0.03 to you the LPF_velocity.Tf in 0.03\n"); - Serial.println("Check the loop execution time (average):"); + Serial.println("\n\n"); + Serial.println("PI controller parameters change:"); + Serial.println("- P value : Prefix P (ex. P0.1)"); + Serial.println("- I value : Prefix I (ex. I0.1)\n"); + Serial.println("Velocity filter:"); + Serial.println("- Tf value : Prefix F (ex. F0.001)\n"); + Serial.println("Average loop execution time:"); Serial.println("- Type T\n"); - Serial.println("Change control loop type by typing:"); + Serial.println("Control loop type:"); Serial.println("- C0 - angle control"); Serial.println("- C1 - velocity control"); Serial.println("- C2 - voltage control\n"); @@ -102,7 +100,6 @@ void setup() { Serial.println(motor.LPF_velocity.Tf,4); _delay(1000); - } // target velocity variable @@ -123,34 +120,6 @@ void loop() { t++; } -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void motor_monitor() { - switch (motor.controller) { - case ControlType::velocity: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_velocity_sp); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - case ControlType::angle: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_angle_sp); - Serial.print("\t"); - Serial.println(motor.shaft_angle); - break; - case ControlType::voltage: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_angle); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); - break; - } -} - // Serial communication callback void serialEvent() { // a string to hold incoming data From d7e0ccc79d9b611326827dcd008da4825948f226 Mon Sep 17 00:00:00 2001 From: askuric Date: Sat, 2 May 2020 19:11:37 +0200 Subject: [PATCH 35/65] FEAT separated minimal arudino example magnetic and encoder --- README.md | 534 ++++++++++++------ .../BLDCMotor.cpp | 0 .../BLDCMotor.h | 2 - .../Encoder.cpp | 0 .../Encoder.h | 0 .../FOCutils.cpp | 0 .../FOCutils.h | 0 .../Sensor.h | 0 arduino_foc_minimal_encoder/SimpleFOC.h | 9 + .../arduino_foc_minimal_encoder.ino | 175 ++++++ arduino_foc_minimal_magnetic/BLDCMotor.cpp | 382 +++++++++++++ arduino_foc_minimal_magnetic/BLDCMotor.h | 173 ++++++ arduino_foc_minimal_magnetic/FOCutils.cpp | 84 +++ arduino_foc_minimal_magnetic/FOCutils.h | 38 ++ .../MagneticSensor.cpp | 0 .../MagneticSensor.h | 0 arduino_foc_minimal_magnetic/Sensor.h | 29 + .../SimpleFOC.h | 1 - .../arduino_foc_minimal_magnetic.ino | 31 +- 19 files changed, 1248 insertions(+), 210 deletions(-) rename {arduino_foc_minimal => arduino_foc_minimal_encoder}/BLDCMotor.cpp (100%) rename {arduino_foc_minimal => arduino_foc_minimal_encoder}/BLDCMotor.h (98%) rename {arduino_foc_minimal => arduino_foc_minimal_encoder}/Encoder.cpp (100%) rename {arduino_foc_minimal => arduino_foc_minimal_encoder}/Encoder.h (100%) rename {arduino_foc_minimal => arduino_foc_minimal_encoder}/FOCutils.cpp (100%) rename {arduino_foc_minimal => arduino_foc_minimal_encoder}/FOCutils.h (100%) rename {arduino_foc_minimal => arduino_foc_minimal_encoder}/Sensor.h (100%) create mode 100644 arduino_foc_minimal_encoder/SimpleFOC.h create mode 100644 arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino create mode 100644 arduino_foc_minimal_magnetic/BLDCMotor.cpp create mode 100644 arduino_foc_minimal_magnetic/BLDCMotor.h create mode 100644 arduino_foc_minimal_magnetic/FOCutils.cpp create mode 100644 arduino_foc_minimal_magnetic/FOCutils.h rename {arduino_foc_minimal => arduino_foc_minimal_magnetic}/MagneticSensor.cpp (100%) rename {arduino_foc_minimal => arduino_foc_minimal_magnetic}/MagneticSensor.h (100%) create mode 100644 arduino_foc_minimal_magnetic/Sensor.h rename {arduino_foc_minimal => arduino_foc_minimal_magnetic}/SimpleFOC.h (87%) rename arduino_foc_minimal/arduino_foc_minimal.ino => arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino (89%) diff --git a/README.md b/README.md index 75be84d4..f939f01d 100644 --- a/README.md +++ b/README.md @@ -13,25 +13,26 @@ Branch | Description | Status [dev](https://github.com/askuric/Arduino-FOC/tree/dev) | Developement library version | ![Library Dev Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Dev%20Compile/badge.svg?branch=dev) [minimal](https://github.com/askuric/Arduino-FOC/tree/minimal) | Minimal Arduino example with integrated library | ![MinimalBuild](https://github.com/askuric/Arduino-FOC/workflows/MinimalBuild/badge.svg?branch=minimal) - # Contents + +# Contents - [Installation](#arduino-simple-foc-instalation) - - [Installing the full library](#installing-simple-foc-full-library) - - [Installing the minimal Arduino example](#download-minimal-simple-foc-arduino-example) + - [Installing the full Arduino Simple FOC library](#installing-simple-foc-full-library) + - [Installing the minimal Arduino example](#download-simple-foc-arduino-minimal-example) - [Electrical connecitons and schematic](#electrical-connections) - - [Minimal setup](#all-you-need-for-this-project-is-an-exaple-in-brackets) - - [Arduino Simple FOC Shield V1.2](#arduino-simple-foc-shield-v12) - - [Arduino UNO + L6234 driver](#arduino-uno--l6234-breakout-broad) + - [Minimal setup](#all-you-need-for-this-project) + - [Arduino Simple FOC Shield](#arduino-simple-foc-shield) + - [Arduino UNO + L6234 driver](#arduino-uno-l6234-driver) - [HMBGC gimbal contorller example](#hmbgc-v22) - [Code explanation and examples](#arduino-simple-foc-library-code) - [Encoder setup](#encoder-setup) + - [Magentic sensor setup](#magnetic-sensor-setup) - [BLDC motor setup](#motor-setup) - [Control loop setup](#control-loop-setup) - [Voltage control loop](#voltage-control-loop) - [Velcoity control loop](#velocity-control-loop) - [Angle control loop](#angle-control-loop) - - [Utra Slow Velocity control loop](#ultra-slow-velocity-control-loop) - [Debugging practice](#debugging) - - [Future work and work in progress](#future-work-roadmap) +- [Future work and work in progress](#work-roadmap) - [Contact](#contact) @@ -53,7 +54,7 @@ If you don't want to use the Arduino IDE and Library manager you can direclty do ``` Now reopen your Arduino IDE and you should have the library examples in `File > Examples > Simple FOC`. -## Download minimal Simple FOC Arduino example +## Download Simple FOC Arduino minimal example To download the minmial verison of Simple FOC intended for those willing to experiment and extend the code I suggest using this version over the full library. This code is completely indepenedet and you can run it as any other Arduino Schetch without the need for any libraries. The code is place in the [minimal branch](https://github.com/askuric/Arduino-FOC/tree/minimal). @@ -67,21 +68,53 @@ The code is place in the [minimal branch](https://github.com/askuric/Arduino-FOC ``` Then you just open it with the Arduino IDE and run it. - - # Electrical connections -### All you need for this project is (an exaple in brackets): - - Brushless DC motor - 3 pahse (IPower GBM4198H-120T [Ebay](https://www.ebay.com/itm/iPower-Gimbal-Brushless-Motor-GBM4108H-120T-for-5N-7N-GH2-ILDC-Aerial-photo-FPV/252025852824?hash=item3aade95398:g:q94AAOSwPcVVo571:rk:2:pf:1&frcectupt=true)) - - Encoder - - Incremental 2400cpr [Ebay](https://www.ebay.com/itm/600P-R-Photoelectric-Incremental-Rotary-Encoder-5V-24V-AB-2-Phases-Shaft-6mm-New/173145939999?epid=19011022356&hash=item28504d601f:g:PZsAAOSwdx1aKQU-:rk:1:pf:1) - - Magnetic 14bit [Aliexpress](https://fr.aliexpress.com/item/4000034013999.html?spm=a2g0o.productlist.0.0.4a7f5c25mYwpN3&algo_pvid=8f452506-7081-4d0a-8f66-d0b725d6de66&algo_expid=8f452506-7081-4d0a-8f66-d0b725d6de66-0&btsid=0b0a0ad815873142372227604ed134&ws_ab_test=searchweb0_0,searchweb201602_,searchweb201603_) -- BLDC motor driver - - L6234 driver [Drotek](https://store-drotek.com/212-brushless-gimbal-controller-l6234.html), [Ebay](https://www.ebay.fr/itm/L6234-Breakout-Board-/153204519965) - - Alternatively the library supports the arduino based gimbal controllers such as: HMBGC V2.2 ([Ebay](https://www.ebay.com/itm/HMBGC-V2-0-3-Axle-Gimbal-Controller-Control-Plate-Board-Module-with-Sensor/351497840990?hash=item51d6e7695e:g:BAsAAOSw0QFXBxrZ:rk:1:pf:1)) - - -## Arduino Simple FOC Shield V1.2 +## All you need for this project +All you need for this project is: +- Brushless DC (BLDC) motor +- BLDC driver +- Position sensor +- Arduino +### BLDC motor +This library is compatible with any 3 phase BLDC motor out there. Feel free to choose anything that suites your applications. The most tests have been done using gimbal morots (up to 2A). +Examples: +- IPower GBM4198H-120T [Ebay](https://www.ebay.com/itm/iPower-Gimbal-Brushless-Motor-GBM4108H-120T-for-5N-7N-GH2-ILDC-Aerial-photo-FPV/252025852824?hash=item3aade95398:g:q94AAOSwPcVVo571:rk:2:pf:1&frcectupt=true) +- GARTT ML5010 300KV [Ebay](https://www.ebay.com/itm/GARTT-ML5010-300KV-Brushless-Motor-For-T960-T810-RC-Multirotor-Quadcopter-MT-092/302082779179?hash=item465589682b:g:h00AAOSwmfhX44X2) +### BLDC motor driver +This library will be compatible with the most of the 3 phase bldc motor dirvers. Such as L6234, DRV8305 or L293. +Examples: +- L6234 driver [Drotek](https://store-drotek.com/212-brushless-gimbal-controller-l6234.html), [Ebay](https://www.ebay.fr/itm/L6234-Breakout-Board-/153204519965) +- Alternatively the library supports the arduino based gimbal controllers such as: HMBGC V2.2 ([Ebay](https://www.ebay.com/itm/HMBGC-V2-0-3-Axle-Gimbal-Controller-Control-Plate-Board-Module-with-Sensor/351497840990?hash=item51d6e7695e:g:BAsAAOSw0QFXBxrZ:rk:1:pf:1)) +- [Arduino Simple FOC shield](#arduino-simple-foc-shield-v12) + +### Position sensor +This library supports two types of position sensors: Encoder and Magnetic sensor. +#### Encoders +Encoders are by far most popular position sensors, both in industry and in hobby community. The main benefits are the precision, standardisation and very low noise level. The main problem with encoders is the efficiency. + +Examples: +- Optical Encoder + - 2400cpr | ~10$ [Ebay](https://www.ebay.com/itm/600P-R-Photoelectric-Incremental-Rotary-Encoder-5V-24V-AB-2-Phases-Shaft-6mm-New/173145939999?epid=19011022356&hash=item28504d601f:g:PZsAAOSwdx1aKQU-:rk:1:pf:1) + - 490-AMT103-V | 8192cpr | ~30$ [Mouser](https://www.mouser.fr/ProductDetail/CUI-Devices/AMT103-V?qs=%2Fha2pyFaduiAsBlScvLoAWHUnKz39jAIpNPVt58AQ0PVb84dpbt53g%3D%3D) +- Magnetic Encoders + - AS5047 | 16384cpr | ~15$ [Mouser](https://www.mouser.fr/ProductDetail/ams/AS5X47U-TS_EK_AB?qs=sGAEpiMZZMve4%2FbfQkoj%252BBDLPCj82ZLyYIPEtADg0FE%3D) [Youtube](https://www.youtube.com/watch?v=Gl-DiOqXXJ8) + +#### Magnetic sensors | SPI interface +Magentic position sensor has many benefits over the encoders: +- Very efficient position calculation ( no counting ) +- Time of execution doesn't depend on velocity or number of sensors +- No need for interrupt hardware +- Absolute position value +- Very low price +- Very simple to mount + +Examples: + - AS5048 | 16384cpr | ~15$ [Aliexpress](https://fr.aliexpress.com/item/4000034013999.html?spm=a2g0o.productlist.0.0.4a7f5c25mYwpN3&algo_pvid=8f452506-7081-4d0a-8f66-d0b725d6de66&algo_expid=8f452506-7081-4d0a-8f66-d0b725d6de66-0&btsid=0b0a0ad815873142372227604ed134&ws_ab_test=searchweb0_0,searchweb201602_,searchweb201603_) + - AS5047 | 16384cpr | ~15$ [Mouser](https://www.mouser.fr/ProductDetail/ams/AS5X47U-TS_EK_AB?qs=sGAEpiMZZMve4%2FbfQkoj%252BBDLPCj82ZLyYIPEtADg0FE%3D) [Youtube](https://www.youtube.com/watch?v=Gl-DiOqXXJ8) + + +## Arduino Simple FOC Shield At this moment we are developing an open source version of Arduin shiled specifically for FOC motor control. We already have prototypes of the board and we are in the testing phase. We will be coming out with the details very soon! @@ -90,32 +123,56 @@ We already have prototypes of the board and we are in the testing phase. We will - Plug and play capability with the Arduino Simple FOC library - Price in the range of \$20-\$40 - Gerber files and BOM available Open Source +- Stackable: running at least 2 motors in the same time ***Let me know if you are interested! antun.skuric@outlook.com*** You can explore the [3D model of the board in the PDF form](https://raw.githubusercontent.com/askuric/Arduino-FOC/master/extras/ArduinoFOCShieldV12.pdf). - +

+

+#### Connection example +

+ + +

-## Arduino UNO + L6234 breakout broad +## Arduino UNO + L6234 driver The code is simple enough to be run on Arudino Uno board. - +### Encoder as position sensor

+

-### Encoder +#### Encoder - Encoder channels `A` and `B` are connected to the Arduino's external intrrupt pins `2` and `3`. - Optionally if your encoder has `index` signal you can connect it to any available pin, figure shows pin `4`. - - If you can choose preferably connect it to an `A0-A5` due to the interrupt rutine, it will have better performance (but any other pin will work as well). -### L6234 breakout board + - For Arudino UNO and similar broads which dont have 3 hardware interrupts, if you can choose, preferably connect index pin to pins `A0-A5` due to the interrupt rutine, it will have better performance (but any other pin will work as well). + - Othervise if you are using different board and have 3 hardware interrupt pins connect the index pin to one of them. +#### L6234 breakout board - Connected to the arduino pins `9`,`10` and `11` (you can use also pins `5` and `6`). - Additionally you can connect the `enable` pin to the any digital pin of the arduino the picture shows pin `8` but this is optional. You can connect the driver enable directly to 5v. - Make sure you connect the common ground of the power supply and your Arduino -### Motor +#### Motor - Motor phases `a`, `b` and `c` are connected directly to the driver outputs +- Motor phases `a`,`b`,`c` and encoder channels `A` and `B` have to be oriented right for the algorightm to work. But don't worry about it too much. Connect it in initialy as you wish and then if it doesnt move reverse pahse `a` and `b` of the motor, that should be enogh. +### Magentic sensor as position sensor +

+ +

-Motor phases `a`,`b`,`c` and encoder channels `A` and `B` have to be oriented right for the algorightm to work. But don't worry about it too much. Connect it in initialy as you wish and then if it doesnt move reverse pahse `a` and `b` of the motor, that should be enogh. +#### Magnetic sensor +- Magnetic sensors SPI interface singals `SCK`, `MISO` and `MOSI` are connected to the Arduino's `SPI` pins (Arduino UNO `13`,`12` and `11`). + - If the application requires more than one sensor all of them are connected to the same pins of theArudino. +- The `chip select` pin is connected to the desired pin. Each sensor connected to the same Arduino has to have unique chip select pin. +#### L6234 breakout board +- Connected to the arduino pins `3`,`5` and `6` (you can use also pin `9` and `10`, pin `11` is taken by the SPI interface). +- Additionally you can connect the `enable` pin to the any digital pin of the arduino the picture shows pin `2` but this is optional. You can connect the driver enable directly to 5v. +- Make sure you connect the common ground of the power supply and your Arduino +#### Motor +- Motor phases `a`, `b` and `c` are connected directly to the driver outputs +- Motor phases `a`,`b`,`c` and the magnetic sensor counting direciton have to be oriented right for the algorightm to work. But don't worry about it too much. Connect it initialy as you wish and then if the motor locks in place inverse `a` and `b` line of the motor. ## HMBGC V2.2 @@ -123,7 +180,7 @@ To use HMBGC controller for vector control (FOC) you need to connect motor to on

- +

@@ -134,13 +191,12 @@ Since HMBGC doesn't have acces to the arduinos external interrupt pins `2` and ` - Optionally if your encoder has `index` signal you can connect it to any available pin, figure shows pin `A2`. ### Motor - Motor phases `a`,`b` and `c` are connected directly to the driver outputs +- Motor phases `a`,`b`,`c` and encoder channels `A` and `B` have to be oriented right for the algorightm to work. But don't worry about it too much. Connect it in initialy as you wish and then if it doesnt move reverse pahse `a` and `b` of the motor, that should be enogh. -Motor phases `a`,`b`,`c` and encoder channels `A` and `B` have to be oriented right for the algorightm to work. But don't worry about it too much. Connect it in initialy as you wish and then if it doesnt move reverse pahse `a` and `b` of the motor, that should be enogh. - - +> HMBGC board doesn't support magnetic sensors because it doesn't have necessary SPI infrastructure. # Arduino Simple FOC library code -The code is organised into a library. The library contains two classes `BLDCmotor` and `Endcoder`. `BLDCmotor` contains all the necessary FOC algorithm funcitons as well as PI controllers for the velocity and angle control. `Encoder` deals with the encoder interupt funcitons, calcualtes motor angle and velocity ( using the [Mixed Time Frequency Method](https://github.com/askuric/Arduino-Mixed-Time-Frequency-Method)). The `Encoder` class will support any type of otpical and magnetic encoder. +The code is organised into a library. The library contains main BLDC motor class `BLDCmotor` and two sensor classes `Endcoder` and `MagneticSensor`. `BLDCmotor` contains all the necessary FOC algorithm funcitons as well as PI controllers for the velocity and angle control. `Encoder` deals with the encoder interupt funcitons, calcualtes motor angle and velocity ( using the [Mixed Time Frequency Method](https://github.com/askuric/Arduino-Mixed-Time-Frequency-Method)). The `Encoder` class will support any type of otpical and magnetic encoder. `MagneticEncoder` class deals with all the necessary communication and calculation infrastructure to handle the magnetic position sensors such as AS5048 and similar. ## Encoder setup To initialise the encoder you need to provide the encoder `A` and `B` channel pins, encoder `PPR` and optionally `index` pin. @@ -173,7 +229,7 @@ There are two ways you can run encoders with Simple FOC libtrary. > Using the hardware external interrupts usualy results in a bit better and more realible performance but software interrupts will work very good as well. #### Arduino Hardware external interrupt -Arduino hadrware external interrupt pins are pin `2` and `3`. And in order to use its functionallities the encoder channels `A` and `B` will have to be connected exacly on these pins. +Arduino UNO has two hadrware external interrupt pins, pin `2` and `3`. And in order to use its functionallities the encoder channels `A` and `B` will have to be connected exacly on these pins. Simple FOC `Encoder` class already has implemented initialisation and encoder `A` and `B` channel callbacks. All you need to do is define two funcitons `doA()` and `doB()`, the buffering functions of encoder callback funcitons `encoder.handleA()` and `encoder.handleB()`. @@ -182,10 +238,10 @@ All you need to do is define two funcitons `doA()` and `doB()`, the buffering fu void doA(){encoder.handleA();} void doB(){encoder.handleB();} ``` -And supply those functions to the encoder initialiasation fucntion `encoder.init()` +And supply those functions to the encoder interrupt init fucntion `encoder.enableInterrupts()` ```cpp -// initialise encoder hardware -encoder.init(doA, doB); +// enable encoder hardware interrupts +encoder.enableInterrupts(doA, doB) ``` You can name the buffering funcitons as you wish. It is just important to supply them to the `encoder.init()` funciton. This procedure is a tradeoff in between scalability and simplicity. This allows you to have more than one encoder connected to the same arduino. All you need to do is to instantiate new `Encoder` class and create new buffer functions. For example: ```cpp @@ -200,65 +256,60 @@ void doB2(){enc2.handleB();} void setup(){ ... - enc1.init(doA1,doB1); - enc2.init(doA2,doB2); + enc1.init(); + enc1.enableInterrupts(doA1,doB1); + enc2.init(); + enc2.enableInterrupts(doA2,doB2); ... } ``` ##### Index pin configuration -In order to read index pin efficienlty Simple FOC algorithm uses Arduino interrupt routine as well. -Simple FOC has implemented the index pin callback `encoder.handleIndex()`. In order to enable the index pin utilisation just add the index pin in the encoder constructor: +In order to read index pin efficienlty Simple FOC algorithm enables you to use the same approach as for the channels `A` and `B`. First you need to provide the `Encoder` class the index pin number: ```cpp Encoder encoder = Encoder(pinA, pinB, cpr, index_pin); ``` -The library make sure to enable the propper interrupts and initialise the `pinMode` based on your [pullup configuration](#encoder-setup). - -The last peace of the index pin enabling puzzle is the Arduino's `ISR` funciton call: -```cpp -// index calback interrupt code -// please set the right PCINT(0,1,2)_vect parameter -// PCINT0_vect - index pin in between D8 and D13 -// PCINT1_vect - index pin in between A0 and A5 (recommended) -// PCINT2_vect - index pin in between D0 and D7 -ISR (PCINT1_vect) { encoder.handleIndex(); } -``` -Make sure you use the right `PCINT(1,2,3)_vect` paramereter of the `ISR` function. -`ISR` Parameter | Arduino pin ------| ----- -PCINT0_vect | D8 - D13 -PCINT1_vect | A0 - A5 -PCINT2_vect | D0 - D7 - -The `ISR` with the vector `PCINT0_vect` will be called each time one of the pins `D8-D13` changes. Each time one of the pins `A0-A5` chenges the Arduino interrupt `ISR` function with the `PCINT1_vect` will be called and finally if any one of the `D0-D7` pins changes the `ISR` function with the parameter `PCINT2_vect` will be called. So therefore it is important to use the index callback `encoder.handleIndex()` funciton in the rigth `ISR` function. -Here is an eaxmple of the setup od two encoders with different `index` locations: +If you are using Arduino board such as Arduino Mega and simialar and if you have more tha 2 hadrware interrupts you can connect your index pin to the hadrware interrupt pin (example Arduino Mega pin `21`). Your code will look like: ```cpp Encoder encoder = Encoder(2,3,600,A0); // A and B interrupt rutine -void doA1(){encoder.handleA();} -void doB1(){encoder.handleB();} -// index interrupt rutine -ISR (PCINT1_vect) { encoder.handleIndex(); } +void doA(){encoder.handleA();} +void doB(){encoder.handleB();} +void doIndex(){encoder.handleIndex();} -void setup(){...} -void loop(){...} +void setup(){ + ... + encoder.enableInterrupts(doA,doB,doIndex); + ... + } ``` -Or for example: +The function `enableInterrupts` will handle all the intialisation for you. +If yo are using Arduino UNO to run this algorithm and you do not have enough hardware interrupt pins you will need to use software interrupt library such as [PciManager library](https://github.com/prampec/arduino-pcimanager). Arduino UNO code for using an encoder with index can be: ```cpp -Encoder encoder = Encoder(2,3,600,13); +Encoder encoder = Encoder(2,3,600,A0); // A and B interrupt rutine -void doA1(){encoder.handleA();} -void doB1(){encoder.handleB();} -// index interrupt rutine -ISR (PCINT0_vect) { encoder.handleIndex(); } +void doA(){encoder.handleA();} +void doB(){encoder.handleB();} +void doIndex(){encoder.handleIndex();} -void setup(){...} -void loop(){...} +// softaware interrupt listener for index pin +PciListenerImp listenerIndex(encoder.index_pin, doIndex); + +void setup(){ + ... + // hardware interrupts for A and B + encoder.enableInterrupts(doA,doB); + // software interrupt for index + PciManager.registerListener(&listenerIndex); + ... + } ``` +The same procedure can be done for pins `A` and `B` if your application makes you run out of the hardware interrupt pins. Software interrupts are very powerfull and produce very comparable results to the hardware interupts, but in general they tend to have a bit worse performance. `index` pin produces an interrupt once per rotation, therefore it is not critical, so software or hardware interrupt doesn't change too much in terms of performance. + To explore better the encoder algorithm an example is provided `encoder_example.ino`. #### Arduino software pin change interrupt -If you are not able to access your pins `2` and `3` of your Arduino or if you want to use more than none encoder you will have to use the software interrupt approach. +If you are not able to access your pins `2` and `3` of your Arduino UNO or if you want to use more than none encoder you will have to use the software interrupt approach. I suggest using the [PciManager library](https://github.com/prampec/arduino-pcimanager). The stps of using this library in code are very similar to [harware interrupt](#arduino-hardware-external-interrupt). @@ -282,7 +333,7 @@ Then you declare listeners `PciListenerImp `: PciListenerImp listenerA(encoder.pinA, doA); PciListenerImp listenerB(encoder.pinB, doB); ``` -And finally instead of supplying the functions `doA` and `doB` to the `encoder.init()` you call the init without parameters and use `PCIManager` library to register the interrupts +Finally, after running `encoder.init()` you skip the call of the `encoder.enableInterrupts()` and call the `PCIManager` library to register the interrupts for all the encoder channels. ```cpp // initialise encoder hardware encoder.init(); @@ -349,7 +400,42 @@ void setup(){ ... } ``` +## Magnetic sensor setup +In order to use your magnetic position sensor with Simple FOC library first create an instance of the `MagneticSensor` class: +```cpp +// MagneticSensor(int cs, float _cpr, int _angle_register) +// cs - SPI chip select pin +// _cpr - counts per revolution +// _angle_register - (optional) angle read register - default 0x3FFF +MagneticSensor sensor = MagneticSensor(10, 16384, 0x3FFF); +``` +The parameters of the class is the `chip select` pin number you connected your sensor to, the range of your sensor (counter value for full rotation) and your `angle register` number telling the library which register value should it ask the sensor for in order to retrieve the angle value. The default `angle_register` number is set to `0x3FFF` as it is the angle register for most of the low cost AS5x4x sensors. + +Finally after the inialisalisation the only thing you need to do afterwards is to call the `init()` function. This function prepares the SPI interface and initialises the sensor hardware. So your magnetic sensor intialisation code will look like: +```cpp +MagneticSensor sensor = MagneticSensor(10, 16384, 0x3FFF); + +void loop(){ + ... + sensor.init(); + ... +} +``` + +If you wish to use more than one magnetic sensor, make sure you connect their `chip select` pins to different arduino pins and follow the same idea as above, here is a simple example: +```cpp +MagneticSensor sensor1 = MagneticSensor(10, 16384, 0x3FFF); +MagneticSensor sensor1 = MagneticSensor(9, 16384, 0x3FFF); +void loop(){ + ... + sensor1.init(); + sensor2.init(); + ... +} +``` + +Please check the `magnetic_sensor_only_example.ino` example to see more about it. ## Motor setup To intialise the motor you need to input the `pwm` pins, number of `pole pairs` and optionally driver `enable` pin. ```cpp @@ -361,38 +447,38 @@ BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); ``` If you are not sure what your `pole_paris` number is I included an example code to estimate your `pole_paris` number in the examples `find_pole_pairs_number.ino`. I hope it helps. -To finalise the motor setup the encoder is added to the motor and the `init` function is called. +To finalise the motor setup the sensor is added to the motor and the `init` function is called. ```cpp // link the motor to the sensor -motor.linkEncoder(&encoder); +// either Encoder class or MagenticSensor class +motor.linkSensor(&sensor); // intialise motor motor.init(); ``` ### Power supply voltage -The default `voltage_power_supply` value is set to `12V`. If you set your power supply to some other vlaue, chnage it here for the control loops to adapt. +The default `power_supply_voltage` value is set to `12V`. If you set your power supply to some other vlaue, chnage it here for the control loops to adapt. ```cpp // power supply voltage -motor.voltage_power_supply = 12; +motor.power_supply_voltage = 12; ``` -The `voltage_power_supply` value tells the FOC algorithm what is the maximum voltage it can output. Additioanlly since the FOC algotihm implemented in the Simple FOC library uses sinusoidal voltages the magnitudes of the sine waves exiting the Drvier circuit is going to be `[-voltage_power_supply/2, voltage_power_supply/2]`. +The `power_supply_voltage` value tells the FOC algorithm what is the maximum voltage it can output. Additioanlly since the FOC algotihm implemented in the Simple FOC library uses sinusoidal voltages the magnitudes of the sine waves exiting the Drvier circuit is going to be `[-power_supply_voltage/2, power_supply_voltage/2]`. + ## Control loop setup The SimpleFOC library gives you the choice of using 4 different plug and play control loops: - voltage control loop - velocity control loop - angle control loop -- ultra slow velocity control loop -You set it by changing the `motor.controller` variable. If you want to control the motor angle you will set the `controller` to `ControlType::angle`, if you seek the DC motor behavior behaviour by controlling the voltage use `ControlType::voltage`, if you wish to control motor angular velocity `ControlType::velocity`. If you wish to control velocities which are very very slow, typically around ~0.01 rad/s you can use the `ControlType::velocity_ultra_slow` controller. +You set it by changing the `motor.controller` variable. If you want to control the motor angle you will set the `controller` to `ControlType::angle`, if you seek the DC motor behavior behaviour by controlling the voltage use `ControlType::voltage`, if you wish to control motor angular velocity `ControlType::velocity`. ```cpp // set FOC loop to be used // ControlType::voltage // ControlType::velocity -// ControlType::velocity_ultra_slow // ControlType::angle motor.controller = ControlType::angle; ``` @@ -402,7 +488,7 @@ This control loop allows you to run the BLDC motor as it is simple DC motor usin // voltage control loop motor.controller = ControlType::voltage; ``` - + You rcan test this algoithm by running the example `voltage_control.ino`. The FOC algorithm reads the angle a from the motor and sets appropriate ua, ub and uc voltages such to always have 90 degree angle in between the magnetic fields of the permanent magents in rotor and the stator. What is exaclty the principle of the DC motor. @@ -416,30 +502,79 @@ This control loop allows you to spin your BLDC motor with desired velocity. Thi motor.controller = ControlType::velocity; ``` - + You can test this algorithm by running the example `velocity_control.ino`. -The velocity control is created by adding a PI velocity controller. This controller reads the motor velocity v and sets the uq voltage to the motor in a such maner that it reaches and maintains the target velocity vd, set by the user. +The velocity control is created by adding a PI velocity controller. This controller reads the motor velocity v, filteres it to vf and sets the uq voltage to the motor in a such maner that it reaches and maintains the target velocity vd, set by the user. #### PI controller parameters To change the parameters of your PI controller to reach desired behaiour you can change `motor.PI_velocity` structure: ```cpp +// contoller configuration based on the controll type // velocity PI controller parameters -// default K=0.5 Ti = 0.01 -motor.PI_velocity.K = 0.2; -motor.PI_velocity.Ti = 0.01; -motor.PI_velocity.voltage_limit = 6; +// default P=0.5 I = 10 +motor.PI_velocity.P = 0.2; +motor.PI_velocity.I = 20; +//defualt voltage_power_supply/2 +motor.PI_velocity.voltage_limit = 6; // jerk control using voltage voltage ramp // default value is 300 volts per sec ~ 0.3V per millisecond -motor.PI_velocity.voltage_ramp = 6; +motor.PI_velocity.voltage_ramp = 1000; + +// velocity low pass filtering +// default 5ms - try different values to see what is the best. +// the lower the less filtered +motor.LPF_velocity.Tf = 0.01; ``` -The parameters of the PI controller are proportional gain `K`, integral time constant `Ti`, voltage limit `voltage_limit` and `voltage_ramp`. +The parameters of the PI controller are proportional gain `P`, integral gain `I`, voltage limit `voltage_limit` and `voltage_ramp`. - The `voltage_limit` parameter is intended if, for some reason, you wish to limit the voltage that can be sent to your motor. -- In general by raising the proportional constant `K` your motor controller will be more reactive, but too much will make it unstable. -- The same goes for integral time constant `Ti` the smaller it is the faster motors reaction to disturbance will be, but too small value will make it unstable. +- In general by raising the proportional gain `P` your motor controller will be more reactive, but too much will make it unstable. Setting it to `0` will disable the proportional part of the controller. +- The same goes for integral gain `I` the higher it is the faster motors reaction to disturbance will be, but too large value will make it unstable. Setting it to `0` will disable the integral part of the controller. - The `voltage_ramp` value it intended to reduce the maximal change of the voltage value which is sent to the motor. The higher the value the PI controller will be able to change faster the Uq value. The lower the value the smaller the possible change and the less responsive your controller becomes. The value of this parameter is set to be `Volts per second[V/s` or in other words how many volts can your controller raise the voltage in one time unit. If you set your `voltage_ramp` value to `10 V/s`, and on average your contol loop will run each `1ms`. Your controller will be able to chnage the Uq value each time `10[V/s]*0.001[s] = 0.01V` waht is not a lot. +Additionally, in order to smooth out the velocity measuement Simple FOC library has implemented the velocity low pass filter. [Low pass filters](https://en.wikipedia.org/wiki/Low-pass_filter) are standard form of signal smoothing, and it only has one parameter - filtering time constant `Tf`. +- The lower the value the less influence the filter has. If you put `Tf` to `0` you basically remove the filter completely. The exact `Tf` value for specific implementation is hard guess in advance, but in general the range of values of `Tf` will be somewhere form `0` to `0.5` seconds. + +In order to get optimal performance you will have to fiddle a bit with with the parameters. :) + +#### Control theory lovers corner :D +Transfer funciton of the PI contorller this library implements is: + +

+ +Continiuos PI is discretized using Tustin transform. The final discrete equation becomes: + +

+ +Where the u(k) is the control signal (voltage Uq in our case) in moment k, e(k),e(k-1) is the tracking error in current moment k and previous step k-1. Tracking error presents the difference in between the target velocity value vd and measured velocity v. + +

+ +Transfer funciton of the Low pass filter is contorller is: + +

+In it discrete form it becomes: + +

+ +where vf(k) is filtered velocity value in moment k, v(k) is the measured velocity in the moment k, Tf is the filter time constant and Ts is the sampling time (or time in between executions of the equation). +This low pass filter can be also written in the form: + +

+ +where: + +

+ +This makes it a bit more clear what the time constat `Tf` of the Low pass filter stands for. If your sample time is around 1millisecond (for arduino UNO this can be taken as an average) then setting the +`Tf` value to `Tf = 0.01` will result in: + +```cpp +alpha = 0.01/(0.01 + 0.001) = 0.91 +``` + +Which means that your actual velocity measurement v will influence the filtered value vf with the coeficient `1-alpha = 0.09` which is going to smooth the velocity values considerably (maybe even too muuch, depends of the application). + -So in order to get optimal performance you will have to fiddle a bit with with the parameters. :) ### Angle control loop This control loop allows you to move your BLDC motor to the desired angle in real time. This mode is enabled by: @@ -448,74 +583,53 @@ This control loop allows you to move your BLDC motor to the desired angle in rea motor.controller = ControlType::angle; ``` - + You can test this algorithm by running the example `angle_control.ino`. -The angle control loop is done by adding one more control loop in cascade on the velocity control loop like showed on the figure above. The loop is closed by using simple P controller. The controller reads the angle a from the motor and determins which velocity vd the motor should move to reach desire angle ad set by the user. And then the velocity controller reads the current velocity from the motor v and sets the voltage uq that is neaded to reach the velocity vd, set by the angle loop. +The angle control loop is done by adding one more control loop in cascade on the velocity control loop like showed on the figure above. The loop is closed by using simple P controller. The controller reads the angle a from the motor and determins which velocity vd the motor should move to reach desire angle ad set by the user. And then the velocity controller reads the current filtered velocity from the motor vf and sets the voltage uq that is neaded to reach the velocity vd, set by the angle loop. #### Controller parameters To tune this control loop you can set the parameters to both angle P controller and velocity PI controller. ```cpp +// contoller configuration based on the controll type // velocity PI controller parameters -// default K=1.0 Ti = 0.003 -motor.PI_velocity.K = 0.5; -motor.PI_velocity.Ti = 0.01; +// default P=0.5 I = 10 +motor.PI_velocity.P = 0.2; +motor.PI_velocity.I = 20; +//defualt voltage_power_supply/2 motor.PI_velocity.voltage_limit = 6; // jerk control using voltage voltage ramp // default value is 300 volts per sec ~ 0.3V per millisecond -motor.PI_velocity.voltage_ramp = 6; +motor.PI_velocity.voltage_ramp = 1000; + +// velocity low pass filtering +// default 5ms - try different values to see what is the best. +// the lower the less filtered +motor.LPF_velocity.Tf = 0.01; + // angle P controller -// default K=70 -motor.P_angle.K = 20; -// maximal velocity of the poisition control +// default P=20 +motor.P_angle.P = 20; +// maximal velocity of the poisiiton control // default 20 -motor.P_angle.velocity_limit = 10; +motor.P_angle.velocity_limit = 4; ``` It is important to paramter both velocity PI and angle P controller to have the optimal performance. The velocity PI controller is parametrisized by updating the `motor.PI_velcity` structure as expalined before. -- Rough rule should be to lower the proportional gain `K` and raise time constant `Ti` in order to achieve less vibrations. +- Rough rule should be to lower the proportional gain `P` in order to achieve less vibrations. +- You probably wont have to touch the `I` value. The angle P controller can be updated by changign the `motor.P_angle` structure. -- Roughly proportional gain `K` will make it more responsive, but too high value will make it unstable. +- Roughly proportional gain `P` will make it more responsive, but too high value will make it unstable. +For the angle control you will be able to see the influence of the velocity LPF filter as well. But the `Tf` value should not change much form the velocity control. So once you have it tuned for the velocity loop you can leave it as is. + Additionally you can configure the `velocity_limit` value of the controller. This value prevents the contorller to set too high velocities $v_d$ to the motor. - If you make your `velocity_limit` very low your motor will be moving in between desired positions with exactly this velocity. If you keep it high, you will not notice that this variable even exists. :D Finally, each application is a bit different and the chances are you will have to tune the controller values a bit to reach desired behaviour. -### Ultra slow velocity control loop -This control loop allows you to spin your BLDC motor with desired velocity as well as the [velocity loop](#velocity-control-loop) but it is intended for very smooth operation in very low velocityes (< 0.1 rad/s). This mode is enabled by: -```cpp -// velocity ultra slow control loop -motor.controller = ControlType::velocity_ultra_slow; -``` - - - -You can test this algorithm by running the example `velocity_ultrasloaw_control_serial.ino` . -This type of the velocity control is nothing more but motor angle control. It works particularly well for the purposes of very slow movements because regular velocity calculation techniques are not vel suited for this application and regular [velocity control loop](#velocity-control-loop) would not work well. -The behavior is achieved by integrating the user set target velocity vd to get the necessary angle ad. And then controlling the motor angle v with high-gain PI controller. This controller reads the motor angle v and sets the uq voltage to the motor in a such maner that it closely follows the target angle ad, to achieve the velocity profile vd, set by the user. -#### PI controller parameters -To change the parameters of your PI controller to reach desired behaiour you can change `motor.PI_velocity` structure: -```cpp -// velocity PI controller parameters - // default K=120.0 Ti = 100.0 -motor.PI_velocity_ultra_slow.K = 120; -motor.PI_velocity_ultra_slow.Ti = 100; -motor.PI_velocity_ultra_slow.voltage_limit = 12; -// jerk control using voltage voltage ramp -// default value is 300 volts per sec ~ 0.3V per millisecond -motor.PI_velocity_ultra_slow.voltage_ramp = 6; -``` -The parameters of the PI controller are proportional gain `K`, integral time constant `Ti` and voltage limit `voltage_limit` which is by default set to the `voltage_power_supply/2` and `voltage_ramp`. -- The `voltage_limit` parameter is intended if some reason you wish to limit the voltage that can be sent to your motor. -- In general by raising the proportional constant `K` your motor controller will be more reactive, but too much will make it unstable. -- The same goes for integral time constant `Ti` the smaller it is the faster motors reaction to disturbance will be, but too small value will make it unstable. By defaualt the integral time constant `Ti` is set `100s`. Which means that it is extreamply slow, meaning that it is not effecting the behvior of the controlle, making it basically a P controller. -- The `voltage_ramp` value it intended to reduce the maximal change of the voltage value which is sent to the motor. The higher the value the PI controller will be able to change faster the Uq value. The lower the value the smaller the possible change and the less responsive your controller becomes. The value of this parameter is set to be `Volts per second[V/s` or in other words how many volts can your controller raise the voltage in one time unit. If you set your `voltage_ramp` value to `10 V/s`, and on average your contol loop will run each `1ms`. Your controller will be able to chnage the Uq value each time `10[V/s]*0.001[s] = 0.01V` waht is not a lot. - -From the PI controller parameters you can see that the values are much higher than in the [velocity control loop](#velocity-control-loop). The reason is because the angle control loop is not the main loop and we need it to follow the profile as good as possible as fast as possible. Therefore we need much higher gain than before. - ### Index search routine Finding the encoder index is performed only if the constructor of the `Encoder` class has been provided with the `index` pin. The search is performed by setting a constant velocity of the motor until it reaches the index pin. To set the desired searching velocity alter the paramterer: ```cpp @@ -527,12 +641,12 @@ This velocity control loop is implemented exaclty the same as [velocity control ```cpp // index search PI contoller parameters // default K=0.5 Ti = 0.01 -motor.PI_velocity_index_search.K = 0.1; -motor.PI_velocity_index_search.Ti = 0.01; +motor.PI_velocity_index_search.P = 0.1; +motor.PI_velocity_index_search.I = 0.01; motor.PI_velocity_index_search.voltage_limit = 3; // jerk control using voltage voltage ramp -// default value is 300 volts per sec ~ 0.3V per millisecond -motor.PI_velocity_index_search.voltage_ramp = 6; +// default value is 100 volts per sec ~ 0.1V per millisecond +motor.PI_velocity_index_search.voltage_ramp = 300; ``` If you are having problems during the finding procedure, try tuning the PI controller constants. The same parameters as the `PI_velocity` should work well, but you can put it a bit more conservative to avoid high jumps. @@ -568,7 +682,7 @@ The funciton `loopFOC()` gets the current motor angle from the encoder, turns in // it can go as low as ~50Hz motor.move(target); ``` -The `move()` method executes the control loops of the algorihtm. If is governed by the `motor.controller` variable. It executes eigther pure voltage loop, velocity loop, angle loop or ultra slow velocity loop. +The `move()` method executes the control loops of the algorihtm. If is governed by the `motor.controller` variable. It executes eigther pure voltage loop, velocity loop or angle loop. It receives one parameter `BLDCMotor::move(float target)` which is current user define target value. - If the user runs [velocity loop](#velocity-control-loop), `move` funciton will interpret `target` as the target velocity vd. @@ -581,59 +695,94 @@ It receives one parameter `BLDCMotor::move(float target)` which is current user ## Examples Examples folder structure -``` -├───examples -│ ├───voltage_control # example of the voltage control loop with configuraiton -│ ├───angle_control # example of angle control loop with configuraiton -│ ├───velocity_control # example of velocity control loop with configuraiton -│ ├───velocity_ultraslow_control # example of ultra slow velocity control using with configuraiton -│ ├───encoder_example # simple example of encoder usage -│ ├───minimal_example # example of code without using configuration -│ ├───HMBGC_example # example of code to be used with HMBGC controller with -│ └───find_pole_pairs_number # simple code example estimating pole pair number of the motor +```shell +│ examples +│ ├─── encoder examples # EXMAPLES OF ENCODER APPLICATIONS +│ │ ├───angle_control # example of angle control loop with configuraiton +│ │ ├───change_direction # simple motor changing velocity direction in real time +│ │ ├───encoder_example # simple example of encoder usage +│ │ ├───find_pole_pairs_number # simple code example estimating pole pair number of the motor +│ │ ├───HMBGC_example # example of code to be used with HMBGC controller with +│ │ ├───velocity_control # example of velocity control loop with configuraiton +│ │ ├───voltage_control # example of the voltage control loop with configuraiton +│ │ └───velocity_PI_tuning # code example of tuning velcity controller by using serial terminal +│ │ +│ └─── magnetic sensor examples # EXMAPLES OF MAGENETIC SENSOR APPLICATIONS AS5047/48 +│ ├───angle_control # example of angle control loop with configuraiton +│ ├───change_direction # simple motor changing velocity direction in real time +│ ├───find_pole_pairs_number # simple code example estimating pole pair number of the motor +│ ├───magnetic_sensor_only_example # simple example of magnetic sensor usage +│ ├───velocity_control # example of velocity control loop with configuraiton +│ ├───voltage_control # example of the voltage control loop with configuraiton +│ └───velocity_PI_tuning # code example of tuning velcity controller by using serial terminal +``` +## Simple FOC library source structure: +```shell +│ src +│ │ +│ ├─ SimpleFOC.h # SimpleFOC library include file +│ │ +│ ├─ BLDCMotor.cpp/h # BLDCMotor class implementing all the FOC operations +│ │ +│ ├─ Sensor.h # Abstract Sensor class that all the sensors implement +│ ├─ Encoder.cpp/h # Enocder class implementing the Quadrature encoder operations +│ ├─ MagneticSensor.cpp/h # class implementing SPI angle read and interface for AS5047/8 type sensors +│ │ +│ └─ FOCutils.cpp/h # Utility functions ``` # Debugging -To debug control loop exection in the examples we added a funciton `motor_monitor()` which log the motor variables to the serial port. The funciton logs different variables based for differenc control loops. + +`BLDCMotor` clsss supports debugging using `Serial` port which is enabled by: +```cpp +motor.useDebugging(Serial); +``` +before running `motor.init()`. +The class will output its status during the intialisation of the motor and the FOC. Enabling tyhe debugger will not directly influence the real-time performance. By default the class will stop its debugging output once it goes to the main loop. + +To debug control loop exection in the examples we added a funciton `motor.monitor()` which log the motor variables to the serial port. The funciton logs different variables based for differenc control loops. ```cpp // utility function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! -void motor_monitor() { - switch (motor.controller) { - case ControlType::velocity_ultra_slow: +void BLDCMotor::monitor() { + if(!debugger) return; + switch (controller) { case ControlType::velocity: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_velocity_sp); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); + debugger->print(voltage_q); + debugger->print("\t"); + debugger->print(shaft_velocity_sp); + debugger->print("\t"); + debugger->println(shaft_velocity); break; case ControlType::angle: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.print(motor.shaft_angle_sp); - Serial.print("\t"); - Serial.println(motor.shaft_angle); + debugger->print(voltage_q); + debugger->print("\t"); + debugger->print(shaft_angle_sp); + debugger->print("\t"); + debugger->println(shaft_angle); break; case ControlType::voltage: - Serial.print(motor.voltage_q); - Serial.print("\t"); - Serial.println(motor.shaft_velocity); + debugger->print(voltage_q); + debugger->print("\t"); + debugger->print(shaft_angle); + debugger->print("\t"); + debugger->println(shaft_velocity); break; } } ``` -This is just a template funciton to help you debug and create your own functions in future. -The funciton accesses the motor variables: +The intention of this method is to be called in main loop funciton along the `loopFOC()` and `move()` funciton. Thsi funciton is going to impaire the execution perfomance and reduce the sampling frequency so therefore take it in consideration when running the code. + +If you wish to implement you own debugging functions or just output the motor variables to the `Serial` terminal here are the public varaibles of the `BLDCMotor` class. + + ```cpp class BLDCMotor { public: ... - // current elelctrical angle - float elctric_angle; // current motor angle float shaft_angle; // current motor velocity @@ -658,28 +807,43 @@ class Encoder{ float getAngle(); } ``` -### BLDCMotor debugging -Additonally a `BLDCMotor` calss now supports debugging using `Serial` port which is enabled by: +As well as magnetic sensor's api, to get the sensor's angle and velocity. ```cpp -motor.useDebugging(Serial); -``` -before running `motor.init()`. +class MagneticSensor{ + public: + // shaft velocity getter + float getVelocity(); + // shaft angle getter + float getAngle(); +} +``` # Work Roadmap ## Future work - [ ] Proper introduction of the **Arudino FOC Shield V1.2** - [ ] Publish a video tutorial fir using the library and the samples + - [x] Initial video with simple demonstration + - [ ] Coding setup and procedure video + - [ ] Two motors running on HMBGC example + - [ ] .... +- [ ] Implement Space Vector Modulation method + - [ ] Pure SVM + - [ ] PWM SVM +- [ ] Implement support for MOSFET control low and high pairs ## Work in progress - [x] Make the library accesible in the Arduino Library Manager - [x] Make minimal version of the arduino code - all in one arduino file - [x] Encoder index proper implementation - [x] Enable more dirver types -- [x] Make support for magnetic encoder AS5048 and similar +- [x] Make support for magnetic encoder AS5048 ABI +- [x] Make support for magnetic encoder AS5048 SPI - [x] Add support for acceleration ramping +- [x] Velocity Low pass filter - [x] Timer interrupt execution rather than in the `loop()` - FAIL: Perfromance not improved +- [x] Sine wave lookup table implementation # Contact Please do not hesitate to leave an issue or contact me direclty by email. diff --git a/arduino_foc_minimal/BLDCMotor.cpp b/arduino_foc_minimal_encoder/BLDCMotor.cpp similarity index 100% rename from arduino_foc_minimal/BLDCMotor.cpp rename to arduino_foc_minimal_encoder/BLDCMotor.cpp diff --git a/arduino_foc_minimal/BLDCMotor.h b/arduino_foc_minimal_encoder/BLDCMotor.h similarity index 98% rename from arduino_foc_minimal/BLDCMotor.h rename to arduino_foc_minimal_encoder/BLDCMotor.h index 60061fc5..6d62a56e 100644 --- a/arduino_foc_minimal/BLDCMotor.h +++ b/arduino_foc_minimal_encoder/BLDCMotor.h @@ -2,8 +2,6 @@ #define BLDCMotor_h #include "Arduino.h" -#include "MagneticSensor.h" -#include "Encoder.h" #include "FOCutils.h" #include "Sensor.h" diff --git a/arduino_foc_minimal/Encoder.cpp b/arduino_foc_minimal_encoder/Encoder.cpp similarity index 100% rename from arduino_foc_minimal/Encoder.cpp rename to arduino_foc_minimal_encoder/Encoder.cpp diff --git a/arduino_foc_minimal/Encoder.h b/arduino_foc_minimal_encoder/Encoder.h similarity index 100% rename from arduino_foc_minimal/Encoder.h rename to arduino_foc_minimal_encoder/Encoder.h diff --git a/arduino_foc_minimal/FOCutils.cpp b/arduino_foc_minimal_encoder/FOCutils.cpp similarity index 100% rename from arduino_foc_minimal/FOCutils.cpp rename to arduino_foc_minimal_encoder/FOCutils.cpp diff --git a/arduino_foc_minimal/FOCutils.h b/arduino_foc_minimal_encoder/FOCutils.h similarity index 100% rename from arduino_foc_minimal/FOCutils.h rename to arduino_foc_minimal_encoder/FOCutils.h diff --git a/arduino_foc_minimal/Sensor.h b/arduino_foc_minimal_encoder/Sensor.h similarity index 100% rename from arduino_foc_minimal/Sensor.h rename to arduino_foc_minimal_encoder/Sensor.h diff --git a/arduino_foc_minimal_encoder/SimpleFOC.h b/arduino_foc_minimal_encoder/SimpleFOC.h new file mode 100644 index 00000000..bd9ecb55 --- /dev/null +++ b/arduino_foc_minimal_encoder/SimpleFOC.h @@ -0,0 +1,9 @@ +#ifndef SIMPLEFOC_H +#define SIMPLEFOC_H + +#include "FOCutils.h" +#include "Sensor.h" +#include "Encoder.h" +#include "BLDCMotor.h" + +#endif diff --git a/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino b/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino new file mode 100644 index 00000000..f37e7885 --- /dev/null +++ b/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino @@ -0,0 +1,175 @@ +#include "SimpleFOC.h" + +// BLDCMotor( int phA, int phB, int phC, int pp, int en) +// - phA, phB, phC - motor A,B,C phase pwm pins +// - pp - pole pair number +// - enable pin - (optional input) +BLDCMotor motor = BLDCMotor(9, 10, 11, 11); + +//Encoder(int encA, int encB , int cpr, int index) +// - encA, encB - encoder A and B pins +// - ppr - impulses per rotation (cpr=ppr*4) +// - index pin - (optional input) +Encoder encoder = Encoder(2, 3, 2048); +// interrupt ruotine intialisation +void doA(){encoder.handleA();} +void doB(){encoder.handleB();} + +void setup() { + // debugging port + Serial.begin(115200); + + // initialise encoder sensor hardware + encoder.init(); + encoder.enableInterrupts(doA,doB); + + // power supply voltage + // default 12V + motor.voltage_power_supply = 12; + + // set control loop type to be used + // ControlType::voltage + // ControlType::velocity + // ControlType::angle + motor.controller = ControlType::angle; + + // contoller configuration based on the controll type + // velocity PI controller parameters + motor.PI_velocity.P = 0.2; + motor.PI_velocity.I = 20; + //defualt voltage_power_supply/2 + motor.PI_velocity.voltage_limit = 6; + // jerk control using voltage voltage ramp + // default value is 300 volts per sec ~ 0.3V per millisecond + motor.PI_velocity.voltage_ramp = 1000; + + // velocity low pass filtering + // default 10ms - try different values to see what is the best. + // the lower the less filtered + motor.LPF_velocity.Tf = 0.0; + + // angle loop controller + motor.P_angle.P = 3; + motor.P_angle.velocity_limit = 10; + + // link the motor to the sensor + motor.linkSensor(&encoder); + + // use debugging with serial for motor init + // comment out if not needed + motor.useDebugging(Serial); + + // intialise motor + motor.init(); + // align encoder and start FOC + motor.initFOC(); + + // this serial print takes around 20% of arduino memory! + Serial.println("\n\n"); + Serial.println("PI controller parameters change:"); + Serial.println("- P value : Prefix P (ex. P0.1)"); + Serial.println("- I value : Prefix I (ex. I0.1)\n"); + Serial.println("Velocity filter:"); + Serial.println("- Tf value : Prefix F (ex. F0.001)\n"); + Serial.println("Average loop execution time:"); + Serial.println("- Type T\n"); + Serial.println("Control loop type:"); + Serial.println("- C0 - angle control"); + Serial.println("- C1 - velocity control"); + Serial.println("- C2 - voltage control\n"); + Serial.println("Initial parameters:"); + Serial.print("PI velocity P: "); + Serial.print(motor.PI_velocity.P); + Serial.print(",\t I: "); + Serial.print(motor.PI_velocity.I); + Serial.print(",\t Low passs filter Tf: "); + Serial.println(motor.LPF_velocity.Tf,4); + + _delay(1000); +} + +// target velocity variable +float target = 0; +// loop stats variables +unsigned long t = 0; +long timestamp = _micros(); + +void loop() { + // iterative setting FOC pahse voltage + motor.loopFOC(); + + // iterative function setting the outter loop target + // velocity, position or voltage + motor.move(target); + + // keep track of loop number + t++; +} + +// Serial communication callback +void serialEvent() { + // a string to hold incoming data + static String inputString; + while (Serial.available()) { + // get the new byte: + char inChar = (char)Serial.read(); + // add it to the inputString: + inputString += inChar; + // if the incoming character is a newline + // end of input + if (inChar == '\n') { + if(inputString.charAt(0) == 'P'){ + motor.PI_velocity.P = inputString.substring(1).toFloat(); + Serial.print("PI velocity P: "); + Serial.print(motor.PI_velocity.P); + Serial.print(",\t I: "); + Serial.print(motor.PI_velocity.I); + Serial.print(",\t Low passs filter Tf: "); + Serial.println(motor.LPF_velocity.Tf,4); + }else if(inputString.charAt(0) == 'I'){ + motor.PI_velocity.I = inputString.substring(1).toFloat(); + Serial.print("PI velocity P: "); + Serial.print(motor.PI_velocity.P); + Serial.print(",\t I: "); + Serial.print(motor.PI_velocity.I); + Serial.print(",\t Low passs filter Tf: "); + Serial.println(motor.LPF_velocity.Tf,4); + }else if(inputString.charAt(0) == 'F'){ + motor.LPF_velocity.Tf = inputString.substring(1).toFloat(); + Serial.print("PI velocity P: "); + Serial.print(motor.PI_velocity.P); + Serial.print(",\t I: "); + Serial.print(motor.PI_velocity.I); + Serial.print(",\t Low passs filter Tf: "); + Serial.println(motor.LPF_velocity.Tf,4); + }else if(inputString.charAt(0) == 'T'){ + Serial.print("Average loop time is (microseconds): "); + Serial.println((_micros() - timestamp)/t); + t = 0; + timestamp = _micros(); + }else if(inputString.charAt(0) == 'C'){ + Serial.print("Contoller type: "); + int cnt = inputString.substring(1).toFloat(); + if(cnt == 0){ + Serial.println("angle!"); + motor.controller = ControlType::angle; + }else if(cnt == 1){ + Serial.println("velocity!"); + motor.controller = ControlType::velocity; + }else if(cnt == 2){ + Serial.println("volatge!"); + motor.controller = ControlType::voltage; + } + Serial.println(); + t = 0; + timestamp = _micros(); + }else{ + target = inputString.toFloat(); + Serial.print("Target : "); + Serial.println(target); + inputString = ""; + } + inputString = ""; + } + } +} diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.cpp b/arduino_foc_minimal_magnetic/BLDCMotor.cpp new file mode 100644 index 00000000..711b0b57 --- /dev/null +++ b/arduino_foc_minimal_magnetic/BLDCMotor.cpp @@ -0,0 +1,382 @@ +#include "BLDCMotor.h" + +// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - phA, phB, phC - motor A,B,C phase pwm pins +// - pp - pole pair number +// - cpr - counts per rotation number (cpm=ppm*4) +// - enable pin - (optionl input) +BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +{ + // Pin intialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + pole_pairs = pp; + + // enable_pin pin + enable_pin = en; + + // Power supply woltage + voltage_power_supply = DEF_POWER_SUPPLY; + + // Velocity loop config + // PI contoroller constant + PI_velocity.P = DEF_PI_VEL_P; + PI_velocity.I = DEF_PI_VEL_I; + PI_velocity.timestamp = _micros(); + PI_velocity.voltage_limit = voltage_power_supply/2; + PI_velocity.voltage_ramp = DEF_PI_VEL_U_RAMP; + PI_velocity.voltage_prev = 0; + PI_velocity.tracking_error_prev = 0; + + // velocity low pass filter + LPF_velocity.Tf = DEF_VEL_FILTER_Tf; + LPF_velocity.timestamp = _micros(); + LPF_velocity.prev = 0; + + // position loop config + // P controller constant + P_angle.P = DEF_P_ANGLE_P; + // maximum angular velocity to be used for positioning + P_angle.velocity_limit = DEF_P_ANGLE_VEL_LIM; + + // index search PI controller + PI_velocity_index_search.P = DEF_PI_VEL_INDEX_P; + PI_velocity_index_search.I = DEF_PI_VEL_INDEX_I; + PI_velocity_index_search.voltage_limit = voltage_power_supply/2; + PI_velocity_index_search.voltage_ramp = DEF_PI_VEL_INDEX_U_RAMP; + PI_velocity_index_search.timestamp = _micros(); + PI_velocity_index_search.voltage_prev = 0; + PI_velocity_index_search.tracking_error_prev = 0; + + // index search velocity + index_search_velocity = DEF_INDEX_SEARCH_TARGET_VELOCITY; + + // electric angle of the zero angle + zero_electric_angle = 0; + + //debugger + debugger = nullptr; +} + +// init hardware pins +void BLDCMotor::init() { + if(debugger) debugger->println("DEBUG: Initilaise the motor pins."); + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(hasEnable()) pinMode(enable_pin, OUTPUT); + + if(debugger) debugger->println("DEBUG: Set high frequency PWM."); + // Increase PWM frequency to 32 kHz + // make silent + setPwmFrequency(pwmA); + setPwmFrequency(pwmB); + setPwmFrequency(pwmC); + + // sanity check for the voltage limit configuration + if(PI_velocity.voltage_limit > voltage_power_supply/2) PI_velocity.voltage_limit = voltage_power_supply/2; + if(PI_velocity_index_search.voltage_limit > voltage_power_supply/2) PI_velocity_index_search.voltage_limit = voltage_power_supply/2; + + _delay(500); + // enable motor + if(debugger) debugger->println("DEBUG: Enabling motor."); + enable(); + _delay(500); + +} + + +// disable motor driver +void BLDCMotor::disable() +{ + // disable the driver - if enable_pin pin available + if (hasEnable()) digitalWrite(enable_pin, LOW); + // set zero to PWM + setPwm(pwmA, 0); + setPwm(pwmB, 0); + setPwm(pwmC, 0); +} +// enable motor driver +void BLDCMotor::enable() +{ + // set zero to PWM + setPwm(pwmA, 0); + setPwm(pwmB, 0); + setPwm(pwmC, 0); + // enable_pin the driver - if enable_pin pin available + if (hasEnable()) digitalWrite(enable_pin, HIGH); + +} + +void BLDCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} + + +// Encoder alignment to electrical 0 angle +int BLDCMotor::alignSensor() { + if(debugger) debugger->println("DEBUG: Align the sensor's and motor electrical 0 angle."); + // align the electircal phases of the motor and sensor + setPwm(pwmA, voltage_power_supply/2.0); + setPwm(pwmB,0); + setPwm(pwmC,0); + _delay(3000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0,0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(debugger){ + if(exit_flag< 0 ) debugger->println("DEBUG: Error: Absolute zero not found!"); + if(exit_flag> 0 ) debugger->println("DEBUG: Success: Absolute zero found!"); + else debugger->println("DEBUG: Absolute zero not availabe!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int BLDCMotor::absoluteZeroAlign() { + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + if(debugger) debugger->println("DEBUG: Aligning the absolute zero."); + + if(debugger && sensor->needsAbsoluteZeroSearch()) debugger->println("DEBUG: Searching for absolute zero."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = velocityIndexSearchPI(index_search_velocity - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); + + // align absoulute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = electricAngle(zero_offset); + } + // return bool is zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +/** + State calculation methods +*/ +// shaft angle calculation +float BLDCMotor::shaftAngle() { + return sensor->getAngle(); +} +// shaft velocity calculation +float BLDCMotor::shaftVelocity() { + float Ts = (_micros() - LPF_velocity.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + // calculate the fitering + float alpha = LPF_velocity.Tf/(LPF_velocity.Tf + Ts); + float vel = alpha*LPF_velocity.prev + (1-alpha)*sensor->getVelocity(); + // save the variables + LPF_velocity.prev = vel; + LPF_velocity.timestamp = _micros(); + return vel; +} +// Electrical angle calculation +float BLDCMotor::electricAngle(float shaftAngle) { + //return normalizeAngle(shaftAngle * pole_pairs); + return (shaftAngle * pole_pairs); +} + +/** + FOC funcitons +*/ + +// FOC initialization function +int BLDCMotor::initFOC() { + // sensor and motor alignment + _delay(500); + int exit_flag = alignSensor(); + _delay(500); + return exit_flag; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void BLDCMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart funciton :) + setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); +} + +// Iterative funciton running outer loop of the FOC algorithm +// Bahvior of this funciton is determined by the motor.controller variable +// It runs either angle, veloctiy or voltage loop +// - needs to be called iteratively it is asynchronious function +void BLDCMotor::move(float target) { + // get angular velocity + shaft_velocity = shaftVelocity(); + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = positionP( shaft_angle_sp - shaft_angle ); + voltage_q = velocityPI(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // inlcude velocity loop + shaft_velocity_sp = target; + voltage_q = velocityPI(shaft_velocity_sp - shaft_velocity); + break; + } +} + + +// Method using FOC to set Uq to the motor at the optimal angle +void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { + + // angle normalisation in between 0 and 2pi + // only necessary if using _sin and _cos - approximation funcitons + float angle = normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + // regular sin + cos ~300us (no memeory usaage) + // approx _sin + _cos ~110us (400Byte ~ 20% of memory) + // Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; + // Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; + Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; + + // // determine the segment I, II, III + // if ((angle >= 0) && (angle <= _120_D2R)) { + // // section I + // Ua = Ualpha + _1_SQRT3 * Ubeta; + // Ub = _2_SQRT3 * Ubeta; + // Uc = 0; + + // } else if ((angle > _120_D2R) && (angle <= (2 * _120_D2R))) { + // // section III + // Ua = 0; + // Ub = _1_SQRT3 * Ubeta - Ualpha; + // Uc = -_1_SQRT3 * Ubeta - Ualpha; + + // } else if ((angle > (2 * _120_D2R)) && (angle <= (3 * _120_D2R))) { + // // section II + // Ua = Ualpha - _1_SQRT3 * Ubeta; + // Ub = 0; + // Uc = - _2_SQRT3 * Ubeta; + // } + + // Clarke transform + Ua = Ualpha; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta; + + // set phase voltages + setPwm(pwmA, Ua); + setPwm(pwmB, Ub); + setPwm(pwmC, Uc); +} + + +// Set voltage to the pwm pin +// - function a bit optimised to get better performance +void BLDCMotor::setPwm(int pinPwm, float U) { + // max value + float U_max = voltage_power_supply/2.0; + + // sets the voltage [-U_max,U_max] to pwm [0,255] + // u_pwm = 255 * (U + U_max)/(2*U_max) + // it can be further optimised + // (example U_max = 6 > U_pwm = 127.5 + 21.25*U) + int U_pwm = 127.5 * (U/U_max + 1); + + + // float U_max = voltage_power_supply; + // // sets the voltage [0,12V(U_max)] to pwm [0,255] + // // - U_max you can set in header file - default 12V + // // - support for HMBGC controller + // int U_pwm = 255.0 * (float)U / (float)U_max; + + // limit the values between 0 and 255 + U_pwm = (U_pwm < 0) ? 0 : (U_pwm >= 255) ? 255 : U_pwm; + + analogWrite(pinPwm, U_pwm); +} + +/** + Utility funcitons +*/ +// normalizing radian angle to [0,2PI] +float BLDCMotor::normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} +// determining if the enable pin has been provided +int BLDCMotor::hasEnable(){ + return enable_pin != 0; +} + + +/** + Motor control functions +*/ +// PI controller function +float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){ + float Ts = (_micros() - cont.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s)e(s) + // tustin discretisation of the PI controller ( a bit optimised ) + // uk = uk_1 + (I*Ts/2 + P)*ek + (I*Ts/2 - P)*ek_1 + float tmp = cont.I*Ts*0.5; + float voltage = cont.voltage_prev + (tmp + cont.P) * tracking_error + (tmp - cont.P) * cont.tracking_error_prev; + + // antiwindup - limit the output voltage_q + if (abs(voltage) > cont.voltage_limit) voltage = voltage > 0 ? cont.voltage_limit : -cont.voltage_limit; + // limit the acceleration by ramping the the voltage + float d_voltage = voltage - cont.voltage_prev; + if (abs(d_voltage)/Ts > cont.voltage_ramp) voltage = d_voltage > 0 ? cont.voltage_prev + cont.voltage_ramp*Ts : cont.voltage_prev - cont.voltage_ramp*Ts; + + cont.voltage_prev = voltage; + cont.tracking_error_prev = tracking_error; + cont.timestamp = _micros(); + return voltage; +} +// velocity control loop PI controller +float BLDCMotor::velocityPI(float tracking_error) { + return controllerPI(tracking_error, PI_velocity); +} +// index search PI contoller +float BLDCMotor::velocityIndexSearchPI(float tracking_error) { + return controllerPI(tracking_error, PI_velocity_index_search); +} +// P controller for position control loop +float BLDCMotor::positionP(float ek) { + float velk = P_angle.P * ek; + if (abs(velk) > P_angle.velocity_limit) velk = velk > 0 ? P_angle.velocity_limit : -P_angle.velocity_limit; + return velk; +} + +/** + * Debugger functions + */ +// funciton implementing the debugger setter +void BLDCMotor::useDebugging(Print &print){ + debugger = &print; //operate on the adress of print + if(debugger )debugger->println("DEBUG: Serial debugger enabled!"); +} \ No newline at end of file diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.h b/arduino_foc_minimal_magnetic/BLDCMotor.h new file mode 100644 index 00000000..6d62a56e --- /dev/null +++ b/arduino_foc_minimal_magnetic/BLDCMotor.h @@ -0,0 +1,173 @@ +#ifndef BLDCMotor_h +#define BLDCMotor_h + +#include "Arduino.h" +#include "FOCutils.h" +#include "Sensor.h" + +// default configuration values +// power supply voltage +#define DEF_POWER_SUPPLY 12.0 +// velocity PI controller params +#define DEF_PI_VEL_P 0.5 +#define DEF_PI_VEL_I 10 +#define DEF_PI_VEL_U_RAMP 300 +// angle P params +#define DEF_P_ANGLE_P 20 +// angle velocity limit default +#define DEF_P_ANGLE_VEL_LIM 20 +// index search velocity +#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 +// velocity PI controller params for index search +#define DEF_PI_VEL_INDEX_P 1 +#define DEF_PI_VEL_INDEX_I 10 +#define DEF_PI_VEL_INDEX_U_RAMP 100 +// velocity filter time constant +#define DEF_VEL_FILTER_Tf 0.005 + +// controller type configuration enum +enum ControlType{ + voltage, + velocity, + angle +}; + +// PI controller strucutre +struct PI_s{ + float P; + float I; + long timestamp; + float voltage_prev, tracking_error_prev; + float voltage_limit; + float voltage_ramp; +}; + +// P controller structure +struct P_s{ + float P; + long timestamp; + float voltage_prev, tracking_error_prev; + float velocity_limit; +}; + +// flow pass filter structure +struct LPF_s{ + float Tf; + long timestamp; + float prev; +}; + +/** + BLDC motor class +*/ +class BLDCMotor +{ + public: + /* + BLDCMotor( int phA, int phB, int phC, int pp , int cpr, int en) + - phA, phB, phC - motor A,B,C phase pwm pins + - pp - pole pair number + - cpr - counts per rotation number (cpm=ppm*4) + - enable pin - (optionl input) + */ + BLDCMotor(int phA,int phB,int phC,int pp, int en = 0); + // change driver state + void init(); + void disable(); + void enable(); + // connect encoder + void linkSensor(Sensor* _sensor); + + // initilise FOC + int initFOC(); + // iterative method updating motor angles and velocity measurement + void loopFOC(); + // iterative control loop defined by controller + void move(float target); + + + // hardware variables + int pwmA; + int pwmB; + int pwmC; + int enable_pin; + int pole_pairs; + + + /** State calculation methods */ + //Shaft angle calculation + float shaftAngle(); + //Shaft velocity calculation + float shaftVelocity(); + + // state variables + // current motor angle + float shaft_angle; + // current motor velocity + float shaft_velocity; + // current target velocity + float shaft_velocity_sp; + // current target angle + float shaft_angle_sp; + // current voltage u_q set + float voltage_q; + + // Power supply woltage + float voltage_power_supply; + + // configuraion structures + ControlType controller; + PI_s PI_velocity; + PI_s PI_velocity_index_search; + P_s P_angle; + LPF_s LPF_velocity; + + // sensor link: + // - Encoder + // - MagneticSensor + Sensor* sensor; + // absolute zero electric angle - if available + float zero_electric_angle; + // index search velocity + float index_search_velocity; + + /** FOC methods */ + //Method using FOC to set Uq to the motor at the optimal angle + void setPhaseVoltage(float Uq, float angle_el); + + // debugging + void useDebugging(Print &print); + Print* debugger; + + float Ua,Ub,Uc; + + private: + //Sensor alignment to electrical 0 angle + int alignSensor(); + //Motor and sensor alignement to the sensors absolute 0 angle + int absoluteZeroAlign(); + + //Electrical angle calculation + float electricAngle(float shaftAngle); + //Set phase voltaget to pwm output + void setPwm(int pinPwm, float U); + + /** Utility funcitons */ + //normalizing radian angle to [0,2PI] + float normalizeAngle(float angle); + // determining if the enable pin has been provided + int hasEnable(); + + /** Motor control functions */ + float controllerPI(float tracking_error, PI_s &controller); + float velocityPI(float tracking_error); + float velocityIndexSearchPI(float tracking_error); + float positionP(float ek); + + // phase voltages + float Ualpha,Ubeta; + +}; + + +#endif diff --git a/arduino_foc_minimal_magnetic/FOCutils.cpp b/arduino_foc_minimal_magnetic/FOCutils.cpp new file mode 100644 index 00000000..5a383f3d --- /dev/null +++ b/arduino_foc_minimal_magnetic/FOCutils.cpp @@ -0,0 +1,84 @@ +#include "FOCutils.h" + +/* + High PWM frequency + https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 +*/ +void setPwmFrequency(int pin) { + if (pin == 5 || pin == 6 || pin == 9 || pin == 10) { + if (pin == 5 || pin == 6) { + // configure the pwm phase-corrected mode + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); + // set prescaler to 1 + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); + } else { + // set prescaler to 1 + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); + } + } + else if (pin == 3 || pin == 11) { + // set prescaler to 1 + TCCR2B = ((TCCR2B & 0b11111000) | 0x01); + } +} + +// funciton buffering delay() +// arduino funciton doesn't work well with interrupts +void _delay(unsigned long ms){ + long t = _micros(); + while((_micros() - t)/1000 < ms){}; +} + + +// funciton buffering _micros() +// arduino funciton doesn't work well with interrupts +unsigned long _micros(){ + // return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +} + + +// lookup table for sine calculation in between 0 and 90 degrees +//float sine_array[200] = {0.0000,0.0079,0.0158,0.0237,0.0316,0.0395,0.0473,0.0552,0.0631,0.0710,0.0789,0.0867,0.0946,0.1024,0.1103,0.1181,0.1260,0.1338,0.1416,0.1494,0.1572,0.1650,0.1728,0.1806,0.1883,0.1961,0.2038,0.2115,0.2192,0.2269,0.2346,0.2423,0.2499,0.2575,0.2652,0.2728,0.2804,0.2879,0.2955,0.3030,0.3105,0.3180,0.3255,0.3329,0.3404,0.3478,0.3552,0.3625,0.3699,0.3772,0.3845,0.3918,0.3990,0.4063,0.4135,0.4206,0.4278,0.4349,0.4420,0.4491,0.4561,0.4631,0.4701,0.4770,0.4840,0.4909,0.4977,0.5046,0.5113,0.5181,0.5249,0.5316,0.5382,0.5449,0.5515,0.5580,0.5646,0.5711,0.5775,0.5839,0.5903,0.5967,0.6030,0.6093,0.6155,0.6217,0.6279,0.6340,0.6401,0.6461,0.6521,0.6581,0.6640,0.6699,0.6758,0.6815,0.6873,0.6930,0.6987,0.7043,0.7099,0.7154,0.7209,0.7264,0.7318,0.7371,0.7424,0.7477,0.7529,0.7581,0.7632,0.7683,0.7733,0.7783,0.7832,0.7881,0.7930,0.7977,0.8025,0.8072,0.8118,0.8164,0.8209,0.8254,0.8298,0.8342,0.8385,0.8428,0.8470,0.8512,0.8553,0.8594,0.8634,0.8673,0.8712,0.8751,0.8789,0.8826,0.8863,0.8899,0.8935,0.8970,0.9005,0.9039,0.9072,0.9105,0.9138,0.9169,0.9201,0.9231,0.9261,0.9291,0.9320,0.9348,0.9376,0.9403,0.9429,0.9455,0.9481,0.9506,0.9530,0.9554,0.9577,0.9599,0.9621,0.9642,0.9663,0.9683,0.9702,0.9721,0.9739,0.9757,0.9774,0.9790,0.9806,0.9821,0.9836,0.9850,0.9863,0.9876,0.9888,0.9899,0.9910,0.9920,0.9930,0.9939,0.9947,0.9955,0.9962,0.9969,0.9975,0.9980,0.9985,0.9989,0.9992,0.9995,0.9997,0.9999,1.0000,1.0000}; + +// int array instead of float array +// 2x storage save (int 2Byte float 4 Byte ) +// sin*10000 +int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,1103,1181,1260,1338,1416,1494,1572,1650,1728,1806,1883,1961,2038,2115,2192,2269,2346,2423,2499,2575,2652,2728,2804,2879,2955,3030,3105,3180,3255,3329,3404,3478,3552,3625,3699,3772,3845,3918,3990,4063,4135,4206,4278,4349,4420,4491,4561,4631,4701,4770,4840,4909,4977,5046,5113,5181,5249,5316,5382,5449,5515,5580,5646,5711,5775,5839,5903,5967,6030,6093,6155,6217,6279,6340,6401,6461,6521,6581,6640,6699,6758,6815,6873,6930,6987,7043,7099,7154,7209,7264,7318,7371,7424,7477,7529,7581,7632,7683,7733,7783,7832,7881,7930,7977,8025,8072,8118,8164,8209,8254,8298,8342,8385,8428,8470,8512,8553,8594,8634,8673,8712,8751,8789,8826,8863,8899,8935,8970,9005,9039,9072,9105,9138,9169,9201,9231,9261,9291,9320,9348,9376,9403,9429,9455,9481,9506,9530,9554,9577,9599,9621,9642,9663,9683,9702,9721,9739,9757,9774,9790,9806,9821,9836,9850,9863,9876,9888,9899,9910,9920,9930,9939,9947,9955,9962,9969,9975,9980,9985,9989,9992,9995,9997,9999,10000,10000}; + +// function approximating the sine calculation by using fixed size array +// ~40us (float array) +// ~50us (int array) +// precision +-0.005 +// it has to receive an angle in between 0 and 2PI +float _sin(float a){ + if(a < _PI_2){ + //return sine_array[(int)(199.0*( a / (M_PI/2.0)))]; + //return sine_array[(int)(126.6873* a)]; // float array optimised + return 0.0001*sine_array[round(126.6873* a)]; // int array optimised + }else if(a < M_PI){ + // return sine_array[(int)(199.0*(1.0 - (a-M_PI/2.0) / (M_PI/2.0)))]; + //return sine_array[398 - (int)(126.6873*a)]; // float array optimised + return 0.0001*sine_array[398 - round(126.6873*a)]; // int array optimised + }else if(a < _3PI_2){ + // return -sine_array[(int)(199.0*((a - M_PI) / (M_PI/2.0)))]; + //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimised + return -0.0001*sine_array[-398 + round(126.6873*a)]; // int array optimised + } else { + // return -sine_array[(int)(199.0*(1.0 - (a - 3*M_PI/2) / (M_PI/2.0)))]; + //return -sine_array[796 - (int)(126.6873*a)]; // float array optimised + return -0.0001*sine_array[796 - round(126.6873*a)]; // int array optimised + } +} + +// function approfimating cosine calculaiton by using fixed size array +// ~55us (float array) +// ~56us (int array) +// precision +-0.005 +// it has to receive an angle in between 0 and 2PI +float _cos(float a){ + float a_sin = a + _PI_2; + a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} diff --git a/arduino_foc_minimal_magnetic/FOCutils.h b/arduino_foc_minimal_magnetic/FOCutils.h new file mode 100644 index 00000000..d6177497 --- /dev/null +++ b/arduino_foc_minimal_magnetic/FOCutils.h @@ -0,0 +1,38 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + +// sign funciton +#define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +// utility defines +#define _2_SQRT3 1.15470053838 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI_2 1.57079632679 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + +// High PWM frequency +void setPwmFrequency(int pin); + +// funciton buffering delay() +// arduino funciton doesn't work well with interrupts +void _delay(unsigned long ms); + +// funciton buffering _micros() +// arduino funciton doesn't work well with interrupts +unsigned long _micros(); + +// function approximating the sine calculation by using fixed size array +// ~40us +// it has to receive an angle in between 0 and 2PI +float _sin(float a); +// function approfimating cosine calculaiton by using fixed size array +// ~50us +// it has to receive an angle in between 0 and 2PI +float _cos(float a); + +#endif \ No newline at end of file diff --git a/arduino_foc_minimal/MagneticSensor.cpp b/arduino_foc_minimal_magnetic/MagneticSensor.cpp similarity index 100% rename from arduino_foc_minimal/MagneticSensor.cpp rename to arduino_foc_minimal_magnetic/MagneticSensor.cpp diff --git a/arduino_foc_minimal/MagneticSensor.h b/arduino_foc_minimal_magnetic/MagneticSensor.h similarity index 100% rename from arduino_foc_minimal/MagneticSensor.h rename to arduino_foc_minimal_magnetic/MagneticSensor.h diff --git a/arduino_foc_minimal_magnetic/Sensor.h b/arduino_foc_minimal_magnetic/Sensor.h new file mode 100644 index 00000000..3555941a --- /dev/null +++ b/arduino_foc_minimal_magnetic/Sensor.h @@ -0,0 +1,29 @@ +#ifndef SENSOR_H +#define SENSOR_H + +// Sensor abstract class defintion +// Each sensor needs to have these functions implemented +class Sensor{ + public: + // get current angle (rad) + virtual float getAngle(); + // get current angular velocity (rad/s) + virtual float getVelocity(); + // set current agle as zero angle + // return the angle [rad] difference + virtual float initRelativeZero(); + // set absoule zero angle as zero angle + // return the angle [rad] difference + virtual float initAbsoluteZero(); + + // returns 0 if it has no absolute 0 measurement + // 0 - incremental encoder without index + // 1 - encoder with index & magnetic sensors + virtual int hasAbsoluteZero(); + // returns 0 if it does need search for absolute zero + // 0 - magnetic sensor (& encoder with index which is found) + // 1 - ecoder with index (with index not found yet) + virtual int needsAbsoluteZeroSearch(); +}; + +#endif \ No newline at end of file diff --git a/arduino_foc_minimal/SimpleFOC.h b/arduino_foc_minimal_magnetic/SimpleFOC.h similarity index 87% rename from arduino_foc_minimal/SimpleFOC.h rename to arduino_foc_minimal_magnetic/SimpleFOC.h index 887ae8df..bd095760 100644 --- a/arduino_foc_minimal/SimpleFOC.h +++ b/arduino_foc_minimal_magnetic/SimpleFOC.h @@ -3,7 +3,6 @@ #include "FOCutils.h" #include "Sensor.h" -#include "Encoder.h" #include "MagneticSensor.h" #include "BLDCMotor.h" diff --git a/arduino_foc_minimal/arduino_foc_minimal.ino b/arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino similarity index 89% rename from arduino_foc_minimal/arduino_foc_minimal.ino rename to arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino index 98cfbb23..2f7b89c7 100644 --- a/arduino_foc_minimal/arduino_foc_minimal.ino +++ b/arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino @@ -7,33 +7,21 @@ // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11); +BLDCMotor motor = BLDCMotor(9, 5, 6, 11); -//Encoder sensor = Encoder(2, 3, 2048); -// interrupt ruotine intialisation -// void doA(){encoder.handleA();} -// void doB(){encoder.handleB();} -// encoder interrupt init -// PciListenerImp listenerA(encoder.pinA, doA); -// PciListenerImp listenerB(encoder.pinB, doB); - - -MagneticSensor sensor = MagneticSensor(10,16384); +// MagneticSensor(int cs, float _cpr, int _angle_register) +// cs - SPI chip select pin +// _cpr - counF per revolution +// _angle_register - (optional) angle read register - default 0x3FFF +MagneticSensor as504x = MagneticSensor(10, 16384); void setup() { // debugging port Serial.begin(115200); - //as5047.init(); - // initialise magnetic sensor hardware - sensor.init(); - //encoder.enableInterrupts(doA,doB); - - // // interrupt intitialisation - // PciManager.registerListener(&listenerA); - // PciManager.registerListener(&listenerB); + as504x.init(); // power supply voltage // default 12V @@ -64,10 +52,8 @@ void setup() { motor.P_angle.P = 3; motor.P_angle.velocity_limit = 10; - // link the motor to the sensor - motor.linkSensor(&sensor); - // motor.linkSensor(&as5047); + motor.linkSensor(&as504x); // use debugging with serial for motor init @@ -79,6 +65,7 @@ void setup() { // align encoder and start FOC motor.initFOC(); + // this serial print takes about 20% of arduino memory!! Serial.println("\n\n"); Serial.println("PI controller parameters change:"); Serial.println("- P value : Prefix P (ex. P0.1)"); From 1612549eef29d273172281c3bceaa9d7958d9c98 Mon Sep 17 00:00:00 2001 From: askuric Date: Sat, 2 May 2020 19:18:40 +0200 Subject: [PATCH 36/65] README examples description --- README.md | 28 ++++++++++++++++++++++++++++ 1 file changed, 28 insertions(+) diff --git a/README.md b/README.md index f939f01d..c63c5afa 100644 --- a/README.md +++ b/README.md @@ -6,6 +6,34 @@ This is the minimal Arduino example of the [Simple FOC](https://github.com/askuric/Arduino-FOC) arduino library intended for mostly for easier experiemtation and modification! +### Minimal repository structure +```shell +├───arduino_foc_minimal_encoder # Arduino minimal code for running a motor with Encoder +│ +└───arduino_foc_minimal_magnetic # Arduino minimal code for running a motor with magentic sensor + # AS5048/47 +``` + +Each of the examples will give you the opportunity to change the PI celocity parameters `P` and `I`, Low pass filter time constant `Tf`, change the control loop in real time and check the average loop execution time, all from the serial terminal. +``` +PI controller parameters change: +- P value : Prefix P (ex. P0.1) +- I value : Prefix I (ex. I0.1) + +Velocity filter: +- Tf value : Prefix F (ex. F0.001) + +Average loop execution time: +- Type T + +Control loop type: +- C0 - angle control +- C1 - velocity control +- C2 - voltage control + +Initial parameters: +PI velocity P: 0.20, I: 20.00, Low passs filter Tf: 0.0000 +``` ## Arduino FOC repo structure Branch | Description | Status ------------ | ------------- | ------------ From 4edc4b38b429693a5bd854601b51705490b0e1a5 Mon Sep 17 00:00:00 2001 From: askuric Date: Sat, 2 May 2020 19:19:40 +0200 Subject: [PATCH 37/65] README terrible typo --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index c63c5afa..f293f88f 100644 --- a/README.md +++ b/README.md @@ -14,7 +14,7 @@ This is the minimal Arduino example of the [Simple FOC](https://github.com/askur # AS5048/47 ``` -Each of the examples will give you the opportunity to change the PI celocity parameters `P` and `I`, Low pass filter time constant `Tf`, change the control loop in real time and check the average loop execution time, all from the serial terminal. +Each of the examples will give you the opportunity to change the PI velocity parameters `P` and `I`, Low pass filter time constant `Tf`, change the control loop in real time and check the average loop execution time, all from the serial terminal. ``` PI controller parameters change: - P value : Prefix P (ex. P0.1) From 729c88571dc94d14bd1ceacea5e40fd19c9c1ebf Mon Sep 17 00:00:00 2001 From: askuric Date: Sun, 3 May 2020 09:35:13 +0200 Subject: [PATCH 38/65] BLDCmotor remove comment --- arduino_foc_minimal_encoder/BLDCMotor.cpp | 20 -------------------- arduino_foc_minimal_magnetic/BLDCMotor.cpp | 22 +--------------------- 2 files changed, 1 insertion(+), 41 deletions(-) diff --git a/arduino_foc_minimal_encoder/BLDCMotor.cpp b/arduino_foc_minimal_encoder/BLDCMotor.cpp index 711b0b57..f231ea8a 100644 --- a/arduino_foc_minimal_encoder/BLDCMotor.cpp +++ b/arduino_foc_minimal_encoder/BLDCMotor.cpp @@ -259,26 +259,6 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; - - // // determine the segment I, II, III - // if ((angle >= 0) && (angle <= _120_D2R)) { - // // section I - // Ua = Ualpha + _1_SQRT3 * Ubeta; - // Ub = _2_SQRT3 * Ubeta; - // Uc = 0; - - // } else if ((angle > _120_D2R) && (angle <= (2 * _120_D2R))) { - // // section III - // Ua = 0; - // Ub = _1_SQRT3 * Ubeta - Ualpha; - // Uc = -_1_SQRT3 * Ubeta - Ualpha; - - // } else if ((angle > (2 * _120_D2R)) && (angle <= (3 * _120_D2R))) { - // // section II - // Ua = Ualpha - _1_SQRT3 * Ubeta; - // Ub = 0; - // Uc = - _2_SQRT3 * Ubeta; - // } // Clarke transform Ua = Ualpha; diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.cpp b/arduino_foc_minimal_magnetic/BLDCMotor.cpp index 711b0b57..3063f3b9 100644 --- a/arduino_foc_minimal_magnetic/BLDCMotor.cpp +++ b/arduino_foc_minimal_magnetic/BLDCMotor.cpp @@ -259,27 +259,7 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; - - // // determine the segment I, II, III - // if ((angle >= 0) && (angle <= _120_D2R)) { - // // section I - // Ua = Ualpha + _1_SQRT3 * Ubeta; - // Ub = _2_SQRT3 * Ubeta; - // Uc = 0; - - // } else if ((angle > _120_D2R) && (angle <= (2 * _120_D2R))) { - // // section III - // Ua = 0; - // Ub = _1_SQRT3 * Ubeta - Ualpha; - // Uc = -_1_SQRT3 * Ubeta - Ualpha; - - // } else if ((angle > (2 * _120_D2R)) && (angle <= (3 * _120_D2R))) { - // // section II - // Ua = Ualpha - _1_SQRT3 * Ubeta; - // Ub = 0; - // Uc = - _2_SQRT3 * Ubeta; - // } - + // Clarke transform Ua = Ualpha; Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta; From 5adf230491b47bd30e99eaa2ded3d634413074a1 Mon Sep 17 00:00:00 2001 From: askuric Date: Fri, 8 May 2020 10:19:24 +0200 Subject: [PATCH 39/65] README delegation to docs --- README.md | 855 ++---------------------------------------------------- 1 file changed, 20 insertions(+), 835 deletions(-) diff --git a/README.md b/README.md index f293f88f..5aa29dda 100644 --- a/README.md +++ b/README.md @@ -34,846 +34,31 @@ Control loop type: Initial parameters: PI velocity P: 0.20, I: 20.00, Low passs filter Tf: 0.0000 ``` -## Arduino FOC repo structure -Branch | Description | Status ------------- | ------------- | ------------ -[master](https://github.com/askuric/Arduino-FOC) | Stable and tested library version | ![Library Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Compile/badge.svg) -[dev](https://github.com/askuric/Arduino-FOC/tree/dev) | Developement library version | ![Library Dev Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Dev%20Compile/badge.svg?branch=dev) -[minimal](https://github.com/askuric/Arduino-FOC/tree/minimal) | Minimal Arduino example with integrated library | ![MinimalBuild](https://github.com/askuric/Arduino-FOC/workflows/MinimalBuild/badge.svg?branch=minimal) +### Installation +For those willing to experiment and to modify the code I suggest using the [minimal version](https://github.com/askuric/Arduino-FOC/tree/minimal) of the code. + > This code is completely indepenedet and you can run it as any other Arduino Schetch without the need for any libraries. -# Contents -- [Installation](#arduino-simple-foc-instalation) - - [Installing the full Arduino Simple FOC library](#installing-simple-foc-full-library) - - [Installing the minimal Arduino example](#download-simple-foc-arduino-minimal-example) -- [Electrical connecitons and schematic](#electrical-connections) - - [Minimal setup](#all-you-need-for-this-project) - - [Arduino Simple FOC Shield](#arduino-simple-foc-shield) - - [Arduino UNO + L6234 driver](#arduino-uno-l6234-driver) - - [HMBGC gimbal contorller example](#hmbgc-v22) -- [Code explanation and examples](#arduino-simple-foc-library-code) - - [Encoder setup](#encoder-setup) - - [Magentic sensor setup](#magnetic-sensor-setup) - - [BLDC motor setup](#motor-setup) - - [Control loop setup](#control-loop-setup) - - [Voltage control loop](#voltage-control-loop) - - [Velcoity control loop](#velocity-control-loop) - - [Angle control loop](#angle-control-loop) - - [Debugging practice](#debugging) -- [Future work and work in progress](#work-roadmap) -- [Contact](#contact) +#### Github webiste downlaod +- Go to [minimal branch](https://github.com/askuric/Arduino-FOC/tree/minimal) +- Downlaod the code by clicking on the `Clone or Download > Download ZIP`. +- Unzip it and open the schetch in Arduino IDE. - -# Arduino Simple FOC instalation -Depending on if you want to use this library as the plug and play Arduino library or you want to get insight in the algorithm and make changes simply there are two ways to install this code. - -## Installing Simple FOC full library -### Arduino IDE - Library manager -The simplest way to get hold of the library is direclty by using Arduino IDE and its integrated Library Manager. Just serarch for `Simple FOC` library and install the lates version. - -### Download library directly -If you don't want to use the Arduino IDE and Library manager you can direclty download the library from this website. -- Simplest way to do it is to download the `zip` aerchieve directly on the top of this webiste. Click first on `Clone or Download` and then on `Download ZIP`. Once you have the zip ardhieve downloaded, unzip it and place it in your Arduino Libraries forlder. On Windows it is usually in `Documents > Arduino > libraries`. - Now reopen your Arduino IDE and you should have the library examples in `File > Examples > Simple FOC`. - -- If you are more experienced with the terminal you can open your terminal in the Arduino libraries folder direclty and clone the Arduino FOC git repsitory: - ```bash - git clone https://github.com/askuric/Arduino-FOC.git - ``` - Now reopen your Arduino IDE and you should have the library examples in `File > Examples > Simple FOC`. - -## Download Simple FOC Arduino minimal example -To download the minmial verison of Simple FOC intended for those willing to experiment and extend the code I suggest using this version over the full library. -This code is completely indepenedet and you can run it as any other Arduino Schetch without the need for any libraries. -The code is place in the [minimal branch](https://github.com/askuric/Arduino-FOC/tree/minimal). - -- You can download it directly form the [minimal branch](https://github.com/askuric/Arduino-FOC/tree/minimal) by clicking on the `Clone or Download > Download ZIP`. - Then you just unzip it and open the schetch in Arduino IDE. - -- You can also clone it using the terminal: - ```bash +#### Using terminal +- Open the terminal: + ```sh + cd *to you desired directory* git clone -b minimal https://github.com/askuric/Arduino-FOC.git ``` - Then you just open it with the Arduino IDE and run it. - -# Electrical connections - -## All you need for this project -All you need for this project is: -- Brushless DC (BLDC) motor -- BLDC driver -- Position sensor -- Arduino -### BLDC motor -This library is compatible with any 3 phase BLDC motor out there. Feel free to choose anything that suites your applications. The most tests have been done using gimbal morots (up to 2A). -Examples: -- IPower GBM4198H-120T [Ebay](https://www.ebay.com/itm/iPower-Gimbal-Brushless-Motor-GBM4108H-120T-for-5N-7N-GH2-ILDC-Aerial-photo-FPV/252025852824?hash=item3aade95398:g:q94AAOSwPcVVo571:rk:2:pf:1&frcectupt=true) -- GARTT ML5010 300KV [Ebay](https://www.ebay.com/itm/GARTT-ML5010-300KV-Brushless-Motor-For-T960-T810-RC-Multirotor-Quadcopter-MT-092/302082779179?hash=item465589682b:g:h00AAOSwmfhX44X2) -### BLDC motor driver -This library will be compatible with the most of the 3 phase bldc motor dirvers. Such as L6234, DRV8305 or L293. -Examples: -- L6234 driver [Drotek](https://store-drotek.com/212-brushless-gimbal-controller-l6234.html), [Ebay](https://www.ebay.fr/itm/L6234-Breakout-Board-/153204519965) -- Alternatively the library supports the arduino based gimbal controllers such as: HMBGC V2.2 ([Ebay](https://www.ebay.com/itm/HMBGC-V2-0-3-Axle-Gimbal-Controller-Control-Plate-Board-Module-with-Sensor/351497840990?hash=item51d6e7695e:g:BAsAAOSw0QFXBxrZ:rk:1:pf:1)) -- [Arduino Simple FOC shield](#arduino-simple-foc-shield-v12) - -### Position sensor -This library supports two types of position sensors: Encoder and Magnetic sensor. -#### Encoders -Encoders are by far most popular position sensors, both in industry and in hobby community. The main benefits are the precision, standardisation and very low noise level. The main problem with encoders is the efficiency. - -Examples: -- Optical Encoder - - 2400cpr | ~10$ [Ebay](https://www.ebay.com/itm/600P-R-Photoelectric-Incremental-Rotary-Encoder-5V-24V-AB-2-Phases-Shaft-6mm-New/173145939999?epid=19011022356&hash=item28504d601f:g:PZsAAOSwdx1aKQU-:rk:1:pf:1) - - 490-AMT103-V | 8192cpr | ~30$ [Mouser](https://www.mouser.fr/ProductDetail/CUI-Devices/AMT103-V?qs=%2Fha2pyFaduiAsBlScvLoAWHUnKz39jAIpNPVt58AQ0PVb84dpbt53g%3D%3D) -- Magnetic Encoders - - AS5047 | 16384cpr | ~15$ [Mouser](https://www.mouser.fr/ProductDetail/ams/AS5X47U-TS_EK_AB?qs=sGAEpiMZZMve4%2FbfQkoj%252BBDLPCj82ZLyYIPEtADg0FE%3D) [Youtube](https://www.youtube.com/watch?v=Gl-DiOqXXJ8) - -#### Magnetic sensors | SPI interface -Magentic position sensor has many benefits over the encoders: -- Very efficient position calculation ( no counting ) -- Time of execution doesn't depend on velocity or number of sensors -- No need for interrupt hardware -- Absolute position value -- Very low price -- Very simple to mount - -Examples: - - AS5048 | 16384cpr | ~15$ [Aliexpress](https://fr.aliexpress.com/item/4000034013999.html?spm=a2g0o.productlist.0.0.4a7f5c25mYwpN3&algo_pvid=8f452506-7081-4d0a-8f66-d0b725d6de66&algo_expid=8f452506-7081-4d0a-8f66-d0b725d6de66-0&btsid=0b0a0ad815873142372227604ed134&ws_ab_test=searchweb0_0,searchweb201602_,searchweb201603_) - - AS5047 | 16384cpr | ~15$ [Mouser](https://www.mouser.fr/ProductDetail/ams/AS5X47U-TS_EK_AB?qs=sGAEpiMZZMve4%2FbfQkoj%252BBDLPCj82ZLyYIPEtADg0FE%3D) [Youtube](https://www.youtube.com/watch?v=Gl-DiOqXXJ8) - - -## Arduino Simple FOC Shield - -At this moment we are developing an open source version of Arduin shiled specifically for FOC motor control. -We already have prototypes of the board and we are in the testing phase. We will be coming out with the details very soon! - -### Features -- Plug and play capability with the Arduino Simple FOC library -- Price in the range of \$20-\$40 -- Gerber files and BOM available Open Source -- Stackable: running at least 2 motors in the same time - -***Let me know if you are interested! antun.skuric@outlook.com*** -You can explore the [3D model of the board in the PDF form](https://raw.githubusercontent.com/askuric/Arduino-FOC/master/extras/ArduinoFOCShieldV12.pdf). - -

-

- -#### Connection example -

- - -

- -## Arduino UNO + L6234 driver -The code is simple enough to be run on Arudino Uno board. -### Encoder as position sensor -

- - -

- -#### Encoder -- Encoder channels `A` and `B` are connected to the Arduino's external intrrupt pins `2` and `3`. -- Optionally if your encoder has `index` signal you can connect it to any available pin, figure shows pin `4`. - - For Arudino UNO and similar broads which dont have 3 hardware interrupts, if you can choose, preferably connect index pin to pins `A0-A5` due to the interrupt rutine, it will have better performance (but any other pin will work as well). - - Othervise if you are using different board and have 3 hardware interrupt pins connect the index pin to one of them. -#### L6234 breakout board -- Connected to the arduino pins `9`,`10` and `11` (you can use also pins `5` and `6`). -- Additionally you can connect the `enable` pin to the any digital pin of the arduino the picture shows pin `8` but this is optional. You can connect the driver enable directly to 5v. -- Make sure you connect the common ground of the power supply and your Arduino -#### Motor -- Motor phases `a`, `b` and `c` are connected directly to the driver outputs -- Motor phases `a`,`b`,`c` and encoder channels `A` and `B` have to be oriented right for the algorightm to work. But don't worry about it too much. Connect it in initialy as you wish and then if it doesnt move reverse pahse `a` and `b` of the motor, that should be enogh. -### Magentic sensor as position sensor -

- -

- -#### Magnetic sensor -- Magnetic sensors SPI interface singals `SCK`, `MISO` and `MOSI` are connected to the Arduino's `SPI` pins (Arduino UNO `13`,`12` and `11`). - - If the application requires more than one sensor all of them are connected to the same pins of theArudino. -- The `chip select` pin is connected to the desired pin. Each sensor connected to the same Arduino has to have unique chip select pin. -#### L6234 breakout board -- Connected to the arduino pins `3`,`5` and `6` (you can use also pin `9` and `10`, pin `11` is taken by the SPI interface). -- Additionally you can connect the `enable` pin to the any digital pin of the arduino the picture shows pin `2` but this is optional. You can connect the driver enable directly to 5v. -- Make sure you connect the common ground of the power supply and your Arduino -#### Motor -- Motor phases `a`, `b` and `c` are connected directly to the driver outputs -- Motor phases `a`,`b`,`c` and the magnetic sensor counting direciton have to be oriented right for the algorightm to work. But don't worry about it too much. Connect it initialy as you wish and then if the motor locks in place inverse `a` and `b` line of the motor. - - -## HMBGC V2.2 -To use HMBGC controller for vector control (FOC) you need to connect motor to one of the motor terminals and connect the Encoder. The shema of connection is shown on the figures above, I also took a (very bad) picture of my setup. - -

- - -

- - -### Encoder -Since HMBGC doesn't have acces to the arduinos external interrupt pins `2` and `3` and additionally we only have acces to the analog pins, we need to read the encoder using the software interrupt. To show the functionallity we provide one example of the HMBGC code (`HMBGC_example.ino`) using the [PciManager library](https://github.com/prampec/arduino-pcimanager). - -- Encoder channels `A` and `B` are connected to the pins `A0` and `A1`. -- Optionally if your encoder has `index` signal you can connect it to any available pin, figure shows pin `A2`. -### Motor -- Motor phases `a`,`b` and `c` are connected directly to the driver outputs -- Motor phases `a`,`b`,`c` and encoder channels `A` and `B` have to be oriented right for the algorightm to work. But don't worry about it too much. Connect it in initialy as you wish and then if it doesnt move reverse pahse `a` and `b` of the motor, that should be enogh. - -> HMBGC board doesn't support magnetic sensors because it doesn't have necessary SPI infrastructure. - -# Arduino Simple FOC library code -The code is organised into a library. The library contains main BLDC motor class `BLDCmotor` and two sensor classes `Endcoder` and `MagneticSensor`. `BLDCmotor` contains all the necessary FOC algorithm funcitons as well as PI controllers for the velocity and angle control. `Encoder` deals with the encoder interupt funcitons, calcualtes motor angle and velocity ( using the [Mixed Time Frequency Method](https://github.com/askuric/Arduino-Mixed-Time-Frequency-Method)). The `Encoder` class will support any type of otpical and magnetic encoder. `MagneticEncoder` class deals with all the necessary communication and calculation infrastructure to handle the magnetic position sensors such as AS5048 and similar. - -## Encoder setup -To initialise the encoder you need to provide the encoder `A` and `B` channel pins, encoder `PPR` and optionally `index` pin. -```cpp -// Encoder(int encA, int encB , int cpr, int index) -// - encA, encB - encoder A and B pins -// - ppr - impulses per rotation (cpr=ppr*4) -// - index pin - (optional input) -Encoder encoder = Encoder(2, 3, 8192, A0); -``` -Next important feature of the encoder is enabling or disabling the `Quadrature` more. If the Encoder is run in the quadratue more its number of impulses per rotation(`PPR`) is quadrupled by detecting each `CHANGE` of the signals `A` and `B` - `CPR = 4xPPR`. In some applicaitons, when the encoder `PPR` is high it can be too much for the Arudino to handle so it is preferable not to use `Quadrature` mode. By default all the encoders use `Quadrature` mode. If you would like to enable or disable this paramter do it in the Arduino setup funciton by running: -```cpp -// check if you need internal pullups -// Quadrature::ENABLE - CPR = 4xPPR - default -// Quadrature::DISABLE - CPR = PPR -encoder.quadrature = Quadrature::ENABLE; -``` -Additionally the encoder has one more important parameters which is whether you want to use Arduino's internal pullup or you have external one. That is set by changing the value of the `encoder.pullup` variuable. The default value is set to `Pullup::EXTERN` -```cpp -// check if you need internal pullups -// Pullup::EXTERN - external pullup added - dafault -// Pullup::INTERN - needs internal arduino pullup -encoder.pullup = Pullup::EXTERN; -``` -### Encoder interrupt configuration -There are two ways you can run encoders with Simple FOC libtrary. -- Using Arduino hardware external interrupt - for Arduino UNO pins `2` and `3` -- Using software pin chnage interrupt by using a library such as [PciManager library](https://github.com/prampec/arduino-pcimanager) - -> Using the hardware external interrupts usualy results in a bit better and more realible performance but software interrupts will work very good as well. - -#### Arduino Hardware external interrupt -Arduino UNO has two hadrware external interrupt pins, pin `2` and `3`. And in order to use its functionallities the encoder channels `A` and `B` will have to be connected exacly on these pins. - -Simple FOC `Encoder` class already has implemented initialisation and encoder `A` and `B` channel callbacks. -All you need to do is define two funcitons `doA()` and `doB()`, the buffering functions of encoder callback funcitons `encoder.handleA()` and `encoder.handleB()`. -```cpp -// interrupt ruotine intialisation -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} -``` -And supply those functions to the encoder interrupt init fucntion `encoder.enableInterrupts()` -```cpp -// enable encoder hardware interrupts -encoder.enableInterrupts(doA, doB) -``` -You can name the buffering funcitons as you wish. It is just important to supply them to the `encoder.init()` funciton. This procedure is a tradeoff in between scalability and simplicity. This allows you to have more than one encoder connected to the same arduino. All you need to do is to instantiate new `Encoder` class and create new buffer functions. For example: -```cpp -// encoder 1 -Encoder enc1 = Encoder(...); -void doA1(){enc1.handleA();} -void doB1(){enc1.handleB();} -// encoder 2 -Encoder enc2 = Encoder(...); -void doA2(){enc2.handleA();} -void doB2(){enc2.handleB();} - -void setup(){ -... - enc1.init(); - enc1.enableInterrupts(doA1,doB1); - enc2.init(); - enc2.enableInterrupts(doA2,doB2); -... -} -``` - -##### Index pin configuration -In order to read index pin efficienlty Simple FOC algorithm enables you to use the same approach as for the channels `A` and `B`. First you need to provide the `Encoder` class the index pin number: -```cpp -Encoder encoder = Encoder(pinA, pinB, cpr, index_pin); -``` -If you are using Arduino board such as Arduino Mega and simialar and if you have more tha 2 hadrware interrupts you can connect your index pin to the hadrware interrupt pin (example Arduino Mega pin `21`). Your code will look like: -```cpp -Encoder encoder = Encoder(2,3,600,A0); -// A and B interrupt rutine -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} -void doIndex(){encoder.handleIndex();} - -void setup(){ - ... - encoder.enableInterrupts(doA,doB,doIndex); - ... - } -``` -The function `enableInterrupts` will handle all the intialisation for you. -If yo are using Arduino UNO to run this algorithm and you do not have enough hardware interrupt pins you will need to use software interrupt library such as [PciManager library](https://github.com/prampec/arduino-pcimanager). Arduino UNO code for using an encoder with index can be: -```cpp -Encoder encoder = Encoder(2,3,600,A0); -// A and B interrupt rutine -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} -void doIndex(){encoder.handleIndex();} - -// softaware interrupt listener for index pin -PciListenerImp listenerIndex(encoder.index_pin, doIndex); - -void setup(){ - ... - // hardware interrupts for A and B - encoder.enableInterrupts(doA,doB); - // software interrupt for index - PciManager.registerListener(&listenerIndex); - ... - } -``` -The same procedure can be done for pins `A` and `B` if your application makes you run out of the hardware interrupt pins. Software interrupts are very powerfull and produce very comparable results to the hardware interupts, but in general they tend to have a bit worse performance. `index` pin produces an interrupt once per rotation, therefore it is not critical, so software or hardware interrupt doesn't change too much in terms of performance. - -To explore better the encoder algorithm an example is provided `encoder_example.ino`. - -#### Arduino software pin change interrupt -If you are not able to access your pins `2` and `3` of your Arduino UNO or if you want to use more than none encoder you will have to use the software interrupt approach. -I suggest using the [PciManager library](https://github.com/prampec/arduino-pcimanager). - -The stps of using this library in code are very similar to [harware interrupt](#arduino-hardware-external-interrupt). -The SimpleFOC `Encoder` class still provides you with all the callbacks `A`, `B` and `Index` channels but the Simple FOC library will not initialise the interrupts for you. - -In order to use the `PCIManager` library you will need to include it in your code: -```cpp -#include -#include -``` -Next step is the same as before, you will just intialise the new `Encoder` instance. -```cpp -Encoder encoder = Encoder(10, 11, 8192); -// A and B interrupt callback buffers -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} -``` -Then you declare listeners `PciListenerImp `: -```cpp -// encoder interrupt init -PciListenerImp listenerA(encoder.pinA, doA); -PciListenerImp listenerB(encoder.pinB, doB); -``` -Finally, after running `encoder.init()` you skip the call of the `encoder.enableInterrupts()` and call the `PCIManager` library to register the interrupts for all the encoder channels. -```cpp -// initialise encoder hardware -encoder.init(); -// interrupt intitialisation -PciManager.registerListener(&listenerA); -PciManager.registerListener(&listenerB); -``` -And that is it, it is very simple. It if you wnat more than one encoder, you just initialise the new class instance, create the new `A` and `B` callbacks, intialise the new listeners. Here is a quick example: -```cpp -// encoder 1 -Encoder enc1 = Encoder(9, 10, 8192); -void doA1(){enc1.handleA();} -void doB1(){enc1.handleB();} -PciListenerImp listA1(enc1.pinA, doA1); -PciListenerImp listB1(enc1.pinB, doB1); - -// encoder 2 -Encoder enc2 = Encoder(13, 12, 8192); -void doA2(){enc2.handleA();} -void doB2(){enc2.handleB();} -PciListenerImp listA2(enc2.pinA, doA2); -PciListenerImp listB2(enc2.pinB, doB2); - -void setup(){ -... - // encoder 1 - enc1.init(); - PciManager.registerListener(&listA1); - PciManager.registerListener(&listB1); - // encoder 2 - enc2.init(); - PciManager.registerListener(&listA2); - PciManager.registerListener(&listB2); -... -} -``` -You can look into the `HMBGC_example.ino` ecxample to see this code in action. -##### Index pin configuration -Enabling index pin in the case of the software interrupt is very simple. You just need to provide it to the `Encoder` class intialisation as additional parameter. -```cpp -Encoder encoder = Encoder(pinA, pinB, cpr, index_pin); -``` -Afterward you create the same type of callback buffering function as for `A` and `B` channels and using the `PCIManager` tools initialise and register the listener for the `index` channel as for the `A` and `B`. Here is a quick example: -xample: -```cpp -// class init -Encoder encoder = Encoder(9, 10, 8192,11); -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} -void doIndex(){encoder.handleIndex();} -// listeners init -PciListenerImp listenerA(encoder.pinA, doA); -PciListenerImp listenerB(encoder.pinB, doB); -PciListenerImp listenerIndex(encoder.index_pin, doIndex); - -void setup(){ -... - // enable the hardware - enc1.init(); - // enable interrupt - PciManager.registerListener(&listenerA); - PciManager.registerListener(&listenerB); - PciManager.registerListener(&listenerIndex); -... -} -``` -## Magnetic sensor setup -In order to use your magnetic position sensor with Simple FOC library first create an instance of the `MagneticSensor` class: -```cpp -// MagneticSensor(int cs, float _cpr, int _angle_register) -// cs - SPI chip select pin -// _cpr - counts per revolution -// _angle_register - (optional) angle read register - default 0x3FFF -MagneticSensor sensor = MagneticSensor(10, 16384, 0x3FFF); -``` -The parameters of the class is the `chip select` pin number you connected your sensor to, the range of your sensor (counter value for full rotation) and your `angle register` number telling the library which register value should it ask the sensor for in order to retrieve the angle value. The default `angle_register` number is set to `0x3FFF` as it is the angle register for most of the low cost AS5x4x sensors. - -Finally after the inialisalisation the only thing you need to do afterwards is to call the `init()` function. This function prepares the SPI interface and initialises the sensor hardware. So your magnetic sensor intialisation code will look like: -```cpp -MagneticSensor sensor = MagneticSensor(10, 16384, 0x3FFF); - -void loop(){ - ... - sensor.init(); - ... -} -``` - -If you wish to use more than one magnetic sensor, make sure you connect their `chip select` pins to different arduino pins and follow the same idea as above, here is a simple example: -```cpp -MagneticSensor sensor1 = MagneticSensor(10, 16384, 0x3FFF); -MagneticSensor sensor1 = MagneticSensor(9, 16384, 0x3FFF); - -void loop(){ - ... - sensor1.init(); - sensor2.init(); - ... -} -``` - -Please check the `magnetic_sensor_only_example.ino` example to see more about it. -## Motor setup -To intialise the motor you need to input the `pwm` pins, number of `pole pairs` and optionally driver `enable` pin. -```cpp -// BLDCMotor( int phA, int phB, int phC, int pp, int en) -// - phA, phB, phC - motor A,B,C phase pwm pins -// - pp - pole pair number -// - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); -``` -If you are not sure what your `pole_paris` number is I included an example code to estimate your `pole_paris` number in the examples `find_pole_pairs_number.ino`. I hope it helps. - -To finalise the motor setup the sensor is added to the motor and the `init` function is called. -```cpp -// link the motor to the sensor -// either Encoder class or MagenticSensor class -motor.linkSensor(&sensor); -// intialise motor -motor.init(); -``` - - -### Power supply voltage -The default `power_supply_voltage` value is set to `12V`. If you set your power supply to some other vlaue, chnage it here for the control loops to adapt. -```cpp -// power supply voltage -motor.power_supply_voltage = 12; -``` -The `power_supply_voltage` value tells the FOC algorithm what is the maximum voltage it can output. Additioanlly since the FOC algotihm implemented in the Simple FOC library uses sinusoidal voltages the magnitudes of the sine waves exiting the Drvier circuit is going to be `[-power_supply_voltage/2, power_supply_voltage/2]`. - - - - -## Control loop setup -The SimpleFOC library gives you the choice of using 4 different plug and play control loops: -- voltage control loop -- velocity control loop -- angle control loop - -You set it by changing the `motor.controller` variable. If you want to control the motor angle you will set the `controller` to `ControlType::angle`, if you seek the DC motor behavior behaviour by controlling the voltage use `ControlType::voltage`, if you wish to control motor angular velocity `ControlType::velocity`. -```cpp -// set FOC loop to be used -// ControlType::voltage -// ControlType::velocity -// ControlType::angle -motor.controller = ControlType::angle; -``` -### Voltage control loop -This control loop allows you to run the BLDC motor as it is simple DC motor using Park transformation. This mode is enabled by: -```cpp -// voltage control loop -motor.controller = ControlType::voltage; -``` - - -You rcan test this algoithm by running the example `voltage_control.ino`. -The FOC algorithm reads the angle a from the motor and sets appropriate ua, ub and uc voltages such to always have 90 degree angle in between the magnetic fields of the permanent magents in rotor and the stator. What is exaclty the principle of the DC motor. -> This control loop will give you the motor which spins freely with the velocity depending on the voltage $U_q$ you set and the disturbance it is facing. *It will turn slower if you try to hold it*. - - -### Velocity control loop -This control loop allows you to spin your BLDC motor with desired velocity. This mode is enabled by: -```cpp -// velocity control loop -motor.controller = ControlType::velocity; -``` - - - -You can test this algorithm by running the example `velocity_control.ino`. -The velocity control is created by adding a PI velocity controller. This controller reads the motor velocity v, filteres it to vf and sets the uq voltage to the motor in a such maner that it reaches and maintains the target velocity vd, set by the user. -#### PI controller parameters -To change the parameters of your PI controller to reach desired behaiour you can change `motor.PI_velocity` structure: -```cpp -// contoller configuration based on the controll type -// velocity PI controller parameters -// default P=0.5 I = 10 -motor.PI_velocity.P = 0.2; -motor.PI_velocity.I = 20; -//defualt voltage_power_supply/2 -motor.PI_velocity.voltage_limit = 6; -// jerk control using voltage voltage ramp -// default value is 300 volts per sec ~ 0.3V per millisecond -motor.PI_velocity.voltage_ramp = 1000; - -// velocity low pass filtering -// default 5ms - try different values to see what is the best. -// the lower the less filtered -motor.LPF_velocity.Tf = 0.01; -``` -The parameters of the PI controller are proportional gain `P`, integral gain `I`, voltage limit `voltage_limit` and `voltage_ramp`. -- The `voltage_limit` parameter is intended if, for some reason, you wish to limit the voltage that can be sent to your motor. -- In general by raising the proportional gain `P` your motor controller will be more reactive, but too much will make it unstable. Setting it to `0` will disable the proportional part of the controller. -- The same goes for integral gain `I` the higher it is the faster motors reaction to disturbance will be, but too large value will make it unstable. Setting it to `0` will disable the integral part of the controller. -- The `voltage_ramp` value it intended to reduce the maximal change of the voltage value which is sent to the motor. The higher the value the PI controller will be able to change faster the Uq value. The lower the value the smaller the possible change and the less responsive your controller becomes. The value of this parameter is set to be `Volts per second[V/s` or in other words how many volts can your controller raise the voltage in one time unit. If you set your `voltage_ramp` value to `10 V/s`, and on average your contol loop will run each `1ms`. Your controller will be able to chnage the Uq value each time `10[V/s]*0.001[s] = 0.01V` waht is not a lot. - -Additionally, in order to smooth out the velocity measuement Simple FOC library has implemented the velocity low pass filter. [Low pass filters](https://en.wikipedia.org/wiki/Low-pass_filter) are standard form of signal smoothing, and it only has one parameter - filtering time constant `Tf`. -- The lower the value the less influence the filter has. If you put `Tf` to `0` you basically remove the filter completely. The exact `Tf` value for specific implementation is hard guess in advance, but in general the range of values of `Tf` will be somewhere form `0` to `0.5` seconds. - -In order to get optimal performance you will have to fiddle a bit with with the parameters. :) - -#### Control theory lovers corner :D -Transfer funciton of the PI contorller this library implements is: - -

- -Continiuos PI is discretized using Tustin transform. The final discrete equation becomes: - -

- -Where the u(k) is the control signal (voltage Uq in our case) in moment k, e(k),e(k-1) is the tracking error in current moment k and previous step k-1. Tracking error presents the difference in between the target velocity value vd and measured velocity v. - -

- -Transfer funciton of the Low pass filter is contorller is: - -

-In it discrete form it becomes: - -

- -where vf(k) is filtered velocity value in moment k, v(k) is the measured velocity in the moment k, Tf is the filter time constant and Ts is the sampling time (or time in between executions of the equation). -This low pass filter can be also written in the form: - -

- -where: - -

- -This makes it a bit more clear what the time constat `Tf` of the Low pass filter stands for. If your sample time is around 1millisecond (for arduino UNO this can be taken as an average) then setting the -`Tf` value to `Tf = 0.01` will result in: - -```cpp -alpha = 0.01/(0.01 + 0.001) = 0.91 -``` - -Which means that your actual velocity measurement v will influence the filtered value vf with the coeficient `1-alpha = 0.09` which is going to smooth the velocity values considerably (maybe even too muuch, depends of the application). - - - -### Angle control loop -This control loop allows you to move your BLDC motor to the desired angle in real time. This mode is enabled by: -```cpp -// angle control loop -motor.controller = ControlType::angle; -``` - - - -You can test this algorithm by running the example `angle_control.ino`. -The angle control loop is done by adding one more control loop in cascade on the velocity control loop like showed on the figure above. The loop is closed by using simple P controller. The controller reads the angle a from the motor and determins which velocity vd the motor should move to reach desire angle ad set by the user. And then the velocity controller reads the current filtered velocity from the motor vf and sets the voltage uq that is neaded to reach the velocity vd, set by the angle loop. - -#### Controller parameters -To tune this control loop you can set the parameters to both angle P controller and velocity PI controller. -```cpp -// contoller configuration based on the controll type -// velocity PI controller parameters -// default P=0.5 I = 10 -motor.PI_velocity.P = 0.2; -motor.PI_velocity.I = 20; -//defualt voltage_power_supply/2 -motor.PI_velocity.voltage_limit = 6; -// jerk control using voltage voltage ramp -// default value is 300 volts per sec ~ 0.3V per millisecond -motor.PI_velocity.voltage_ramp = 1000; - -// velocity low pass filtering -// default 5ms - try different values to see what is the best. -// the lower the less filtered -motor.LPF_velocity.Tf = 0.01; - -// angle P controller -// default P=20 -motor.P_angle.P = 20; -// maximal velocity of the poisiiton control -// default 20 -motor.P_angle.velocity_limit = 4; -``` -It is important to paramter both velocity PI and angle P controller to have the optimal performance. -The velocity PI controller is parametrisized by updating the `motor.PI_velcity` structure as expalined before. -- Rough rule should be to lower the proportional gain `P` in order to achieve less vibrations. -- You probably wont have to touch the `I` value. - -The angle P controller can be updated by changign the `motor.P_angle` structure. -- Roughly proportional gain `P` will make it more responsive, but too high value will make it unstable. - -For the angle control you will be able to see the influence of the velocity LPF filter as well. But the `Tf` value should not change much form the velocity control. So once you have it tuned for the velocity loop you can leave it as is. - -Additionally you can configure the `velocity_limit` value of the controller. This value prevents the contorller to set too high velocities $v_d$ to the motor. -- If you make your `velocity_limit` very low your motor will be moving in between desired positions with exactly this velocity. If you keep it high, you will not notice that this variable even exists. :D - -Finally, each application is a bit different and the chances are you will have to tune the controller values a bit to reach desired behaviour. - - -### Index search routine -Finding the encoder index is performed only if the constructor of the `Encoder` class has been provided with the `index` pin. The search is performed by setting a constant velocity of the motor until it reaches the index pin. To set the desired searching velocity alter the paramterer: -```cpp -// index search velocity - default 1rad/s -motor.index_search_velocity = 2; -``` - -This velocity control loop is implemented exaclty the same as [velocity control loop](#velocity-control-loop) but it has different contorller paramters which can be set by: -```cpp -// index search PI contoller parameters -// default K=0.5 Ti = 0.01 -motor.PI_velocity_index_search.P = 0.1; -motor.PI_velocity_index_search.I = 0.01; -motor.PI_velocity_index_search.voltage_limit = 3; -// jerk control using voltage voltage ramp -// default value is 100 volts per sec ~ 0.1V per millisecond -motor.PI_velocity_index_search.voltage_ramp = 300; -``` -If you are having problems during the finding procedure, try tuning the PI controller constants. The same parameters as the `PI_velocity` should work well, but you can put it a bit more conservative to avoid high jumps. - - -## FOC routine -### Intialisation - `setup()` -After the motor and encoder are intialised and the driver and control loops are configured you intialise the FOC algorithm. -```cpp -// align encoder and start FOC -motor.initFOC(); -``` -This function aligns encoder and motor zero positions and intialises FOC variables. It is intended to be run in the `setup` function of the Arudino. After the call of this funciton FOC is ready to start following your instructions. - -### Real-time execution `loop()` - -The real time execution of the Arduino Simple FOC library is govenred by two funcitons `motor.loopFOC()` and `motor.move(float target)`. -```cpp -// iterative setting FOC pahse voltage -// the faster you run this funciton the better -// in arduino loop it should have ~1kHz -// the best would be to be in ~10kHz range -motor.loopFOC(); -``` -The funciton `loopFOC()` gets the current motor angle from the encoder, turns in into the electrical angle and computes Clarke transfrom to set the desired Uq voltage to the motor. Basically it implements the funcitonality of the [voltage control loop](#voltage-control-loop). -- The faster you can run this funciton the better -- In the empty arduino loop it runs at ~1kHz but idealy it would be around ~10kHz - - -```cpp -// iterative function setting the outter loop target -// velocity, position or voltage -// this funciton can be run at much lower frequency than loopFOC funciton -// it can go as low as ~50Hz -motor.move(target); -``` -The `move()` method executes the control loops of the algorihtm. If is governed by the `motor.controller` variable. It executes eigther pure voltage loop, velocity loop or angle loop. - -It receives one parameter `BLDCMotor::move(float target)` which is current user define target value. -- If the user runs [velocity loop](#velocity-control-loop), `move` funciton will interpret `target` as the target velocity vd. -- If the user runs [angle loop](#angle-control-loop), `move` will interpret `target` parameter as the target anglead. -- If the user runs the [voltage loop](#voltage-control-loop), `move` funciton will interpret the `target` parameter as voltage ud. - - -> At this point because we are oriented to simplicity we did not implement synchornious version of this code. Uing timer interrupt. The main reason for the moment is that Arduino UNO doesn't have enough timers to run it. -> *But in future we are planning to include this functionality.* - -## Examples -Examples folder structure -```shell -│ examples -│ ├─── encoder examples # EXMAPLES OF ENCODER APPLICATIONS -│ │ ├───angle_control # example of angle control loop with configuraiton -│ │ ├───change_direction # simple motor changing velocity direction in real time -│ │ ├───encoder_example # simple example of encoder usage -│ │ ├───find_pole_pairs_number # simple code example estimating pole pair number of the motor -│ │ ├───HMBGC_example # example of code to be used with HMBGC controller with -│ │ ├───velocity_control # example of velocity control loop with configuraiton -│ │ ├───voltage_control # example of the voltage control loop with configuraiton -│ │ └───velocity_PI_tuning # code example of tuning velcity controller by using serial terminal -│ │ -│ └─── magnetic sensor examples # EXMAPLES OF MAGENETIC SENSOR APPLICATIONS AS5047/48 -│ ├───angle_control # example of angle control loop with configuraiton -│ ├───change_direction # simple motor changing velocity direction in real time -│ ├───find_pole_pairs_number # simple code example estimating pole pair number of the motor -│ ├───magnetic_sensor_only_example # simple example of magnetic sensor usage -│ ├───velocity_control # example of velocity control loop with configuraiton -│ ├───voltage_control # example of the voltage control loop with configuraiton -│ └───velocity_PI_tuning # code example of tuning velcity controller by using serial terminal -``` -## Simple FOC library source structure: -```shell -│ src -│ │ -│ ├─ SimpleFOC.h # SimpleFOC library include file -│ │ -│ ├─ BLDCMotor.cpp/h # BLDCMotor class implementing all the FOC operations -│ │ -│ ├─ Sensor.h # Abstract Sensor class that all the sensors implement -│ ├─ Encoder.cpp/h # Enocder class implementing the Quadrature encoder operations -│ ├─ MagneticSensor.cpp/h # class implementing SPI angle read and interface for AS5047/8 type sensors -│ │ -│ └─ FOCutils.cpp/h # Utility functions -``` +- Then you just open it with the Arduino IDE and run it. +## Documentation +Find out more information about the Arduino SimpleFOC project in [docs website](https://askuric.github.io/Arduino-FOC/) -# Debugging -`BLDCMotor` clsss supports debugging using `Serial` port which is enabled by: -```cpp -motor.useDebugging(Serial); -``` -before running `motor.init()`. -The class will output its status during the intialisation of the motor and the FOC. Enabling tyhe debugger will not directly influence the real-time performance. By default the class will stop its debugging output once it goes to the main loop. - -To debug control loop exection in the examples we added a funciton `motor.monitor()` which log the motor variables to the serial port. The funciton logs different variables based for differenc control loops. -```cpp -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void BLDCMotor::monitor() { - if(!debugger) return; - switch (controller) { - case ControlType::velocity: - debugger->print(voltage_q); - debugger->print("\t"); - debugger->print(shaft_velocity_sp); - debugger->print("\t"); - debugger->println(shaft_velocity); - break; - case ControlType::angle: - debugger->print(voltage_q); - debugger->print("\t"); - debugger->print(shaft_angle_sp); - debugger->print("\t"); - debugger->println(shaft_angle); - break; - case ControlType::voltage: - debugger->print(voltage_q); - debugger->print("\t"); - debugger->print(shaft_angle); - debugger->print("\t"); - debugger->println(shaft_velocity); - break; - } -} -``` -The intention of this method is to be called in main loop funciton along the `loopFOC()` and `move()` funciton. Thsi funciton is going to impaire the execution perfomance and reduce the sampling frequency so therefore take it in consideration when running the code. - -If you wish to implement you own debugging functions or just output the motor variables to the `Serial` terminal here are the public varaibles of the `BLDCMotor` class. - - -```cpp - -class BLDCMotor -{ - public: - ... - // current motor angle - float shaft_angle; - // current motor velocity - float shaft_velocity; - // current target velocity - float shaft_velocity_sp; - // current target angle - float shaft_angle_sp; - // current voltage u_q set - float voltage_q; -... -} -``` -Additionally it is possible to use encoder api directly to get the encoder angle and velocity. -```cpp - -class Encoder{ - public: - // shaft velocity getter - float getVelocity(); - // shaft angle getter - float getAngle(); -} -``` -As well as magnetic sensor's api, to get the sensor's angle and velocity. -```cpp - -class MagneticSensor{ - public: - // shaft velocity getter - float getVelocity(); - // shaft angle getter - float getAngle(); -} -``` - -# Work Roadmap -## Future work -- [ ] Proper introduction of the **Arudino FOC Shield V1.2** -- [ ] Publish a video tutorial fir using the library and the samples - - [x] Initial video with simple demonstration - - [ ] Coding setup and procedure video - - [ ] Two motors running on HMBGC example - - [ ] .... -- [ ] Implement Space Vector Modulation method - - [ ] Pure SVM - - [ ] PWM SVM -- [ ] Implement support for MOSFET control low and high pairs - -## Work in progress -- [x] Make the library accesible in the Arduino Library Manager -- [x] Make minimal version of the arduino code - all in one arduino file -- [x] Encoder index proper implementation -- [x] Enable more dirver types -- [x] Make support for magnetic encoder AS5048 ABI -- [x] Make support for magnetic encoder AS5048 SPI -- [x] Add support for acceleration ramping -- [x] Velocity Low pass filter -- [x] Timer interrupt execution rather than in the `loop()` - - FAIL: Perfromance not improved -- [x] Sine wave lookup table implementation - -# Contact -Please do not hesitate to leave an issue or contact me direclty by email. -I will be very happy to hear your experiences. -antun.skuric@outlook.com \ No newline at end of file +## Arduino FOC repo structure +Branch | Description | Status +------------ | ------------- | ------------ +[master](https://github.com/askuric/Arduino-FOC) | Stable and tested library version | ![Library Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Compile/badge.svg) +[dev](https://github.com/askuric/Arduino-FOC/tree/dev) | Developement library version | ![Library Dev Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Dev%20Compile/badge.svg?branch=dev) +[minimal](https://github.com/askuric/Arduino-FOC/tree/minimal) | Minimal Arduino example with integrated library | ![MinimalBuild](https://github.com/askuric/Arduino-FOC/workflows/MinimalBuild/badge.svg?branch=minimal) From c7405df8b685decad5f8b0eda0890d76a93e36b3 Mon Sep 17 00:00:00 2001 From: askuric Date: Fri, 8 May 2020 10:20:38 +0200 Subject: [PATCH 40/65] README typo --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 5aa29dda..27e8fd65 100644 --- a/README.md +++ b/README.md @@ -40,7 +40,7 @@ For those willing to experiment and to modify the code I suggest using the [mini > This code is completely indepenedet and you can run it as any other Arduino Schetch without the need for any libraries. #### Github webiste downlaod -- Go to [minimal branch](https://github.com/askuric/Arduino-FOC/tree/minimal) +- Make sure you are in [minimal branch](https://github.com/askuric/Arduino-FOC/tree/minimal) - Downlaod the code by clicking on the `Clone or Download > Download ZIP`. - Unzip it and open the schetch in Arduino IDE. From 29efc2074f993cc72f385226053935e4b115ff30 Mon Sep 17 00:00:00 2001 From: askuric Date: Fri, 15 May 2020 17:58:31 +0200 Subject: [PATCH 41/65] TYPO removed a lot typos --- README.md | 16 +- arduino_foc_minimal_encoder/BLDCMotor.cpp | 83 ++++--- arduino_foc_minimal_encoder/BLDCMotor.h | 15 +- arduino_foc_minimal_encoder/Encoder.cpp | 18 +- arduino_foc_minimal_encoder/Encoder.h | 8 +- arduino_foc_minimal_encoder/FOCutils.cpp | 8 +- arduino_foc_minimal_encoder/FOCutils.h | 12 +- .../MagneticSensor.cpp | 189 +++++++++++++++ arduino_foc_minimal_encoder/MagneticSensor.h | 71 ++++++ arduino_foc_minimal_encoder/Sensor.h | 4 +- arduino_foc_minimal_encoder/SimpleFOC.h | 1 + .../arduino_foc_minimal_encoder.ino | 20 +- arduino_foc_minimal_magnetic/BLDCMotor.cpp | 83 ++++--- arduino_foc_minimal_magnetic/BLDCMotor.h | 15 +- arduino_foc_minimal_magnetic/Encoder.cpp | 229 ++++++++++++++++++ arduino_foc_minimal_magnetic/Encoder.h | 92 +++++++ arduino_foc_minimal_magnetic/FOCutils.cpp | 8 +- arduino_foc_minimal_magnetic/FOCutils.h | 12 +- .../MagneticSensor.cpp | 10 +- arduino_foc_minimal_magnetic/MagneticSensor.h | 8 +- arduino_foc_minimal_magnetic/Sensor.h | 4 +- arduino_foc_minimal_magnetic/SimpleFOC.h | 1 + .../arduino_foc_minimal_magnetic.ino | 18 +- 23 files changed, 778 insertions(+), 147 deletions(-) create mode 100644 arduino_foc_minimal_encoder/MagneticSensor.cpp create mode 100644 arduino_foc_minimal_encoder/MagneticSensor.h create mode 100644 arduino_foc_minimal_magnetic/Encoder.cpp create mode 100644 arduino_foc_minimal_magnetic/Encoder.h diff --git a/README.md b/README.md index 27e8fd65..956b06e5 100644 --- a/README.md +++ b/README.md @@ -4,13 +4,13 @@ [![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT) [![arduino-library-badge](https://www.ardu-badge.com/badge/Simple%20FOC.svg?)](https://www.ardu-badge.com/badge/Simple%20FOC.svg) -This is the minimal Arduino example of the [Simple FOC](https://github.com/askuric/Arduino-FOC) arduino library intended for mostly for easier experiemtation and modification! +This is the minimal Arduino example of the [Simple FOC](https://github.com/askuric/Arduino-FOC) arduino library intended for mostly for easier experimentation and modification! ### Minimal repository structure ```shell ├───arduino_foc_minimal_encoder # Arduino minimal code for running a motor with Encoder │ -└───arduino_foc_minimal_magnetic # Arduino minimal code for running a motor with magentic sensor +└───arduino_foc_minimal_magnetic # Arduino minimal code for running a motor with magnetic sensor # AS5048/47 ``` @@ -32,17 +32,17 @@ Control loop type: - C2 - voltage control Initial parameters: -PI velocity P: 0.20, I: 20.00, Low passs filter Tf: 0.0000 +PI velocity P: 0.20, I: 20.00, Low pass filter Tf: 0.0000 ``` ### Installation For those willing to experiment and to modify the code I suggest using the [minimal version](https://github.com/askuric/Arduino-FOC/tree/minimal) of the code. - > This code is completely indepenedet and you can run it as any other Arduino Schetch without the need for any libraries. + > This code is completely independent and you can run it as any other Arduino Sketch without the need for any libraries. -#### Github webiste downlaod +#### Github website download - Make sure you are in [minimal branch](https://github.com/askuric/Arduino-FOC/tree/minimal) -- Downlaod the code by clicking on the `Clone or Download > Download ZIP`. -- Unzip it and open the schetch in Arduino IDE. +- Download the code by clicking on the `Clone or Download > Download ZIP`. +- Unzip it and open the sketch in Arduino IDE. #### Using terminal - Open the terminal: @@ -60,5 +60,5 @@ Find out more information about the Arduino SimpleFOC project in [docs website]( Branch | Description | Status ------------ | ------------- | ------------ [master](https://github.com/askuric/Arduino-FOC) | Stable and tested library version | ![Library Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Compile/badge.svg) -[dev](https://github.com/askuric/Arduino-FOC/tree/dev) | Developement library version | ![Library Dev Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Dev%20Compile/badge.svg?branch=dev) +[dev](https://github.com/askuric/Arduino-FOC/tree/dev) | Development library version | ![Library Dev Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Dev%20Compile/badge.svg?branch=dev) [minimal](https://github.com/askuric/Arduino-FOC/tree/minimal) | Minimal Arduino example with integrated library | ![MinimalBuild](https://github.com/askuric/Arduino-FOC/workflows/MinimalBuild/badge.svg?branch=minimal) diff --git a/arduino_foc_minimal_encoder/BLDCMotor.cpp b/arduino_foc_minimal_encoder/BLDCMotor.cpp index f231ea8a..df86ad5f 100644 --- a/arduino_foc_minimal_encoder/BLDCMotor.cpp +++ b/arduino_foc_minimal_encoder/BLDCMotor.cpp @@ -4,10 +4,10 @@ // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - cpr - counts per rotation number (cpm=ppm*4) -// - enable pin - (optionl input) +// - enable pin - (optional input) BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) { - // Pin intialization + // Pin initialization pwmA = phA; pwmB = phB; pwmC = phC; @@ -16,7 +16,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // enable_pin pin enable_pin = en; - // Power supply woltage + // Power supply voltage voltage_power_supply = DEF_POWER_SUPPLY; // Velocity loop config @@ -61,7 +61,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // init hardware pins void BLDCMotor::init() { - if(debugger) debugger->println("DEBUG: Initilaise the motor pins."); + if(debugger) debugger->println("DEBUG: Initialize the motor pins."); // PWM pins pinMode(pwmA, OUTPUT); pinMode(pwmB, OUTPUT); @@ -118,7 +118,7 @@ void BLDCMotor::linkSensor(Sensor* _sensor) { // Encoder alignment to electrical 0 angle int BLDCMotor::alignSensor() { if(debugger) debugger->println("DEBUG: Align the sensor's and motor electrical 0 angle."); - // align the electircal phases of the motor and sensor + // align the electrical phases of the motor and sensor setPwm(pwmA, voltage_power_supply/2.0); setPwm(pwmB,0); setPwm(pwmC,0); @@ -159,7 +159,7 @@ int BLDCMotor::absoluteZeroAlign() { // disable motor setPhaseVoltage(0,0); - // align absoulute zero if it has been found + // align absolute zero if it has been found if(!sensor->needsAbsoluteZeroSearch()){ // align the sensor with the absolute zero float zero_offset = sensor->initAbsoluteZero(); @@ -182,7 +182,7 @@ float BLDCMotor::shaftVelocity() { float Ts = (_micros() - LPF_velocity.timestamp) * 1e-6; // quick fix for strange cases (micros overflow) if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - // calculate the fitering + // calculate the filtering float alpha = LPF_velocity.Tf/(LPF_velocity.Tf + Ts); float vel = alpha*LPF_velocity.prev + (1-alpha)*sensor->getVelocity(); // save the variables @@ -197,7 +197,7 @@ float BLDCMotor::electricAngle(float shaftAngle) { } /** - FOC funcitons + FOC functions */ // FOC initialization function @@ -214,14 +214,14 @@ int BLDCMotor::initFOC() { void BLDCMotor::loopFOC() { // shaft angle shaft_angle = shaftAngle(); - // set the phase voltage - FOC heart funciton :) + // set the phase voltage - FOC heart function :) setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); } -// Iterative funciton running outer loop of the FOC algorithm -// Bahvior of this funciton is determined by the motor.controller variable -// It runs either angle, veloctiy or voltage loop -// - needs to be called iteratively it is asynchronious function +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function void BLDCMotor::move(float target) { // get angular velocity shaft_velocity = shaftVelocity(); @@ -238,7 +238,7 @@ void BLDCMotor::move(float target) { break; case ControlType::velocity: // velocity set point - // inlcude velocity loop + // include velocity loop shaft_velocity_sp = target; voltage_q = velocityPI(shaft_velocity_sp - shaft_velocity); break; @@ -250,16 +250,16 @@ void BLDCMotor::move(float target) { void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // angle normalisation in between 0 and 2pi - // only necessary if using _sin and _cos - approximation funcitons + // only necessary if using _sin and _cos - approximation functions float angle = normalizeAngle(angle_el + zero_electric_angle); // Inverse park transform - // regular sin + cos ~300us (no memeory usaage) + // regular sin + cos ~300us (no memory usaage) // approx _sin + _cos ~110us (400Byte ~ 20% of memory) // Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; // Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; - + // Clarke transform Ua = Ualpha; Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta; @@ -273,24 +273,17 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // Set voltage to the pwm pin -// - function a bit optimised to get better performance +// - function a bit optimized to get better performance void BLDCMotor::setPwm(int pinPwm, float U) { // max value float U_max = voltage_power_supply/2.0; // sets the voltage [-U_max,U_max] to pwm [0,255] // u_pwm = 255 * (U + U_max)/(2*U_max) - // it can be further optimised + // it can be further optimized // (example U_max = 6 > U_pwm = 127.5 + 21.25*U) int U_pwm = 127.5 * (U/U_max + 1); - - - // float U_max = voltage_power_supply; - // // sets the voltage [0,12V(U_max)] to pwm [0,255] - // // - U_max you can set in header file - default 12V - // // - support for HMBGC controller - // int U_pwm = 255.0 * (float)U / (float)U_max; - + // limit the values between 0 and 255 U_pwm = (U_pwm < 0) ? 0 : (U_pwm >= 255) ? 255 : U_pwm; @@ -298,7 +291,7 @@ void BLDCMotor::setPwm(int pinPwm, float U) { } /** - Utility funcitons + Utility functions */ // normalizing radian angle to [0,2PI] float BLDCMotor::normalizeAngle(float angle){ @@ -321,7 +314,7 @@ float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){ if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; // u(s) = (P + I/s)e(s) - // tustin discretisation of the PI controller ( a bit optimised ) + // Tustin transform of the PI controller ( a bit optimized ) // uk = uk_1 + (I*Ts/2 + P)*ek + (I*Ts/2 - P)*ek_1 float tmp = cont.I*Ts*0.5; float voltage = cont.voltage_prev + (tmp + cont.P) * tracking_error + (tmp - cont.P) * cont.tracking_error_prev; @@ -355,8 +348,36 @@ float BLDCMotor::positionP(float ek) { /** * Debugger functions */ -// funciton implementing the debugger setter +// function implementing the debugger setter void BLDCMotor::useDebugging(Print &print){ - debugger = &print; //operate on the adress of print + debugger = &print; //operate on the address of print if(debugger )debugger->println("DEBUG: Serial debugger enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void BLDCMotor::monitor() { + if(!debugger) return; + switch (controller) { + case ControlType::velocity: + debugger->print(voltage_q); + debugger->print("\t"); + debugger->print(shaft_velocity_sp); + debugger->print("\t"); + debugger->println(shaft_velocity); + break; + case ControlType::angle: + debugger->print(voltage_q); + debugger->print("\t"); + debugger->print(shaft_angle_sp); + debugger->print("\t"); + debugger->println(shaft_angle); + break; + case ControlType::voltage: + debugger->print(voltage_q); + debugger->print("\t"); + debugger->print(shaft_angle); + debugger->print("\t"); + debugger->println(shaft_velocity); + break; + } } \ No newline at end of file diff --git a/arduino_foc_minimal_encoder/BLDCMotor.h b/arduino_foc_minimal_encoder/BLDCMotor.h index 6d62a56e..2ee03629 100644 --- a/arduino_foc_minimal_encoder/BLDCMotor.h +++ b/arduino_foc_minimal_encoder/BLDCMotor.h @@ -2,6 +2,8 @@ #define BLDCMotor_h #include "Arduino.h" +#include "MagneticSensor.h" +#include "Encoder.h" #include "FOCutils.h" #include "Sensor.h" @@ -32,7 +34,7 @@ enum ControlType{ angle }; -// PI controller strucutre +// PI controller structure struct PI_s{ float P; float I; @@ -68,7 +70,7 @@ class BLDCMotor - phA, phB, phC - motor A,B,C phase pwm pins - pp - pole pair number - cpr - counts per rotation number (cpm=ppm*4) - - enable pin - (optionl input) + - enable pin - (optional input) */ BLDCMotor(int phA,int phB,int phC,int pp, int en = 0); // change driver state @@ -112,10 +114,10 @@ class BLDCMotor // current voltage u_q set float voltage_q; - // Power supply woltage + // Power supply voltage float voltage_power_supply; - // configuraion structures + // configuration structures ControlType controller; PI_s PI_velocity; PI_s PI_velocity_index_search; @@ -137,6 +139,7 @@ class BLDCMotor // debugging void useDebugging(Print &print); + void monitor(); Print* debugger; float Ua,Ub,Uc; @@ -144,7 +147,7 @@ class BLDCMotor private: //Sensor alignment to electrical 0 angle int alignSensor(); - //Motor and sensor alignement to the sensors absolute 0 angle + //Motor and sensor alignment to the sensors absolute 0 angle int absoluteZeroAlign(); //Electrical angle calculation @@ -152,7 +155,7 @@ class BLDCMotor //Set phase voltaget to pwm output void setPwm(int pinPwm, float U); - /** Utility funcitons */ + /** Utility functions */ //normalizing radian angle to [0,2PI] float normalizeAngle(float angle); // determining if the enable pin has been provided diff --git a/arduino_foc_minimal_encoder/Encoder.cpp b/arduino_foc_minimal_encoder/Encoder.cpp index 85cb8142..da6f78e2 100644 --- a/arduino_foc_minimal_encoder/Encoder.cpp +++ b/arduino_foc_minimal_encoder/Encoder.cpp @@ -26,7 +26,7 @@ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ index_pin = _index; // its 0 if not used index_pulse_counter = 0; - // velocity calculation varibles + // velocity calculation variables prev_Th = 0; pulse_per_second = 0; prev_pulse_counter = 0; @@ -87,7 +87,7 @@ void Encoder::handleIndex() { if(hasIndex()){ int I = digitalRead(index_pin); if(I && !I_active){ - // aling encoder on each index + // align encoder on each index if(index_pulse_counter){ long tmp = pulse_counter; // corrent the counter value @@ -111,7 +111,7 @@ float Encoder::getAngle(){ } /* Shaft velocity calculation - funciton using mixed time and frequency measurement technique + function using mixed time and frequency measurement technique */ float Encoder::getVelocity(){ // timestamp @@ -157,20 +157,20 @@ int Encoder::needsAbsoluteZeroSearch(){ int Encoder::hasAbsoluteZero(){ return hasIndex(); } -// intialise counter to zero +// initialize counter to zero float Encoder::initRelativeZero(){ long angle_offset = -pulse_counter; pulse_counter = 0; pulse_timestamp = _micros(); return _2PI * (angle_offset) / ((float)cpr); } -// intialise index to zero +// initialize index to zero float Encoder::initAbsoluteZero(){ pulse_counter -= index_pulse_counter; prev_pulse_counter = pulse_counter; return (index_pulse_counter) / ((float)cpr) * (_2PI); } -// private funciton used to determine if encoder has index +// private function used to determine if encoder has index int Encoder::hasIndex(){ return index_pin != 0; } @@ -194,7 +194,7 @@ void Encoder::init(){ // counter setup pulse_counter = 0; pulse_timestamp = _micros(); - // velocity calculation varibles + // velocity calculation variables prev_Th = 0; pulse_per_second = 0; prev_pulse_counter = 0; @@ -206,7 +206,7 @@ void Encoder::init(){ } -// funciton enabling hardware interrupts of the for the callback provided +// function enabling hardware interrupts of the for the callback provided // if callback is not provided then the interrupt is not enabled void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){ // attach interrupt if functions provided @@ -223,7 +223,7 @@ void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){ break; } - // if index used intialise the index interrupt + // if index used initialize the index interrupt if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE); } diff --git a/arduino_foc_minimal_encoder/Encoder.h b/arduino_foc_minimal_encoder/Encoder.h index 084fe16f..d115fe25 100644 --- a/arduino_foc_minimal_encoder/Encoder.h +++ b/arduino_foc_minimal_encoder/Encoder.h @@ -6,7 +6,7 @@ #include "Sensor.h" -// Pullup configuation structure +// Pullup configuration structure enum Pullup{ INTERN, EXTERN @@ -29,7 +29,7 @@ class Encoder: public Sensor{ // encoder initialise pins void init(); - // funciton enabling hardware interrupts of the for the callback provided + // function enabling hardware interrupts of the for the callback provided // if callback is not provided then the interrupt is not enabled void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr); @@ -57,7 +57,7 @@ class Encoder: public Sensor{ float getAngle(); // get current angular velocity (rad/s) float getVelocity(); - // set current agle as zero angle + // set current angle as zero angle // return the angle [rad] difference float initRelativeZero(); // set index angle as zero angle @@ -82,7 +82,7 @@ class Encoder: public Sensor{ volatile int I_active; // index active volatile long index_pulse_counter; // pulse counter of the index - // velocity calculation varibles + // velocity calculation variables float prev_Th, pulse_per_second; volatile long prev_pulse_counter, prev_timestamp_us; diff --git a/arduino_foc_minimal_encoder/FOCutils.cpp b/arduino_foc_minimal_encoder/FOCutils.cpp index 5a383f3d..c9f0db4c 100644 --- a/arduino_foc_minimal_encoder/FOCutils.cpp +++ b/arduino_foc_minimal_encoder/FOCutils.cpp @@ -22,16 +22,16 @@ void setPwmFrequency(int pin) { } } -// funciton buffering delay() -// arduino funciton doesn't work well with interrupts +// function buffering delay() +// arduino function doesn't work well with interrupts void _delay(unsigned long ms){ long t = _micros(); while((_micros() - t)/1000 < ms){}; } -// funciton buffering _micros() -// arduino funciton doesn't work well with interrupts +// function buffering _micros() +// arduino function doesn't work well with interrupts unsigned long _micros(){ // return the value based on the prescaler if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); diff --git a/arduino_foc_minimal_encoder/FOCutils.h b/arduino_foc_minimal_encoder/FOCutils.h index d6177497..d431ad28 100644 --- a/arduino_foc_minimal_encoder/FOCutils.h +++ b/arduino_foc_minimal_encoder/FOCutils.h @@ -3,7 +3,7 @@ #include "Arduino.h" -// sign funciton +// sign function #define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) // utility defines #define _2_SQRT3 1.15470053838 @@ -18,19 +18,19 @@ // High PWM frequency void setPwmFrequency(int pin); -// funciton buffering delay() -// arduino funciton doesn't work well with interrupts +// function buffering delay() +// arduino function doesn't work well with interrupts void _delay(unsigned long ms); -// funciton buffering _micros() -// arduino funciton doesn't work well with interrupts +// function buffering _micros() +// arduino function doesn't work well with interrupts unsigned long _micros(); // function approximating the sine calculation by using fixed size array // ~40us // it has to receive an angle in between 0 and 2PI float _sin(float a); -// function approfimating cosine calculaiton by using fixed size array +// function approximating cosine calculation by using fixed size array // ~50us // it has to receive an angle in between 0 and 2PI float _cos(float a); diff --git a/arduino_foc_minimal_encoder/MagneticSensor.cpp b/arduino_foc_minimal_encoder/MagneticSensor.cpp new file mode 100644 index 00000000..d045eab5 --- /dev/null +++ b/arduino_foc_minimal_encoder/MagneticSensor.cpp @@ -0,0 +1,189 @@ +#include "MagneticSensor.h" + + +// MagneticSensor(int cs, float _cpr, int _angle_register) +// cs - SPI chip select pin +// _cpr - count per revolution +// _angle_register - (optional) angle read register - default 0x3FFF +MagneticSensor::MagneticSensor(int cs, float _cpr, int _angle_register){ + // chip select pin + chip_select_pin = cs; + // angle read register of the magnetic sensor + angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTAR; + // register maximum value (counts per revolution) + cpr = _cpr; + +} + + +void MagneticSensor::init(){ + // 1MHz clock (AMS should be able to accept up to 10MHz) + settings = SPISettings(1000000, MSBFIRST, SPI_MODE1); + + //setup pins + pinMode(chip_select_pin, OUTPUT); + + //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices + SPI.begin(); + + // velocity calculation init + angle_prev = 0; + velocity_calc_timestamp = _micros(); + + // full rotations tracking number + full_rotation_offset = 0; + angle_data_prev = getRawCount(); + zero_offset = 0; +} + +// Shaft angle calculation +// angle is in radians [rad] +float MagneticSensor::getAngle(){ + // raw data from the sensor + float angle_data = getRawCount(); + + // tracking the number of rotations + // in order to expand angle range form [0,2PI] + // to basically infinity + float d_angle = angle_data - angle_data_prev; + // if overflow happened track it as full rotation + if(abs(d_angle) > (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; + // save the current angle value for the next steps + // in order to know if overflow happened + angle_data_prev = angle_data; + + // zero offset adding + angle_data -= (int)zero_offset; + // return the full angle + // (number of full rotations)*2PI + current sensor angle + return full_rotation_offset + ( angle_data / (float)cpr) * _2PI; +} + +// Shaft velocity calculation +float MagneticSensor::getVelocity(){ + // calculate sample time + float Ts = (_micros() - velocity_calc_timestamp)*1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // current angle + float angle_c = getAngle(); + // velocity calculation + float vel = (angle_c - angle_prev)/Ts; + + // save variables for future pass + angle_prev = angle_c; + velocity_calc_timestamp = _micros(); + return vel; +} + +// set current angle as zero angle +// return the angle [rad] difference +float MagneticSensor::initRelativeZero(){ + float angle_offset = -getAngle(); + zero_offset = getRawCount(); + + // angle tracking variables + full_rotation_offset = 0; + return angle_offset; +} +// set absolute zero angle as zero angle +// return the angle [rad] difference +float MagneticSensor::initAbsoluteZero(){ + float rotation = -(int)zero_offset; + // init absolute zero + zero_offset = 0; + + // angle tracking variables + full_rotation_offset = 0; + // return offset in radians + return rotation / (float)cpr * _2PI; +} +// returns 0 if it has no absolute 0 measurement +// 0 - incremental encoder without index +// 1 - encoder with index & magnetic sensors +int MagneticSensor::hasAbsoluteZero(){ + return 1; +} +// returns 0 if it does need search for absolute zero +// 0 - magnetic sensor +// 1 - ecoder with index +int MagneticSensor::needsAbsoluteZeroSearch(){ + return 0; +} + + +// function reading the raw counter of the magnetic sensor +int MagneticSensor::getRawCount(){ + return (int)MagneticSensor::read(angle_register); +} + +// SPI functions +/** + * Utility function used to calculate even parity of word + */ +byte MagneticSensor::spiCalcEvenParity(word value){ + byte cnt = 0; + byte i; + + for (i = 0; i < 16; i++) + { + if (value & 0x1) cnt++; + value >>= 1; + } + return cnt & 0x1; +} + + /* + * Read a register from the sensor + * Takes the address of the register as a 16 bit word + * Returns the value of the register + */ +word MagneticSensor::read(word angle_register){ + word command = 0b0100000000000000; // PAR=0 R/W=R + command = command | angle_register; + + //Add a parity bit on the the MSB + command |= ((word)spiCalcEvenParity(command)<<15); + + //Split the command into two bytes + byte right_byte = command & 0xFF; + byte left_byte = ( command >> 8 ) & 0xFF; + + //SPI - begin transaction + SPI.beginTransaction(settings); + + //Send the command + digitalWrite(chip_select_pin, LOW); + SPI.transfer(left_byte); + SPI.transfer(right_byte); + digitalWrite(chip_select_pin,HIGH); + + //Now read the response + digitalWrite(chip_select_pin, LOW); + left_byte = SPI.transfer(0x00); + right_byte = SPI.transfer(0x00); + digitalWrite(chip_select_pin, HIGH); + + //SPI - end transaction + SPI.endTransaction(); + + //Check if the error bit is set + if (left_byte & 0x40) { + errorFlag = true; + } + else { + errorFlag = false; + } + + //Return the data, stripping the parity and error bits + return (( ( left_byte & 0xFF ) << 8 ) | ( right_byte & 0xFF )) & ~0xC000; +} + +/** + * Closes the SPI connection + * SPI has an internal SPI-device counter, for each init()-call the close() function must be called exactly 1 time + */ +void MagneticSensor::close(){ + SPI.end(); +} diff --git a/arduino_foc_minimal_encoder/MagneticSensor.h b/arduino_foc_minimal_encoder/MagneticSensor.h new file mode 100644 index 00000000..50665982 --- /dev/null +++ b/arduino_foc_minimal_encoder/MagneticSensor.h @@ -0,0 +1,71 @@ +#ifndef MAGNETICSENSOR_LIB_H +#define MAGNETICSENSOR_LIB_H + +#include "Arduino.h" +#include +#include "FOCutils.h" +#include "Sensor.h" + +#define DEF_ANGLE_REGISTAR 0x3FFF + +class MagneticSensor: public Sensor{ + public: + + + // MagneticSensor(int cs, float _cpr, int _angle_register) + // cs - SPI chip select pin + // _cpr - counts per revolution + // _angle_register - (optional) angle read register - default 0x3FFF + MagneticSensor(int cs, float _cpr, int angle_register = 0); + + // SPI angle register to read + int angle_register; + // encoder initialise pins + void init(); + + // implementation of abstract functions of the Sensor class + // get current angle (rad) + float getAngle(); + // get current angular velocity (rad/s) + float getVelocity(); + // set current angle as zero angle + // return the angle [rad] difference + float initRelativeZero(); + // set absolute zero angle as zero angle + // return the angle [rad] difference + float initAbsoluteZero(); + // returns 1 because it is the absolute sensor + int hasAbsoluteZero(); + // returns 0 maning it doesn't need search for absolute zero + int needsAbsoluteZeroSearch(); + + + private: + // spi variables + int chip_select_pin; + bool errorFlag; + SPISettings settings; + // spi functions + void close(); + word read(word angle_register); + byte spiCalcEvenParity(word value); + + + // zero offset + word zero_offset; + // function getting current register value + int getRawCount(); + + // total angle tracking variables + float full_rotation_offset; + float angle_data_prev; + // impulse cpr + float cpr; + // velocity calculation variables + float angle_prev; + long velocity_calc_timestamp; + +}; + + +#endif diff --git a/arduino_foc_minimal_encoder/Sensor.h b/arduino_foc_minimal_encoder/Sensor.h index 3555941a..b03c3b5f 100644 --- a/arduino_foc_minimal_encoder/Sensor.h +++ b/arduino_foc_minimal_encoder/Sensor.h @@ -9,10 +9,10 @@ class Sensor{ virtual float getAngle(); // get current angular velocity (rad/s) virtual float getVelocity(); - // set current agle as zero angle + // set current angle as zero angle // return the angle [rad] difference virtual float initRelativeZero(); - // set absoule zero angle as zero angle + // set absolute zero angle as zero angle // return the angle [rad] difference virtual float initAbsoluteZero(); diff --git a/arduino_foc_minimal_encoder/SimpleFOC.h b/arduino_foc_minimal_encoder/SimpleFOC.h index bd9ecb55..887ae8df 100644 --- a/arduino_foc_minimal_encoder/SimpleFOC.h +++ b/arduino_foc_minimal_encoder/SimpleFOC.h @@ -4,6 +4,7 @@ #include "FOCutils.h" #include "Sensor.h" #include "Encoder.h" +#include "MagneticSensor.h" #include "BLDCMotor.h" #endif diff --git a/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino b/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino index f37e7885..c531f49c 100644 --- a/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino +++ b/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino @@ -11,7 +11,7 @@ BLDCMotor motor = BLDCMotor(9, 10, 11, 11); // - ppr - impulses per rotation (cpr=ppr*4) // - index pin - (optional input) Encoder encoder = Encoder(2, 3, 2048); -// interrupt ruotine intialisation +// interrupt routine intialisation void doA(){encoder.handleA();} void doB(){encoder.handleB();} @@ -19,7 +19,7 @@ void setup() { // debugging port Serial.begin(115200); - // initialise encoder sensor hardware + // initialize encoder sensor hardware encoder.init(); encoder.enableInterrupts(doA,doB); @@ -37,7 +37,7 @@ void setup() { // velocity PI controller parameters motor.PI_velocity.P = 0.2; motor.PI_velocity.I = 20; - //defualt voltage_power_supply/2 + // default voltage_power_supply/2 motor.PI_velocity.voltage_limit = 6; // jerk control using voltage voltage ramp // default value is 300 volts per sec ~ 0.3V per millisecond @@ -59,7 +59,7 @@ void setup() { // comment out if not needed motor.useDebugging(Serial); - // intialise motor + // initialise motor motor.init(); // align encoder and start FOC motor.initFOC(); @@ -82,7 +82,7 @@ void setup() { Serial.print(motor.PI_velocity.P); Serial.print(",\t I: "); Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low passs filter Tf: "); + Serial.print(",\t Low pass filter Tf: "); Serial.println(motor.LPF_velocity.Tf,4); _delay(1000); @@ -95,7 +95,7 @@ unsigned long t = 0; long timestamp = _micros(); void loop() { - // iterative setting FOC pahse voltage + // iterative setting FOC phase voltage motor.loopFOC(); // iterative function setting the outter loop target @@ -124,7 +124,7 @@ void serialEvent() { Serial.print(motor.PI_velocity.P); Serial.print(",\t I: "); Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low passs filter Tf: "); + Serial.print(",\t Low pass filter Tf: "); Serial.println(motor.LPF_velocity.Tf,4); }else if(inputString.charAt(0) == 'I'){ motor.PI_velocity.I = inputString.substring(1).toFloat(); @@ -132,7 +132,7 @@ void serialEvent() { Serial.print(motor.PI_velocity.P); Serial.print(",\t I: "); Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low passs filter Tf: "); + Serial.print(",\t Low pass filter Tf: "); Serial.println(motor.LPF_velocity.Tf,4); }else if(inputString.charAt(0) == 'F'){ motor.LPF_velocity.Tf = inputString.substring(1).toFloat(); @@ -140,7 +140,7 @@ void serialEvent() { Serial.print(motor.PI_velocity.P); Serial.print(",\t I: "); Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low passs filter Tf: "); + Serial.print(",\t Low pass filter Tf: "); Serial.println(motor.LPF_velocity.Tf,4); }else if(inputString.charAt(0) == 'T'){ Serial.print("Average loop time is (microseconds): "); @@ -157,7 +157,7 @@ void serialEvent() { Serial.println("velocity!"); motor.controller = ControlType::velocity; }else if(cnt == 2){ - Serial.println("volatge!"); + Serial.println("voltage!"); motor.controller = ControlType::voltage; } Serial.println(); diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.cpp b/arduino_foc_minimal_magnetic/BLDCMotor.cpp index 3063f3b9..df86ad5f 100644 --- a/arduino_foc_minimal_magnetic/BLDCMotor.cpp +++ b/arduino_foc_minimal_magnetic/BLDCMotor.cpp @@ -4,10 +4,10 @@ // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - cpr - counts per rotation number (cpm=ppm*4) -// - enable pin - (optionl input) +// - enable pin - (optional input) BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) { - // Pin intialization + // Pin initialization pwmA = phA; pwmB = phB; pwmC = phC; @@ -16,7 +16,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // enable_pin pin enable_pin = en; - // Power supply woltage + // Power supply voltage voltage_power_supply = DEF_POWER_SUPPLY; // Velocity loop config @@ -61,7 +61,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // init hardware pins void BLDCMotor::init() { - if(debugger) debugger->println("DEBUG: Initilaise the motor pins."); + if(debugger) debugger->println("DEBUG: Initialize the motor pins."); // PWM pins pinMode(pwmA, OUTPUT); pinMode(pwmB, OUTPUT); @@ -118,7 +118,7 @@ void BLDCMotor::linkSensor(Sensor* _sensor) { // Encoder alignment to electrical 0 angle int BLDCMotor::alignSensor() { if(debugger) debugger->println("DEBUG: Align the sensor's and motor electrical 0 angle."); - // align the electircal phases of the motor and sensor + // align the electrical phases of the motor and sensor setPwm(pwmA, voltage_power_supply/2.0); setPwm(pwmB,0); setPwm(pwmC,0); @@ -159,7 +159,7 @@ int BLDCMotor::absoluteZeroAlign() { // disable motor setPhaseVoltage(0,0); - // align absoulute zero if it has been found + // align absolute zero if it has been found if(!sensor->needsAbsoluteZeroSearch()){ // align the sensor with the absolute zero float zero_offset = sensor->initAbsoluteZero(); @@ -182,7 +182,7 @@ float BLDCMotor::shaftVelocity() { float Ts = (_micros() - LPF_velocity.timestamp) * 1e-6; // quick fix for strange cases (micros overflow) if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - // calculate the fitering + // calculate the filtering float alpha = LPF_velocity.Tf/(LPF_velocity.Tf + Ts); float vel = alpha*LPF_velocity.prev + (1-alpha)*sensor->getVelocity(); // save the variables @@ -197,7 +197,7 @@ float BLDCMotor::electricAngle(float shaftAngle) { } /** - FOC funcitons + FOC functions */ // FOC initialization function @@ -214,14 +214,14 @@ int BLDCMotor::initFOC() { void BLDCMotor::loopFOC() { // shaft angle shaft_angle = shaftAngle(); - // set the phase voltage - FOC heart funciton :) + // set the phase voltage - FOC heart function :) setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); } -// Iterative funciton running outer loop of the FOC algorithm -// Bahvior of this funciton is determined by the motor.controller variable -// It runs either angle, veloctiy or voltage loop -// - needs to be called iteratively it is asynchronious function +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function void BLDCMotor::move(float target) { // get angular velocity shaft_velocity = shaftVelocity(); @@ -238,7 +238,7 @@ void BLDCMotor::move(float target) { break; case ControlType::velocity: // velocity set point - // inlcude velocity loop + // include velocity loop shaft_velocity_sp = target; voltage_q = velocityPI(shaft_velocity_sp - shaft_velocity); break; @@ -250,16 +250,16 @@ void BLDCMotor::move(float target) { void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // angle normalisation in between 0 and 2pi - // only necessary if using _sin and _cos - approximation funcitons + // only necessary if using _sin and _cos - approximation functions float angle = normalizeAngle(angle_el + zero_electric_angle); // Inverse park transform - // regular sin + cos ~300us (no memeory usaage) + // regular sin + cos ~300us (no memory usaage) // approx _sin + _cos ~110us (400Byte ~ 20% of memory) // Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; // Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; - + // Clarke transform Ua = Ualpha; Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta; @@ -273,24 +273,17 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // Set voltage to the pwm pin -// - function a bit optimised to get better performance +// - function a bit optimized to get better performance void BLDCMotor::setPwm(int pinPwm, float U) { // max value float U_max = voltage_power_supply/2.0; // sets the voltage [-U_max,U_max] to pwm [0,255] // u_pwm = 255 * (U + U_max)/(2*U_max) - // it can be further optimised + // it can be further optimized // (example U_max = 6 > U_pwm = 127.5 + 21.25*U) int U_pwm = 127.5 * (U/U_max + 1); - - - // float U_max = voltage_power_supply; - // // sets the voltage [0,12V(U_max)] to pwm [0,255] - // // - U_max you can set in header file - default 12V - // // - support for HMBGC controller - // int U_pwm = 255.0 * (float)U / (float)U_max; - + // limit the values between 0 and 255 U_pwm = (U_pwm < 0) ? 0 : (U_pwm >= 255) ? 255 : U_pwm; @@ -298,7 +291,7 @@ void BLDCMotor::setPwm(int pinPwm, float U) { } /** - Utility funcitons + Utility functions */ // normalizing radian angle to [0,2PI] float BLDCMotor::normalizeAngle(float angle){ @@ -321,7 +314,7 @@ float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){ if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; // u(s) = (P + I/s)e(s) - // tustin discretisation of the PI controller ( a bit optimised ) + // Tustin transform of the PI controller ( a bit optimized ) // uk = uk_1 + (I*Ts/2 + P)*ek + (I*Ts/2 - P)*ek_1 float tmp = cont.I*Ts*0.5; float voltage = cont.voltage_prev + (tmp + cont.P) * tracking_error + (tmp - cont.P) * cont.tracking_error_prev; @@ -355,8 +348,36 @@ float BLDCMotor::positionP(float ek) { /** * Debugger functions */ -// funciton implementing the debugger setter +// function implementing the debugger setter void BLDCMotor::useDebugging(Print &print){ - debugger = &print; //operate on the adress of print + debugger = &print; //operate on the address of print if(debugger )debugger->println("DEBUG: Serial debugger enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void BLDCMotor::monitor() { + if(!debugger) return; + switch (controller) { + case ControlType::velocity: + debugger->print(voltage_q); + debugger->print("\t"); + debugger->print(shaft_velocity_sp); + debugger->print("\t"); + debugger->println(shaft_velocity); + break; + case ControlType::angle: + debugger->print(voltage_q); + debugger->print("\t"); + debugger->print(shaft_angle_sp); + debugger->print("\t"); + debugger->println(shaft_angle); + break; + case ControlType::voltage: + debugger->print(voltage_q); + debugger->print("\t"); + debugger->print(shaft_angle); + debugger->print("\t"); + debugger->println(shaft_velocity); + break; + } } \ No newline at end of file diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.h b/arduino_foc_minimal_magnetic/BLDCMotor.h index 6d62a56e..2ee03629 100644 --- a/arduino_foc_minimal_magnetic/BLDCMotor.h +++ b/arduino_foc_minimal_magnetic/BLDCMotor.h @@ -2,6 +2,8 @@ #define BLDCMotor_h #include "Arduino.h" +#include "MagneticSensor.h" +#include "Encoder.h" #include "FOCutils.h" #include "Sensor.h" @@ -32,7 +34,7 @@ enum ControlType{ angle }; -// PI controller strucutre +// PI controller structure struct PI_s{ float P; float I; @@ -68,7 +70,7 @@ class BLDCMotor - phA, phB, phC - motor A,B,C phase pwm pins - pp - pole pair number - cpr - counts per rotation number (cpm=ppm*4) - - enable pin - (optionl input) + - enable pin - (optional input) */ BLDCMotor(int phA,int phB,int phC,int pp, int en = 0); // change driver state @@ -112,10 +114,10 @@ class BLDCMotor // current voltage u_q set float voltage_q; - // Power supply woltage + // Power supply voltage float voltage_power_supply; - // configuraion structures + // configuration structures ControlType controller; PI_s PI_velocity; PI_s PI_velocity_index_search; @@ -137,6 +139,7 @@ class BLDCMotor // debugging void useDebugging(Print &print); + void monitor(); Print* debugger; float Ua,Ub,Uc; @@ -144,7 +147,7 @@ class BLDCMotor private: //Sensor alignment to electrical 0 angle int alignSensor(); - //Motor and sensor alignement to the sensors absolute 0 angle + //Motor and sensor alignment to the sensors absolute 0 angle int absoluteZeroAlign(); //Electrical angle calculation @@ -152,7 +155,7 @@ class BLDCMotor //Set phase voltaget to pwm output void setPwm(int pinPwm, float U); - /** Utility funcitons */ + /** Utility functions */ //normalizing radian angle to [0,2PI] float normalizeAngle(float angle); // determining if the enable pin has been provided diff --git a/arduino_foc_minimal_magnetic/Encoder.cpp b/arduino_foc_minimal_magnetic/Encoder.cpp new file mode 100644 index 00000000..da6f78e2 --- /dev/null +++ b/arduino_foc_minimal_magnetic/Encoder.cpp @@ -0,0 +1,229 @@ +#include "Encoder.h" + + +/* + Encoder(int encA, int encB , int cpr, int index) + - encA, encB - encoder A and B pins + - cpr - counts per rotation number (cpm=ppm*4) + - index pin - (optional input) +*/ + +Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ + + // Encoder measurement structure init + // hardware pins + pinA = _encA; + pinB = _encB; + // counter setup + pulse_counter = 0; + pulse_timestamp = 0; + + cpr = _ppr; + A_active = 0; + B_active = 0; + I_active = 0; + // index pin + index_pin = _index; // its 0 if not used + index_pulse_counter = 0; + + // velocity calculation variables + prev_Th = 0; + pulse_per_second = 0; + prev_pulse_counter = 0; + prev_timestamp_us = _micros(); + + // extern pullup as default + pullup = Pullup::EXTERN; + // enable quadrature encoder by default + quadrature = Quadrature::ENABLE; +} + +// Encoder interrupt callback functions +// A channel +void Encoder::handleA() { + int A = digitalRead(pinA); + switch (quadrature){ + case Quadrature::ENABLE: + // CPR = 4xPPR + if ( A != A_active ) { + pulse_counter += (A_active == B_active) ? 1 : -1; + pulse_timestamp = _micros(); + A_active = A; + } + break; + case Quadrature::DISABLE: + // CPR = PPR + if(A && !digitalRead(pinB)){ + pulse_counter++; + pulse_timestamp = _micros(); + } + break; + } +} +// B channel +void Encoder::handleB() { + int B = digitalRead(pinB); + switch (quadrature){ + case Quadrature::ENABLE: + // // CPR = 4xPPR + if ( B != B_active ) { + pulse_counter += (A_active != B_active) ? 1 : -1; + pulse_timestamp = _micros(); + B_active = B; + } + break; + case Quadrature::DISABLE: + // CPR = PPR + if(B && !digitalRead(pinA)){ + pulse_counter--; + pulse_timestamp = _micros(); + } + break; + } +} + +// Index channel +void Encoder::handleIndex() { + if(hasIndex()){ + int I = digitalRead(index_pin); + if(I && !I_active){ + // align encoder on each index + if(index_pulse_counter){ + long tmp = pulse_counter; + // corrent the counter value + pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; + // preserve relative speed + prev_pulse_counter += pulse_counter - tmp; + } else { + // initial offset + index_pulse_counter = pulse_counter; + } + } + I_active = I; + } +} + +/* + Shaft angle calculation +*/ +float Encoder::getAngle(){ + return _2PI * (pulse_counter) / ((float)cpr); +} +/* + Shaft velocity calculation + function using mixed time and frequency measurement technique +*/ +float Encoder::getVelocity(){ + // timestamp + long timestamp_us = _micros(); + // sampling time calculation + float Ts = (timestamp_us - prev_timestamp_us) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // time from last impulse + float Th = (timestamp_us - pulse_timestamp) * 1e-6; + long dN = pulse_counter - prev_pulse_counter; + + // Pulse per second calculation (Eq.3.) + // dN - impulses received + // Ts - sampling time - time in between function calls + // Th - time from last impulse + // Th_1 - time form last impulse of the previous call + // only increment if some impulses received + float dt = Ts + prev_Th - Th; + pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second; + + // if more than 0.3 passed in between impulses + if ( Th > 0.15) pulse_per_second = 0; + + // velocity calculation + float velocity = pulse_per_second / ((float)cpr) * (_2PI); + + // save variables for next pass + prev_timestamp_us = timestamp_us; + // save velocity calculation variables + prev_Th = Th; + prev_pulse_counter = pulse_counter; + return (velocity); +} + +// getter for index pin +// return -1 if no index +int Encoder::needsAbsoluteZeroSearch(){ + return index_pulse_counter == 0; +} +// getter for index pin +int Encoder::hasAbsoluteZero(){ + return hasIndex(); +} +// initialize counter to zero +float Encoder::initRelativeZero(){ + long angle_offset = -pulse_counter; + pulse_counter = 0; + pulse_timestamp = _micros(); + return _2PI * (angle_offset) / ((float)cpr); +} +// initialize index to zero +float Encoder::initAbsoluteZero(){ + pulse_counter -= index_pulse_counter; + prev_pulse_counter = pulse_counter; + return (index_pulse_counter) / ((float)cpr) * (_2PI); +} +// private function used to determine if encoder has index +int Encoder::hasIndex(){ + return index_pin != 0; +} + + +// encoder initialisation of the hardware pins +// and calculation variables +void Encoder::init(){ + + // Encoder - check if pullup needed for your encoder + if(pullup == Pullup::INTERN){ + pinMode(pinA, INPUT_PULLUP); + pinMode(pinB, INPUT_PULLUP); + if(hasIndex()) pinMode(index_pin,INPUT_PULLUP); + }else{ + pinMode(pinA, INPUT); + pinMode(pinB, INPUT); + if(hasIndex()) pinMode(index_pin,INPUT); + } + + // counter setup + pulse_counter = 0; + pulse_timestamp = _micros(); + // velocity calculation variables + prev_Th = 0; + pulse_per_second = 0; + prev_pulse_counter = 0; + prev_timestamp_us = _micros(); + + // initial cpr = PPR + // change it if the mode is quadrature + if(quadrature == Quadrature::ENABLE) cpr = 4*cpr; + +} + +// function enabling hardware interrupts of the for the callback provided +// if callback is not provided then the interrupt is not enabled +void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){ + // attach interrupt if functions provided + switch(quadrature){ + case Quadrature::ENABLE: + // A callback and B callback + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); + break; + case Quadrature::DISABLE: + // A callback and B callback + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); + break; + } + + // if index used initialize the index interrupt + if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE); +} + diff --git a/arduino_foc_minimal_magnetic/Encoder.h b/arduino_foc_minimal_magnetic/Encoder.h new file mode 100644 index 00000000..d115fe25 --- /dev/null +++ b/arduino_foc_minimal_magnetic/Encoder.h @@ -0,0 +1,92 @@ +#ifndef ENCODER_LIB_H +#define ENCODER_LIB_H + +#include "Arduino.h" +#include "FOCutils.h" +#include "Sensor.h" + + +// Pullup configuration structure +enum Pullup{ + INTERN, + EXTERN +}; + +enum Quadrature{ + ENABLE, // CPR = 4xPPR + DISABLE // CPR = PPR +}; + +class Encoder: public Sensor{ + public: + /* + Encoder(int encA, int encB , int cpr, int index) + - encA, encB - encoder A and B pins + - ppr - impulses per rotation (cpr=ppr*4) + - index pin - (optional input) + */ + Encoder(int encA, int encB , float ppr, int index = 0); + + // encoder initialise pins + void init(); + // function enabling hardware interrupts of the for the callback provided + // if callback is not provided then the interrupt is not enabled + void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr); + + // Encoder interrupt callback functions + // enabling CPR=4xPPR behaviour + // A channel + void handleA(); + // B channel + void handleB(); + // index handle + void handleIndex(); + + + // pins A and B + int pinA, pinB; // encoder hardware pins + // index pin + int index_pin; + // encoder pullup type + Pullup pullup; + // use 4xppr or not + Quadrature quadrature; + + // implementation of abstract functions of the Sensor class + // get current angle (rad) + float getAngle(); + // get current angular velocity (rad/s) + float getVelocity(); + // set current angle as zero angle + // return the angle [rad] difference + float initRelativeZero(); + // set index angle as zero angle + // return the angle [rad] difference + float initAbsoluteZero(); + // returns 0 if it has no index + // 0 - encoder without index + // 1 - encoder with index + int hasAbsoluteZero(); + // returns 0 if it does need search for absolute zero + // 0 - encoder without index + // 1 - ecoder with index + int needsAbsoluteZeroSearch(); + + private: + int hasIndex(); + + volatile long pulse_counter; // current pulse counter + volatile long pulse_timestamp; // last impulse timestamp in us + float cpr; // impulse cpr + volatile int A_active, B_active; // current active states of A and B line + volatile int I_active; // index active + volatile long index_pulse_counter; // pulse counter of the index + + // velocity calculation variables + float prev_Th, pulse_per_second; + volatile long prev_pulse_counter, prev_timestamp_us; + +}; + + +#endif diff --git a/arduino_foc_minimal_magnetic/FOCutils.cpp b/arduino_foc_minimal_magnetic/FOCutils.cpp index 5a383f3d..c9f0db4c 100644 --- a/arduino_foc_minimal_magnetic/FOCutils.cpp +++ b/arduino_foc_minimal_magnetic/FOCutils.cpp @@ -22,16 +22,16 @@ void setPwmFrequency(int pin) { } } -// funciton buffering delay() -// arduino funciton doesn't work well with interrupts +// function buffering delay() +// arduino function doesn't work well with interrupts void _delay(unsigned long ms){ long t = _micros(); while((_micros() - t)/1000 < ms){}; } -// funciton buffering _micros() -// arduino funciton doesn't work well with interrupts +// function buffering _micros() +// arduino function doesn't work well with interrupts unsigned long _micros(){ // return the value based on the prescaler if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); diff --git a/arduino_foc_minimal_magnetic/FOCutils.h b/arduino_foc_minimal_magnetic/FOCutils.h index d6177497..d431ad28 100644 --- a/arduino_foc_minimal_magnetic/FOCutils.h +++ b/arduino_foc_minimal_magnetic/FOCutils.h @@ -3,7 +3,7 @@ #include "Arduino.h" -// sign funciton +// sign function #define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) // utility defines #define _2_SQRT3 1.15470053838 @@ -18,19 +18,19 @@ // High PWM frequency void setPwmFrequency(int pin); -// funciton buffering delay() -// arduino funciton doesn't work well with interrupts +// function buffering delay() +// arduino function doesn't work well with interrupts void _delay(unsigned long ms); -// funciton buffering _micros() -// arduino funciton doesn't work well with interrupts +// function buffering _micros() +// arduino function doesn't work well with interrupts unsigned long _micros(); // function approximating the sine calculation by using fixed size array // ~40us // it has to receive an angle in between 0 and 2PI float _sin(float a); -// function approfimating cosine calculaiton by using fixed size array +// function approximating cosine calculation by using fixed size array // ~50us // it has to receive an angle in between 0 and 2PI float _cos(float a); diff --git a/arduino_foc_minimal_magnetic/MagneticSensor.cpp b/arduino_foc_minimal_magnetic/MagneticSensor.cpp index 1812b369..d045eab5 100644 --- a/arduino_foc_minimal_magnetic/MagneticSensor.cpp +++ b/arduino_foc_minimal_magnetic/MagneticSensor.cpp @@ -3,7 +3,7 @@ // MagneticSensor(int cs, float _cpr, int _angle_register) // cs - SPI chip select pin -// _cpr - counF per revolution +// _cpr - count per revolution // _angle_register - (optional) angle read register - default 0x3FFF MagneticSensor::MagneticSensor(int cs, float _cpr, int _angle_register){ // chip select pin @@ -17,8 +17,8 @@ MagneticSensor::MagneticSensor(int cs, float _cpr, int _angle_register){ void MagneticSensor::init(){ - // 10MHz clock (AMS should be able to accept up to 10MHz) - settings = SPISettings(10000000, MSBFIRST, SPI_MODE1); + // 1MHz clock (AMS should be able to accept up to 10MHz) + settings = SPISettings(1000000, MSBFIRST, SPI_MODE1); //setup pins pinMode(chip_select_pin, OUTPUT); @@ -77,7 +77,7 @@ float MagneticSensor::getVelocity(){ return vel; } -// set current agle as zero angle +// set current angle as zero angle // return the angle [rad] difference float MagneticSensor::initRelativeZero(){ float angle_offset = -getAngle(); @@ -87,7 +87,7 @@ float MagneticSensor::initRelativeZero(){ full_rotation_offset = 0; return angle_offset; } -// set absoule zero angle as zero angle +// set absolute zero angle as zero angle // return the angle [rad] difference float MagneticSensor::initAbsoluteZero(){ float rotation = -(int)zero_offset; diff --git a/arduino_foc_minimal_magnetic/MagneticSensor.h b/arduino_foc_minimal_magnetic/MagneticSensor.h index 600c0880..50665982 100644 --- a/arduino_foc_minimal_magnetic/MagneticSensor.h +++ b/arduino_foc_minimal_magnetic/MagneticSensor.h @@ -28,10 +28,10 @@ class MagneticSensor: public Sensor{ float getAngle(); // get current angular velocity (rad/s) float getVelocity(); - // set current agle as zero angle + // set current angle as zero angle // return the angle [rad] difference float initRelativeZero(); - // set absoule zero angle as zero angle + // set absolute zero angle as zero angle // return the angle [rad] difference float initAbsoluteZero(); // returns 1 because it is the absolute sensor @@ -45,7 +45,7 @@ class MagneticSensor: public Sensor{ int chip_select_pin; bool errorFlag; SPISettings settings; - // spi funcitons + // spi functions void close(); word read(word angle_register); byte spiCalcEvenParity(word value); @@ -53,7 +53,7 @@ class MagneticSensor: public Sensor{ // zero offset word zero_offset; - // funciton getting current register value + // function getting current register value int getRawCount(); // total angle tracking variables diff --git a/arduino_foc_minimal_magnetic/Sensor.h b/arduino_foc_minimal_magnetic/Sensor.h index 3555941a..b03c3b5f 100644 --- a/arduino_foc_minimal_magnetic/Sensor.h +++ b/arduino_foc_minimal_magnetic/Sensor.h @@ -9,10 +9,10 @@ class Sensor{ virtual float getAngle(); // get current angular velocity (rad/s) virtual float getVelocity(); - // set current agle as zero angle + // set current angle as zero angle // return the angle [rad] difference virtual float initRelativeZero(); - // set absoule zero angle as zero angle + // set absolute zero angle as zero angle // return the angle [rad] difference virtual float initAbsoluteZero(); diff --git a/arduino_foc_minimal_magnetic/SimpleFOC.h b/arduino_foc_minimal_magnetic/SimpleFOC.h index bd095760..887ae8df 100644 --- a/arduino_foc_minimal_magnetic/SimpleFOC.h +++ b/arduino_foc_minimal_magnetic/SimpleFOC.h @@ -3,6 +3,7 @@ #include "FOCutils.h" #include "Sensor.h" +#include "Encoder.h" #include "MagneticSensor.h" #include "BLDCMotor.h" diff --git a/arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino b/arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino index 2f7b89c7..9b995288 100644 --- a/arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino +++ b/arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino @@ -12,7 +12,7 @@ BLDCMotor motor = BLDCMotor(9, 5, 6, 11); // MagneticSensor(int cs, float _cpr, int _angle_register) // cs - SPI chip select pin -// _cpr - counF per revolution +// _cpr - count per revolution // _angle_register - (optional) angle read register - default 0x3FFF MagneticSensor as504x = MagneticSensor(10, 16384); @@ -37,7 +37,7 @@ void setup() { // velocity PI controller parameters motor.PI_velocity.P = 0.2; motor.PI_velocity.I = 20; - //defualt voltage_power_supply/2 + // default voltage_power_supply/2 motor.PI_velocity.voltage_limit = 6; // jerk control using voltage voltage ramp // default value is 300 volts per sec ~ 0.3V per millisecond @@ -60,7 +60,7 @@ void setup() { // comment out if not needed motor.useDebugging(Serial); - // intialise motor + // initialize motor motor.init(); // align encoder and start FOC motor.initFOC(); @@ -83,7 +83,7 @@ void setup() { Serial.print(motor.PI_velocity.P); Serial.print(",\t I: "); Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low passs filter Tf: "); + Serial.print(",\t Low pass filter Tf: "); Serial.println(motor.LPF_velocity.Tf,4); _delay(1000); @@ -96,7 +96,7 @@ unsigned long t = 0; long timestamp = _micros(); void loop() { - // iterative setting FOC pahse voltage + // iterative setting FOC phase voltage motor.loopFOC(); // iterative function setting the outter loop target @@ -125,7 +125,7 @@ void serialEvent() { Serial.print(motor.PI_velocity.P); Serial.print(",\t I: "); Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low passs filter Tf: "); + Serial.print(",\t Low pass filter Tf: "); Serial.println(motor.LPF_velocity.Tf,4); }else if(inputString.charAt(0) == 'I'){ motor.PI_velocity.I = inputString.substring(1).toFloat(); @@ -133,7 +133,7 @@ void serialEvent() { Serial.print(motor.PI_velocity.P); Serial.print(",\t I: "); Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low passs filter Tf: "); + Serial.print(",\t Low pass filter Tf: "); Serial.println(motor.LPF_velocity.Tf,4); }else if(inputString.charAt(0) == 'F'){ motor.LPF_velocity.Tf = inputString.substring(1).toFloat(); @@ -141,7 +141,7 @@ void serialEvent() { Serial.print(motor.PI_velocity.P); Serial.print(",\t I: "); Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low passs filter Tf: "); + Serial.print(",\t Low pass filter Tf: "); Serial.println(motor.LPF_velocity.Tf,4); }else if(inputString.charAt(0) == 'T'){ Serial.print("Average loop time is (microseconds): "); @@ -158,7 +158,7 @@ void serialEvent() { Serial.println("velocity!"); motor.controller = ControlType::velocity; }else if(cnt == 2){ - Serial.println("volatge!"); + Serial.println("voltage!"); motor.controller = ControlType::voltage; } Serial.println(); From 452aeef5dd21c168d5ce2388e135662a820629b7 Mon Sep 17 00:00:00 2001 From: askuric Date: Wed, 20 May 2020 17:13:37 +0200 Subject: [PATCH 42/65] FEATURE Added Space Vector modulation --- arduino_foc_minimal_encoder/BLDCMotor.cpp | 147 ++++++++++++++---- arduino_foc_minimal_encoder/BLDCMotor.h | 11 +- arduino_foc_minimal_encoder/FOCutils.h | 2 + .../arduino_foc_minimal_encoder.ino | 5 + arduino_foc_minimal_magnetic/BLDCMotor.cpp | 147 ++++++++++++++---- arduino_foc_minimal_magnetic/BLDCMotor.h | 11 +- arduino_foc_minimal_magnetic/FOCutils.h | 2 + .../arduino_foc_minimal_magnetic.ino | 5 + 8 files changed, 260 insertions(+), 70 deletions(-) diff --git a/arduino_foc_minimal_encoder/BLDCMotor.cpp b/arduino_foc_minimal_encoder/BLDCMotor.cpp index df86ad5f..2f6fd4d9 100644 --- a/arduino_foc_minimal_encoder/BLDCMotor.cpp +++ b/arduino_foc_minimal_encoder/BLDCMotor.cpp @@ -20,7 +20,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) voltage_power_supply = DEF_POWER_SUPPLY; // Velocity loop config - // PI contoroller constant + // PI controller constant PI_velocity.P = DEF_PI_VEL_P; PI_velocity.I = DEF_PI_VEL_I; PI_velocity.timestamp = _micros(); @@ -55,6 +55,9 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // electric angle of the zero angle zero_electric_angle = 0; + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + //debugger debugger = nullptr; } @@ -76,8 +79,8 @@ void BLDCMotor::init() { setPwmFrequency(pwmC); // sanity check for the voltage limit configuration - if(PI_velocity.voltage_limit > voltage_power_supply/2) PI_velocity.voltage_limit = voltage_power_supply/2; - if(PI_velocity_index_search.voltage_limit > voltage_power_supply/2) PI_velocity_index_search.voltage_limit = voltage_power_supply/2; + if(PI_velocity.voltage_limit > 0.7*voltage_power_supply) PI_velocity.voltage_limit = 0.7*voltage_power_supply; + if(PI_velocity_index_search.voltage_limit > 0.7*voltage_power_supply) PI_velocity_index_search.voltage_limit = 0.7*voltage_power_supply; _delay(500); // enable motor @@ -135,7 +138,7 @@ int BLDCMotor::alignSensor() { if(debugger){ if(exit_flag< 0 ) debugger->println("DEBUG: Error: Absolute zero not found!"); if(exit_flag> 0 ) debugger->println("DEBUG: Success: Absolute zero found!"); - else debugger->println("DEBUG: Absolute zero not availabe!"); + else debugger->println("DEBUG: Absolute zero not available!"); } return exit_flag; } @@ -199,7 +202,6 @@ float BLDCMotor::electricAngle(float shaftAngle) { /** FOC functions */ - // FOC initialization function int BLDCMotor::initFOC() { // sensor and motor alignment @@ -225,6 +227,7 @@ void BLDCMotor::loopFOC() { void BLDCMotor::move(float target) { // get angular velocity shaft_velocity = shaftVelocity(); + // choose control loop switch (controller) { case ControlType::voltage: voltage_q = target; @@ -247,43 +250,121 @@ void BLDCMotor::move(float target) { // Method using FOC to set Uq to the motor at the optimal angle +// Function implementing Space Vector PWM and Sine PWM algorithms +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { + switch (foc_modulation) + { + case FOCModulationType::SinePWM : + // Sinusoidal PWM modulation + // Inverse Park + Clarke transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + + // Clarke transform + Ua = Ualpha + voltage_power_supply/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + break; - // angle normalisation in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - float angle = normalizeAngle(angle_el + zero_electric_angle); - // Inverse park transform - // regular sin + cos ~300us (no memory usaage) - // approx _sin + _cos ~110us (400Byte ~ 20% of memory) - // Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; - // Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; - Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; - - // Clarke transform - Ua = Ualpha; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta; + case FOCModulationType::SpaceVectorPWM : + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // https://www.youtube.com/watch?v=QMSWUMEAejg + + // if negative voltages change inverse the phase + // angle + 180degrees + if(Uq < 0) angle_el += M_PI; + Uq = abs(Uq); + + // angle normalisation in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = normalizeAngle(angle_el + zero_electric_angle + _PI_2); + + // find the sector we are in currently + int sector = floor(angle_el / _PI_3) + 1; + // calculate the duty cycles + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el); + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3); + // two versions possible + // centered around voltage_power_supply/2 + float T0 = 1 - T1 - T2; + // centered around 0 + //T0 = 0; + + // calculate the duty cycles(times) + float Ta,Tb,Tc; + switch(sector){ + case 1: + Ta = T1 + T2 + T0/2; + Tb = T2 + T0/2; + Tc = T0/2; + break; + case 2: + Ta = T1 + T0/2; + Tb = T1 + T2 + T0/2; + Tc = T0/2; + break; + case 3: + Ta = T0/2; + Tb = T1 + T2 + T0/2; + Tc = T2 + T0/2; + break; + case 4: + Ta = T0/2; + Tb = T1+ T0/2; + Tc = T1 + T2 + T0/2; + break; + case 5: + Ta = T2 + T0/2; + Tb = T0/2; + Tc = T1 + T2 + T0/2; + break; + case 6: + Ta = T1 + T2 + T0/2; + Tb = T0/2; + Tc = T1 + T0/2; + break; + default: + // possible error state + Ta = 0; + Tb = 0; + Tc = 0; + } + + // calculate the phase voltages + Ua = Ta*Uq; + Ub = Tb*Uq; + Uc = Tc*Uq; + break; + } - // set phase voltages + // set the voltages in hardware setPwm(pwmA, Ua); setPwm(pwmB, Ub); setPwm(pwmC, Uc); } + + // Set voltage to the pwm pin // - function a bit optimized to get better performance void BLDCMotor::setPwm(int pinPwm, float U) { // max value - float U_max = voltage_power_supply/2.0; - - // sets the voltage [-U_max,U_max] to pwm [0,255] - // u_pwm = 255 * (U + U_max)/(2*U_max) - // it can be further optimized - // (example U_max = 6 > U_pwm = 127.5 + 21.25*U) - int U_pwm = 127.5 * (U/U_max + 1); - + float U_max = voltage_power_supply; + + // sets the voltage [0,12V(U_max)] to pwm [0,255] + // - U_max you can set in header file - default 12V + int U_pwm = 255.0 * U / U_max; + // limit the values between 0 and 255 U_pwm = (U_pwm < 0) ? 0 : (U_pwm >= 255) ? 255 : U_pwm; @@ -340,9 +421,11 @@ float BLDCMotor::velocityIndexSearchPI(float tracking_error) { } // P controller for position control loop float BLDCMotor::positionP(float ek) { - float velk = P_angle.P * ek; - if (abs(velk) > P_angle.velocity_limit) velk = velk > 0 ? P_angle.velocity_limit : -P_angle.velocity_limit; - return velk; + // calculate the target velocity from the position error + float velocity_target = P_angle.P * ek; + // constrain velocity target value + if (abs(velocity_target) > P_angle.velocity_limit) velocity_target = velocity_target > 0 ? P_angle.velocity_limit : -P_angle.velocity_limit; + return velocity_target; } /** diff --git a/arduino_foc_minimal_encoder/BLDCMotor.h b/arduino_foc_minimal_encoder/BLDCMotor.h index 2ee03629..8f57deb4 100644 --- a/arduino_foc_minimal_encoder/BLDCMotor.h +++ b/arduino_foc_minimal_encoder/BLDCMotor.h @@ -2,8 +2,6 @@ #define BLDCMotor_h #include "Arduino.h" -#include "MagneticSensor.h" -#include "Encoder.h" #include "FOCutils.h" #include "Sensor.h" @@ -34,6 +32,12 @@ enum ControlType{ angle }; +// FOC Type +enum FOCModulationType{ + SinePWM, + SpaceVectorPWM +}; + // PI controller structure struct PI_s{ float P; @@ -77,7 +81,7 @@ class BLDCMotor void init(); void disable(); void enable(); - // connect encoder + // connect sensor void linkSensor(Sensor* _sensor); // initilise FOC @@ -119,6 +123,7 @@ class BLDCMotor // configuration structures ControlType controller; + FOCModulationType foc_modulation; PI_s PI_velocity; PI_s PI_velocity_index_search; P_s P_angle; diff --git a/arduino_foc_minimal_encoder/FOCutils.h b/arduino_foc_minimal_encoder/FOCutils.h index d431ad28..11882a81 100644 --- a/arduino_foc_minimal_encoder/FOCutils.h +++ b/arduino_foc_minimal_encoder/FOCutils.h @@ -7,11 +7,13 @@ #define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) // utility defines #define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 #define _1_SQRT3 0.57735026919 #define _SQRT3_2 0.86602540378 #define _SQRT2 1.41421356237 #define _120_D2R 2.09439510239 #define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 #define _2PI 6.28318530718 #define _3PI_2 4.71238898038 diff --git a/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino b/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino index c531f49c..1c4f6a75 100644 --- a/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino +++ b/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino @@ -23,6 +23,11 @@ void setup() { encoder.init(); encoder.enableInterrupts(doA,doB); + // choose FOC algorithm to be used: + // FOCModulationType::SinePWM (default) + // FOCModulationType::SpaceVectorPWM + motor.foc_modulation = FOCModulationType::SpaceVectorPWM; + // power supply voltage // default 12V motor.voltage_power_supply = 12; diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.cpp b/arduino_foc_minimal_magnetic/BLDCMotor.cpp index df86ad5f..2f6fd4d9 100644 --- a/arduino_foc_minimal_magnetic/BLDCMotor.cpp +++ b/arduino_foc_minimal_magnetic/BLDCMotor.cpp @@ -20,7 +20,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) voltage_power_supply = DEF_POWER_SUPPLY; // Velocity loop config - // PI contoroller constant + // PI controller constant PI_velocity.P = DEF_PI_VEL_P; PI_velocity.I = DEF_PI_VEL_I; PI_velocity.timestamp = _micros(); @@ -55,6 +55,9 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // electric angle of the zero angle zero_electric_angle = 0; + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + //debugger debugger = nullptr; } @@ -76,8 +79,8 @@ void BLDCMotor::init() { setPwmFrequency(pwmC); // sanity check for the voltage limit configuration - if(PI_velocity.voltage_limit > voltage_power_supply/2) PI_velocity.voltage_limit = voltage_power_supply/2; - if(PI_velocity_index_search.voltage_limit > voltage_power_supply/2) PI_velocity_index_search.voltage_limit = voltage_power_supply/2; + if(PI_velocity.voltage_limit > 0.7*voltage_power_supply) PI_velocity.voltage_limit = 0.7*voltage_power_supply; + if(PI_velocity_index_search.voltage_limit > 0.7*voltage_power_supply) PI_velocity_index_search.voltage_limit = 0.7*voltage_power_supply; _delay(500); // enable motor @@ -135,7 +138,7 @@ int BLDCMotor::alignSensor() { if(debugger){ if(exit_flag< 0 ) debugger->println("DEBUG: Error: Absolute zero not found!"); if(exit_flag> 0 ) debugger->println("DEBUG: Success: Absolute zero found!"); - else debugger->println("DEBUG: Absolute zero not availabe!"); + else debugger->println("DEBUG: Absolute zero not available!"); } return exit_flag; } @@ -199,7 +202,6 @@ float BLDCMotor::electricAngle(float shaftAngle) { /** FOC functions */ - // FOC initialization function int BLDCMotor::initFOC() { // sensor and motor alignment @@ -225,6 +227,7 @@ void BLDCMotor::loopFOC() { void BLDCMotor::move(float target) { // get angular velocity shaft_velocity = shaftVelocity(); + // choose control loop switch (controller) { case ControlType::voltage: voltage_q = target; @@ -247,43 +250,121 @@ void BLDCMotor::move(float target) { // Method using FOC to set Uq to the motor at the optimal angle +// Function implementing Space Vector PWM and Sine PWM algorithms +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { + switch (foc_modulation) + { + case FOCModulationType::SinePWM : + // Sinusoidal PWM modulation + // Inverse Park + Clarke transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + + // Clarke transform + Ua = Ualpha + voltage_power_supply/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + break; - // angle normalisation in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - float angle = normalizeAngle(angle_el + zero_electric_angle); - // Inverse park transform - // regular sin + cos ~300us (no memory usaage) - // approx _sin + _cos ~110us (400Byte ~ 20% of memory) - // Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; - // Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; - Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle) * Uq; // cos(angle) * Uq; - - // Clarke transform - Ua = Ualpha; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta; + case FOCModulationType::SpaceVectorPWM : + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // https://www.youtube.com/watch?v=QMSWUMEAejg + + // if negative voltages change inverse the phase + // angle + 180degrees + if(Uq < 0) angle_el += M_PI; + Uq = abs(Uq); + + // angle normalisation in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = normalizeAngle(angle_el + zero_electric_angle + _PI_2); + + // find the sector we are in currently + int sector = floor(angle_el / _PI_3) + 1; + // calculate the duty cycles + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el); + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3); + // two versions possible + // centered around voltage_power_supply/2 + float T0 = 1 - T1 - T2; + // centered around 0 + //T0 = 0; + + // calculate the duty cycles(times) + float Ta,Tb,Tc; + switch(sector){ + case 1: + Ta = T1 + T2 + T0/2; + Tb = T2 + T0/2; + Tc = T0/2; + break; + case 2: + Ta = T1 + T0/2; + Tb = T1 + T2 + T0/2; + Tc = T0/2; + break; + case 3: + Ta = T0/2; + Tb = T1 + T2 + T0/2; + Tc = T2 + T0/2; + break; + case 4: + Ta = T0/2; + Tb = T1+ T0/2; + Tc = T1 + T2 + T0/2; + break; + case 5: + Ta = T2 + T0/2; + Tb = T0/2; + Tc = T1 + T2 + T0/2; + break; + case 6: + Ta = T1 + T2 + T0/2; + Tb = T0/2; + Tc = T1 + T0/2; + break; + default: + // possible error state + Ta = 0; + Tb = 0; + Tc = 0; + } + + // calculate the phase voltages + Ua = Ta*Uq; + Ub = Tb*Uq; + Uc = Tc*Uq; + break; + } - // set phase voltages + // set the voltages in hardware setPwm(pwmA, Ua); setPwm(pwmB, Ub); setPwm(pwmC, Uc); } + + // Set voltage to the pwm pin // - function a bit optimized to get better performance void BLDCMotor::setPwm(int pinPwm, float U) { // max value - float U_max = voltage_power_supply/2.0; - - // sets the voltage [-U_max,U_max] to pwm [0,255] - // u_pwm = 255 * (U + U_max)/(2*U_max) - // it can be further optimized - // (example U_max = 6 > U_pwm = 127.5 + 21.25*U) - int U_pwm = 127.5 * (U/U_max + 1); - + float U_max = voltage_power_supply; + + // sets the voltage [0,12V(U_max)] to pwm [0,255] + // - U_max you can set in header file - default 12V + int U_pwm = 255.0 * U / U_max; + // limit the values between 0 and 255 U_pwm = (U_pwm < 0) ? 0 : (U_pwm >= 255) ? 255 : U_pwm; @@ -340,9 +421,11 @@ float BLDCMotor::velocityIndexSearchPI(float tracking_error) { } // P controller for position control loop float BLDCMotor::positionP(float ek) { - float velk = P_angle.P * ek; - if (abs(velk) > P_angle.velocity_limit) velk = velk > 0 ? P_angle.velocity_limit : -P_angle.velocity_limit; - return velk; + // calculate the target velocity from the position error + float velocity_target = P_angle.P * ek; + // constrain velocity target value + if (abs(velocity_target) > P_angle.velocity_limit) velocity_target = velocity_target > 0 ? P_angle.velocity_limit : -P_angle.velocity_limit; + return velocity_target; } /** diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.h b/arduino_foc_minimal_magnetic/BLDCMotor.h index 2ee03629..8f57deb4 100644 --- a/arduino_foc_minimal_magnetic/BLDCMotor.h +++ b/arduino_foc_minimal_magnetic/BLDCMotor.h @@ -2,8 +2,6 @@ #define BLDCMotor_h #include "Arduino.h" -#include "MagneticSensor.h" -#include "Encoder.h" #include "FOCutils.h" #include "Sensor.h" @@ -34,6 +32,12 @@ enum ControlType{ angle }; +// FOC Type +enum FOCModulationType{ + SinePWM, + SpaceVectorPWM +}; + // PI controller structure struct PI_s{ float P; @@ -77,7 +81,7 @@ class BLDCMotor void init(); void disable(); void enable(); - // connect encoder + // connect sensor void linkSensor(Sensor* _sensor); // initilise FOC @@ -119,6 +123,7 @@ class BLDCMotor // configuration structures ControlType controller; + FOCModulationType foc_modulation; PI_s PI_velocity; PI_s PI_velocity_index_search; P_s P_angle; diff --git a/arduino_foc_minimal_magnetic/FOCutils.h b/arduino_foc_minimal_magnetic/FOCutils.h index d431ad28..11882a81 100644 --- a/arduino_foc_minimal_magnetic/FOCutils.h +++ b/arduino_foc_minimal_magnetic/FOCutils.h @@ -7,11 +7,13 @@ #define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) // utility defines #define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 #define _1_SQRT3 0.57735026919 #define _SQRT3_2 0.86602540378 #define _SQRT2 1.41421356237 #define _120_D2R 2.09439510239 #define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 #define _2PI 6.28318530718 #define _3PI_2 4.71238898038 diff --git a/arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino b/arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino index 9b995288..82a6c28e 100644 --- a/arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino +++ b/arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino @@ -23,6 +23,11 @@ void setup() { // initialise magnetic sensor hardware as504x.init(); + // choose FOC algorithm to be used: + // FOCModulationType::SinePWM (default) + // FOCModulationType::SpaceVectorPWM + motor.foc_modulation = FOCModulationType::SpaceVectorPWM; + // power supply voltage // default 12V motor.voltage_power_supply = 12; From ca5d9e3c35aa123d1ff70f0af944d9ca5493d528 Mon Sep 17 00:00:00 2001 From: askuric Date: Tue, 26 May 2020 12:30:05 +0200 Subject: [PATCH 43/65] FEAT addded the defualts file --- arduino_foc_minimal_device_specific.zip | Bin 0 -> 30352 bytes arduino_foc_minimal_encoder/BLDCMotor.h | 21 +-------------------- arduino_foc_minimal_encoder/defaults.h | 19 +++++++++++++++++++ arduino_foc_minimal_magnetic/BLDCMotor.h | 21 +-------------------- arduino_foc_minimal_magnetic/defaults.h | 19 +++++++++++++++++++ 5 files changed, 40 insertions(+), 40 deletions(-) create mode 100644 arduino_foc_minimal_device_specific.zip create mode 100644 arduino_foc_minimal_encoder/defaults.h create mode 100644 arduino_foc_minimal_magnetic/defaults.h diff --git a/arduino_foc_minimal_device_specific.zip b/arduino_foc_minimal_device_specific.zip new file mode 100644 index 0000000000000000000000000000000000000000..632dbd2a780ec877648010dcce2fab5ad7c801cd GIT binary patch literal 30352 zcmeFZV{oN`wyv9w)v=u!+qRvKZQHhO+qUg=Y}*~HV<)Fq9jvwQJ^QY6f8Krj$NV$D znpLyv8#Ug6_Zf0hAfPBfKtPZ{hS}wEaYP!vuHZmGwrD^=Tz|gRcQA4`x3SeVu{G4S zHn%ai*0<6%wlTCdGIpT*e|Sdw=Qo#XnzmRRC_b@CUv?QwHlZ|9eoe|!KZOLbp~@>o zBo|A?-qwB?(@Whpjecy5pCiH3~indyB2ckZ*-)>xCdm)p@DG%%%XpY){srr7` zXiPjPJSbdH^qa8N1^2Zmj06p0jGLj&_}pXUhJ6>h>S?!NpX0+>2OtJtJ1T&pPfZ*F zsj7_;>P{1)S5%QWgz-MtkOZWW^DEym&;iF#v6kTG4{N4|7nnl3{{7rmT3%|a%H1}hkWmS-&u`Bl?2Us zIKpZSTDET&I3GDdho;>IGsJBIG|-~pAU;})PQp6*_!bdO1B>;rxf5AM0wnv&RiplL z@ivZ&%Jum0HLO0Qn^+XCT%}|dsc4xaZ6qsjj{Zn4nftEJKX7x`q_)+@(>qcs8~U!z zGPb<@7u8djvN@MtX@c@ekh7duMwq#B8ye2Rw<#d}$*55JBA9+DaBX@lK_doJuuMm3 zmv#p;<}R3%Wk_#}R;`j2*U+{N>s&76w6_TTE7#(;rcOfX5yz*f;S)2%CkM;)Bm;;krW+Z{*b*n|1# zuFI+wkj~aC2|Mplv2ctzm0@}*1Cw&!>S3hM)cH~5*}lAFF&9xwtbir4<+4oe1?3J> z^XToRn?+^)GpRjD&~6ZlWg^NeP9u*5&DHdQN-sMgX^G=Km<9!3fo=mzV)dWYEL2XQ zlbtqt19EmXRiKLXr;j__yo4HZ6sn_?#>T2Ul*y*Er>eb6(G`mBD6TIN-#|n^?e6uI zeuumD1qbmp=`GqgV|f;bWGV=eu@IMc%lg2R{dB(YDXlYRyVvFTP+c9l1VN)k>mq=w z>z=}Q(@@7^Ht-<;6RxmpR6W*9{CKj&YPwPDTsW+($6psPlfj%R=nQ%UJ?{6!#p_VV zcJ8N*wVtV3?S<&1=L+*pEjg<8-;-j2eKLPOa%ZB)YU!8F#yF78uUrC0$lb4qbK?v^gZ&$Tg!Fc z`q)8a%&|(+mR?@+dyzsp50U_4JrfdH@dis<^vXnV)$XBg>cBYRgN=IDIoOXZJ)`>^ zMzQ_>NAg@gkf;CvPy4$rUh0?G`Il(u1Q=wUiqEuHLmyBr%FpV=t?tC{pDn?CKaV z!63;ib}@=ziZ;m}AIRbXrQU9ymD|fVb0$b@w(++xiA~sOoE{rx{%^Da^-k*1+9CKBJfF*%5#Rz8?2<$JUHcocPij>uhA7L?sWb8Vqi%NO|^pH=5kO^io&J5zCYH zZCv2AU~--|n*?rto7gg?wj7(hU%GkaQm}HZevF@b4Z%!3cmHg&Hwex2a;AXsdoGy^ zO-xjl3JK+b?EEsiw)z5=`wx1S*&>Bm{T&FXi3SLW;@{|*ptP`%jIEQc1FfN*-4K?g z?S|;BBgij4D~C3maM)ALgQ57=3p+k{t0bxL zYqGPQRI_TE+3DF&lW;HSxKjfLH9r>y4^|2j*<%-`4i`pZ@%Yx)kq#5coRT7q-0Spx zaMtmO?uhn!8;K9`DR0AtbL$~N^7h<=L5KQ>_l6-=j7o$Zx{<$N+ja58#8%v7Z;*_6-#dos{1R=Qn zh``B{oO^ntq~Vr>B7U=t#fSQ4Dzgizw#c~Hi=@~FhlC&IUBtp18+z|%hA(!{zAqNX z$N$2lB^_dh1DFy7B?oatu=d^8);Y5sd}w}?haf=yY~kKSw|ZhWmch88%v#Qtmm(^^M4q6hqXhOvHD zAI@Xw<6tZ^VsUMtF6g}r6F=8~Z5nM5ZBwlA0Y4+y1 zNTDI-=uFf|vZS&2LHDRbzt)ccB*d!Y_jBor*q0TT18(W*QqaQfCFgXjyCqw6%Q+*= z7Mxb;O>&MS9o>0Bf&G~`p+aL$vA-v6dO{mwPBAYJ=QF(rdKRvio2OIAx*H!>E{C~n zutiF#2kB^~a2LXhLb$Fn)*W=fo}%8jwGWH;sU>%NdwoEQ*J@}1N{B=b@Fu#VsWa%2 z_PCP|jUuIFdLMgd#Df-lFl0ZsuAK24%uK?))c%L61avcLR99(jEL^GW(@zXJCvp}g zbre5KI=s4jBZFXOTRo0 z^=}Nj-oC-(L$gy3`KRoMjprS|xf1p)qjRR_t1eA`*Kc`z-2O4+#aM($mx$OgYgKNN zn&c~&Ih+j^N=DWPpo!%E-OzL2rGY&8nSFRx11raORU>?x*VxN|?5u8CBj}D@#c1nF zPmVk6r1vXccQ4FHL;5wy3|9^_(3Ml_%?;Td#nUlcIV#M(qL%)JO=yPSUDnVPaSj>d z`>S}jnUk@gjs#?%qbz2fcdPI88bv=mUoodD%Q3glSNWn2_>K4)j-9r%;*d!&D& z{VYo~3IE_pQL^=GZ5^W*P#4bo=}z6#u8~3d>nOlI(6fDAUukd|7>UL_W&_i1vEyJr z_*V3|ACQE;D|pKtIS3%b8;gTCS$u$VK-Zu&?*;YTNq4V@0Xb$kc1#kphdZnbJNglo zxM<$f5qf0KkXcS`sbDRqMA$^<`r;T#QYc_-?$z(Bkc@7wL~++c4w^WMWo&aZ3HnW| zj9G(=bwd=1RVcu}uuULcok`TgKpUy+tdB5AePWcJ-uU8N5O2aniZbR3oZ{v}9TOv7 z;SLMGbPV)s*4byUo(uBF`#o2iwsV|s3}MeyPqnga3?#y7MwK&b4h*V>5O z7w2gzO3Iu-K80F?VXp=$_tnfjradw-NfsU2B_fLMQ)n=J5Qh_BJQ3*7(j=ZN(;Kf! z2XEt)s!^hM!yaC%Bm6sTm;b08Q3+Tru7D`;5$|hfrf^uh-$HN?FH*k0cT@ zV+X2a0NJ?B5UM}s&)y0~)Q3MOD|lKTtUeytxLPRLag0(ZZ<5xyjd1TwC?7T};j&$6 zg3Sr7?yk)$#$eM|xIhW8loaEfm2^sBH# z0#2w=LqRknjFEd{{}9$tz=Zv4NIo#i z4kH5%)&(w1yS1@lUb({o2`w4FRPqXjO+uL@gNx8d(U1(!d*2)Cg^5mv^3iKfd4625 zZEo~zdatKf#ZVZFxcG{MRt|*OmUSgM1Ma0bSxd*<4g}b*Kn}@&#}VwA3b(wSy|=oC zDs#GNU9?#rEOt5w_-qviP>Y?F;OI@Yo8$lv%AGzPcNUedDr6R7m(~IZZZ+fE6*g&| zvq~S1kBOYTc`Es?8Ye0cuq_XOyj@j?s z@8w9|_H;kU7SY22jq2aC@JalnO==`anH*{RU8|`yyVq%VqzNuQ6i4w(z7Z^x$Kfph z1lF8Esf~&Z8zxTIHB98ryRAz!1HltR2#X)+ES0vcFE-f@ggq7o!kXNNy(dT{j<)q% zYoJWuC(+WeE77IPOc6Puy#2iT@4OCQS#{qJYV)Ox2i931@9|+RpFu>BfM8 z@@&EHW)~PVtTEK*6)!QHV2dh%qgYSlfNPQ`J5ZYwKL5xnf7^o(3ul|Z@+x!z`x!xj zTm~#(z}lRha*JU_EASGe&DG&AeNxaadu0NO#t8TiswDC3R-X=`6>+4e_MNdqrjMM%cN-E=nM z#pHO0n0=6~x|INff8y^}#FC~Ynjn;8IWh7$<{l(4Gir!Us9iRMGD^&;D@Zz{z#ffR z#P_Ctmg=(!$!&fXSQzE@H|D+}=Yy{)0U>+!OO~-2Z^4~BUtfU~`LKG|6DLWuHG?3iHmL}_4+R&^*%Ln*$LqON-AZ?bJ$*NAov<3Z782YOpXizTWdtDFe z0ku0!J(+?v{b#Ff7C;NE5{4x|4z(smf7#A*TX-{m79V^rieJiZAL~b`12Ldix?QE? z#gob!c{#GhkzW82CzJR5d^h5MRx#C7G?I0+J@+b7it!}q)IDv_Xcdi_o`~MbGR$@b z{BT1sUieNC8CU%y>9klu{W24>RL0u8JRl%t;J&i?=?VMUfx%Psm(~!E9jCw9S8jRG zl(fzfQ7LlWrW@7W-lu`0ypEBb{ovjqTW$bY@KQ;E53z9hqn8j6Ms~yCFPY;p$#gHKm9nYm# ziJ_>hsXU5<)CV{8pEHIRUYlcc$#};Cnc+T~r9!F|NFzId;|hV&Un8hkOMwwV^mp$>3WCfTHfb27a*+A35J?5^oGKNWLZ zmv5ECLL9ESbtgwSE^U8a85V!u?#>)kJj#m>8C*JYJ)O5@0Jxs3YlgatX)O~C+0hym z9_Do52`unp5HOmya(7-*fIswGb?)-;R} zQ4mHLi@P{NN&*?AS0^Sl{~qUUzQni%Ue&gNxA8r_>UO8~{mkWV^h*DjzHQ>+R#i9o zBg$qx%WC%F-Na#pCH1ss!yOz+BcTQ1XVauwGV=ZX<3iDVQn_kpY5jA^g}EqNfRU3> zW8oAS1!}6w>ZO)8VVFNviTv=y_bnA9%W<0}*=RrY2X}TU6jqOir;BNb z4*ZNw)%@Fyc7P97M_St^V?e^4!2Hb!{2hg`J2KUZIirRg?k>Bn1z_6Lwf|dig11P7 zUizg4pY_DrNam^SsR3tC?t235$P<2v)WP9`Q446P1u;MxfY(kq1Wd0kyKuv0|+V(+>VEZNa(#$ZrmdWu{J(uFdtq z{(fjg>o*hy!Z9Derk`u*8a9dmlBRsboVjLLPNLLl=fnqz`HqN0-o(4F#M00P*`{g8 zNBBPWV!`eojTvOE)m_+&?hZwMc}7iks#TUjuF7?u7Ix5#!usj0&L`G&3-3C9C6rj7U~uzNWz+80EXr3r@apjKw6o zSbNM*dpxx;u)&WJk{=_$x$idgkO-i{K>2a-zJcB2ebGFxy>fjVFx^q-TB zq+HWOBF8U^|I9=U~x?DJQ#3oQH4|?|vkkf@%tZ`NkW_nzcd< zctg4?)wN?~0zdn6fi(g7gr*jw<TW^hUwdjC|MiR9Bxa3Z{*yh@%i9vj;sD4>7?&vp0R4XyC@QKo@3z z34^P)nHVe|$!a`sULG;o0gdYPMCazMjK26%$@olyYm#}`oa2G_pmaTBZ(A)UvSEW@ zh{^}OI-s?vm{CF!+o7n(%R43pU;J2e0F4aOPu_Sh(%eH z@FLyhg_{MUT>!SR`wf+CtQVWZ8ON)E?3M>P_QXu)4#Hz4vk@D0gizD6=fEn)V8w zY-ny`ZupO3V6*a$?HMbEx7fb#vlE%MJ|&5Hvw7fy|EFky*5bew5o5SS6)EeA%XrQD z=k=RaC_-L7w-qfZ)=xRFlHB6Q?}7!Yuo5 z3v;S^YmCL1hZ$z1Zr|Fbgls+qg$I+whYi&j;nMk4Xb21#h%$-@9J(i+8*cz=pc_ja z+QaF1OrL(4HTEF;Jj2a|88_USitY+s&0WiEDS*Zx+QK0o&xiFlk02pYE z`^u}}g*Q&~XYEgp5@U|Gxx4313NwCmv3VF#CI_c>?6|&wV*bm8ZZ_=e;yG?3tY{S_ zOG74q^n{~j<7~O}CI+l_OD$T2va3v^j4KV;quydC7c{%j>Rp_oCx6ByT;*h%qR|%T zbfkv{Jo~R0N-`0JY^k1-hB{~?squbu;;bUTV@hR}G92-hMiqP<0$%YWsJVsAA#;%= z;tPn~4*`o(U2op81Lem({W=09L<#>g!CxsqXr^nIU;-qt z%^Lk?pUdyb94E_qmysQaoGWW*&3M^e>#gv4cn-;Jn~ z04Q2g@g+*j;x61}9(5&aiZ)N~z3cvYBvpsavU%^WS_Ibpom-V}@?TdbkFLJ#-4qJ_ zV{2w>T4CXLfUV+|pJ~Y1nL-+?(9In3NNhdj>xOOfZ!*j3(4;xLtRZ2NcfSL*r+` zx6VL&t_O8hetTXE+3o}2qq68zk+cI6#@2$^s+-I=!UmCav|Z~o5YJ0Oq_Q}sB|!&h zXh@U^>swcM*9PuLRaIj@N#0>UH`#g#AT{jlzkTxY@}fB9Bpx+$9-E%a=TX4zUA7z|bq&%D!NCbqn0Qdmg^bj63e4zn!_J0BwL+ z?FI~S_(WG7V|-44cFw|qvGOdg!X=uXe{cEboi$Q`?!6J&_vuCbailRC4CW>@1f|3{^okwdc)Ac!iFOHZ?f2P%F}!L|V$u zOR_MwV@wyB1ZG$<0Qd9!L%$hjAywH6TJy%yDGIKWdGn$p`I0iGvv^uw9?DoCeFIo4 zuD>2A1hc_a_r736tf4xsp$v7e50s_MK_L$?zZbp~WEiukAmC&iInLS;DJmQ<$&hXFem#6#JK0(!$C!v(6}IsT$=Gt4xljSi zDLAuc=tDYop4d6|yA*h+CQx9@y)&}@l2Y4lyXb{}lHY#v^V>gz>mR0yPwR4mAc#MK zh5hdv5|RIIuK0)QO#LxXY_OvE==i-ulz>1}grApOKI+Zj7LlI78u_Od4b`Cs#-F66 zQBwd8i7oGTT;XgBtTy3_bJwg-Gawk~M| zC$0J%CDd|+-+p=x3Hy>77xTI0G-M(?-NP0a08FB^#D&dr64H{m(KC=*5|7}AMY5#? zBnfJuB}nKT5>_H%Fd!t_F_I4ro}%LmhyiqsY~+$frI=Mo&7c)qycz~p7_eT3CDAO3 zhSStk0*>WX`803sR} zGg1R4MEEIMW1c#6>E&WT1yg^Ci-)idT&DUMy0mx)`4o3e9+%iSs0fCPIp8IsJ^SYD zr<*fylbz2{J(l#`7|}soeu2M`hs1N#uVCV4y>hXQ{Kma5BlUPYcPXR{66cawR|zVg zc!ta32%6I4J5;G}-xd24fa?y>;_L!l?Z!AvHDJ^@jHGhv8WTvoh71zbR~ z98fZsNb&=UtVGYHv9#?Rgh|gpcJGg0=1#*OuqG(f1ZpfYRFwMr3qJRkO%D*GM)7Tc zE@TUypCMPb%734C?h4U2R8&ZX`%KW9-Lj=Gxd&_`M=%1$vW_?=T3S=Ueq0Xs1DPyD zi3o`Eo`NJ0pV^6x)3q0^1s#`0m3%W`QE~~lq)p_2!YX!V2bwR_!##t)uecrU9HSWZ zaAZo)T2}{>2Ew|C!ZO2Jy4QUZei9`%Bj9#8`94e#_=zfY@Qd z_3@y<;Qo3Kyb^xIbjzeQ3J!4l&avjcdTEbgb344f-AdmwSiu#{F2~)2FH#>{@GMUr z(F-nu@$Hum!4PE8b2wMc;F&+ znxcM5)lpdE%^Nq9D3>LSaGqmvlT9Zv>opD<-; zvl;hFg@=yvDqxhuvDsUqF~b`846-AK^G6{613=%h-j+0fIJ8ru9ROXCqle00YoMmO zCzK?eYD{F-ZE#gh4$p&guD z^)k4YHBHPMohql^og?7t(xK~E*I~pcIKZE)2*!hwN^4(K*|(33R?-4XE8Ok1~T(NI}L3KY2-84+Wxtv$Q3$4A?Pkol^@>_q%rupSR#+h zbl!wLULiWpVMuE+C$tSqHF)%0r)i8!*-(b=`{q!TGrG+vB6@iu@lZS9quz z0eRNHhnm2cd4dh0GV}fH=TMB)<9zjwHFSnGTrDEXM>Gx*l;cY}paTp&&vUdNK1wp* zh;G{$hS3;xA452gGRtvYbK`M8H6>yTYYJbHvYefjpFk5^imRRzB#%;cs@lOeEA+nt zj$!@HxH#GGWQAGPPW%Xp5^*881AQlE@42;3+L+p#9{Pk9!8;VNx*)CD`bHT}yj0Hw zW+wCM0(gpjZ2I_tEg3*4}pf)OM3SdZtcHX(_*cY{%I;by@ znZn;n6X8cj@JU-TeQ+Y5dC@MfJ{fSf>a9#XL#Iwv(_UB}y)6f$MDPfDo=JWqz8DD| zzUlJ(T#F3xnPqm>yPwcv$CQkB7y?G$J z;)nOz%S^T-CogtxS1ulI&sR*(DayPD9^hyO{3Yt-s%V*}+gja8ZZ`m=9O{g8qv9BzDJri>-TeFRb8i4KAmIAm1VxsXbm3TeSEN**|5P2ELj$CyYDBc!&nYE zM;}3Je365N{^V_w38)k{@W~k?b|XmwQS#yl^lA-on$S$N0WE%ip;qsnSPeVR3B*?e zR%EHlLmhWnZDE{iX5h*#hDWuBJVzfdYoL; zP3uPhkG`pH%)_?x3=++Jo=8uMjr#glJtrn_sJ$6pq6!To*%<(pLYaX+f=fJn)g_!E z(Le!PL0&y=+09)!eX<#`-sqeZl?QpdM0G1e{U*1P-4l0(#7Ce4hj@!DY2xWLhT{C& z`NGQWCl43&rHlZL|8=?oIYcNxfX1Ff`s+-2)dEs#NjAbZ?j~sIv^>I?+;?SB0;40e zXi@v#x7qI#i&@S*pvN2fJJLf=ftgrAj@5CYjOMVnHPdmIOG4MkpOwPIF}=~E&LW(| zTrJ9T<0hPEc8T2nH)T9N3;9QJsVMsu^lHn^CSd}bwEbPE^67012Z0y&1juB4=bSNS z8&GxdsX8O4+{p*DhcCVOU3Y?{VyLx(vI%gUmC_z2^YUoH zE1x3mJTIBX0-o)I*l!Rx<8XZGLNylVRm3|-0Zd-_=vWiO4A@^Xu(IjV;SXJcS;!{v z3?@r77t3Kpj&9Bl2|g*E4DdrmjN&pdWIZk}T5olwc z$Ul1r@_&;ZM1Kf5JDFQK{-e(CUe^49Er!x}<4W8!Nbb!*9FqN(H5<7onS8t0rHZ(| z%Tj-~I;ztuL3F#ub;lRS@5nGED~$EjIFDoLc4Rkp7bemTDp0hlOcAea)^N zGsGHOzenqdsC)Wts>JuL^SlH72;#1W>-20U5v`#~&(OU8Wiy~PoS;59&KriI11+JI z#z^W(>qH0XgSg43#W5dj!(GrEw@Ruy@S#V>2!v^sped^TyR~AGgbOnTu8gEUii9=F z%G{PZHq`tpN9sBt%hUxuiwrWDVS%yUtyHLU9t_yi6-g6$=Y_Si759hpD_YjF`-;XZ zKOepW_K>BZmjkoJ7=yEz7@MWN`PCa~eW;CSKTQ5(bgtF?K$#11uXn&5?~ z0SPi0m9rvLQmK@L#zl_#3~m@{f8~{Us5x^zV+wO*8SU}SekC;p%FPa9&iEu&r>g+6 zS;CFg7$Po(IPLwh#M=wUOhSkn1GpkGu^5K)3l4X&-GIXjmJ`LfjshBIMD;{1PPi_o zET{TORq94`Z7F;C+#pVTvs0K4VAnd(n0jF;?Wml-H#v(d$f7(W>x4p*-^0oKNd8pH z&`=ZuQEE(Gpz&eka=*NM;f9g94tVN=|*h5h3SXd+ii z%bYn)<_=Q^_F1F=vm^!B3yswR=fKDmPzvZ30_P2AXqR#}IZd)n#b)^@Hq zo$=oFSlw`N>>)(#K80*9L~J&NtR_UP zI)yAML@cs}%%VihyoF4xL`<}WjHE=2c!dmTL=13+^x#DFp9OS}0J^IJ+9Lq%b^*;Y zfM&XYdKf_6Q$W=MpsFdLECEpF6i}o9C}Il8LjdGH1!OJ&GMfTY69B1B0f`ELM7Drf z6hO>dK*S0lqAdWB0swdgglGUlxB>!j0KsQI{v#p&RX*MkA>MXA?lK|nbUw~7Ax=*| zb_*ePO+Ho$Ay!U4W(px@Og=^kA%;&rx(gw?O+K0lA(~D;stO^hY(9!8AqsCkGAki6 zZ9WnyArf9bA{rqgTs{IgA;M=K{38MURUX_C0o-=p_ho|b(|NGN1h74MFfC=&&=WkW zN1aPx_#q!lOC}#CHyu8tHMCRD7SHz^H;0;y8!hWE`&0Cl55Djb@I>8zIz3BLS7`;~ zZLx7apps(M%sqp8>q6d~me}#K@#rJvUY3LP#WQ_*u=DeAmDC5z$3%G5r}woz|7n*u z!uNY~?d?nGm~C7-t7l3Cf%A-q{^H<{4wW0>82+~a#Ietq-$%3ht7vw(oVzJ4sM*SWARxp zy1&4mhCA_6Huk1d_-s}$*6crQ4NFYsf7r5p{04QSXg=><@#KTqNeki;;$ueq{M_4_ zX8TZJw5X*x-AD}T1d-m*z`vFl9K5CfU`F&5`;w%DZFhUVvaJ>TIE-EU@EsFMX?kMy za>RQ4{+UdTgQw-I()Cj9hJN0;O*8zlJ@gEAJ^yvAt^MGAZG$&`-f<40wL>e@`GK<* zs<0n>)CFhm)8U?VcA)58^f4u{xsrTV$aMSiFFS^Ro-*|c!|wx%y0O;grYbKUlOv{Pa+MG!xt z|8X*%!?B2otfaB}YWHKLHTNndwe{ifR_0^x`2;j^_>Av%kAo+8u8P_z(K^cYvAqNC zMYuRF2%@*vk009ZTU{QIor`$x%qg?ncbf*9%}NuyI-qNQ9`=O+W~|PECSB9>Fy9*4 z7Iq-r$NY%^^gmN%;(rqX zipDmMf2`(a)rwM5APfjS=&$(T&1(`KX*1=huc#X$5*3GLZ z!ElC-(q#{_XP!ExGm()`u%GSFBOa_}vheb7jw0ni){mxDOL!V!-!sg5!akv;c`|S0 z82s(eU{z(KPb3+^Ydd~)T{zAwAY>gWsdq!?eM`*bBx)87FX=NHlp`lTzJ|QhaO*2u zqdZ3P;_Tp;v4>LzhIIKY5PnDpZ~lP<+yfmi}LPO3L~Nx0felTLIh+0}z?ItCsi7w7hE zJ-z{vO8@r5g5xX59?OP+LDt4o(n7;&3n}y+`;d?B@2}ohf z7&Gk@_u34Q*Ad4L0NI-PsEH?nIvV$RF5GI}7D2a`*t{)!ir5`n%OoOai$2CoL)GFo z?UV?@^~56BB??S12gGc=Jq(IWVgU;7-4mK*I{ARZWum)he54D zw_zI!@@l`|_8%MNi$wHnFve>9X7d19w5G^SYD|}7qK>X_a+`?OYhV(1qdarr%NeOx z-Tf^H6}bUynGNPxw)nzeN?JTjQuI_VbW%o`eNG~(l;lpU>K9(W+TBdVJ9_oPreQB~ z1vr_T>Un(SgC-uDX?gN^#3MIX+>_TxC%-8--4!w}N ztQNTCQ*`96I)g5aI{q5EEzB^KYIBXk4fr?wu>H+cx2d4QLH_G~o2F5~I&sW_^Y=4p z$?l);s9@5;KVb`EH)t?S!SJ{&RpKH}ldx+7V!@h~`#GqOM+r~pm#hb1HpMcJfV-2Y39;k`XY6iMVS@M_ha^ zR={uvUnj`UaD?net9%(cmWfCokWV;4xtl?m&o&+go?ekb)G}*G$TlPq0&34s*INTw z&X5^BxO*m>RpfV|3Z9RFl55={kI#6NIx;#G>D`8Q9tXEm=XX}N2X`N~7J$%>aH&zF)p92p8 z*nn>tKFk{NxDwywDK~K!*LIFR2Qyw7ax8tj1X7{=;e;om@eP%1bV0OO!odzeA^!Q-HsI!%Df4>Uq$|XL$6jg%ARhfnXl=r{Uex8 zc)->%C#+oDqdQ5e1%q;|@NA_nxem<0pzHdCtn|OXI+;s=g49|2N zbOcj_5|{(Xv_^S+ecnLlKS(}1BEyYp4_hrX`2#!=l@lywL=+Pcve$sLMGb&R5ys?F z*Y1?1EP-m$mO)#KV%MK zT0UEU4CE$LQAc~6LFjsiEn>IwJgiFzaFd!EB*7tY`f4GO#)md~A3aH56>M*BmS&j_ zNG(Lu5KlJ-EzsB_xm_OIbl&0X)KQ-X!&|0D;m{ZHq*uUDiUn5B8X0u*oaJ;J70D8tLlU7qz$Y#VIYq`6N_-B!w_F!aW z=P6Zqa0Hv5uCAJI=>Jr>^gmksuOuJkzf-usDBoX{?=Q;t7v=kl^8H2m{-S(;QNF(@ z-(QsPFUt29<@<~B{eK7L`$yCFuPEPtwo?C}lS{gPHhq6tzP~KrUzYDL%lDV%`>)3G zt^E;&e`WdT{@o<-FU=t$^R8ye|^4xeZGHvzJGnbe|^6HHGIDR5P*O6`Tl3F!2i1d{5AUi z7cu&R{jpo}48g#s{~`L}QGtN|Z3`;%KYW+}!}0rv_^DR=$8l-24{DH4cy#qV0&A+2 z7I+jNny#2+j52H?2ev-6V0u94G6Bk%gZP?x_QxfUs|hu4 zjIq4NNP^B*M5we1WyYBF@!|PlvGdk*2VF5S5hZTKIi1N7D zORgiq*vyGgqPv%H>dJ;(qavV5+W5~c2F8X4t4ccTLub}}!4#!&=bYu_@$BCrY-n(| z0V^U{3F<*HVPjIT6e;0l3lX9}bbpX0esufjk&)?QoLs+o3i~x7qVOGxIlh@q+vg1K zQgFOz6Wj$=6c;560XxD5qq6Sv>=^9gYyOZunR+ntc{$j?uQ^^gZ)IzIn>a0Zyb4y? zm#98NtrpRcf=;`Uw3WllP=h`|#V^&u$hG#aaztGqji*#p?(2fxHRtZ|e!>$`wNMA9RhLJG%23(OPj51bG(6NgziiZcGp^`j~$J|w5VsfQQkGIxK)RFz+=)jb{ zg@5z<{`ir3Zf{oCPm`n%mu30xMYKYh&?qQMDIY)NTH3I|onpHfSRssMWpp-5lbhA` zb-ImxIIj&Itz}0ziqt$@6Ix$yTY>sRo&=S`F3qx9D=1!E(W4pYR2`wGplDJRrII+l zSXe~eTNK)|He2Z+X&Gs={0td8{7fm0bQht{ib;n+S1hxcrxOfks{o6->#t9Q1dO+8PxG}Vkp|iBX|wmsQz&%;rk-T4|3fJq>R|I)q=S6C>lFj z*(5u+OTg4{^A;`{wHFc{??4tV~8O+>dcn|uejsD~?QV!xBLmJoKrzblt`wa6kgDhQN1l#GuwgyqZH z?wciW06d_c}rNYr-y?XN%}m}8y^0##Qpql8W`rm$!dgt75beDjPPl?xUco- z?J*&kU5p%1t6`}9jrwaGJO~qbgVD7#?GG(Mu{2 zRO8q;pSv&ZGd`s%rFbNm+DWD)^P(*`kEJ& z2NSQ<*ViuwC}4!-Wn=kJ>KS0?lxV=QO|W7LA(RoPrpW0$?c7m#3|>wj5f2oy8A*!S z;8v;B!yx^X@ujo8{;n3DOo3pLuBbJRWrRxSlG+{KqU_$;aDJmc7^?Sl4SZNyLo2K= zW9G}_0xub7`DX}Ff|H@&c|2c8WuOWROefJZm(jw{xrJH%#<6e>gB2)WaL)ZK)cxE< z^@Pdh;YK~+oM~?zZ&?bUJ#}%|U@lI-JqY3&e};WrIE|4_%x$!Z*f!Flu=$)cH5KpU zHs@pYKop}lTcZ6A%?AF3F*fc*2P-SvWay28vz=1|j3ugKr zl+P`0j7=W6uO2pg@}k~~h@HQ_>?O|N3?)mUA{pY0CDHzE3!SvG1r+%cx^ESX005RQ zMp(mHvKj#<4b7tPgJtNJQ&phSI7NkS(?t%QYQ!@|iTO3%Ppm2*ucBckw)U*uj2J;N zOLyp-R=8}X$I?vlY5{#xg|3?&bhs2~D^QWARw2$r;sAniuybnOuO`xGEF0_=&+s1v z>UWu9zoM5u)zoD?jDrPznLx0k$$BJG{pHVZL|YV`a$BU*re5KbK5o`@_+Ha?>QNPM z!8?Of37@WgaSxW0vv4M%{%!JWq)!0=o}o|jwPMZ*vN`8NtZc*Pr<)*hvO$Z7!vrxk zzb?SpNoDI@E?$PyW$iv1xWnGAZa1UqJjGbM+^dkl%e4_f( z%3i2tNq%m&Cr7WoMG2%{sRhQfY55&)Cst?|5<({Kn7=8INkccO{!6g*cFsr>KT{q- zr}Pz*^$kC0^jG1hq7CUT^WmGQhs6Pa)iBp5U#-)ws`tJIH)vtAC3v20;_D6o`XN6X zmnp{In(m5nJD?^OiHDXI__le*+c1noBThoS-~e?&AwUG!!Cce$MRgSCs0WFa5^}ng zw?`AkJwitobGedd`aS(fJ7#$p`s}zTPKoCRw149^j-)Gx7o2ow&hD>t;#<%3o1~9C zJXBjDP%Qe^tX=oZ!f2aY0@Or&Dd7WRd0iH%k7LX0-8LS9FH;N9h09gHXB?x9v`t^KDqUDEX2j=VIeo>Zu!U=-Xzj<0z*u7 zF?-ddAkG%lQ2Ry0bQ*_!+V(Yo%XQqL2dZqAU>CqWN zjE33E2Va<*2RDX+=(A6Ro7nS;$Jc@xVx^i3RgQ3-?_|B+!eaimlz5O)lis_?n~-P8 z@-jJ0?UANGF$ZWuxc8XxcFw?uyLj=Sew5H~hEF8mWTl}-{K-T(hjWI^b=Wn>f}5jm z=6GNRr-A*@Ty#K${k!A9;euNamXe@vF7+9v^XUrnC-rtptWQk^xmnv4aoChM<(U@4 zBaYnZ6iyGb`TU+KFr8oDyVpmh@R<%g50iDs<`BNpi>n&h)EHHv(+Z=@K?S-f9n@x( ztMIbOs)8Upq9@+0XzC1LFN%!kT!v3fupYNh>Hna~fm9w)nCuixSY^-e1WA^*77Ns= z7?{Q;t){;G9RA@R@Xlk23W@d20w>2@KuDHIlvaJXl#yj`(@}=imlvG!RLEjV)4}G= zm<5hY5-5<|v@tM<2ny9Ri89fsy@l$o<9#n$wVY8UQJNpj8**4s;D|3WsnL=-Ifv;(J#6{M++V|_etuH9IfW} zK2Kyx6YzjG@WI|?*4G9+Ah=Y48=6=$|1&+A|F!*^cCb^h3vw{39Nz6O7rn0!d6p^u z!}ar31O5D#uq&FFcFfu`ID7*anr3_7*&%ZZztqv3HpHW|7~epKDj|1$T`#9$iDRo@_Wz73@UA$ zRksP&_>8F)8)=!70QV*O$F98p2w{nKp3cc)XFw_w6MT%UApA)eAXreMRm6TsqB0JY z_&X@+o>bVJu`$Rex-T-qiWp72+shPk07rxvgA$(^9bc=_Sf5VOZ3_eC2g;_p)nA~q zFs5htiSGL++mY?2qo)(!`XHBG&a$H^m;3J-cw1_@ofT0F6}J4tTjkG+ddUL4-72C4 zu#ne?JF(QEFk4=St@0F@k5)(og_;f7gSz`brnQ|)fw!Ie zXYg%y)7nd;pe1bgK!0zD(DKkyu#yfxirr=_EuS9+Dt&nmsOjH4fYd#k)>4B4=OoXv zyLDd09q?^-(|Yuxplz=0fu=RMX-)nVq^!qYNb1qeOr8+w=mf~GEb Date: Tue, 26 May 2020 12:35:14 +0200 Subject: [PATCH 44/65] FIX typo default -> defaults --- arduino_foc_minimal_encoder/BLDCMotor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arduino_foc_minimal_encoder/BLDCMotor.h b/arduino_foc_minimal_encoder/BLDCMotor.h index 4b98b23b..437f767a 100644 --- a/arduino_foc_minimal_encoder/BLDCMotor.h +++ b/arduino_foc_minimal_encoder/BLDCMotor.h @@ -4,7 +4,7 @@ #include "Arduino.h" #include "FOCutils.h" #include "Sensor.h" -#include "default.h +#include "defaults.h // controller type configuration enum enum ControlType{ From cb2a17e8aee109de8d888acd85f3feeb920c2fb5 Mon Sep 17 00:00:00 2001 From: askuric Date: Tue, 26 May 2020 12:36:55 +0200 Subject: [PATCH 45/65] FIX typo closed quotes --- arduino_foc_minimal_encoder/BLDCMotor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/arduino_foc_minimal_encoder/BLDCMotor.h b/arduino_foc_minimal_encoder/BLDCMotor.h index 437f767a..7cc4f324 100644 --- a/arduino_foc_minimal_encoder/BLDCMotor.h +++ b/arduino_foc_minimal_encoder/BLDCMotor.h @@ -4,7 +4,7 @@ #include "Arduino.h" #include "FOCutils.h" #include "Sensor.h" -#include "defaults.h +#include "defaults.h" // controller type configuration enum enum ControlType{ From e4e24ffae74cfac3809196f621221da81a2c6394 Mon Sep 17 00:00:00 2001 From: askuric Date: Sun, 31 May 2020 10:27:09 +0200 Subject: [PATCH 46/65] FIX removed zip file --- arduino_foc_minimal_device_specific.zip | Bin 30352 -> 0 bytes 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 arduino_foc_minimal_device_specific.zip diff --git a/arduino_foc_minimal_device_specific.zip b/arduino_foc_minimal_device_specific.zip deleted file mode 100644 index 632dbd2a780ec877648010dcce2fab5ad7c801cd..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 30352 zcmeFZV{oN`wyv9w)v=u!+qRvKZQHhO+qUg=Y}*~HV<)Fq9jvwQJ^QY6f8Krj$NV$D znpLyv8#Ug6_Zf0hAfPBfKtPZ{hS}wEaYP!vuHZmGwrD^=Tz|gRcQA4`x3SeVu{G4S zHn%ai*0<6%wlTCdGIpT*e|Sdw=Qo#XnzmRRC_b@CUv?QwHlZ|9eoe|!KZOLbp~@>o zBo|A?-qwB?(@Whpjecy5pCiH3~indyB2ckZ*-)>xCdm)p@DG%%%XpY){srr7` zXiPjPJSbdH^qa8N1^2Zmj06p0jGLj&_}pXUhJ6>h>S?!NpX0+>2OtJtJ1T&pPfZ*F zsj7_;>P{1)S5%QWgz-MtkOZWW^DEym&;iF#v6kTG4{N4|7nnl3{{7rmT3%|a%H1}hkWmS-&u`Bl?2Us zIKpZSTDET&I3GDdho;>IGsJBIG|-~pAU;})PQp6*_!bdO1B>;rxf5AM0wnv&RiplL z@ivZ&%Jum0HLO0Qn^+XCT%}|dsc4xaZ6qsjj{Zn4nftEJKX7x`q_)+@(>qcs8~U!z zGPb<@7u8djvN@MtX@c@ekh7duMwq#B8ye2Rw<#d}$*55JBA9+DaBX@lK_doJuuMm3 zmv#p;<}R3%Wk_#}R;`j2*U+{N>s&76w6_TTE7#(;rcOfX5yz*f;S)2%CkM;)Bm;;krW+Z{*b*n|1# zuFI+wkj~aC2|Mplv2ctzm0@}*1Cw&!>S3hM)cH~5*}lAFF&9xwtbir4<+4oe1?3J> z^XToRn?+^)GpRjD&~6ZlWg^NeP9u*5&DHdQN-sMgX^G=Km<9!3fo=mzV)dWYEL2XQ zlbtqt19EmXRiKLXr;j__yo4HZ6sn_?#>T2Ul*y*Er>eb6(G`mBD6TIN-#|n^?e6uI zeuumD1qbmp=`GqgV|f;bWGV=eu@IMc%lg2R{dB(YDXlYRyVvFTP+c9l1VN)k>mq=w z>z=}Q(@@7^Ht-<;6RxmpR6W*9{CKj&YPwPDTsW+($6psPlfj%R=nQ%UJ?{6!#p_VV zcJ8N*wVtV3?S<&1=L+*pEjg<8-;-j2eKLPOa%ZB)YU!8F#yF78uUrC0$lb4qbK?v^gZ&$Tg!Fc z`q)8a%&|(+mR?@+dyzsp50U_4JrfdH@dis<^vXnV)$XBg>cBYRgN=IDIoOXZJ)`>^ zMzQ_>NAg@gkf;CvPy4$rUh0?G`Il(u1Q=wUiqEuHLmyBr%FpV=t?tC{pDn?CKaV z!63;ib}@=ziZ;m}AIRbXrQU9ymD|fVb0$b@w(++xiA~sOoE{rx{%^Da^-k*1+9CKBJfF*%5#Rz8?2<$JUHcocPij>uhA7L?sWb8Vqi%NO|^pH=5kO^io&J5zCYH zZCv2AU~--|n*?rto7gg?wj7(hU%GkaQm}HZevF@b4Z%!3cmHg&Hwex2a;AXsdoGy^ zO-xjl3JK+b?EEsiw)z5=`wx1S*&>Bm{T&FXi3SLW;@{|*ptP`%jIEQc1FfN*-4K?g z?S|;BBgij4D~C3maM)ALgQ57=3p+k{t0bxL zYqGPQRI_TE+3DF&lW;HSxKjfLH9r>y4^|2j*<%-`4i`pZ@%Yx)kq#5coRT7q-0Spx zaMtmO?uhn!8;K9`DR0AtbL$~N^7h<=L5KQ>_l6-=j7o$Zx{<$N+ja58#8%v7Z;*_6-#dos{1R=Qn zh``B{oO^ntq~Vr>B7U=t#fSQ4Dzgizw#c~Hi=@~FhlC&IUBtp18+z|%hA(!{zAqNX z$N$2lB^_dh1DFy7B?oatu=d^8);Y5sd}w}?haf=yY~kKSw|ZhWmch88%v#Qtmm(^^M4q6hqXhOvHD zAI@Xw<6tZ^VsUMtF6g}r6F=8~Z5nM5ZBwlA0Y4+y1 zNTDI-=uFf|vZS&2LHDRbzt)ccB*d!Y_jBor*q0TT18(W*QqaQfCFgXjyCqw6%Q+*= z7Mxb;O>&MS9o>0Bf&G~`p+aL$vA-v6dO{mwPBAYJ=QF(rdKRvio2OIAx*H!>E{C~n zutiF#2kB^~a2LXhLb$Fn)*W=fo}%8jwGWH;sU>%NdwoEQ*J@}1N{B=b@Fu#VsWa%2 z_PCP|jUuIFdLMgd#Df-lFl0ZsuAK24%uK?))c%L61avcLR99(jEL^GW(@zXJCvp}g zbre5KI=s4jBZFXOTRo0 z^=}Nj-oC-(L$gy3`KRoMjprS|xf1p)qjRR_t1eA`*Kc`z-2O4+#aM($mx$OgYgKNN zn&c~&Ih+j^N=DWPpo!%E-OzL2rGY&8nSFRx11raORU>?x*VxN|?5u8CBj}D@#c1nF zPmVk6r1vXccQ4FHL;5wy3|9^_(3Ml_%?;Td#nUlcIV#M(qL%)JO=yPSUDnVPaSj>d z`>S}jnUk@gjs#?%qbz2fcdPI88bv=mUoodD%Q3glSNWn2_>K4)j-9r%;*d!&D& z{VYo~3IE_pQL^=GZ5^W*P#4bo=}z6#u8~3d>nOlI(6fDAUukd|7>UL_W&_i1vEyJr z_*V3|ACQE;D|pKtIS3%b8;gTCS$u$VK-Zu&?*;YTNq4V@0Xb$kc1#kphdZnbJNglo zxM<$f5qf0KkXcS`sbDRqMA$^<`r;T#QYc_-?$z(Bkc@7wL~++c4w^WMWo&aZ3HnW| zj9G(=bwd=1RVcu}uuULcok`TgKpUy+tdB5AePWcJ-uU8N5O2aniZbR3oZ{v}9TOv7 z;SLMGbPV)s*4byUo(uBF`#o2iwsV|s3}MeyPqnga3?#y7MwK&b4h*V>5O z7w2gzO3Iu-K80F?VXp=$_tnfjradw-NfsU2B_fLMQ)n=J5Qh_BJQ3*7(j=ZN(;Kf! z2XEt)s!^hM!yaC%Bm6sTm;b08Q3+Tru7D`;5$|hfrf^uh-$HN?FH*k0cT@ zV+X2a0NJ?B5UM}s&)y0~)Q3MOD|lKTtUeytxLPRLag0(ZZ<5xyjd1TwC?7T};j&$6 zg3Sr7?yk)$#$eM|xIhW8loaEfm2^sBH# z0#2w=LqRknjFEd{{}9$tz=Zv4NIo#i z4kH5%)&(w1yS1@lUb({o2`w4FRPqXjO+uL@gNx8d(U1(!d*2)Cg^5mv^3iKfd4625 zZEo~zdatKf#ZVZFxcG{MRt|*OmUSgM1Ma0bSxd*<4g}b*Kn}@&#}VwA3b(wSy|=oC zDs#GNU9?#rEOt5w_-qviP>Y?F;OI@Yo8$lv%AGzPcNUedDr6R7m(~IZZZ+fE6*g&| zvq~S1kBOYTc`Es?8Ye0cuq_XOyj@j?s z@8w9|_H;kU7SY22jq2aC@JalnO==`anH*{RU8|`yyVq%VqzNuQ6i4w(z7Z^x$Kfph z1lF8Esf~&Z8zxTIHB98ryRAz!1HltR2#X)+ES0vcFE-f@ggq7o!kXNNy(dT{j<)q% zYoJWuC(+WeE77IPOc6Puy#2iT@4OCQS#{qJYV)Ox2i931@9|+RpFu>BfM8 z@@&EHW)~PVtTEK*6)!QHV2dh%qgYSlfNPQ`J5ZYwKL5xnf7^o(3ul|Z@+x!z`x!xj zTm~#(z}lRha*JU_EASGe&DG&AeNxaadu0NO#t8TiswDC3R-X=`6>+4e_MNdqrjMM%cN-E=nM z#pHO0n0=6~x|INff8y^}#FC~Ynjn;8IWh7$<{l(4Gir!Us9iRMGD^&;D@Zz{z#ffR z#P_Ctmg=(!$!&fXSQzE@H|D+}=Yy{)0U>+!OO~-2Z^4~BUtfU~`LKG|6DLWuHG?3iHmL}_4+R&^*%Ln*$LqON-AZ?bJ$*NAov<3Z782YOpXizTWdtDFe z0ku0!J(+?v{b#Ff7C;NE5{4x|4z(smf7#A*TX-{m79V^rieJiZAL~b`12Ldix?QE? z#gob!c{#GhkzW82CzJR5d^h5MRx#C7G?I0+J@+b7it!}q)IDv_Xcdi_o`~MbGR$@b z{BT1sUieNC8CU%y>9klu{W24>RL0u8JRl%t;J&i?=?VMUfx%Psm(~!E9jCw9S8jRG zl(fzfQ7LlWrW@7W-lu`0ypEBb{ovjqTW$bY@KQ;E53z9hqn8j6Ms~yCFPY;p$#gHKm9nYm# ziJ_>hsXU5<)CV{8pEHIRUYlcc$#};Cnc+T~r9!F|NFzId;|hV&Un8hkOMwwV^mp$>3WCfTHfb27a*+A35J?5^oGKNWLZ zmv5ECLL9ESbtgwSE^U8a85V!u?#>)kJj#m>8C*JYJ)O5@0Jxs3YlgatX)O~C+0hym z9_Do52`unp5HOmya(7-*fIswGb?)-;R} zQ4mHLi@P{NN&*?AS0^Sl{~qUUzQni%Ue&gNxA8r_>UO8~{mkWV^h*DjzHQ>+R#i9o zBg$qx%WC%F-Na#pCH1ss!yOz+BcTQ1XVauwGV=ZX<3iDVQn_kpY5jA^g}EqNfRU3> zW8oAS1!}6w>ZO)8VVFNviTv=y_bnA9%W<0}*=RrY2X}TU6jqOir;BNb z4*ZNw)%@Fyc7P97M_St^V?e^4!2Hb!{2hg`J2KUZIirRg?k>Bn1z_6Lwf|dig11P7 zUizg4pY_DrNam^SsR3tC?t235$P<2v)WP9`Q446P1u;MxfY(kq1Wd0kyKuv0|+V(+>VEZNa(#$ZrmdWu{J(uFdtq z{(fjg>o*hy!Z9Derk`u*8a9dmlBRsboVjLLPNLLl=fnqz`HqN0-o(4F#M00P*`{g8 zNBBPWV!`eojTvOE)m_+&?hZwMc}7iks#TUjuF7?u7Ix5#!usj0&L`G&3-3C9C6rj7U~uzNWz+80EXr3r@apjKw6o zSbNM*dpxx;u)&WJk{=_$x$idgkO-i{K>2a-zJcB2ebGFxy>fjVFx^q-TB zq+HWOBF8U^|I9=U~x?DJQ#3oQH4|?|vkkf@%tZ`NkW_nzcd< zctg4?)wN?~0zdn6fi(g7gr*jw<TW^hUwdjC|MiR9Bxa3Z{*yh@%i9vj;sD4>7?&vp0R4XyC@QKo@3z z34^P)nHVe|$!a`sULG;o0gdYPMCazMjK26%$@olyYm#}`oa2G_pmaTBZ(A)UvSEW@ zh{^}OI-s?vm{CF!+o7n(%R43pU;J2e0F4aOPu_Sh(%eH z@FLyhg_{MUT>!SR`wf+CtQVWZ8ON)E?3M>P_QXu)4#Hz4vk@D0gizD6=fEn)V8w zY-ny`ZupO3V6*a$?HMbEx7fb#vlE%MJ|&5Hvw7fy|EFky*5bew5o5SS6)EeA%XrQD z=k=RaC_-L7w-qfZ)=xRFlHB6Q?}7!Yuo5 z3v;S^YmCL1hZ$z1Zr|Fbgls+qg$I+whYi&j;nMk4Xb21#h%$-@9J(i+8*cz=pc_ja z+QaF1OrL(4HTEF;Jj2a|88_USitY+s&0WiEDS*Zx+QK0o&xiFlk02pYE z`^u}}g*Q&~XYEgp5@U|Gxx4313NwCmv3VF#CI_c>?6|&wV*bm8ZZ_=e;yG?3tY{S_ zOG74q^n{~j<7~O}CI+l_OD$T2va3v^j4KV;quydC7c{%j>Rp_oCx6ByT;*h%qR|%T zbfkv{Jo~R0N-`0JY^k1-hB{~?squbu;;bUTV@hR}G92-hMiqP<0$%YWsJVsAA#;%= z;tPn~4*`o(U2op81Lem({W=09L<#>g!CxsqXr^nIU;-qt z%^Lk?pUdyb94E_qmysQaoGWW*&3M^e>#gv4cn-;Jn~ z04Q2g@g+*j;x61}9(5&aiZ)N~z3cvYBvpsavU%^WS_Ibpom-V}@?TdbkFLJ#-4qJ_ zV{2w>T4CXLfUV+|pJ~Y1nL-+?(9In3NNhdj>xOOfZ!*j3(4;xLtRZ2NcfSL*r+` zx6VL&t_O8hetTXE+3o}2qq68zk+cI6#@2$^s+-I=!UmCav|Z~o5YJ0Oq_Q}sB|!&h zXh@U^>swcM*9PuLRaIj@N#0>UH`#g#AT{jlzkTxY@}fB9Bpx+$9-E%a=TX4zUA7z|bq&%D!NCbqn0Qdmg^bj63e4zn!_J0BwL+ z?FI~S_(WG7V|-44cFw|qvGOdg!X=uXe{cEboi$Q`?!6J&_vuCbailRC4CW>@1f|3{^okwdc)Ac!iFOHZ?f2P%F}!L|V$u zOR_MwV@wyB1ZG$<0Qd9!L%$hjAywH6TJy%yDGIKWdGn$p`I0iGvv^uw9?DoCeFIo4 zuD>2A1hc_a_r736tf4xsp$v7e50s_MK_L$?zZbp~WEiukAmC&iInLS;DJmQ<$&hXFem#6#JK0(!$C!v(6}IsT$=Gt4xljSi zDLAuc=tDYop4d6|yA*h+CQx9@y)&}@l2Y4lyXb{}lHY#v^V>gz>mR0yPwR4mAc#MK zh5hdv5|RIIuK0)QO#LxXY_OvE==i-ulz>1}grApOKI+Zj7LlI78u_Od4b`Cs#-F66 zQBwd8i7oGTT;XgBtTy3_bJwg-Gawk~M| zC$0J%CDd|+-+p=x3Hy>77xTI0G-M(?-NP0a08FB^#D&dr64H{m(KC=*5|7}AMY5#? zBnfJuB}nKT5>_H%Fd!t_F_I4ro}%LmhyiqsY~+$frI=Mo&7c)qycz~p7_eT3CDAO3 zhSStk0*>WX`803sR} zGg1R4MEEIMW1c#6>E&WT1yg^Ci-)idT&DUMy0mx)`4o3e9+%iSs0fCPIp8IsJ^SYD zr<*fylbz2{J(l#`7|}soeu2M`hs1N#uVCV4y>hXQ{Kma5BlUPYcPXR{66cawR|zVg zc!ta32%6I4J5;G}-xd24fa?y>;_L!l?Z!AvHDJ^@jHGhv8WTvoh71zbR~ z98fZsNb&=UtVGYHv9#?Rgh|gpcJGg0=1#*OuqG(f1ZpfYRFwMr3qJRkO%D*GM)7Tc zE@TUypCMPb%734C?h4U2R8&ZX`%KW9-Lj=Gxd&_`M=%1$vW_?=T3S=Ueq0Xs1DPyD zi3o`Eo`NJ0pV^6x)3q0^1s#`0m3%W`QE~~lq)p_2!YX!V2bwR_!##t)uecrU9HSWZ zaAZo)T2}{>2Ew|C!ZO2Jy4QUZei9`%Bj9#8`94e#_=zfY@Qd z_3@y<;Qo3Kyb^xIbjzeQ3J!4l&avjcdTEbgb344f-AdmwSiu#{F2~)2FH#>{@GMUr z(F-nu@$Hum!4PE8b2wMc;F&+ znxcM5)lpdE%^Nq9D3>LSaGqmvlT9Zv>opD<-; zvl;hFg@=yvDqxhuvDsUqF~b`846-AK^G6{613=%h-j+0fIJ8ru9ROXCqle00YoMmO zCzK?eYD{F-ZE#gh4$p&guD z^)k4YHBHPMohql^og?7t(xK~E*I~pcIKZE)2*!hwN^4(K*|(33R?-4XE8Ok1~T(NI}L3KY2-84+Wxtv$Q3$4A?Pkol^@>_q%rupSR#+h zbl!wLULiWpVMuE+C$tSqHF)%0r)i8!*-(b=`{q!TGrG+vB6@iu@lZS9quz z0eRNHhnm2cd4dh0GV}fH=TMB)<9zjwHFSnGTrDEXM>Gx*l;cY}paTp&&vUdNK1wp* zh;G{$hS3;xA452gGRtvYbK`M8H6>yTYYJbHvYefjpFk5^imRRzB#%;cs@lOeEA+nt zj$!@HxH#GGWQAGPPW%Xp5^*881AQlE@42;3+L+p#9{Pk9!8;VNx*)CD`bHT}yj0Hw zW+wCM0(gpjZ2I_tEg3*4}pf)OM3SdZtcHX(_*cY{%I;by@ znZn;n6X8cj@JU-TeQ+Y5dC@MfJ{fSf>a9#XL#Iwv(_UB}y)6f$MDPfDo=JWqz8DD| zzUlJ(T#F3xnPqm>yPwcv$CQkB7y?G$J z;)nOz%S^T-CogtxS1ulI&sR*(DayPD9^hyO{3Yt-s%V*}+gja8ZZ`m=9O{g8qv9BzDJri>-TeFRb8i4KAmIAm1VxsXbm3TeSEN**|5P2ELj$CyYDBc!&nYE zM;}3Je365N{^V_w38)k{@W~k?b|XmwQS#yl^lA-on$S$N0WE%ip;qsnSPeVR3B*?e zR%EHlLmhWnZDE{iX5h*#hDWuBJVzfdYoL; zP3uPhkG`pH%)_?x3=++Jo=8uMjr#glJtrn_sJ$6pq6!To*%<(pLYaX+f=fJn)g_!E z(Le!PL0&y=+09)!eX<#`-sqeZl?QpdM0G1e{U*1P-4l0(#7Ce4hj@!DY2xWLhT{C& z`NGQWCl43&rHlZL|8=?oIYcNxfX1Ff`s+-2)dEs#NjAbZ?j~sIv^>I?+;?SB0;40e zXi@v#x7qI#i&@S*pvN2fJJLf=ftgrAj@5CYjOMVnHPdmIOG4MkpOwPIF}=~E&LW(| zTrJ9T<0hPEc8T2nH)T9N3;9QJsVMsu^lHn^CSd}bwEbPE^67012Z0y&1juB4=bSNS z8&GxdsX8O4+{p*DhcCVOU3Y?{VyLx(vI%gUmC_z2^YUoH zE1x3mJTIBX0-o)I*l!Rx<8XZGLNylVRm3|-0Zd-_=vWiO4A@^Xu(IjV;SXJcS;!{v z3?@r77t3Kpj&9Bl2|g*E4DdrmjN&pdWIZk}T5olwc z$Ul1r@_&;ZM1Kf5JDFQK{-e(CUe^49Er!x}<4W8!Nbb!*9FqN(H5<7onS8t0rHZ(| z%Tj-~I;ztuL3F#ub;lRS@5nGED~$EjIFDoLc4Rkp7bemTDp0hlOcAea)^N zGsGHOzenqdsC)Wts>JuL^SlH72;#1W>-20U5v`#~&(OU8Wiy~PoS;59&KriI11+JI z#z^W(>qH0XgSg43#W5dj!(GrEw@Ruy@S#V>2!v^sped^TyR~AGgbOnTu8gEUii9=F z%G{PZHq`tpN9sBt%hUxuiwrWDVS%yUtyHLU9t_yi6-g6$=Y_Si759hpD_YjF`-;XZ zKOepW_K>BZmjkoJ7=yEz7@MWN`PCa~eW;CSKTQ5(bgtF?K$#11uXn&5?~ z0SPi0m9rvLQmK@L#zl_#3~m@{f8~{Us5x^zV+wO*8SU}SekC;p%FPa9&iEu&r>g+6 zS;CFg7$Po(IPLwh#M=wUOhSkn1GpkGu^5K)3l4X&-GIXjmJ`LfjshBIMD;{1PPi_o zET{TORq94`Z7F;C+#pVTvs0K4VAnd(n0jF;?Wml-H#v(d$f7(W>x4p*-^0oKNd8pH z&`=ZuQEE(Gpz&eka=*NM;f9g94tVN=|*h5h3SXd+ii z%bYn)<_=Q^_F1F=vm^!B3yswR=fKDmPzvZ30_P2AXqR#}IZd)n#b)^@Hq zo$=oFSlw`N>>)(#K80*9L~J&NtR_UP zI)yAML@cs}%%VihyoF4xL`<}WjHE=2c!dmTL=13+^x#DFp9OS}0J^IJ+9Lq%b^*;Y zfM&XYdKf_6Q$W=MpsFdLECEpF6i}o9C}Il8LjdGH1!OJ&GMfTY69B1B0f`ELM7Drf z6hO>dK*S0lqAdWB0swdgglGUlxB>!j0KsQI{v#p&RX*MkA>MXA?lK|nbUw~7Ax=*| zb_*ePO+Ho$Ay!U4W(px@Og=^kA%;&rx(gw?O+K0lA(~D;stO^hY(9!8AqsCkGAki6 zZ9WnyArf9bA{rqgTs{IgA;M=K{38MURUX_C0o-=p_ho|b(|NGN1h74MFfC=&&=WkW zN1aPx_#q!lOC}#CHyu8tHMCRD7SHz^H;0;y8!hWE`&0Cl55Djb@I>8zIz3BLS7`;~ zZLx7apps(M%sqp8>q6d~me}#K@#rJvUY3LP#WQ_*u=DeAmDC5z$3%G5r}woz|7n*u z!uNY~?d?nGm~C7-t7l3Cf%A-q{^H<{4wW0>82+~a#Ietq-$%3ht7vw(oVzJ4sM*SWARxp zy1&4mhCA_6Huk1d_-s}$*6crQ4NFYsf7r5p{04QSXg=><@#KTqNeki;;$ueq{M_4_ zX8TZJw5X*x-AD}T1d-m*z`vFl9K5CfU`F&5`;w%DZFhUVvaJ>TIE-EU@EsFMX?kMy za>RQ4{+UdTgQw-I()Cj9hJN0;O*8zlJ@gEAJ^yvAt^MGAZG$&`-f<40wL>e@`GK<* zs<0n>)CFhm)8U?VcA)58^f4u{xsrTV$aMSiFFS^Ro-*|c!|wx%y0O;grYbKUlOv{Pa+MG!xt z|8X*%!?B2otfaB}YWHKLHTNndwe{ifR_0^x`2;j^_>Av%kAo+8u8P_z(K^cYvAqNC zMYuRF2%@*vk009ZTU{QIor`$x%qg?ncbf*9%}NuyI-qNQ9`=O+W~|PECSB9>Fy9*4 z7Iq-r$NY%^^gmN%;(rqX zipDmMf2`(a)rwM5APfjS=&$(T&1(`KX*1=huc#X$5*3GLZ z!ElC-(q#{_XP!ExGm()`u%GSFBOa_}vheb7jw0ni){mxDOL!V!-!sg5!akv;c`|S0 z82s(eU{z(KPb3+^Ydd~)T{zAwAY>gWsdq!?eM`*bBx)87FX=NHlp`lTzJ|QhaO*2u zqdZ3P;_Tp;v4>LzhIIKY5PnDpZ~lP<+yfmi}LPO3L~Nx0felTLIh+0}z?ItCsi7w7hE zJ-z{vO8@r5g5xX59?OP+LDt4o(n7;&3n}y+`;d?B@2}ohf z7&Gk@_u34Q*Ad4L0NI-PsEH?nIvV$RF5GI}7D2a`*t{)!ir5`n%OoOai$2CoL)GFo z?UV?@^~56BB??S12gGc=Jq(IWVgU;7-4mK*I{ARZWum)he54D zw_zI!@@l`|_8%MNi$wHnFve>9X7d19w5G^SYD|}7qK>X_a+`?OYhV(1qdarr%NeOx z-Tf^H6}bUynGNPxw)nzeN?JTjQuI_VbW%o`eNG~(l;lpU>K9(W+TBdVJ9_oPreQB~ z1vr_T>Un(SgC-uDX?gN^#3MIX+>_TxC%-8--4!w}N ztQNTCQ*`96I)g5aI{q5EEzB^KYIBXk4fr?wu>H+cx2d4QLH_G~o2F5~I&sW_^Y=4p z$?l);s9@5;KVb`EH)t?S!SJ{&RpKH}ldx+7V!@h~`#GqOM+r~pm#hb1HpMcJfV-2Y39;k`XY6iMVS@M_ha^ zR={uvUnj`UaD?net9%(cmWfCokWV;4xtl?m&o&+go?ekb)G}*G$TlPq0&34s*INTw z&X5^BxO*m>RpfV|3Z9RFl55={kI#6NIx;#G>D`8Q9tXEm=XX}N2X`N~7J$%>aH&zF)p92p8 z*nn>tKFk{NxDwywDK~K!*LIFR2Qyw7ax8tj1X7{=;e;om@eP%1bV0OO!odzeA^!Q-HsI!%Df4>Uq$|XL$6jg%ARhfnXl=r{Uex8 zc)->%C#+oDqdQ5e1%q;|@NA_nxem<0pzHdCtn|OXI+;s=g49|2N zbOcj_5|{(Xv_^S+ecnLlKS(}1BEyYp4_hrX`2#!=l@lywL=+Pcve$sLMGb&R5ys?F z*Y1?1EP-m$mO)#KV%MK zT0UEU4CE$LQAc~6LFjsiEn>IwJgiFzaFd!EB*7tY`f4GO#)md~A3aH56>M*BmS&j_ zNG(Lu5KlJ-EzsB_xm_OIbl&0X)KQ-X!&|0D;m{ZHq*uUDiUn5B8X0u*oaJ;J70D8tLlU7qz$Y#VIYq`6N_-B!w_F!aW z=P6Zqa0Hv5uCAJI=>Jr>^gmksuOuJkzf-usDBoX{?=Q;t7v=kl^8H2m{-S(;QNF(@ z-(QsPFUt29<@<~B{eK7L`$yCFuPEPtwo?C}lS{gPHhq6tzP~KrUzYDL%lDV%`>)3G zt^E;&e`WdT{@o<-FU=t$^R8ye|^4xeZGHvzJGnbe|^6HHGIDR5P*O6`Tl3F!2i1d{5AUi z7cu&R{jpo}48g#s{~`L}QGtN|Z3`;%KYW+}!}0rv_^DR=$8l-24{DH4cy#qV0&A+2 z7I+jNny#2+j52H?2ev-6V0u94G6Bk%gZP?x_QxfUs|hu4 zjIq4NNP^B*M5we1WyYBF@!|PlvGdk*2VF5S5hZTKIi1N7D zORgiq*vyGgqPv%H>dJ;(qavV5+W5~c2F8X4t4ccTLub}}!4#!&=bYu_@$BCrY-n(| z0V^U{3F<*HVPjIT6e;0l3lX9}bbpX0esufjk&)?QoLs+o3i~x7qVOGxIlh@q+vg1K zQgFOz6Wj$=6c;560XxD5qq6Sv>=^9gYyOZunR+ntc{$j?uQ^^gZ)IzIn>a0Zyb4y? zm#98NtrpRcf=;`Uw3WllP=h`|#V^&u$hG#aaztGqji*#p?(2fxHRtZ|e!>$`wNMA9RhLJG%23(OPj51bG(6NgziiZcGp^`j~$J|w5VsfQQkGIxK)RFz+=)jb{ zg@5z<{`ir3Zf{oCPm`n%mu30xMYKYh&?qQMDIY)NTH3I|onpHfSRssMWpp-5lbhA` zb-ImxIIj&Itz}0ziqt$@6Ix$yTY>sRo&=S`F3qx9D=1!E(W4pYR2`wGplDJRrII+l zSXe~eTNK)|He2Z+X&Gs={0td8{7fm0bQht{ib;n+S1hxcrxOfks{o6->#t9Q1dO+8PxG}Vkp|iBX|wmsQz&%;rk-T4|3fJq>R|I)q=S6C>lFj z*(5u+OTg4{^A;`{wHFc{??4tV~8O+>dcn|uejsD~?QV!xBLmJoKrzblt`wa6kgDhQN1l#GuwgyqZH z?wciW06d_c}rNYr-y?XN%}m}8y^0##Qpql8W`rm$!dgt75beDjPPl?xUco- z?J*&kU5p%1t6`}9jrwaGJO~qbgVD7#?GG(Mu{2 zRO8q;pSv&ZGd`s%rFbNm+DWD)^P(*`kEJ& z2NSQ<*ViuwC}4!-Wn=kJ>KS0?lxV=QO|W7LA(RoPrpW0$?c7m#3|>wj5f2oy8A*!S z;8v;B!yx^X@ujo8{;n3DOo3pLuBbJRWrRxSlG+{KqU_$;aDJmc7^?Sl4SZNyLo2K= zW9G}_0xub7`DX}Ff|H@&c|2c8WuOWROefJZm(jw{xrJH%#<6e>gB2)WaL)ZK)cxE< z^@Pdh;YK~+oM~?zZ&?bUJ#}%|U@lI-JqY3&e};WrIE|4_%x$!Z*f!Flu=$)cH5KpU zHs@pYKop}lTcZ6A%?AF3F*fc*2P-SvWay28vz=1|j3ugKr zl+P`0j7=W6uO2pg@}k~~h@HQ_>?O|N3?)mUA{pY0CDHzE3!SvG1r+%cx^ESX005RQ zMp(mHvKj#<4b7tPgJtNJQ&phSI7NkS(?t%QYQ!@|iTO3%Ppm2*ucBckw)U*uj2J;N zOLyp-R=8}X$I?vlY5{#xg|3?&bhs2~D^QWARw2$r;sAniuybnOuO`xGEF0_=&+s1v z>UWu9zoM5u)zoD?jDrPznLx0k$$BJG{pHVZL|YV`a$BU*re5KbK5o`@_+Ha?>QNPM z!8?Of37@WgaSxW0vv4M%{%!JWq)!0=o}o|jwPMZ*vN`8NtZc*Pr<)*hvO$Z7!vrxk zzb?SpNoDI@E?$PyW$iv1xWnGAZa1UqJjGbM+^dkl%e4_f( z%3i2tNq%m&Cr7WoMG2%{sRhQfY55&)Cst?|5<({Kn7=8INkccO{!6g*cFsr>KT{q- zr}Pz*^$kC0^jG1hq7CUT^WmGQhs6Pa)iBp5U#-)ws`tJIH)vtAC3v20;_D6o`XN6X zmnp{In(m5nJD?^OiHDXI__le*+c1noBThoS-~e?&AwUG!!Cce$MRgSCs0WFa5^}ng zw?`AkJwitobGedd`aS(fJ7#$p`s}zTPKoCRw149^j-)Gx7o2ow&hD>t;#<%3o1~9C zJXBjDP%Qe^tX=oZ!f2aY0@Or&Dd7WRd0iH%k7LX0-8LS9FH;N9h09gHXB?x9v`t^KDqUDEX2j=VIeo>Zu!U=-Xzj<0z*u7 zF?-ddAkG%lQ2Ry0bQ*_!+V(Yo%XQqL2dZqAU>CqWN zjE33E2Va<*2RDX+=(A6Ro7nS;$Jc@xVx^i3RgQ3-?_|B+!eaimlz5O)lis_?n~-P8 z@-jJ0?UANGF$ZWuxc8XxcFw?uyLj=Sew5H~hEF8mWTl}-{K-T(hjWI^b=Wn>f}5jm z=6GNRr-A*@Ty#K${k!A9;euNamXe@vF7+9v^XUrnC-rtptWQk^xmnv4aoChM<(U@4 zBaYnZ6iyGb`TU+KFr8oDyVpmh@R<%g50iDs<`BNpi>n&h)EHHv(+Z=@K?S-f9n@x( ztMIbOs)8Upq9@+0XzC1LFN%!kT!v3fupYNh>Hna~fm9w)nCuixSY^-e1WA^*77Ns= z7?{Q;t){;G9RA@R@Xlk23W@d20w>2@KuDHIlvaJXl#yj`(@}=imlvG!RLEjV)4}G= zm<5hY5-5<|v@tM<2ny9Ri89fsy@l$o<9#n$wVY8UQJNpj8**4s;D|3WsnL=-Ifv;(J#6{M++V|_etuH9IfW} zK2Kyx6YzjG@WI|?*4G9+Ah=Y48=6=$|1&+A|F!*^cCb^h3vw{39Nz6O7rn0!d6p^u z!}ar31O5D#uq&FFcFfu`ID7*anr3_7*&%ZZztqv3HpHW|7~epKDj|1$T`#9$iDRo@_Wz73@UA$ zRksP&_>8F)8)=!70QV*O$F98p2w{nKp3cc)XFw_w6MT%UApA)eAXreMRm6TsqB0JY z_&X@+o>bVJu`$Rex-T-qiWp72+shPk07rxvgA$(^9bc=_Sf5VOZ3_eC2g;_p)nA~q zFs5htiSGL++mY?2qo)(!`XHBG&a$H^m;3J-cw1_@ofT0F6}J4tTjkG+ddUL4-72C4 zu#ne?JF(QEFk4=St@0F@k5)(og_;f7gSz`brnQ|)fw!Ie zXYg%y)7nd;pe1bgK!0zD(DKkyu#yfxirr=_EuS9+Dt&nmsOjH4fYd#k)>4B4=OoXv zyLDd09q?^-(|Yuxplz=0fu=RMX-)nVq^!qYNb1qeOr8+w=mf~GEb Date: Thu, 18 Jun 2020 12:50:12 +0200 Subject: [PATCH 47/65] version 1.3.0 intial change --- arduino_foc_minimal_encoder/BLDCMotor.cpp | 237 ++++++++++---- arduino_foc_minimal_encoder/BLDCMotor.h | 295 ++++++++++++------ arduino_foc_minimal_encoder/Encoder.cpp | 20 +- arduino_foc_minimal_encoder/Encoder.h | 110 ++++--- arduino_foc_minimal_encoder/FOCutils.cpp | 49 ++- arduino_foc_minimal_encoder/FOCutils.h | 43 ++- .../MagneticSensor.cpp | 189 ----------- arduino_foc_minimal_encoder/MagneticSensor.h | 71 ----- arduino_foc_minimal_encoder/Sensor.h | 38 ++- arduino_foc_minimal_encoder/SimpleFOC.h | 1 - .../arduino_foc_minimal_encoder.ino | 179 +++++------ arduino_foc_minimal_encoder/defaults.h | 30 +- arduino_foc_minimal_magnetic/BLDCMotor.cpp | 237 ++++++++++---- arduino_foc_minimal_magnetic/BLDCMotor.h | 295 ++++++++++++------ arduino_foc_minimal_magnetic/Encoder.cpp | 229 -------------- arduino_foc_minimal_magnetic/Encoder.h | 92 ------ arduino_foc_minimal_magnetic/FOCutils.cpp | 49 ++- arduino_foc_minimal_magnetic/FOCutils.h | 43 ++- .../MagneticSensor.cpp | 101 +++--- arduino_foc_minimal_magnetic/MagneticSensor.h | 68 ++-- arduino_foc_minimal_magnetic/Sensor.h | 38 ++- arduino_foc_minimal_magnetic/defaults.h | 30 +- 22 files changed, 1220 insertions(+), 1224 deletions(-) delete mode 100644 arduino_foc_minimal_encoder/MagneticSensor.cpp delete mode 100644 arduino_foc_minimal_encoder/MagneticSensor.h delete mode 100644 arduino_foc_minimal_magnetic/Encoder.cpp delete mode 100644 arduino_foc_minimal_magnetic/Encoder.h diff --git a/arduino_foc_minimal_encoder/BLDCMotor.cpp b/arduino_foc_minimal_encoder/BLDCMotor.cpp index 2f6fd4d9..1e119858 100644 --- a/arduino_foc_minimal_encoder/BLDCMotor.cpp +++ b/arduino_foc_minimal_encoder/BLDCMotor.cpp @@ -24,7 +24,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) PI_velocity.P = DEF_PI_VEL_P; PI_velocity.I = DEF_PI_VEL_I; PI_velocity.timestamp = _micros(); - PI_velocity.voltage_limit = voltage_power_supply/2; + PI_velocity.voltage_limit = voltage_power_supply; PI_velocity.voltage_ramp = DEF_PI_VEL_U_RAMP; PI_velocity.voltage_prev = 0; PI_velocity.tracking_error_prev = 0; @@ -40,17 +40,10 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // maximum angular velocity to be used for positioning P_angle.velocity_limit = DEF_P_ANGLE_VEL_LIM; - // index search PI controller - PI_velocity_index_search.P = DEF_PI_VEL_INDEX_P; - PI_velocity_index_search.I = DEF_PI_VEL_INDEX_I; - PI_velocity_index_search.voltage_limit = voltage_power_supply/2; - PI_velocity_index_search.voltage_ramp = DEF_PI_VEL_INDEX_U_RAMP; - PI_velocity_index_search.timestamp = _micros(); - PI_velocity_index_search.voltage_prev = 0; - PI_velocity_index_search.tracking_error_prev = 0; - // index search velocity - index_search_velocity = DEF_INDEX_SEARCH_TARGET_VELOCITY; + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; // electric angle of the zero angle zero_electric_angle = 0; @@ -58,20 +51,23 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // default modulation is SinePWM foc_modulation = FOCModulationType::SinePWM; - //debugger - debugger = nullptr; + // default target value + target = 0; + + //monitor_port + monitor_port = nullptr; } // init hardware pins void BLDCMotor::init() { - if(debugger) debugger->println("DEBUG: Initialize the motor pins."); + if(monitor_port) monitor_port->println("MONITOR: Initialize the motor pins."); // PWM pins pinMode(pwmA, OUTPUT); pinMode(pwmB, OUTPUT); pinMode(pwmC, OUTPUT); if(hasEnable()) pinMode(enable_pin, OUTPUT); - if(debugger) debugger->println("DEBUG: Set high frequency PWM."); + if(monitor_port) monitor_port->println("MONITOR: Set high frequency PWM."); // Increase PWM frequency to 32 kHz // make silent setPwmFrequency(pwmA); @@ -79,12 +75,11 @@ void BLDCMotor::init() { setPwmFrequency(pwmC); // sanity check for the voltage limit configuration - if(PI_velocity.voltage_limit > 0.7*voltage_power_supply) PI_velocity.voltage_limit = 0.7*voltage_power_supply; - if(PI_velocity_index_search.voltage_limit > 0.7*voltage_power_supply) PI_velocity_index_search.voltage_limit = 0.7*voltage_power_supply; + if(PI_velocity.voltage_limit > voltage_power_supply) PI_velocity.voltage_limit = voltage_power_supply; _delay(500); // enable motor - if(debugger) debugger->println("DEBUG: Enabling motor."); + if(monitor_port) monitor_port->println("MONITOR: Enabling motor."); enable(); _delay(500); @@ -120,11 +115,11 @@ void BLDCMotor::linkSensor(Sensor* _sensor) { // Encoder alignment to electrical 0 angle int BLDCMotor::alignSensor() { - if(debugger) debugger->println("DEBUG: Align the sensor's and motor electrical 0 angle."); + if(monitor_port) monitor_port->println("MONITOR: Align the sensor's and motor electrical 0 angle."); // align the electrical phases of the motor and sensor - setPwm(pwmA, voltage_power_supply/2.0); - setPwm(pwmB,0); - setPwm(pwmC,0); + // set angle -90 degrees + setPhaseVoltage(voltage_sensor_align, _3PI_2); + // let the motor stabilize for 3 sec _delay(3000); // set sensor to zero sensor->initRelativeZero(); @@ -135,10 +130,10 @@ int BLDCMotor::alignSensor() { // find the index if available int exit_flag = absoluteZeroAlign(); _delay(500); - if(debugger){ - if(exit_flag< 0 ) debugger->println("DEBUG: Error: Absolute zero not found!"); - if(exit_flag> 0 ) debugger->println("DEBUG: Success: Absolute zero found!"); - else debugger->println("DEBUG: Absolute zero not available!"); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MONITOR: Error: Absolute zero not found!"); + if(exit_flag> 0 ) monitor_port->println("MONITOR: Success: Absolute zero found!"); + else monitor_port->println("MONITOR: Absolute zero not available!"); } return exit_flag; } @@ -150,13 +145,13 @@ int BLDCMotor::absoluteZeroAlign() { // if no absolute zero return if(!sensor->hasAbsoluteZero()) return 0; - if(debugger) debugger->println("DEBUG: Aligning the absolute zero."); + if(monitor_port) monitor_port->println("MONITOR: Aligning the absolute zero."); - if(debugger && sensor->needsAbsoluteZeroSearch()) debugger->println("DEBUG: Searching for absolute zero."); + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MONITOR: Searching for absolute zero."); // search the absolute zero with small velocity while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ loopFOC(); - voltage_q = velocityIndexSearchPI(index_search_velocity - shaftVelocity()); + voltage_q = velocityPI(velocity_index_search - shaftVelocity()); } voltage_q = 0; // disable motor @@ -169,7 +164,7 @@ int BLDCMotor::absoluteZeroAlign() { // remember zero electric angle zero_electric_angle = electricAngle(zero_offset); } - // return bool is zero found + // return bool if zero found return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; } @@ -208,6 +203,9 @@ int BLDCMotor::initFOC() { _delay(500); int exit_flag = alignSensor(); _delay(500); + + if(monitor_port) monitor_port->println("MONITOR: FOC init finished - motor ready."); + return exit_flag; } @@ -224,13 +222,16 @@ void BLDCMotor::loopFOC() { // Behavior of this function is determined by the motor.controller variable // It runs either angle, velocity or voltage loop // - needs to be called iteratively it is asynchronous function -void BLDCMotor::move(float target) { +// - if target is not set it uses motor.target value +void BLDCMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; // get angular velocity shaft_velocity = shaftVelocity(); // choose control loop switch (controller) { case ControlType::voltage: - voltage_q = target; + voltage_q = target; break; case ControlType::angle: // angle set point @@ -281,7 +282,7 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // if negative voltages change inverse the phase // angle + 180degrees - if(Uq < 0) angle_el += M_PI; + if(Uq < 0) angle_el += _PI; Uq = abs(Uq); // angle normalisation in between 0 and 2pi @@ -296,7 +297,7 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // two versions possible // centered around voltage_power_supply/2 float T0 = 1 - T1 - T2; - // centered around 0 + // pulled to 0 - better for low power supply voltage //T0 = 0; // calculate the duty cycles(times) @@ -381,7 +382,7 @@ float BLDCMotor::normalizeAngle(float angle){ } // determining if the enable pin has been provided int BLDCMotor::hasEnable(){ - return enable_pin != 0; + return enable_pin != NOT_SET; } @@ -391,6 +392,7 @@ int BLDCMotor::hasEnable(){ // PI controller function float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){ float Ts = (_micros() - cont.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; @@ -406,6 +408,7 @@ float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){ float d_voltage = voltage - cont.voltage_prev; if (abs(d_voltage)/Ts > cont.voltage_ramp) voltage = d_voltage > 0 ? cont.voltage_prev + cont.voltage_ramp*Ts : cont.voltage_prev - cont.voltage_ramp*Ts; + cont.voltage_prev = voltage; cont.tracking_error_prev = tracking_error; cont.timestamp = _micros(); @@ -415,10 +418,7 @@ float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){ float BLDCMotor::velocityPI(float tracking_error) { return controllerPI(tracking_error, PI_velocity); } -// index search PI contoller -float BLDCMotor::velocityIndexSearchPI(float tracking_error) { - return controllerPI(tracking_error, PI_velocity_index_search); -} + // P controller for position control loop float BLDCMotor::positionP(float ek) { // calculate the target velocity from the position error @@ -429,38 +429,153 @@ float BLDCMotor::positionP(float ek) { } /** - * Debugger functions + * Monitoring functions */ -// function implementing the debugger setter -void BLDCMotor::useDebugging(Print &print){ - debugger = &print; //operate on the address of print - if(debugger )debugger->println("DEBUG: Serial debugger enabled!"); +// function implementing the monitor_port setter +void BLDCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MONITOR: Serial monitor enabled!"); } // utility function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! void BLDCMotor::monitor() { - if(!debugger) return; + if(!monitor_port) return; switch (controller) { case ControlType::velocity: - debugger->print(voltage_q); - debugger->print("\t"); - debugger->print(shaft_velocity_sp); - debugger->print("\t"); - debugger->println(shaft_velocity); + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); break; case ControlType::angle: - debugger->print(voltage_q); - debugger->print("\t"); - debugger->print(shaft_angle_sp); - debugger->print("\t"); - debugger->println(shaft_angle); + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); break; case ControlType::voltage: - debugger->print(voltage_q); - debugger->print("\t"); - debugger->print(shaft_angle); - debugger->print("\t"); - debugger->println(shaft_velocity); + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); break; } -} \ No newline at end of file +} + +int BLDCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("PI velocity P: "); + if(!GET) PI_velocity.P = value; + if(monitor_port) monitor_port->println(PI_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("PI velocity I: "); + if(!GET) PI_velocity.I = value; + if(monitor_port) monitor_port->println(PI_velocity.I); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("PI velocity voltage limit: "); + if(!GET)PI_velocity.voltage_limit = value; + if(monitor_port) monitor_port->println(PI_velocity.voltage_limit); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("PI velocity voltage ramp: "); + if(!GET) PI_velocity.voltage_ramp = value; + if(monitor_port) monitor_port->println(PI_velocity.voltage_ramp); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("LPF velocity time constant: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print("P angle P value: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("P angle velocity limit: "); + if(!GET) P_angle.velocity_limit = value; + if(monitor_port) monitor_port->println(P_angle.velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Contoller type: "); + + if(GET){ // if get commang + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} + + diff --git a/arduino_foc_minimal_encoder/BLDCMotor.h b/arduino_foc_minimal_encoder/BLDCMotor.h index 7cc4f324..bebe974d 100644 --- a/arduino_foc_minimal_encoder/BLDCMotor.h +++ b/arduino_foc_minimal_encoder/BLDCMotor.h @@ -1,3 +1,8 @@ +/** + * @file BLDCMotor.h + * + */ + #ifndef BLDCMotor_h #define BLDCMotor_h @@ -6,155 +11,265 @@ #include "Sensor.h" #include "defaults.h" -// controller type configuration enum + +#define NOT_SET -12345.0 + +/** + * Motiron control type + */ enum ControlType{ - voltage, - velocity, - angle + voltage,//!< Torque control using voltage + velocity,//!< Velocity motion control + angle//!< Position/angle motion control }; -// FOC Type +/** + * FOC modulation type + */ enum FOCModulationType{ - SinePWM, - SpaceVectorPWM + SinePWM, //!< Sinusoidal PWM modulation + SpaceVectorPWM //!< Space vector modulation method }; -// PI controller structure +/** + * PI controller structure + */ struct PI_s{ - float P; - float I; - long timestamp; - float voltage_prev, tracking_error_prev; - float voltage_limit; - float voltage_ramp; + float P; //!< Proportional gain + float I; //!< Integral gain + float voltage_limit; //!< Voltage limit of the controller output + float voltage_ramp; //!< Maximum speed of change of the output value + long timestamp; //!< Last execution timestamp + float voltage_prev; //!< last controller output value + float tracking_error_prev; //!< last tracking error value }; // P controller structure struct P_s{ - float P; - long timestamp; - float voltage_prev, tracking_error_prev; - float velocity_limit; + float P; //!< Proportional gain + long timestamp; //!< Last execution timestamp + float velocity_limit; //!< Velocity limit of the controller output }; -// flow pass filter structure +/** + * Low pass filter structure + */ struct LPF_s{ - float Tf; - long timestamp; - float prev; + float Tf; //!< Low pass filter time constant + long timestamp; //!< Last execution timestamp + float prev; //!< filtered value in previous execution step }; + + + /** BLDC motor class */ class BLDCMotor { public: - /* - BLDCMotor( int phA, int phB, int phC, int pp , int cpr, int en) - - phA, phB, phC - motor A,B,C phase pwm pins - - pp - pole pair number - - cpr - counts per rotation number (cpm=ppm*4) - - enable pin - (optional input) + /** + BLDCMotor class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param pp pole pair number + @param cpr counts per rotation number (cpm=ppm*4) + @param en enable pin (optional input) */ - BLDCMotor(int phA,int phB,int phC,int pp, int en = 0); - // change driver state + BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + + /** Motor hardware init function */ void init(); + /** Motor disable function */ void disable(); + /** Motor enable function */ void enable(); - // connect sensor - void linkSensor(Sensor* _sensor); - // initilise FOC - int initFOC(); - // iterative method updating motor angles and velocity measurement + /** + * Function linking a motor and a sensor + * + * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity + */ + void linkSensor(Sensor* sensor); + + /** + * Function intializing FOC algorithm + * and aligning sensor's and motors's zero position + */ + int initFOC(); + /** + * Function runing FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ void loopFOC(); - // iterative control loop defined by controller - void move(float target); + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET); // hardware variables - int pwmA; - int pwmB; - int pwmC; - int enable_pin; - int pole_pairs; + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + - /** State calculation methods */ - //Shaft angle calculation + // State calculation methods + /** Shaft angle calculation in radians [rad] */ float shaftAngle(); - //Shaft velocity calculation + /** + * Shaft angle calculation function in radian per second [rad/s] + * It implements low pass filtering + */ float shaftVelocity(); // state variables - // current motor angle - float shaft_angle; - // current motor velocity - float shaft_velocity; - // current target velocity - float shaft_velocity_sp; - // current target angle - float shaft_angle_sp; - // current voltage u_q set - float voltage_q; - - // Power supply voltage - float voltage_power_supply; + float target; //!< current target value - depends of the controller + float shaft_angle;//!< current motor angle + float shaft_velocity;//!< current motor velocity + float shaft_velocity_sp;//!< current target velocity + float shaft_angle_sp;//!< current target angle + float voltage_q;//!< current voltage u_q set + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + + // motor configuration parameters + float voltage_power_supply;//!< Power supply voltage + float voltage_sensor_align;//!< sensor and motor align voltage parameter + float velocity_index_search;//!< target velocity for index search + int pole_pairs;//!< Motor pole pairs number // configuration structures - ControlType controller; - FOCModulationType foc_modulation; - PI_s PI_velocity; - PI_s PI_velocity_index_search; - P_s P_angle; - LPF_s LPF_velocity; - - // sensor link: - // - Encoder - // - MagneticSensor - Sensor* sensor; - // absolute zero electric angle - if available - float zero_electric_angle; - // index search velocity - float index_search_velocity; - - /** FOC methods */ - //Method using FOC to set Uq to the motor at the optimal angle + ControlType controller; //!< parameter determining the control loop to be used + FOCModulationType foc_modulation;//!< parameter derterniming modulation algorithm + PI_s PI_velocity;//!< parameter determining the velocity PI configuration + P_s P_angle; //!< parameter determining the position P configuration + LPF_s LPF_velocity;//!< parameter determining the velocity Lpw pass filter configuration + + /** + * Sensor link: + * - Encoder + * - MagneticSensor + */ + Sensor* sensor; + + float zero_electric_angle;//! Ts/2) ? dN / dt : pulse_per_second; - // if more than 0.3 passed in between impulses - if ( Th > 0.15) pulse_per_second = 0; + // if more than 0.05 passed in between impulses + if ( Th > 0.1) pulse_per_second = 0; // velocity calculation float velocity = pulse_per_second / ((float)cpr) * (_2PI); @@ -202,7 +202,7 @@ void Encoder::init(){ // initial cpr = PPR // change it if the mode is quadrature - if(quadrature == Quadrature::ENABLE) cpr = 4*cpr; + if(quadrature == Quadrature::ON) cpr = 4*cpr; } @@ -211,12 +211,12 @@ void Encoder::init(){ void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){ // attach interrupt if functions provided switch(quadrature){ - case Quadrature::ENABLE: + case Quadrature::ON: // A callback and B callback if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); break; - case Quadrature::DISABLE: + case Quadrature::OFF: // A callback and B callback if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING); if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); diff --git a/arduino_foc_minimal_encoder/Encoder.h b/arduino_foc_minimal_encoder/Encoder.h index d115fe25..fc65a7a9 100644 --- a/arduino_foc_minimal_encoder/Encoder.h +++ b/arduino_foc_minimal_encoder/Encoder.h @@ -6,86 +6,106 @@ #include "Sensor.h" -// Pullup configuration structure +/** + * Pullup configuration structure + */ enum Pullup{ - INTERN, - EXTERN + INTERN, //!< Use internal pullups + EXTERN //!< Use external pullups }; +/** + * Quadrature mode configuration structure + */ enum Quadrature{ - ENABLE, // CPR = 4xPPR - DISABLE // CPR = PPR + ON, //!< Enable quadrature mode CPR = 4xPPR + OFF //!< Disable quadrature mode / CPR = PPR }; class Encoder: public Sensor{ public: - /* - Encoder(int encA, int encB , int cpr, int index) - - encA, encB - encoder A and B pins - - ppr - impulses per rotation (cpr=ppr*4) - - index pin - (optional input) + /** + Encoder class constructor + @param encA encoder B pin + @param encB encoder B pin + @param ppr impulses per rotation (cpr=ppr*4) + @param index index pin number (optional input) */ Encoder(int encA, int encB , float ppr, int index = 0); - // encoder initialise pins + /** encoder initialise pins */ void init(); - // function enabling hardware interrupts of the for the callback provided - // if callback is not provided then the interrupt is not enabled + /** + * function enabling hardware interrupts for the encoder channels with provided callback functions + * if callback is not provided then the interrupt is not enabled + * + * @param doA pointer to the A channel interrupt handler function + * @param doB pointer to the B channel interrupt handler function + * @param doIndex pointer to the Index channel interrupt handler function + * + */ void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr); // Encoder interrupt callback functions - // enabling CPR=4xPPR behaviour - // A channel + /** A channel callback function */ void handleA(); - // B channel + /** B channel callback function */ void handleB(); - // index handle + /** Index channel callback function */ void handleIndex(); // pins A and B - int pinA, pinB; // encoder hardware pins - // index pin - int index_pin; - // encoder pullup type - Pullup pullup; - // use 4xppr or not - Quadrature quadrature; + int pinA; //!< encoder hardware pin A + int pinB; //!< encoder hardware pin B + int index_pin; //!< index pin - // implementation of abstract functions of the Sensor class - // get current angle (rad) + // Encoder configuration + Pullup pullup; //!< Configuration parameter internal or external pullups + Quadrature quadrature;//!< Configuration parameter enable or disable quadrature mode + float cpr;//!< encoder cpr number + + // Abstract functions of the Sensor class implementation + /** get current angle (rad) */ float getAngle(); - // get current angular velocity (rad/s) + /** get current angular velocity (rad/s) */ float getVelocity(); - // set current angle as zero angle - // return the angle [rad] difference + /** + * set current angle as zero angle + * return the angle [rad] difference + */ float initRelativeZero(); - // set index angle as zero angle - // return the angle [rad] difference + /** + * set index angle as zero angle + * return the angle [rad] difference + */ float initAbsoluteZero(); - // returns 0 if it has no index - // 0 - encoder without index - // 1 - encoder with index + /** + * returns 0 if it has no index + * 0 - encoder without index + * 1 - encoder with index + */ int hasAbsoluteZero(); - // returns 0 if it does need search for absolute zero - // 0 - encoder without index - // 1 - ecoder with index + /** + * returns 0 if it does need search for absolute zero + * 0 - encoder without index + * 1 - ecoder with index + */ int needsAbsoluteZeroSearch(); private: - int hasIndex(); + int hasIndex(); //!< function returning 1 if encoder has index pin and 0 if not. - volatile long pulse_counter; // current pulse counter - volatile long pulse_timestamp; // last impulse timestamp in us - float cpr; // impulse cpr - volatile int A_active, B_active; // current active states of A and B line - volatile int I_active; // index active - volatile long index_pulse_counter; // pulse counter of the index + volatile long pulse_counter;//!< current pulse counter + volatile long pulse_timestamp;//!< last impulse timestamp in us + volatile int A_active; //!< current active states of A channel + volatile int B_active; //!< current active states of B channel + volatile int I_active; //!< current active states of Index channel + volatile long index_pulse_counter; //!< impulse counter number upon first index interrupt // velocity calculation variables float prev_Th, pulse_per_second; volatile long prev_pulse_counter, prev_timestamp_us; - }; diff --git a/arduino_foc_minimal_encoder/FOCutils.cpp b/arduino_foc_minimal_encoder/FOCutils.cpp index c9f0db4c..31ec1c15 100644 --- a/arduino_foc_minimal_encoder/FOCutils.cpp +++ b/arduino_foc_minimal_encoder/FOCutils.cpp @@ -1,10 +1,10 @@ #include "FOCutils.h" -/* - High PWM frequency - https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 -*/ + void setPwmFrequency(int pin) { +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other atmega328p chips +// High PWM frequency +// https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 if (pin == 5 || pin == 6 || pin == 9 || pin == 10) { if (pin == 5 || pin == 6) { // configure the pwm phase-corrected mode @@ -20,22 +20,39 @@ void setPwmFrequency(int pin) { // set prescaler to 1 TCCR2B = ((TCCR2B & 0b11111000) | 0x01); } +#elif defined(_STM32_DEF_) // if stm chips + analogWrite(pin,0); + analogWriteFrequency(50000); // la valeur par défaut est 20000 Hz +#endif } // function buffering delay() -// arduino function doesn't work well with interrupts +// arduino uno function doesn't work well with interrupts void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // return the value based on the prescaler long t = _micros(); - while((_micros() - t)/1000 < ms){}; + while((_micros() - t)/1000 < ms){}; +#else + // regular micros + return delay(ms); +#endif } // function buffering _micros() // arduino function doesn't work well with interrupts unsigned long _micros(){ - // return the value based on the prescaler +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); else return (micros()); +#else + // regular micros + return micros(); +#endif } @@ -54,21 +71,21 @@ int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,110 // it has to receive an angle in between 0 and 2PI float _sin(float a){ if(a < _PI_2){ - //return sine_array[(int)(199.0*( a / (M_PI/2.0)))]; + //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; //return sine_array[(int)(126.6873* a)]; // float array optimised - return 0.0001*sine_array[round(126.6873* a)]; // int array optimised - }else if(a < M_PI){ - // return sine_array[(int)(199.0*(1.0 - (a-M_PI/2.0) / (M_PI/2.0)))]; + return 0.0001*sine_array[_round(126.6873* a)]; // int array optimised + }else if(a < _PI){ + // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; //return sine_array[398 - (int)(126.6873*a)]; // float array optimised - return 0.0001*sine_array[398 - round(126.6873*a)]; // int array optimised + return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimised }else if(a < _3PI_2){ - // return -sine_array[(int)(199.0*((a - M_PI) / (M_PI/2.0)))]; + // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimised - return -0.0001*sine_array[-398 + round(126.6873*a)]; // int array optimised + return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimised } else { - // return -sine_array[(int)(199.0*(1.0 - (a - 3*M_PI/2) / (M_PI/2.0)))]; + // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; //return -sine_array[796 - (int)(126.6873*a)]; // float array optimised - return -0.0001*sine_array[796 - round(126.6873*a)]; // int array optimised + return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimised } } diff --git a/arduino_foc_minimal_encoder/FOCutils.h b/arduino_foc_minimal_encoder/FOCutils.h index 11882a81..0b333757 100644 --- a/arduino_foc_minimal_encoder/FOCutils.h +++ b/arduino_foc_minimal_encoder/FOCutils.h @@ -5,6 +5,8 @@ // sign function #define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + // utility defines #define _2_SQRT3 1.15470053838 #define _SQRT3 1.73205080757 @@ -12,29 +14,48 @@ #define _SQRT3_2 0.86602540378 #define _SQRT2 1.41421356237 #define _120_D2R 2.09439510239 +#define _PI 3.14159265359 #define _PI_2 1.57079632679 #define _PI_3 1.0471975512 #define _2PI 6.28318530718 #define _3PI_2 4.71238898038 -// High PWM frequency +/** + * High PWM frequency setting function + * - hardware specific + * + * @param pin pin number to configure + */ void setPwmFrequency(int pin); -// function buffering delay() -// arduino function doesn't work well with interrupts +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + * + * @param ms number of milliseconds to wait + */ void _delay(unsigned long ms); -// function buffering _micros() -// arduino function doesn't work well with interrupts +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ unsigned long _micros(); -// function approximating the sine calculation by using fixed size array -// ~40us -// it has to receive an angle in between 0 and 2PI +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ float _sin(float a); -// function approximating cosine calculation by using fixed size array -// ~50us -// it has to receive an angle in between 0 and 2PI +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ float _cos(float a); #endif \ No newline at end of file diff --git a/arduino_foc_minimal_encoder/MagneticSensor.cpp b/arduino_foc_minimal_encoder/MagneticSensor.cpp deleted file mode 100644 index d045eab5..00000000 --- a/arduino_foc_minimal_encoder/MagneticSensor.cpp +++ /dev/null @@ -1,189 +0,0 @@ -#include "MagneticSensor.h" - - -// MagneticSensor(int cs, float _cpr, int _angle_register) -// cs - SPI chip select pin -// _cpr - count per revolution -// _angle_register - (optional) angle read register - default 0x3FFF -MagneticSensor::MagneticSensor(int cs, float _cpr, int _angle_register){ - // chip select pin - chip_select_pin = cs; - // angle read register of the magnetic sensor - angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTAR; - // register maximum value (counts per revolution) - cpr = _cpr; - -} - - -void MagneticSensor::init(){ - // 1MHz clock (AMS should be able to accept up to 10MHz) - settings = SPISettings(1000000, MSBFIRST, SPI_MODE1); - - //setup pins - pinMode(chip_select_pin, OUTPUT); - - //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices - SPI.begin(); - - // velocity calculation init - angle_prev = 0; - velocity_calc_timestamp = _micros(); - - // full rotations tracking number - full_rotation_offset = 0; - angle_data_prev = getRawCount(); - zero_offset = 0; -} - -// Shaft angle calculation -// angle is in radians [rad] -float MagneticSensor::getAngle(){ - // raw data from the sensor - float angle_data = getRawCount(); - - // tracking the number of rotations - // in order to expand angle range form [0,2PI] - // to basically infinity - float d_angle = angle_data - angle_data_prev; - // if overflow happened track it as full rotation - if(abs(d_angle) > (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; - // save the current angle value for the next steps - // in order to know if overflow happened - angle_data_prev = angle_data; - - // zero offset adding - angle_data -= (int)zero_offset; - // return the full angle - // (number of full rotations)*2PI + current sensor angle - return full_rotation_offset + ( angle_data / (float)cpr) * _2PI; -} - -// Shaft velocity calculation -float MagneticSensor::getVelocity(){ - // calculate sample time - float Ts = (_micros() - velocity_calc_timestamp)*1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // current angle - float angle_c = getAngle(); - // velocity calculation - float vel = (angle_c - angle_prev)/Ts; - - // save variables for future pass - angle_prev = angle_c; - velocity_calc_timestamp = _micros(); - return vel; -} - -// set current angle as zero angle -// return the angle [rad] difference -float MagneticSensor::initRelativeZero(){ - float angle_offset = -getAngle(); - zero_offset = getRawCount(); - - // angle tracking variables - full_rotation_offset = 0; - return angle_offset; -} -// set absolute zero angle as zero angle -// return the angle [rad] difference -float MagneticSensor::initAbsoluteZero(){ - float rotation = -(int)zero_offset; - // init absolute zero - zero_offset = 0; - - // angle tracking variables - full_rotation_offset = 0; - // return offset in radians - return rotation / (float)cpr * _2PI; -} -// returns 0 if it has no absolute 0 measurement -// 0 - incremental encoder without index -// 1 - encoder with index & magnetic sensors -int MagneticSensor::hasAbsoluteZero(){ - return 1; -} -// returns 0 if it does need search for absolute zero -// 0 - magnetic sensor -// 1 - ecoder with index -int MagneticSensor::needsAbsoluteZeroSearch(){ - return 0; -} - - -// function reading the raw counter of the magnetic sensor -int MagneticSensor::getRawCount(){ - return (int)MagneticSensor::read(angle_register); -} - -// SPI functions -/** - * Utility function used to calculate even parity of word - */ -byte MagneticSensor::spiCalcEvenParity(word value){ - byte cnt = 0; - byte i; - - for (i = 0; i < 16; i++) - { - if (value & 0x1) cnt++; - value >>= 1; - } - return cnt & 0x1; -} - - /* - * Read a register from the sensor - * Takes the address of the register as a 16 bit word - * Returns the value of the register - */ -word MagneticSensor::read(word angle_register){ - word command = 0b0100000000000000; // PAR=0 R/W=R - command = command | angle_register; - - //Add a parity bit on the the MSB - command |= ((word)spiCalcEvenParity(command)<<15); - - //Split the command into two bytes - byte right_byte = command & 0xFF; - byte left_byte = ( command >> 8 ) & 0xFF; - - //SPI - begin transaction - SPI.beginTransaction(settings); - - //Send the command - digitalWrite(chip_select_pin, LOW); - SPI.transfer(left_byte); - SPI.transfer(right_byte); - digitalWrite(chip_select_pin,HIGH); - - //Now read the response - digitalWrite(chip_select_pin, LOW); - left_byte = SPI.transfer(0x00); - right_byte = SPI.transfer(0x00); - digitalWrite(chip_select_pin, HIGH); - - //SPI - end transaction - SPI.endTransaction(); - - //Check if the error bit is set - if (left_byte & 0x40) { - errorFlag = true; - } - else { - errorFlag = false; - } - - //Return the data, stripping the parity and error bits - return (( ( left_byte & 0xFF ) << 8 ) | ( right_byte & 0xFF )) & ~0xC000; -} - -/** - * Closes the SPI connection - * SPI has an internal SPI-device counter, for each init()-call the close() function must be called exactly 1 time - */ -void MagneticSensor::close(){ - SPI.end(); -} diff --git a/arduino_foc_minimal_encoder/MagneticSensor.h b/arduino_foc_minimal_encoder/MagneticSensor.h deleted file mode 100644 index 50665982..00000000 --- a/arduino_foc_minimal_encoder/MagneticSensor.h +++ /dev/null @@ -1,71 +0,0 @@ -#ifndef MAGNETICSENSOR_LIB_H -#define MAGNETICSENSOR_LIB_H - -#include "Arduino.h" -#include -#include "FOCutils.h" -#include "Sensor.h" - -#define DEF_ANGLE_REGISTAR 0x3FFF - -class MagneticSensor: public Sensor{ - public: - - - // MagneticSensor(int cs, float _cpr, int _angle_register) - // cs - SPI chip select pin - // _cpr - counts per revolution - // _angle_register - (optional) angle read register - default 0x3FFF - MagneticSensor(int cs, float _cpr, int angle_register = 0); - - // SPI angle register to read - int angle_register; - // encoder initialise pins - void init(); - - // implementation of abstract functions of the Sensor class - // get current angle (rad) - float getAngle(); - // get current angular velocity (rad/s) - float getVelocity(); - // set current angle as zero angle - // return the angle [rad] difference - float initRelativeZero(); - // set absolute zero angle as zero angle - // return the angle [rad] difference - float initAbsoluteZero(); - // returns 1 because it is the absolute sensor - int hasAbsoluteZero(); - // returns 0 maning it doesn't need search for absolute zero - int needsAbsoluteZeroSearch(); - - - private: - // spi variables - int chip_select_pin; - bool errorFlag; - SPISettings settings; - // spi functions - void close(); - word read(word angle_register); - byte spiCalcEvenParity(word value); - - - // zero offset - word zero_offset; - // function getting current register value - int getRawCount(); - - // total angle tracking variables - float full_rotation_offset; - float angle_data_prev; - // impulse cpr - float cpr; - // velocity calculation variables - float angle_prev; - long velocity_calc_timestamp; - -}; - - -#endif diff --git a/arduino_foc_minimal_encoder/Sensor.h b/arduino_foc_minimal_encoder/Sensor.h index b03c3b5f..56e4d286 100644 --- a/arduino_foc_minimal_encoder/Sensor.h +++ b/arduino_foc_minimal_encoder/Sensor.h @@ -1,28 +1,38 @@ #ifndef SENSOR_H #define SENSOR_H -// Sensor abstract class defintion -// Each sensor needs to have these functions implemented +/** + * Sensor abstract class defintion + * Each sensor needs to have these functions implemented + */ class Sensor{ public: - // get current angle (rad) + /** get current angle (rad) */ virtual float getAngle(); - // get current angular velocity (rad/s) + /** get current angular velocity (rad/s)*/ virtual float getVelocity(); - // set current angle as zero angle - // return the angle [rad] difference + /** + * set current angle as zero angle + * return the angle [rad] difference + */ virtual float initRelativeZero(); - // set absolute zero angle as zero angle - // return the angle [rad] difference + /** + * set absolute zero angle as zero angle + * return the angle [rad] difference + */ virtual float initAbsoluteZero(); - // returns 0 if it has no absolute 0 measurement - // 0 - incremental encoder without index - // 1 - encoder with index & magnetic sensors + /** + * returns 0 if it has no absolute 0 measurement + * 0 - incremental encoder without index + * 1 - encoder with index & magnetic sensors + */ virtual int hasAbsoluteZero(); - // returns 0 if it does need search for absolute zero - // 0 - magnetic sensor (& encoder with index which is found) - // 1 - ecoder with index (with index not found yet) + /** + * returns 0 if it does need search for absolute zero + * 0 - magnetic sensor (& encoder with index which is found) + * 1 - ecoder with index (with index not found yet) + */ virtual int needsAbsoluteZeroSearch(); }; diff --git a/arduino_foc_minimal_encoder/SimpleFOC.h b/arduino_foc_minimal_encoder/SimpleFOC.h index 887ae8df..bd9ecb55 100644 --- a/arduino_foc_minimal_encoder/SimpleFOC.h +++ b/arduino_foc_minimal_encoder/SimpleFOC.h @@ -4,7 +4,6 @@ #include "FOCutils.h" #include "Sensor.h" #include "Encoder.h" -#include "MagneticSensor.h" #include "BLDCMotor.h" #endif diff --git a/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino b/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino index 1c4f6a75..646ac7f7 100644 --- a/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino +++ b/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino @@ -1,44 +1,88 @@ +/** + * Comprehensive BLDC motor control example using encoder and the minimal version off the SimpleFOC library + * - THis code is completely stand alone and you dont need to have SimpleFOClibary installed to run it + * + * Check the docs.simplefoc.com for more information + * + * Using serial terminal user can send motor commands and configure the motor and FOC in real-time: + * - configure PID controller constants + * - change motion control loops + * - monitor motor variabels + * - set target values + * - check all the configuration values + * + * To check the config value just enter the command letter. + * For example: - to read velocity PI controller P gain run: P + * - to set velocity PI controller P gain to 1.2 run: P1.2 + * + * To change the target value just enter a number in the terminal: + * For example: - to change the target value to -0.1453 enter: -0.1453 + * - to get the current target value enter: V3 + * + * List of commands: + * - P: velocity PI controller P gain + * - I: velocity PI controller I gain + * - L: velocity PI controller voltage limit + * - R: velocity PI controller voltage ramp + * - F: velocity Low pass filter time constant + * - K: angle P controller P gain + * - N: angle P controller velocity limit + * - C: control loop + * - 0: voltage + * - 1: velocity + * - 2: angle + * - V: get motor variables + * - 0: currently set voltage + * - 1: current velocity + * - 2: current angle + * - 3: current target value + * + */ + #include "SimpleFOC.h" // BLDCMotor( int phA, int phB, int phC, int pp, int en) // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11); +BLDCMotor motor = BLDCMotor(3, 10, 11, 11,7); //Encoder(int encA, int encB , int cpr, int index) // - encA, encB - encoder A and B pins // - ppr - impulses per rotation (cpr=ppr*4) // - index pin - (optional input) -Encoder encoder = Encoder(2, 3, 2048); +Encoder encoder = Encoder(A1, A2, 8196); // interrupt routine intialisation void doA(){encoder.handleA();} void doB(){encoder.handleB();} void setup() { - // debugging port - Serial.begin(115200); // initialize encoder sensor hardware encoder.init(); encoder.enableInterrupts(doA,doB); + // link the motor to the sensor + motor.linkSensor(&encoder); // choose FOC algorithm to be used: // FOCModulationType::SinePWM (default) // FOCModulationType::SpaceVectorPWM motor.foc_modulation = FOCModulationType::SpaceVectorPWM; - // power supply voltage + // power supply voltage [V] // default 12V motor.voltage_power_supply = 12; + // motor and sensor aligning voltage [V] + // default 6V + motor.voltage_sensor_align = 3; // set control loop type to be used // ControlType::voltage // ControlType::velocity // ControlType::angle - motor.controller = ControlType::angle; + motor.controller = ControlType::voltage; - // contoller configuration based on the controll type + // controller configuration based on the control type // velocity PI controller parameters motor.PI_velocity.P = 0.2; motor.PI_velocity.I = 20; @@ -57,40 +101,25 @@ void setup() { motor.P_angle.P = 3; motor.P_angle.velocity_limit = 10; - // link the motor to the sensor - motor.linkSensor(&encoder); - - // use debugging with serial for motor init - // comment out if not needed - motor.useDebugging(Serial); + // use monitoring with serial for motor init + // monitoring port + Serial.begin(115200); + // enable monitoring + motor.useMonitoring(Serial); // initialise motor motor.init(); // align encoder and start FOC motor.initFOC(); - // this serial print takes around 20% of arduino memory! - Serial.println("\n\n"); - Serial.println("PI controller parameters change:"); - Serial.println("- P value : Prefix P (ex. P0.1)"); - Serial.println("- I value : Prefix I (ex. I0.1)\n"); - Serial.println("Velocity filter:"); - Serial.println("- Tf value : Prefix F (ex. F0.001)\n"); - Serial.println("Average loop execution time:"); - Serial.println("- Type T\n"); - Serial.println("Control loop type:"); - Serial.println("- C0 - angle control"); - Serial.println("- C1 - velocity control"); - Serial.println("- C2 - voltage control\n"); - Serial.println("Initial parameters:"); - Serial.print("PI velocity P: "); - Serial.print(motor.PI_velocity.P); - Serial.print(",\t I: "); - Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low pass filter Tf: "); - Serial.println(motor.LPF_velocity.Tf,4); + // set the inital target value + motor.target = 2; + + Serial.println("Full control example: "); + Serial.println("Voltage control target 2V."); _delay(1000); + } // target velocity variable @@ -105,76 +134,36 @@ void loop() { // iterative function setting the outter loop target // velocity, position or voltage - motor.move(target); + // if tatget not set in parameter uses motor.target variable + motor.move(); - // keep track of loop number - t++; + // user communication + motor.command(serialReceiveUserCommand()); } -// Serial communication callback -void serialEvent() { +// utility function enabling serial communication the user +String serialReceiveUserCommand() { + // a string to hold incoming data - static String inputString; + static String received_chars; + + String command = ""; + while (Serial.available()) { // get the new byte: char inChar = (char)Serial.read(); - // add it to the inputString: - inputString += inChar; - // if the incoming character is a newline - // end of input + // add it to the string buffer: + received_chars += inChar; + + // end of user input if (inChar == '\n') { - if(inputString.charAt(0) == 'P'){ - motor.PI_velocity.P = inputString.substring(1).toFloat(); - Serial.print("PI velocity P: "); - Serial.print(motor.PI_velocity.P); - Serial.print(",\t I: "); - Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low pass filter Tf: "); - Serial.println(motor.LPF_velocity.Tf,4); - }else if(inputString.charAt(0) == 'I'){ - motor.PI_velocity.I = inputString.substring(1).toFloat(); - Serial.print("PI velocity P: "); - Serial.print(motor.PI_velocity.P); - Serial.print(",\t I: "); - Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low pass filter Tf: "); - Serial.println(motor.LPF_velocity.Tf,4); - }else if(inputString.charAt(0) == 'F'){ - motor.LPF_velocity.Tf = inputString.substring(1).toFloat(); - Serial.print("PI velocity P: "); - Serial.print(motor.PI_velocity.P); - Serial.print(",\t I: "); - Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low pass filter Tf: "); - Serial.println(motor.LPF_velocity.Tf,4); - }else if(inputString.charAt(0) == 'T'){ - Serial.print("Average loop time is (microseconds): "); - Serial.println((_micros() - timestamp)/t); - t = 0; - timestamp = _micros(); - }else if(inputString.charAt(0) == 'C'){ - Serial.print("Contoller type: "); - int cnt = inputString.substring(1).toFloat(); - if(cnt == 0){ - Serial.println("angle!"); - motor.controller = ControlType::angle; - }else if(cnt == 1){ - Serial.println("velocity!"); - motor.controller = ControlType::velocity; - }else if(cnt == 2){ - Serial.println("voltage!"); - motor.controller = ControlType::voltage; - } - Serial.println(); - t = 0; - timestamp = _micros(); - }else{ - target = inputString.toFloat(); - Serial.print("Target : "); - Serial.println(target); - inputString = ""; - } - inputString = ""; + + // execute the user command + command = received_chars; + + // reset the command buffer + received_chars = ""; } } + return command; } diff --git a/arduino_foc_minimal_encoder/defaults.h b/arduino_foc_minimal_encoder/defaults.h index 1cdbf23f..5bcb0118 100644 --- a/arduino_foc_minimal_encoder/defaults.h +++ b/arduino_foc_minimal_encoder/defaults.h @@ -1,19 +1,17 @@ // default configuration values -// power supply voltage -#define DEF_POWER_SUPPLY 12.0 +// change this file to optimal values for your application + +#define DEF_POWER_SUPPLY 12.0 //!< default power supply voltage // velocity PI controller params -#define DEF_PI_VEL_P 0.5 -#define DEF_PI_VEL_I 10 -#define DEF_PI_VEL_U_RAMP 300 +#define DEF_PI_VEL_P 0.5 //!< default PI controller P value +#define DEF_PI_VEL_I 10 //!< default PI controller I value +#define DEF_PI_VEL_U_RAMP 1000 //!< default PI controller voltage ramp value // angle P params -#define DEF_P_ANGLE_P 20 -// angle velocity limit default -#define DEF_P_ANGLE_VEL_LIM 20 -// index search velocity -#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 -// velocity PI controller params for index search -#define DEF_PI_VEL_INDEX_P 1 -#define DEF_PI_VEL_INDEX_I 10 -#define DEF_PI_VEL_INDEX_U_RAMP 100 -// velocity filter time constant -#define DEF_VEL_FILTER_Tf 0.005 \ No newline at end of file +#define DEF_P_ANGLE_P 20 //!< default P controller P value +#define DEF_P_ANGLE_VEL_LIM 20 //!< angle velocity limit default +// index search +#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 //!< default index search velocity +// align voltage +#define DEF_VOLTAGE_SENSOR_ALIGN 6.0 //!< default voltage for sensor and motor zero alignemt +// low pass filter velocity +#define DEF_VEL_FILTER_Tf 0.005 //!< default velocity filter time constant \ No newline at end of file diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.cpp b/arduino_foc_minimal_magnetic/BLDCMotor.cpp index 2f6fd4d9..1e119858 100644 --- a/arduino_foc_minimal_magnetic/BLDCMotor.cpp +++ b/arduino_foc_minimal_magnetic/BLDCMotor.cpp @@ -24,7 +24,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) PI_velocity.P = DEF_PI_VEL_P; PI_velocity.I = DEF_PI_VEL_I; PI_velocity.timestamp = _micros(); - PI_velocity.voltage_limit = voltage_power_supply/2; + PI_velocity.voltage_limit = voltage_power_supply; PI_velocity.voltage_ramp = DEF_PI_VEL_U_RAMP; PI_velocity.voltage_prev = 0; PI_velocity.tracking_error_prev = 0; @@ -40,17 +40,10 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // maximum angular velocity to be used for positioning P_angle.velocity_limit = DEF_P_ANGLE_VEL_LIM; - // index search PI controller - PI_velocity_index_search.P = DEF_PI_VEL_INDEX_P; - PI_velocity_index_search.I = DEF_PI_VEL_INDEX_I; - PI_velocity_index_search.voltage_limit = voltage_power_supply/2; - PI_velocity_index_search.voltage_ramp = DEF_PI_VEL_INDEX_U_RAMP; - PI_velocity_index_search.timestamp = _micros(); - PI_velocity_index_search.voltage_prev = 0; - PI_velocity_index_search.tracking_error_prev = 0; - // index search velocity - index_search_velocity = DEF_INDEX_SEARCH_TARGET_VELOCITY; + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; // electric angle of the zero angle zero_electric_angle = 0; @@ -58,20 +51,23 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // default modulation is SinePWM foc_modulation = FOCModulationType::SinePWM; - //debugger - debugger = nullptr; + // default target value + target = 0; + + //monitor_port + monitor_port = nullptr; } // init hardware pins void BLDCMotor::init() { - if(debugger) debugger->println("DEBUG: Initialize the motor pins."); + if(monitor_port) monitor_port->println("MONITOR: Initialize the motor pins."); // PWM pins pinMode(pwmA, OUTPUT); pinMode(pwmB, OUTPUT); pinMode(pwmC, OUTPUT); if(hasEnable()) pinMode(enable_pin, OUTPUT); - if(debugger) debugger->println("DEBUG: Set high frequency PWM."); + if(monitor_port) monitor_port->println("MONITOR: Set high frequency PWM."); // Increase PWM frequency to 32 kHz // make silent setPwmFrequency(pwmA); @@ -79,12 +75,11 @@ void BLDCMotor::init() { setPwmFrequency(pwmC); // sanity check for the voltage limit configuration - if(PI_velocity.voltage_limit > 0.7*voltage_power_supply) PI_velocity.voltage_limit = 0.7*voltage_power_supply; - if(PI_velocity_index_search.voltage_limit > 0.7*voltage_power_supply) PI_velocity_index_search.voltage_limit = 0.7*voltage_power_supply; + if(PI_velocity.voltage_limit > voltage_power_supply) PI_velocity.voltage_limit = voltage_power_supply; _delay(500); // enable motor - if(debugger) debugger->println("DEBUG: Enabling motor."); + if(monitor_port) monitor_port->println("MONITOR: Enabling motor."); enable(); _delay(500); @@ -120,11 +115,11 @@ void BLDCMotor::linkSensor(Sensor* _sensor) { // Encoder alignment to electrical 0 angle int BLDCMotor::alignSensor() { - if(debugger) debugger->println("DEBUG: Align the sensor's and motor electrical 0 angle."); + if(monitor_port) monitor_port->println("MONITOR: Align the sensor's and motor electrical 0 angle."); // align the electrical phases of the motor and sensor - setPwm(pwmA, voltage_power_supply/2.0); - setPwm(pwmB,0); - setPwm(pwmC,0); + // set angle -90 degrees + setPhaseVoltage(voltage_sensor_align, _3PI_2); + // let the motor stabilize for 3 sec _delay(3000); // set sensor to zero sensor->initRelativeZero(); @@ -135,10 +130,10 @@ int BLDCMotor::alignSensor() { // find the index if available int exit_flag = absoluteZeroAlign(); _delay(500); - if(debugger){ - if(exit_flag< 0 ) debugger->println("DEBUG: Error: Absolute zero not found!"); - if(exit_flag> 0 ) debugger->println("DEBUG: Success: Absolute zero found!"); - else debugger->println("DEBUG: Absolute zero not available!"); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MONITOR: Error: Absolute zero not found!"); + if(exit_flag> 0 ) monitor_port->println("MONITOR: Success: Absolute zero found!"); + else monitor_port->println("MONITOR: Absolute zero not available!"); } return exit_flag; } @@ -150,13 +145,13 @@ int BLDCMotor::absoluteZeroAlign() { // if no absolute zero return if(!sensor->hasAbsoluteZero()) return 0; - if(debugger) debugger->println("DEBUG: Aligning the absolute zero."); + if(monitor_port) monitor_port->println("MONITOR: Aligning the absolute zero."); - if(debugger && sensor->needsAbsoluteZeroSearch()) debugger->println("DEBUG: Searching for absolute zero."); + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MONITOR: Searching for absolute zero."); // search the absolute zero with small velocity while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ loopFOC(); - voltage_q = velocityIndexSearchPI(index_search_velocity - shaftVelocity()); + voltage_q = velocityPI(velocity_index_search - shaftVelocity()); } voltage_q = 0; // disable motor @@ -169,7 +164,7 @@ int BLDCMotor::absoluteZeroAlign() { // remember zero electric angle zero_electric_angle = electricAngle(zero_offset); } - // return bool is zero found + // return bool if zero found return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; } @@ -208,6 +203,9 @@ int BLDCMotor::initFOC() { _delay(500); int exit_flag = alignSensor(); _delay(500); + + if(monitor_port) monitor_port->println("MONITOR: FOC init finished - motor ready."); + return exit_flag; } @@ -224,13 +222,16 @@ void BLDCMotor::loopFOC() { // Behavior of this function is determined by the motor.controller variable // It runs either angle, velocity or voltage loop // - needs to be called iteratively it is asynchronous function -void BLDCMotor::move(float target) { +// - if target is not set it uses motor.target value +void BLDCMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; // get angular velocity shaft_velocity = shaftVelocity(); // choose control loop switch (controller) { case ControlType::voltage: - voltage_q = target; + voltage_q = target; break; case ControlType::angle: // angle set point @@ -281,7 +282,7 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // if negative voltages change inverse the phase // angle + 180degrees - if(Uq < 0) angle_el += M_PI; + if(Uq < 0) angle_el += _PI; Uq = abs(Uq); // angle normalisation in between 0 and 2pi @@ -296,7 +297,7 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // two versions possible // centered around voltage_power_supply/2 float T0 = 1 - T1 - T2; - // centered around 0 + // pulled to 0 - better for low power supply voltage //T0 = 0; // calculate the duty cycles(times) @@ -381,7 +382,7 @@ float BLDCMotor::normalizeAngle(float angle){ } // determining if the enable pin has been provided int BLDCMotor::hasEnable(){ - return enable_pin != 0; + return enable_pin != NOT_SET; } @@ -391,6 +392,7 @@ int BLDCMotor::hasEnable(){ // PI controller function float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){ float Ts = (_micros() - cont.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; @@ -406,6 +408,7 @@ float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){ float d_voltage = voltage - cont.voltage_prev; if (abs(d_voltage)/Ts > cont.voltage_ramp) voltage = d_voltage > 0 ? cont.voltage_prev + cont.voltage_ramp*Ts : cont.voltage_prev - cont.voltage_ramp*Ts; + cont.voltage_prev = voltage; cont.tracking_error_prev = tracking_error; cont.timestamp = _micros(); @@ -415,10 +418,7 @@ float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){ float BLDCMotor::velocityPI(float tracking_error) { return controllerPI(tracking_error, PI_velocity); } -// index search PI contoller -float BLDCMotor::velocityIndexSearchPI(float tracking_error) { - return controllerPI(tracking_error, PI_velocity_index_search); -} + // P controller for position control loop float BLDCMotor::positionP(float ek) { // calculate the target velocity from the position error @@ -429,38 +429,153 @@ float BLDCMotor::positionP(float ek) { } /** - * Debugger functions + * Monitoring functions */ -// function implementing the debugger setter -void BLDCMotor::useDebugging(Print &print){ - debugger = &print; //operate on the address of print - if(debugger )debugger->println("DEBUG: Serial debugger enabled!"); +// function implementing the monitor_port setter +void BLDCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MONITOR: Serial monitor enabled!"); } // utility function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! void BLDCMotor::monitor() { - if(!debugger) return; + if(!monitor_port) return; switch (controller) { case ControlType::velocity: - debugger->print(voltage_q); - debugger->print("\t"); - debugger->print(shaft_velocity_sp); - debugger->print("\t"); - debugger->println(shaft_velocity); + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); break; case ControlType::angle: - debugger->print(voltage_q); - debugger->print("\t"); - debugger->print(shaft_angle_sp); - debugger->print("\t"); - debugger->println(shaft_angle); + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); break; case ControlType::voltage: - debugger->print(voltage_q); - debugger->print("\t"); - debugger->print(shaft_angle); - debugger->print("\t"); - debugger->println(shaft_velocity); + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); break; } -} \ No newline at end of file +} + +int BLDCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("PI velocity P: "); + if(!GET) PI_velocity.P = value; + if(monitor_port) monitor_port->println(PI_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("PI velocity I: "); + if(!GET) PI_velocity.I = value; + if(monitor_port) monitor_port->println(PI_velocity.I); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("PI velocity voltage limit: "); + if(!GET)PI_velocity.voltage_limit = value; + if(monitor_port) monitor_port->println(PI_velocity.voltage_limit); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("PI velocity voltage ramp: "); + if(!GET) PI_velocity.voltage_ramp = value; + if(monitor_port) monitor_port->println(PI_velocity.voltage_ramp); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("LPF velocity time constant: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print("P angle P value: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("P angle velocity limit: "); + if(!GET) P_angle.velocity_limit = value; + if(monitor_port) monitor_port->println(P_angle.velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Contoller type: "); + + if(GET){ // if get commang + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} + + diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.h b/arduino_foc_minimal_magnetic/BLDCMotor.h index 7cc4f324..bebe974d 100644 --- a/arduino_foc_minimal_magnetic/BLDCMotor.h +++ b/arduino_foc_minimal_magnetic/BLDCMotor.h @@ -1,3 +1,8 @@ +/** + * @file BLDCMotor.h + * + */ + #ifndef BLDCMotor_h #define BLDCMotor_h @@ -6,155 +11,265 @@ #include "Sensor.h" #include "defaults.h" -// controller type configuration enum + +#define NOT_SET -12345.0 + +/** + * Motiron control type + */ enum ControlType{ - voltage, - velocity, - angle + voltage,//!< Torque control using voltage + velocity,//!< Velocity motion control + angle//!< Position/angle motion control }; -// FOC Type +/** + * FOC modulation type + */ enum FOCModulationType{ - SinePWM, - SpaceVectorPWM + SinePWM, //!< Sinusoidal PWM modulation + SpaceVectorPWM //!< Space vector modulation method }; -// PI controller structure +/** + * PI controller structure + */ struct PI_s{ - float P; - float I; - long timestamp; - float voltage_prev, tracking_error_prev; - float voltage_limit; - float voltage_ramp; + float P; //!< Proportional gain + float I; //!< Integral gain + float voltage_limit; //!< Voltage limit of the controller output + float voltage_ramp; //!< Maximum speed of change of the output value + long timestamp; //!< Last execution timestamp + float voltage_prev; //!< last controller output value + float tracking_error_prev; //!< last tracking error value }; // P controller structure struct P_s{ - float P; - long timestamp; - float voltage_prev, tracking_error_prev; - float velocity_limit; + float P; //!< Proportional gain + long timestamp; //!< Last execution timestamp + float velocity_limit; //!< Velocity limit of the controller output }; -// flow pass filter structure +/** + * Low pass filter structure + */ struct LPF_s{ - float Tf; - long timestamp; - float prev; + float Tf; //!< Low pass filter time constant + long timestamp; //!< Last execution timestamp + float prev; //!< filtered value in previous execution step }; + + + /** BLDC motor class */ class BLDCMotor { public: - /* - BLDCMotor( int phA, int phB, int phC, int pp , int cpr, int en) - - phA, phB, phC - motor A,B,C phase pwm pins - - pp - pole pair number - - cpr - counts per rotation number (cpm=ppm*4) - - enable pin - (optional input) + /** + BLDCMotor class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param pp pole pair number + @param cpr counts per rotation number (cpm=ppm*4) + @param en enable pin (optional input) */ - BLDCMotor(int phA,int phB,int phC,int pp, int en = 0); - // change driver state + BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + + /** Motor hardware init function */ void init(); + /** Motor disable function */ void disable(); + /** Motor enable function */ void enable(); - // connect sensor - void linkSensor(Sensor* _sensor); - // initilise FOC - int initFOC(); - // iterative method updating motor angles and velocity measurement + /** + * Function linking a motor and a sensor + * + * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity + */ + void linkSensor(Sensor* sensor); + + /** + * Function intializing FOC algorithm + * and aligning sensor's and motors's zero position + */ + int initFOC(); + /** + * Function runing FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ void loopFOC(); - // iterative control loop defined by controller - void move(float target); + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET); // hardware variables - int pwmA; - int pwmB; - int pwmC; - int enable_pin; - int pole_pairs; + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + - /** State calculation methods */ - //Shaft angle calculation + // State calculation methods + /** Shaft angle calculation in radians [rad] */ float shaftAngle(); - //Shaft velocity calculation + /** + * Shaft angle calculation function in radian per second [rad/s] + * It implements low pass filtering + */ float shaftVelocity(); // state variables - // current motor angle - float shaft_angle; - // current motor velocity - float shaft_velocity; - // current target velocity - float shaft_velocity_sp; - // current target angle - float shaft_angle_sp; - // current voltage u_q set - float voltage_q; - - // Power supply voltage - float voltage_power_supply; + float target; //!< current target value - depends of the controller + float shaft_angle;//!< current motor angle + float shaft_velocity;//!< current motor velocity + float shaft_velocity_sp;//!< current target velocity + float shaft_angle_sp;//!< current target angle + float voltage_q;//!< current voltage u_q set + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + + // motor configuration parameters + float voltage_power_supply;//!< Power supply voltage + float voltage_sensor_align;//!< sensor and motor align voltage parameter + float velocity_index_search;//!< target velocity for index search + int pole_pairs;//!< Motor pole pairs number // configuration structures - ControlType controller; - FOCModulationType foc_modulation; - PI_s PI_velocity; - PI_s PI_velocity_index_search; - P_s P_angle; - LPF_s LPF_velocity; - - // sensor link: - // - Encoder - // - MagneticSensor - Sensor* sensor; - // absolute zero electric angle - if available - float zero_electric_angle; - // index search velocity - float index_search_velocity; - - /** FOC methods */ - //Method using FOC to set Uq to the motor at the optimal angle + ControlType controller; //!< parameter determining the control loop to be used + FOCModulationType foc_modulation;//!< parameter derterniming modulation algorithm + PI_s PI_velocity;//!< parameter determining the velocity PI configuration + P_s P_angle; //!< parameter determining the position P configuration + LPF_s LPF_velocity;//!< parameter determining the velocity Lpw pass filter configuration + + /** + * Sensor link: + * - Encoder + * - MagneticSensor + */ + Sensor* sensor; + + float zero_electric_angle;//! 0.5) Ts = 1e-3; - - // time from last impulse - float Th = (timestamp_us - pulse_timestamp) * 1e-6; - long dN = pulse_counter - prev_pulse_counter; - - // Pulse per second calculation (Eq.3.) - // dN - impulses received - // Ts - sampling time - time in between function calls - // Th - time from last impulse - // Th_1 - time form last impulse of the previous call - // only increment if some impulses received - float dt = Ts + prev_Th - Th; - pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second; - - // if more than 0.3 passed in between impulses - if ( Th > 0.15) pulse_per_second = 0; - - // velocity calculation - float velocity = pulse_per_second / ((float)cpr) * (_2PI); - - // save variables for next pass - prev_timestamp_us = timestamp_us; - // save velocity calculation variables - prev_Th = Th; - prev_pulse_counter = pulse_counter; - return (velocity); -} - -// getter for index pin -// return -1 if no index -int Encoder::needsAbsoluteZeroSearch(){ - return index_pulse_counter == 0; -} -// getter for index pin -int Encoder::hasAbsoluteZero(){ - return hasIndex(); -} -// initialize counter to zero -float Encoder::initRelativeZero(){ - long angle_offset = -pulse_counter; - pulse_counter = 0; - pulse_timestamp = _micros(); - return _2PI * (angle_offset) / ((float)cpr); -} -// initialize index to zero -float Encoder::initAbsoluteZero(){ - pulse_counter -= index_pulse_counter; - prev_pulse_counter = pulse_counter; - return (index_pulse_counter) / ((float)cpr) * (_2PI); -} -// private function used to determine if encoder has index -int Encoder::hasIndex(){ - return index_pin != 0; -} - - -// encoder initialisation of the hardware pins -// and calculation variables -void Encoder::init(){ - - // Encoder - check if pullup needed for your encoder - if(pullup == Pullup::INTERN){ - pinMode(pinA, INPUT_PULLUP); - pinMode(pinB, INPUT_PULLUP); - if(hasIndex()) pinMode(index_pin,INPUT_PULLUP); - }else{ - pinMode(pinA, INPUT); - pinMode(pinB, INPUT); - if(hasIndex()) pinMode(index_pin,INPUT); - } - - // counter setup - pulse_counter = 0; - pulse_timestamp = _micros(); - // velocity calculation variables - prev_Th = 0; - pulse_per_second = 0; - prev_pulse_counter = 0; - prev_timestamp_us = _micros(); - - // initial cpr = PPR - // change it if the mode is quadrature - if(quadrature == Quadrature::ENABLE) cpr = 4*cpr; - -} - -// function enabling hardware interrupts of the for the callback provided -// if callback is not provided then the interrupt is not enabled -void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){ - // attach interrupt if functions provided - switch(quadrature){ - case Quadrature::ENABLE: - // A callback and B callback - if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); - if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); - break; - case Quadrature::DISABLE: - // A callback and B callback - if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING); - if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); - break; - } - - // if index used initialize the index interrupt - if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE); -} - diff --git a/arduino_foc_minimal_magnetic/Encoder.h b/arduino_foc_minimal_magnetic/Encoder.h deleted file mode 100644 index d115fe25..00000000 --- a/arduino_foc_minimal_magnetic/Encoder.h +++ /dev/null @@ -1,92 +0,0 @@ -#ifndef ENCODER_LIB_H -#define ENCODER_LIB_H - -#include "Arduino.h" -#include "FOCutils.h" -#include "Sensor.h" - - -// Pullup configuration structure -enum Pullup{ - INTERN, - EXTERN -}; - -enum Quadrature{ - ENABLE, // CPR = 4xPPR - DISABLE // CPR = PPR -}; - -class Encoder: public Sensor{ - public: - /* - Encoder(int encA, int encB , int cpr, int index) - - encA, encB - encoder A and B pins - - ppr - impulses per rotation (cpr=ppr*4) - - index pin - (optional input) - */ - Encoder(int encA, int encB , float ppr, int index = 0); - - // encoder initialise pins - void init(); - // function enabling hardware interrupts of the for the callback provided - // if callback is not provided then the interrupt is not enabled - void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr); - - // Encoder interrupt callback functions - // enabling CPR=4xPPR behaviour - // A channel - void handleA(); - // B channel - void handleB(); - // index handle - void handleIndex(); - - - // pins A and B - int pinA, pinB; // encoder hardware pins - // index pin - int index_pin; - // encoder pullup type - Pullup pullup; - // use 4xppr or not - Quadrature quadrature; - - // implementation of abstract functions of the Sensor class - // get current angle (rad) - float getAngle(); - // get current angular velocity (rad/s) - float getVelocity(); - // set current angle as zero angle - // return the angle [rad] difference - float initRelativeZero(); - // set index angle as zero angle - // return the angle [rad] difference - float initAbsoluteZero(); - // returns 0 if it has no index - // 0 - encoder without index - // 1 - encoder with index - int hasAbsoluteZero(); - // returns 0 if it does need search for absolute zero - // 0 - encoder without index - // 1 - ecoder with index - int needsAbsoluteZeroSearch(); - - private: - int hasIndex(); - - volatile long pulse_counter; // current pulse counter - volatile long pulse_timestamp; // last impulse timestamp in us - float cpr; // impulse cpr - volatile int A_active, B_active; // current active states of A and B line - volatile int I_active; // index active - volatile long index_pulse_counter; // pulse counter of the index - - // velocity calculation variables - float prev_Th, pulse_per_second; - volatile long prev_pulse_counter, prev_timestamp_us; - -}; - - -#endif diff --git a/arduino_foc_minimal_magnetic/FOCutils.cpp b/arduino_foc_minimal_magnetic/FOCutils.cpp index c9f0db4c..31ec1c15 100644 --- a/arduino_foc_minimal_magnetic/FOCutils.cpp +++ b/arduino_foc_minimal_magnetic/FOCutils.cpp @@ -1,10 +1,10 @@ #include "FOCutils.h" -/* - High PWM frequency - https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 -*/ + void setPwmFrequency(int pin) { +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other atmega328p chips +// High PWM frequency +// https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 if (pin == 5 || pin == 6 || pin == 9 || pin == 10) { if (pin == 5 || pin == 6) { // configure the pwm phase-corrected mode @@ -20,22 +20,39 @@ void setPwmFrequency(int pin) { // set prescaler to 1 TCCR2B = ((TCCR2B & 0b11111000) | 0x01); } +#elif defined(_STM32_DEF_) // if stm chips + analogWrite(pin,0); + analogWriteFrequency(50000); // la valeur par défaut est 20000 Hz +#endif } // function buffering delay() -// arduino function doesn't work well with interrupts +// arduino uno function doesn't work well with interrupts void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // return the value based on the prescaler long t = _micros(); - while((_micros() - t)/1000 < ms){}; + while((_micros() - t)/1000 < ms){}; +#else + // regular micros + return delay(ms); +#endif } // function buffering _micros() // arduino function doesn't work well with interrupts unsigned long _micros(){ - // return the value based on the prescaler +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); else return (micros()); +#else + // regular micros + return micros(); +#endif } @@ -54,21 +71,21 @@ int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,110 // it has to receive an angle in between 0 and 2PI float _sin(float a){ if(a < _PI_2){ - //return sine_array[(int)(199.0*( a / (M_PI/2.0)))]; + //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; //return sine_array[(int)(126.6873* a)]; // float array optimised - return 0.0001*sine_array[round(126.6873* a)]; // int array optimised - }else if(a < M_PI){ - // return sine_array[(int)(199.0*(1.0 - (a-M_PI/2.0) / (M_PI/2.0)))]; + return 0.0001*sine_array[_round(126.6873* a)]; // int array optimised + }else if(a < _PI){ + // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; //return sine_array[398 - (int)(126.6873*a)]; // float array optimised - return 0.0001*sine_array[398 - round(126.6873*a)]; // int array optimised + return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimised }else if(a < _3PI_2){ - // return -sine_array[(int)(199.0*((a - M_PI) / (M_PI/2.0)))]; + // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimised - return -0.0001*sine_array[-398 + round(126.6873*a)]; // int array optimised + return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimised } else { - // return -sine_array[(int)(199.0*(1.0 - (a - 3*M_PI/2) / (M_PI/2.0)))]; + // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; //return -sine_array[796 - (int)(126.6873*a)]; // float array optimised - return -0.0001*sine_array[796 - round(126.6873*a)]; // int array optimised + return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimised } } diff --git a/arduino_foc_minimal_magnetic/FOCutils.h b/arduino_foc_minimal_magnetic/FOCutils.h index 11882a81..0b333757 100644 --- a/arduino_foc_minimal_magnetic/FOCutils.h +++ b/arduino_foc_minimal_magnetic/FOCutils.h @@ -5,6 +5,8 @@ // sign function #define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + // utility defines #define _2_SQRT3 1.15470053838 #define _SQRT3 1.73205080757 @@ -12,29 +14,48 @@ #define _SQRT3_2 0.86602540378 #define _SQRT2 1.41421356237 #define _120_D2R 2.09439510239 +#define _PI 3.14159265359 #define _PI_2 1.57079632679 #define _PI_3 1.0471975512 #define _2PI 6.28318530718 #define _3PI_2 4.71238898038 -// High PWM frequency +/** + * High PWM frequency setting function + * - hardware specific + * + * @param pin pin number to configure + */ void setPwmFrequency(int pin); -// function buffering delay() -// arduino function doesn't work well with interrupts +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + * + * @param ms number of milliseconds to wait + */ void _delay(unsigned long ms); -// function buffering _micros() -// arduino function doesn't work well with interrupts +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ unsigned long _micros(); -// function approximating the sine calculation by using fixed size array -// ~40us -// it has to receive an angle in between 0 and 2PI +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ float _sin(float a); -// function approximating cosine calculation by using fixed size array -// ~50us -// it has to receive an angle in between 0 and 2PI +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ float _cos(float a); #endif \ No newline at end of file diff --git a/arduino_foc_minimal_magnetic/MagneticSensor.cpp b/arduino_foc_minimal_magnetic/MagneticSensor.cpp index d045eab5..4cb78bb2 100644 --- a/arduino_foc_minimal_magnetic/MagneticSensor.cpp +++ b/arduino_foc_minimal_magnetic/MagneticSensor.cpp @@ -1,6 +1,5 @@ #include "MagneticSensor.h" - // MagneticSensor(int cs, float _cpr, int _angle_register) // cs - SPI chip select pin // _cpr - count per revolution @@ -23,9 +22,14 @@ void MagneticSensor::init(){ //setup pins pinMode(chip_select_pin, OUTPUT); + //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices SPI.begin(); + SPI.setBitOrder(MSBFIRST); // Set the SPI_1 bit order + SPI.setDataMode(SPI_MODE1) ; + SPI.setClockDivider(SPI_CLOCK_DIV8); + digitalWrite(chip_select_pin, HIGH); // velocity calculation init angle_prev = 0; velocity_calc_timestamp = _micros(); @@ -36,27 +40,27 @@ void MagneticSensor::init(){ zero_offset = 0; } -// Shaft angle calculation +// Shaft angle calculation // angle is in radians [rad] float MagneticSensor::getAngle(){ - // raw data from the sensor - float angle_data = getRawCount(); - - // tracking the number of rotations - // in order to expand angle range form [0,2PI] - // to basically infinity - float d_angle = angle_data - angle_data_prev; - // if overflow happened track it as full rotation - if(abs(d_angle) > (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; - // save the current angle value for the next steps - // in order to know if overflow happened - angle_data_prev = angle_data; - - // zero offset adding - angle_data -= (int)zero_offset; - // return the full angle - // (number of full rotations)*2PI + current sensor angle - return full_rotation_offset + ( angle_data / (float)cpr) * _2PI; + // raw data from the sensor + float angle_data = getRawCount(); + + // tracking the number of rotations + // in order to expand angle range form [0,2PI] + // to basically infinity + float d_angle = angle_data - angle_data_prev; + // if overflow happened track it as full rotation + if(abs(d_angle) > (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; + // save the current angle value for the next steps + // in order to know if overflow happened + angle_data_prev = angle_data; + + // zero offset adding + angle_data -= (int)zero_offset; + // return the full angle + // (number of full rotations)*2PI + current sensor angle + return full_rotation_offset + ( angle_data / (float)cpr) * _2PI; } // Shaft velocity calculation @@ -150,33 +154,38 @@ word MagneticSensor::read(word angle_register){ byte right_byte = command & 0xFF; byte left_byte = ( command >> 8 ) & 0xFF; - //SPI - begin transaction - SPI.beginTransaction(settings); - - //Send the command - digitalWrite(chip_select_pin, LOW); - SPI.transfer(left_byte); - SPI.transfer(right_byte); - digitalWrite(chip_select_pin,HIGH); - - //Now read the response - digitalWrite(chip_select_pin, LOW); - left_byte = SPI.transfer(0x00); - right_byte = SPI.transfer(0x00); - digitalWrite(chip_select_pin, HIGH); - - //SPI - end transaction - SPI.endTransaction(); - - //Check if the error bit is set - if (left_byte & 0x40) { - errorFlag = true; - } - else { - errorFlag = false; - } - //Return the data, stripping the parity and error bits +#if !defined(_STM32_DEF_) // if not stm chips + //SPI - begin transaction + SPI.beginTransaction(settings); +#endif + //SPI - begin transaction + //SPI.beginTransaction(settings); + + //Send the command + digitalWrite(chip_select_pin, LOW); + digitalWrite(chip_select_pin, LOW); + SPI.transfer(left_byte); + SPI.transfer(right_byte); + digitalWrite(chip_select_pin,HIGH); + digitalWrite(chip_select_pin,HIGH); + + delayMicroseconds(10); + + //Now read the response + digitalWrite(chip_select_pin, LOW); + digitalWrite(chip_select_pin, LOW); + left_byte = SPI.transfer(0x00); + right_byte = SPI.transfer(0x00); + digitalWrite(chip_select_pin, HIGH); + digitalWrite(chip_select_pin,HIGH); + +#if !defined(_STM32_DEF_) // if not stm chips + //SPI - end transaction + SPI.endTransaction(); +#endif + + // Return the data, stripping the parity and error bits return (( ( left_byte & 0xFF ) << 8 ) | ( right_byte & 0xFF )) & ~0xC000; } diff --git a/arduino_foc_minimal_magnetic/MagneticSensor.h b/arduino_foc_minimal_magnetic/MagneticSensor.h index 50665982..90b6b291 100644 --- a/arduino_foc_minimal_magnetic/MagneticSensor.h +++ b/arduino_foc_minimal_magnetic/MagneticSensor.h @@ -10,60 +10,68 @@ class MagneticSensor: public Sensor{ public: + /** + * MagneticSensor class constructor + * @param cs SPI chip select pin + * @param cpr counts per revolution + * @param angle_register (optional) angle read register - default 0x3FFF + */ + MagneticSensor(int cs, float cpr, int angle_register = 0); - // MagneticSensor(int cs, float _cpr, int _angle_register) - // cs - SPI chip select pin - // _cpr - counts per revolution - // _angle_register - (optional) angle read register - default 0x3FFF - MagneticSensor(int cs, float _cpr, int angle_register = 0); - - // SPI angle register to read - int angle_register; - // encoder initialise pins + /** sensor initialise pins */ void init(); // implementation of abstract functions of the Sensor class - // get current angle (rad) + /** get current angle (rad) */ float getAngle(); - // get current angular velocity (rad/s) + /** get current angular velocity (rad/s) **/ float getVelocity(); - // set current angle as zero angle - // return the angle [rad] difference + /** + * set current angle as zero angle + * return the angle [rad] difference + */ float initRelativeZero(); - // set absolute zero angle as zero angle - // return the angle [rad] difference + /** + * set absolute zero angle as zero angle + * return the angle [rad] difference + */ float initAbsoluteZero(); - // returns 1 because it is the absolute sensor + /** returns 1 because it is the absolute sensor */ int hasAbsoluteZero(); - // returns 0 maning it doesn't need search for absolute zero + /** returns 0 maning it doesn't need search for absolute zero */ int needsAbsoluteZeroSearch(); private: + float cpr; //!< Maximum range of the magnetic sensor // spi variables - int chip_select_pin; - bool errorFlag; - SPISettings settings; + int angle_register; //!< SPI angle register to read + int chip_select_pin; //!< SPI chip select pin + SPISettings settings; //!< SPI settings variable // spi functions - void close(); + /** Stop SPI communication */ + void close(); + /** Read one SPI register value */ word read(word angle_register); + /** Calculate parity value */ byte spiCalcEvenParity(word value); - // zero offset - word zero_offset; - // function getting current register value + word zero_offset; //!< user defined zero offset + /** + * Function getting current angle register value + * it uses angle_register variable + */ int getRawCount(); // total angle tracking variables - float full_rotation_offset; - float angle_data_prev; - // impulse cpr - float cpr; + float full_rotation_offset; //! Date: Thu, 18 Jun 2020 13:23:36 +0200 Subject: [PATCH 48/65] FEAT support for version 1.3.0 --- README.md | 36 ++-- arduino_foc_minimal_encoder/BLDCMotor.cpp | 8 + arduino_foc_minimal_encoder/BLDCMotor.h | 8 +- arduino_foc_minimal_magnetic/BLDCMotor.cpp | 8 + arduino_foc_minimal_magnetic/BLDCMotor.h | 8 +- arduino_foc_minimal_magnetic/SimpleFOC.h | 1 - .../arduino_foc_minimal_magnetic.ino | 184 ++++++++---------- 7 files changed, 129 insertions(+), 124 deletions(-) diff --git a/README.md b/README.md index 956b06e5..5ce98606 100644 --- a/README.md +++ b/README.md @@ -14,26 +14,28 @@ This is the minimal Arduino example of the [Simple FOC](https://github.com/askur # AS5048/47 ``` -Each of the examples will give you the opportunity to change the PI velocity parameters `P` and `I`, Low pass filter time constant `Tf`, change the control loop in real time and check the average loop execution time, all from the serial terminal. -``` -PI controller parameters change: -- P value : Prefix P (ex. P0.1) -- I value : Prefix I (ex. I0.1) - -Velocity filter: -- Tf value : Prefix F (ex. F0.001) +Each of the examples will give you the opportunity to change the PI velocity parameters `P` and `I`, Low pass filter time constant `Tf`, change the control loop in real time and check the average loop execution time, all from the serial terminal. -Average loop execution time: -- Type T +List of commands: +- **P**: velocity PI controller P gain +- **I**: velocity PI controller I gain +- **L**: velocity PI controller voltage limit +- **R**: velocity PI controller voltage ramp +- **F**: velocity Low pass filter time constant +- **K**: angle P controller P gain +- **N**: angle P controller velocity limit +- **C**: control loop + - **0**: voltage + - **1**: velocity + - **2**: angle +- **V**: get motor variables + - **0**: currently set voltage + - **1**: current velocity + - **2**: current angle + - **3**: current target value -Control loop type: -- C0 - angle control -- C1 - velocity control -- C2 - voltage control -Initial parameters: -PI velocity P: 0.20, I: 20.00, Low pass filter Tf: 0.0000 -``` +Find more information about the **motor commands** in the [docs.simplefoc.com](https://docs.simplefoc.com/communication) ### Installation For those willing to experiment and to modify the code I suggest using the [minimal version](https://github.com/askuric/Arduino-FOC/tree/minimal) of the code. diff --git a/arduino_foc_minimal_encoder/BLDCMotor.cpp b/arduino_foc_minimal_encoder/BLDCMotor.cpp index 1e119858..57cdb2ad 100644 --- a/arduino_foc_minimal_encoder/BLDCMotor.cpp +++ b/arduino_foc_minimal_encoder/BLDCMotor.cpp @@ -468,6 +468,9 @@ void BLDCMotor::monitor() { int BLDCMotor::command(String user_command) { // error flag int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + // parse command letter char cmd = user_command.charAt(0); // check if get command @@ -512,6 +515,11 @@ int BLDCMotor::command(String user_command) { if(!GET) P_angle.velocity_limit = value; if(monitor_port) monitor_port->println(P_angle.velocity_limit); break; + case 'T': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("P angle velocity limit: "); + if(!GET) P_angle.velocity_limit = value; + if(monitor_port) monitor_port->println(P_angle.velocity_limit); + break; case 'C': // change control type if(monitor_port) monitor_port->print("Contoller type: "); diff --git a/arduino_foc_minimal_encoder/BLDCMotor.h b/arduino_foc_minimal_encoder/BLDCMotor.h index bebe974d..df95445d 100644 --- a/arduino_foc_minimal_encoder/BLDCMotor.h +++ b/arduino_foc_minimal_encoder/BLDCMotor.h @@ -95,12 +95,12 @@ class BLDCMotor void linkSensor(Sensor* sensor); /** - * Function intializing FOC algorithm - * and aligning sensor's and motors's zero position + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position */ int initFOC(); /** - * Function runing FOC algorithm in real-time + * Function running FOC algorithm in real-time * it calculates the gets motor angle and sets the appropriate voltages * to the phase pwm signals * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us @@ -171,7 +171,7 @@ class BLDCMotor * Method using FOC to set Uq to the motor at the optimal angle * Heart of the FOC algorithm * - * @param Uq Current volatge in q axis to set to the motor + * @param Uq Current voltage in q axis to set to the motor * @param angle_el current electrical angle of the motor */ void setPhaseVoltage(float Uq, float angle_el); diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.cpp b/arduino_foc_minimal_magnetic/BLDCMotor.cpp index 1e119858..57cdb2ad 100644 --- a/arduino_foc_minimal_magnetic/BLDCMotor.cpp +++ b/arduino_foc_minimal_magnetic/BLDCMotor.cpp @@ -468,6 +468,9 @@ void BLDCMotor::monitor() { int BLDCMotor::command(String user_command) { // error flag int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + // parse command letter char cmd = user_command.charAt(0); // check if get command @@ -512,6 +515,11 @@ int BLDCMotor::command(String user_command) { if(!GET) P_angle.velocity_limit = value; if(monitor_port) monitor_port->println(P_angle.velocity_limit); break; + case 'T': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("P angle velocity limit: "); + if(!GET) P_angle.velocity_limit = value; + if(monitor_port) monitor_port->println(P_angle.velocity_limit); + break; case 'C': // change control type if(monitor_port) monitor_port->print("Contoller type: "); diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.h b/arduino_foc_minimal_magnetic/BLDCMotor.h index bebe974d..df95445d 100644 --- a/arduino_foc_minimal_magnetic/BLDCMotor.h +++ b/arduino_foc_minimal_magnetic/BLDCMotor.h @@ -95,12 +95,12 @@ class BLDCMotor void linkSensor(Sensor* sensor); /** - * Function intializing FOC algorithm - * and aligning sensor's and motors's zero position + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position */ int initFOC(); /** - * Function runing FOC algorithm in real-time + * Function running FOC algorithm in real-time * it calculates the gets motor angle and sets the appropriate voltages * to the phase pwm signals * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us @@ -171,7 +171,7 @@ class BLDCMotor * Method using FOC to set Uq to the motor at the optimal angle * Heart of the FOC algorithm * - * @param Uq Current volatge in q axis to set to the motor + * @param Uq Current voltage in q axis to set to the motor * @param angle_el current electrical angle of the motor */ void setPhaseVoltage(float Uq, float angle_el); diff --git a/arduino_foc_minimal_magnetic/SimpleFOC.h b/arduino_foc_minimal_magnetic/SimpleFOC.h index 887ae8df..bd095760 100644 --- a/arduino_foc_minimal_magnetic/SimpleFOC.h +++ b/arduino_foc_minimal_magnetic/SimpleFOC.h @@ -3,7 +3,6 @@ #include "FOCutils.h" #include "Sensor.h" -#include "Encoder.h" #include "MagneticSensor.h" #include "BLDCMotor.h" diff --git a/arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino b/arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino index 82a6c28e..4c381893 100644 --- a/arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino +++ b/arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino @@ -1,20 +1,59 @@ +/** + * Comprehensive BLDC motor control example using magnetic sensor and the minimal version off the SimpleFOC library + * - THis code is completely stand alone and you dont need to have SimpleFOClibary installed to run it + * + * Check the docs.simplefoc.com for more information + * + * Using serial terminal user can send motor commands and configure the motor and FOC in real-time: + * - configure PID controller constants + * - change motion control loops + * - monitor motor variabels + * - set target values + * - check all the configuration values + * + * To check the config value just enter the command letter. + * For example: - to read velocity PI controller P gain run: P + * - to set velocity PI controller P gain to 1.2 run: P1.2 + * + * To change the target value just enter a number in the terminal: + * For example: - to change the target value to -0.1453 enter: -0.1453 + * - to get the current target value enter: V3 + * + * List of commands: + * - P: velocity PI controller P gain + * - I: velocity PI controller I gain + * - L: velocity PI controller voltage limit + * - R: velocity PI controller voltage ramp + * - F: velocity Low pass filter time constant + * - K: angle P controller P gain + * - N: angle P controller velocity limit + * - C: control loop + * - 0: voltage + * - 1: velocity + * - 2: angle + * - V: get motor variables + * - 0: currently set voltage + * - 1: current velocity + * - 2: current angle + * - 3: current target value + * + */ + + #include "SimpleFOC.h" -// // software interrupt library -// #include -// #include // BLDCMotor( int phA, int phB, int phC, int pp, int en) // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 5, 6, 11); +BLDCMotor motor = BLDCMotor(9, 5, 6, 11, 8); // MagneticSensor(int cs, float _cpr, int _angle_register) // cs - SPI chip select pin // _cpr - count per revolution // _angle_register - (optional) angle read register - default 0x3FFF -MagneticSensor as504x = MagneticSensor(10, 16384); +MagneticSensor as504x = MagneticSensor(2, 16384); void setup() { // debugging port @@ -22,23 +61,28 @@ void setup() { // initialise magnetic sensor hardware as504x.init(); + // link sensor and motor + motor.linkSensor(&as504x); // choose FOC algorithm to be used: // FOCModulationType::SinePWM (default) // FOCModulationType::SpaceVectorPWM motor.foc_modulation = FOCModulationType::SpaceVectorPWM; - // power supply voltage + // power supply voltage [V] // default 12V motor.voltage_power_supply = 12; + // motor and sensor aligning voltage [V] + // default 6V + motor.voltage_sensor_align = 3; // set control loop type to be used // ControlType::voltage // ControlType::velocity // ControlType::angle - motor.controller = ControlType::angle; + motor.controller = ControlType::voltage; - // contoller configuration based on the controll type + // controller configuration based on the control type // velocity PI controller parameters motor.PI_velocity.P = 0.2; motor.PI_velocity.I = 20; @@ -57,41 +101,25 @@ void setup() { motor.P_angle.P = 3; motor.P_angle.velocity_limit = 10; - // link the motor to the sensor - motor.linkSensor(&as504x); - - - // use debugging with serial for motor init - // comment out if not needed - motor.useDebugging(Serial); + // use monitoring with serial for motor init + // monitoring port + Serial.begin(115200); + // enable monitoring + motor.useMonitoring(Serial); - // initialize motor + // initialise motor motor.init(); // align encoder and start FOC motor.initFOC(); - // this serial print takes about 20% of arduino memory!! - Serial.println("\n\n"); - Serial.println("PI controller parameters change:"); - Serial.println("- P value : Prefix P (ex. P0.1)"); - Serial.println("- I value : Prefix I (ex. I0.1)\n"); - Serial.println("Velocity filter:"); - Serial.println("- Tf value : Prefix F (ex. F0.001)\n"); - Serial.println("Average loop execution time:"); - Serial.println("- Type T\n"); - Serial.println("Control loop type:"); - Serial.println("- C0 - angle control"); - Serial.println("- C1 - velocity control"); - Serial.println("- C2 - voltage control\n"); - Serial.println("Initial parameters:"); - Serial.print("PI velocity P: "); - Serial.print(motor.PI_velocity.P); - Serial.print(",\t I: "); - Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low pass filter Tf: "); - Serial.println(motor.LPF_velocity.Tf,4); + // set the inital target value + motor.target = 2; + + Serial.println("Full control example: "); + Serial.println("Voltage control target 2V."); _delay(1000); + } // target velocity variable @@ -106,76 +134,36 @@ void loop() { // iterative function setting the outter loop target // velocity, position or voltage - motor.move(target); + // if tatget not set in parameter uses motor.target variable + motor.move(); - // keep track of loop number - t++; + // user communication + motor.command(serialReceiveUserCommand()); } -// Serial communication callback -void serialEvent() { +// utility function enabling serial communication the user +String serialReceiveUserCommand() { + // a string to hold incoming data - static String inputString; + static String received_chars; + + String command = ""; + while (Serial.available()) { // get the new byte: char inChar = (char)Serial.read(); - // add it to the inputString: - inputString += inChar; - // if the incoming character is a newline - // end of input + // add it to the string buffer: + received_chars += inChar; + + // end of user input if (inChar == '\n') { - if(inputString.charAt(0) == 'P'){ - motor.PI_velocity.P = inputString.substring(1).toFloat(); - Serial.print("PI velocity P: "); - Serial.print(motor.PI_velocity.P); - Serial.print(",\t I: "); - Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low pass filter Tf: "); - Serial.println(motor.LPF_velocity.Tf,4); - }else if(inputString.charAt(0) == 'I'){ - motor.PI_velocity.I = inputString.substring(1).toFloat(); - Serial.print("PI velocity P: "); - Serial.print(motor.PI_velocity.P); - Serial.print(",\t I: "); - Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low pass filter Tf: "); - Serial.println(motor.LPF_velocity.Tf,4); - }else if(inputString.charAt(0) == 'F'){ - motor.LPF_velocity.Tf = inputString.substring(1).toFloat(); - Serial.print("PI velocity P: "); - Serial.print(motor.PI_velocity.P); - Serial.print(",\t I: "); - Serial.print(motor.PI_velocity.I); - Serial.print(",\t Low pass filter Tf: "); - Serial.println(motor.LPF_velocity.Tf,4); - }else if(inputString.charAt(0) == 'T'){ - Serial.print("Average loop time is (microseconds): "); - Serial.println((_micros() - timestamp)/t); - t = 0; - timestamp = _micros(); - }else if(inputString.charAt(0) == 'C'){ - Serial.print("Contoller type: "); - int cnt = inputString.substring(1).toFloat(); - if(cnt == 0){ - Serial.println("angle!"); - motor.controller = ControlType::angle; - }else if(cnt == 1){ - Serial.println("velocity!"); - motor.controller = ControlType::velocity; - }else if(cnt == 2){ - Serial.println("voltage!"); - motor.controller = ControlType::voltage; - } - Serial.println(); - t = 0; - timestamp = _micros(); - }else{ - target = inputString.toFloat(); - Serial.print("Target : "); - Serial.println(target); - inputString = ""; - } - inputString = ""; + + // execute the user command + command = received_chars; + + // reset the command buffer + received_chars = ""; } } + return command; } From 78148fddc99b8fa34d0c8a472daf30788f84f708 Mon Sep 17 00:00:00 2001 From: askuric Date: Sat, 1 Aug 2020 08:56:18 +0200 Subject: [PATCH 49/65] FEAT updated with library version 1.4.0 --- arduino_foc_minimal_encoder/FOCutils.cpp | 2 +- arduino_foc_minimal_encoder/FOCutils.h | 2 +- arduino_foc_minimal_encoder/SimpleFOC.h | 9 - .../arduino_foc_minimal_encoder.ino | 7 +- arduino_foc_minimal_magnetic/BLDCMotor.cpp | 6 +- arduino_foc_minimal_magnetic/FOCutils.cpp | 2 +- arduino_foc_minimal_magnetic/FOCutils.h | 2 +- .../MagneticSensorI2C.cpp | 153 ++++++++++ .../MagneticSensorI2C.h | 78 +++++ .../MagneticSensorSPI.cpp | 198 +++++++++++++ .../MagneticSensorSPI.h | 79 +++++ arduino_foc_minimal_magnetic/SimpleFOC.h | 9 - .../arduino_foc_minimal_magnetic.ino | 30 +- .../BLDCMotor.cpp | 6 +- src/BLDCMotor.h | 277 ++++++++++++++++++ src/Encoder.cpp | 229 +++++++++++++++ src/Encoder.h | 112 +++++++ src/FOCutils.cpp | 101 +++++++ src/FOCutils.h | 61 ++++ .../MagneticSensor.cpp | 0 .../MagneticSensor.h | 0 src/MagneticSensorI2C.cpp | 153 ++++++++++ src/MagneticSensorI2C.h | 78 +++++ src/MagneticSensorSPI.cpp | 198 +++++++++++++ src/MagneticSensorSPI.h | 79 +++++ src/Sensor.h | 39 +++ src/SimpleFOC.h | 96 ++++++ src/defaults.h | 17 ++ 28 files changed, 1982 insertions(+), 41 deletions(-) delete mode 100644 arduino_foc_minimal_encoder/SimpleFOC.h create mode 100644 arduino_foc_minimal_magnetic/MagneticSensorI2C.cpp create mode 100644 arduino_foc_minimal_magnetic/MagneticSensorI2C.h create mode 100644 arduino_foc_minimal_magnetic/MagneticSensorSPI.cpp create mode 100644 arduino_foc_minimal_magnetic/MagneticSensorSPI.h delete mode 100644 arduino_foc_minimal_magnetic/SimpleFOC.h rename {arduino_foc_minimal_encoder => src}/BLDCMotor.cpp (99%) create mode 100644 src/BLDCMotor.h create mode 100644 src/Encoder.cpp create mode 100644 src/Encoder.h create mode 100644 src/FOCutils.cpp create mode 100644 src/FOCutils.h rename {arduino_foc_minimal_magnetic => src}/MagneticSensor.cpp (100%) rename {arduino_foc_minimal_magnetic => src}/MagneticSensor.h (100%) create mode 100644 src/MagneticSensorI2C.cpp create mode 100644 src/MagneticSensorI2C.h create mode 100644 src/MagneticSensorSPI.cpp create mode 100644 src/MagneticSensorSPI.h create mode 100644 src/Sensor.h create mode 100644 src/SimpleFOC.h create mode 100644 src/defaults.h diff --git a/arduino_foc_minimal_encoder/FOCutils.cpp b/arduino_foc_minimal_encoder/FOCutils.cpp index 31ec1c15..04c6cfbf 100644 --- a/arduino_foc_minimal_encoder/FOCutils.cpp +++ b/arduino_foc_minimal_encoder/FOCutils.cpp @@ -1,7 +1,7 @@ #include "FOCutils.h" -void setPwmFrequency(int pin) { +void _setPwmFrequency(int pin) { #if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other atmega328p chips // High PWM frequency // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 diff --git a/arduino_foc_minimal_encoder/FOCutils.h b/arduino_foc_minimal_encoder/FOCutils.h index 0b333757..b60978b3 100644 --- a/arduino_foc_minimal_encoder/FOCutils.h +++ b/arduino_foc_minimal_encoder/FOCutils.h @@ -26,7 +26,7 @@ * * @param pin pin number to configure */ -void setPwmFrequency(int pin); +void _setPwmFrequency(int pin); /** * Function implementing delay() function in milliseconds diff --git a/arduino_foc_minimal_encoder/SimpleFOC.h b/arduino_foc_minimal_encoder/SimpleFOC.h deleted file mode 100644 index bd9ecb55..00000000 --- a/arduino_foc_minimal_encoder/SimpleFOC.h +++ /dev/null @@ -1,9 +0,0 @@ -#ifndef SIMPLEFOC_H -#define SIMPLEFOC_H - -#include "FOCutils.h" -#include "Sensor.h" -#include "Encoder.h" -#include "BLDCMotor.h" - -#endif diff --git a/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino b/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino index 646ac7f7..41e29569 100644 --- a/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino +++ b/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino @@ -39,19 +39,20 @@ * */ -#include "SimpleFOC.h" +#include "BLDCMotor.h" +#include "Encoder.h" // BLDCMotor( int phA, int phB, int phC, int pp, int en) // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(3, 10, 11, 11,7); +BLDCMotor motor = BLDCMotor(9, 10, 11, 11,8); //Encoder(int encA, int encB , int cpr, int index) // - encA, encB - encoder A and B pins // - ppr - impulses per rotation (cpr=ppr*4) // - index pin - (optional input) -Encoder encoder = Encoder(A1, A2, 8196); +Encoder encoder = Encoder(2, 3, 8196); // interrupt routine intialisation void doA(){encoder.handleA();} void doB(){encoder.handleB();} diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.cpp b/arduino_foc_minimal_magnetic/BLDCMotor.cpp index 57cdb2ad..a826a366 100644 --- a/arduino_foc_minimal_magnetic/BLDCMotor.cpp +++ b/arduino_foc_minimal_magnetic/BLDCMotor.cpp @@ -70,9 +70,9 @@ void BLDCMotor::init() { if(monitor_port) monitor_port->println("MONITOR: Set high frequency PWM."); // Increase PWM frequency to 32 kHz // make silent - setPwmFrequency(pwmA); - setPwmFrequency(pwmB); - setPwmFrequency(pwmC); + _setPwmFrequency(pwmA); + _setPwmFrequency(pwmB); + _setPwmFrequency(pwmC); // sanity check for the voltage limit configuration if(PI_velocity.voltage_limit > voltage_power_supply) PI_velocity.voltage_limit = voltage_power_supply; diff --git a/arduino_foc_minimal_magnetic/FOCutils.cpp b/arduino_foc_minimal_magnetic/FOCutils.cpp index 31ec1c15..04c6cfbf 100644 --- a/arduino_foc_minimal_magnetic/FOCutils.cpp +++ b/arduino_foc_minimal_magnetic/FOCutils.cpp @@ -1,7 +1,7 @@ #include "FOCutils.h" -void setPwmFrequency(int pin) { +void _setPwmFrequency(int pin) { #if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other atmega328p chips // High PWM frequency // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 diff --git a/arduino_foc_minimal_magnetic/FOCutils.h b/arduino_foc_minimal_magnetic/FOCutils.h index 0b333757..b60978b3 100644 --- a/arduino_foc_minimal_magnetic/FOCutils.h +++ b/arduino_foc_minimal_magnetic/FOCutils.h @@ -26,7 +26,7 @@ * * @param pin pin number to configure */ -void setPwmFrequency(int pin); +void _setPwmFrequency(int pin); /** * Function implementing delay() function in milliseconds diff --git a/arduino_foc_minimal_magnetic/MagneticSensorI2C.cpp b/arduino_foc_minimal_magnetic/MagneticSensorI2C.cpp new file mode 100644 index 00000000..52778025 --- /dev/null +++ b/arduino_foc_minimal_magnetic/MagneticSensorI2C.cpp @@ -0,0 +1,153 @@ +#include "MagneticSensorI2C.h" + +// MagneticSensorI2C(uint8_t _chip_address, float _cpr, uint8_t _angle_register_msb) +// @param _chip_address I2C chip address +// @param _bit_resolution bit resolution of the sensor +// @param _angle_register_msb angle read register +// @param _bits_used_msb number of used bits in msb +MagneticSensorI2C::MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _bits_used_msb){ + // chip I2C address + chip_address = _chip_address; + // angle read register of the magnetic sensor + angle_register_msb = _angle_register_msb; + // register maximum value (counts per revolution) + cpr = pow(2,_bit_resolution); + + // depending on the sensor architecture there are different combinations of + // LSB and MSB register used bits + // AS5600 uses 0..7 LSB and 8..11 MSB + // AS5048 uses 0..5 LSB and 6..13 MSB + // used bits in LSB + lsb_used = _bit_resolution - _bits_used_msb; + // extraction masks + lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); + msb_mask = (uint8_t)( (2 << _bits_used_msb) - 1 ); +} + + +void MagneticSensorI2C::init(){ + + //I2C communication begin + Wire.begin(); + + // velocity calculation init + angle_prev = 0; + velocity_calc_timestamp = _micros(); + + // full rotations tracking number + full_rotation_offset = 0; + angle_data_prev = getRawCount(); + zero_offset = 0; +} + +// Shaft angle calculation +// angle is in radians [rad] +float MagneticSensorI2C::getAngle(){ + // raw data from the sensor + float angle_data = getRawCount(); + + // tracking the number of rotations + // in order to expand angle range form [0,2PI] + // to basically infinity + float d_angle = angle_data - angle_data_prev; + // if overflow happened track it as full rotation + if(abs(d_angle) > (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; + // save the current angle value for the next steps + // in order to know if overflow happened + angle_data_prev = angle_data; + + // zero offset adding + angle_data -= (int)zero_offset; + // return the full angle + // (number of full rotations)*2PI + current sensor angle + return full_rotation_offset + ( angle_data / (float)cpr) * _2PI; +} + +// Shaft velocity calculation +float MagneticSensorI2C::getVelocity(){ + // calculate sample time + float Ts = (_micros() - velocity_calc_timestamp)*1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // current angle + float angle_c = getAngle(); + // velocity calculation + float vel = (angle_c - angle_prev)/Ts; + + // save variables for future pass + angle_prev = angle_c; + velocity_calc_timestamp = _micros(); + return vel; +} + +// set current angle as zero angle +// return the angle [rad] difference +float MagneticSensorI2C::initRelativeZero(){ + float angle_offset = -getAngle(); + zero_offset = getRawCount(); + + // angle tracking variables + full_rotation_offset = 0; + return angle_offset; +} +// set absolute zero angle as zero angle +// return the angle [rad] difference +float MagneticSensorI2C::initAbsoluteZero(){ + float rotation = -(int)zero_offset; + // init absolute zero + zero_offset = 0; + + // angle tracking variables + full_rotation_offset = 0; + // return offset in radians + return rotation / (float)cpr * _2PI; +} +// returns 0 if it has no absolute 0 measurement +// 0 - incremental encoder without index +// 1 - encoder with index & magnetic sensors +int MagneticSensorI2C::hasAbsoluteZero(){ + return 1; +} +// returns 0 if it does need search for absolute zero +// 0 - magnetic sensor +// 1 - ecoder with index +int MagneticSensorI2C::needsAbsoluteZeroSearch(){ + return 0; +} + + +// function reading the raw counter of the magnetic sensor +int MagneticSensorI2C::getRawCount(){ + return (int)MagneticSensorI2C::read(angle_register_msb); +} + +// I2C functions +/* +* Read a register from the sensor +* Takes the address of the register as a uint8_t +* Returns the value of the register +*/ +int MagneticSensorI2C::read(uint8_t angle_reg_msb) { + // read the angle register first MSB then LSB + byte readArray[2]; + uint16_t readValue = 0; + // notify the device that is aboout to be read + Wire.beginTransmission(chip_address); + Wire.write(angle_reg_msb); + Wire.endTransmission(false); + + // read the data msb and lsb + Wire.requestFrom(chip_address, (uint8_t)2); + for (byte i=0; i < 2; i++) { + readArray[i] = Wire.read(); + } + + // depending on the sensor architecture there are different combinations of + // LSB and MSB register used bits + // AS5600 uses 0..7 LSB and 8..11 MSB + // AS5048 uses 0..5 LSB and 6..13 MSB + readValue = ( readArray[1] & lsb_mask ); + readValue += ( ( readArray[0] & msb_mask ) << lsb_used ); + return readValue; +} diff --git a/arduino_foc_minimal_magnetic/MagneticSensorI2C.h b/arduino_foc_minimal_magnetic/MagneticSensorI2C.h new file mode 100644 index 00000000..c5dc3489 --- /dev/null +++ b/arduino_foc_minimal_magnetic/MagneticSensorI2C.h @@ -0,0 +1,78 @@ +#ifndef MAGNETICSENSORI2C_LIB_H +#define MAGNETICSENSORI2C_LIB_H + +#include "Arduino.h" +#include +#include "FOCutils.h" +#include "Sensor.h" + + +class MagneticSensorI2C: public Sensor{ + public: + /** + * MagneticSensorI2C class constructor + * @param chip_address I2C chip address + * @param bits number of bits of the sensor resolution + * @param angle_register_msb angle read register msb + * @param _bits_used_msb number of used bits in msb + */ + MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _msb_bits_used); + + + /** sensor initialise pins */ + void init(); + + // implementation of abstract functions of the Sensor class + /** get current angle (rad) */ + float getAngle(); + /** get current angular velocity (rad/s) **/ + float getVelocity(); + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + float initRelativeZero(); + /** + * set absolute zero angle as zero angle + * return the angle [rad] difference + */ + float initAbsoluteZero(); + /** returns 1 because it is the absolute sensor */ + int hasAbsoluteZero(); + /** returns 0 maning it doesn't need search for absolute zero */ + int needsAbsoluteZeroSearch(); + + + private: + float cpr; //!< Maximum range of the magnetic sensor + uint16_t lsb_used; //!< Number of bits used in LSB register + uint8_t lsb_mask; + uint8_t msb_mask; + + // I2C variables + uint8_t angle_register_msb; //!< I2C angle register to read + uint8_t chip_address; //!< I2C chip select pins + + // I2C functions + /** Read one I2C register value */ + int read(uint8_t angle_register_msb); + + word zero_offset; //!< user defined zero offset + /** + * Function getting current angle register value + * it uses angle_register variable + */ + int getRawCount(); + + // total angle tracking variables + float full_rotation_offset; //! (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; + // save the current angle value for the next steps + // in order to know if overflow happened + angle_data_prev = angle_data; + + // zero offset adding + angle_data -= (int)zero_offset; + // return the full angle + // (number of full rotations)*2PI + current sensor angle + return full_rotation_offset + ( angle_data / (float)cpr) * _2PI; +} + +// Shaft velocity calculation +float MagneticSensorSPI::getVelocity(){ + // calculate sample time + float Ts = (_micros() - velocity_calc_timestamp)*1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // current angle + float angle_c = getAngle(); + // velocity calculation + float vel = (angle_c - angle_prev)/Ts; + + // save variables for future pass + angle_prev = angle_c; + velocity_calc_timestamp = _micros(); + return vel; +} + +// set current angle as zero angle +// return the angle [rad] difference +float MagneticSensorSPI::initRelativeZero(){ + float angle_offset = -getAngle(); + zero_offset = getRawCount(); + + // angle tracking variables + full_rotation_offset = 0; + return angle_offset; +} +// set absolute zero angle as zero angle +// return the angle [rad] difference +float MagneticSensorSPI::initAbsoluteZero(){ + float rotation = -(int)zero_offset; + // init absolute zero + zero_offset = 0; + + // angle tracking variables + full_rotation_offset = 0; + // return offset in radians + return rotation / (float)cpr * _2PI; +} +// returns 0 if it has no absolute 0 measurement +// 0 - incremental encoder without index +// 1 - encoder with index & magnetic sensors +int MagneticSensorSPI::hasAbsoluteZero(){ + return 1; +} +// returns 0 if it does need search for absolute zero +// 0 - magnetic sensor +// 1 - ecoder with index +int MagneticSensorSPI::needsAbsoluteZeroSearch(){ + return 0; +} + + +// function reading the raw counter of the magnetic sensor +int MagneticSensorSPI::getRawCount(){ + return (int)MagneticSensorSPI::read(angle_register); +} + +// SPI functions +/** + * Utility function used to calculate even parity of word + */ +byte MagneticSensorSPI::spiCalcEvenParity(word value){ + byte cnt = 0; + byte i; + + for (i = 0; i < 16; i++) + { + if (value & 0x1) cnt++; + value >>= 1; + } + return cnt & 0x1; +} + + /* + * Read a register from the sensor + * Takes the address of the register as a 16 bit word + * Returns the value of the register + */ +word MagneticSensorSPI::read(word angle_register){ + word command = 0b0100000000000000; // PAR=0 R/W=R + command = command | angle_register; + + //Add a parity bit on the the MSB + command |= ((word)spiCalcEvenParity(command)<<15); + + //Split the command into two bytes + byte right_byte = command & 0xFF; + byte left_byte = ( command >> 8 ) & 0xFF; + + +#if !defined(_STM32_DEF_) // if not stm chips + //SPI - begin transaction + SPI.beginTransaction(settings); +#endif + //SPI - begin transaction + //SPI.beginTransaction(settings); + + //Send the command + digitalWrite(chip_select_pin, LOW); + digitalWrite(chip_select_pin, LOW); + SPI.transfer(left_byte); + SPI.transfer(right_byte); + digitalWrite(chip_select_pin,HIGH); + digitalWrite(chip_select_pin,HIGH); + + delayMicroseconds(10); + + //Now read the response + digitalWrite(chip_select_pin, LOW); + digitalWrite(chip_select_pin, LOW); + left_byte = SPI.transfer(0x00); + right_byte = SPI.transfer(0x00); + digitalWrite(chip_select_pin, HIGH); + digitalWrite(chip_select_pin,HIGH); + +#if !defined(_STM32_DEF_) // if not stm chips + //SPI - end transaction + SPI.endTransaction(); +#endif + + // Return the data, stripping the parity and error bits + return (( ( left_byte & 0xFF ) << 8 ) | ( right_byte & 0xFF )) & ~0xC000; +} + +/** + * Closes the SPI connection + * SPI has an internal SPI-device counter, for each init()-call the close() function must be called exactly 1 time + */ +void MagneticSensorSPI::close(){ + SPI.end(); +} diff --git a/arduino_foc_minimal_magnetic/MagneticSensorSPI.h b/arduino_foc_minimal_magnetic/MagneticSensorSPI.h new file mode 100644 index 00000000..da70c0c4 --- /dev/null +++ b/arduino_foc_minimal_magnetic/MagneticSensorSPI.h @@ -0,0 +1,79 @@ +#ifndef MAGNETICSENSORSPI_LIB_H +#define MAGNETICSENSORSPI_LIB_H + +#include "Arduino.h" +#include +#include "FOCutils.h" +#include "Sensor.h" + +#define DEF_ANGLE_REGISTAR 0x3FFF + +class MagneticSensorSPI: public Sensor{ + public: + /** + * MagneticSensorSPI class constructor + * @param cs SPI chip select pin + * @param bit_resolution sensor resolution bit number + * @param angle_register (optional) angle read register - default 0x3FFF + */ + MagneticSensorSPI(int cs, float bit_resolution, int angle_register = 0); + + + /** sensor initialise pins */ + void init(); + + // implementation of abstract functions of the Sensor class + /** get current angle (rad) */ + float getAngle(); + /** get current angular velocity (rad/s) **/ + float getVelocity(); + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + float initRelativeZero(); + /** + * set absolute zero angle as zero angle + * return the angle [rad] difference + */ + float initAbsoluteZero(); + /** returns 1 because it is the absolute sensor */ + int hasAbsoluteZero(); + /** returns 0 maning it doesn't need search for absolute zero */ + int needsAbsoluteZeroSearch(); + + + private: + float cpr; //!< Maximum range of the magnetic sensor + // spi variables + int angle_register; //!< SPI angle register to read + int chip_select_pin; //!< SPI chip select pin + SPISettings settings; //!< SPI settings variable + // spi functions + /** Stop SPI communication */ + void close(); + /** Read one SPI register value */ + word read(word angle_register); + /** Calculate parity value */ + byte spiCalcEvenParity(word value); + + + word zero_offset; //!< user defined zero offset + /** + * Function getting current angle register value + * it uses angle_register variable + */ + int getRawCount(); + + // total angle tracking variables + float full_rotation_offset; //!println("MONITOR: Set high frequency PWM."); // Increase PWM frequency to 32 kHz // make silent - setPwmFrequency(pwmA); - setPwmFrequency(pwmB); - setPwmFrequency(pwmC); + _setPwmFrequency(pwmA); + _setPwmFrequency(pwmB); + _setPwmFrequency(pwmC); // sanity check for the voltage limit configuration if(PI_velocity.voltage_limit > voltage_power_supply) PI_velocity.voltage_limit = voltage_power_supply; diff --git a/src/BLDCMotor.h b/src/BLDCMotor.h new file mode 100644 index 00000000..df95445d --- /dev/null +++ b/src/BLDCMotor.h @@ -0,0 +1,277 @@ +/** + * @file BLDCMotor.h + * + */ + +#ifndef BLDCMotor_h +#define BLDCMotor_h + +#include "Arduino.h" +#include "FOCutils.h" +#include "Sensor.h" +#include "defaults.h" + + +#define NOT_SET -12345.0 + +/** + * Motiron control type + */ +enum ControlType{ + voltage,//!< Torque control using voltage + velocity,//!< Velocity motion control + angle//!< Position/angle motion control +}; + +/** + * FOC modulation type + */ +enum FOCModulationType{ + SinePWM, //!< Sinusoidal PWM modulation + SpaceVectorPWM //!< Space vector modulation method +}; + +/** + * PI controller structure + */ +struct PI_s{ + float P; //!< Proportional gain + float I; //!< Integral gain + float voltage_limit; //!< Voltage limit of the controller output + float voltage_ramp; //!< Maximum speed of change of the output value + long timestamp; //!< Last execution timestamp + float voltage_prev; //!< last controller output value + float tracking_error_prev; //!< last tracking error value +}; + +// P controller structure +struct P_s{ + float P; //!< Proportional gain + long timestamp; //!< Last execution timestamp + float velocity_limit; //!< Velocity limit of the controller output +}; + +/** + * Low pass filter structure + */ +struct LPF_s{ + float Tf; //!< Low pass filter time constant + long timestamp; //!< Last execution timestamp + float prev; //!< filtered value in previous execution step +}; + + + + +/** + BLDC motor class +*/ +class BLDCMotor +{ + public: + /** + BLDCMotor class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param pp pole pair number + @param cpr counts per rotation number (cpm=ppm*4) + @param en enable pin (optional input) + */ + BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + + /** Motor hardware init function */ + void init(); + /** Motor disable function */ + void disable(); + /** Motor enable function */ + void enable(); + + /** + * Function linking a motor and a sensor + * + * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity + */ + void linkSensor(Sensor* sensor); + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + */ + int initFOC(); + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + void loopFOC(); + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET); + + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + + + + // State calculation methods + /** Shaft angle calculation in radians [rad] */ + float shaftAngle(); + /** + * Shaft angle calculation function in radian per second [rad/s] + * It implements low pass filtering + */ + float shaftVelocity(); + + // state variables + float target; //!< current target value - depends of the controller + float shaft_angle;//!< current motor angle + float shaft_velocity;//!< current motor velocity + float shaft_velocity_sp;//!< current target velocity + float shaft_angle_sp;//!< current target angle + float voltage_q;//!< current voltage u_q set + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + + // motor configuration parameters + float voltage_power_supply;//!< Power supply voltage + float voltage_sensor_align;//!< sensor and motor align voltage parameter + float velocity_index_search;//!< target velocity for index search + int pole_pairs;//!< Motor pole pairs number + + // configuration structures + ControlType controller; //!< parameter determining the control loop to be used + FOCModulationType foc_modulation;//!< parameter derterniming modulation algorithm + PI_s PI_velocity;//!< parameter determining the velocity PI configuration + P_s P_angle; //!< parameter determining the position P configuration + LPF_s LPF_velocity;//!< parameter determining the velocity Lpw pass filter configuration + + /** + * Sensor link: + * - Encoder + * - MagneticSensor + */ + Sensor* sensor; + + float zero_electric_angle;//! 0.5) Ts = 1e-3; + + // time from last impulse + float Th = (timestamp_us - pulse_timestamp) * 1e-6; + long dN = pulse_counter - prev_pulse_counter; + + // Pulse per second calculation (Eq.3.) + // dN - impulses received + // Ts - sampling time - time in between function calls + // Th - time from last impulse + // Th_1 - time form last impulse of the previous call + // only increment if some impulses received + float dt = Ts + prev_Th - Th; + pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second; + + // if more than 0.05 passed in between impulses + if ( Th > 0.1) pulse_per_second = 0; + + // velocity calculation + float velocity = pulse_per_second / ((float)cpr) * (_2PI); + + // save variables for next pass + prev_timestamp_us = timestamp_us; + // save velocity calculation variables + prev_Th = Th; + prev_pulse_counter = pulse_counter; + return (velocity); +} + +// getter for index pin +// return -1 if no index +int Encoder::needsAbsoluteZeroSearch(){ + return index_pulse_counter == 0; +} +// getter for index pin +int Encoder::hasAbsoluteZero(){ + return hasIndex(); +} +// initialize counter to zero +float Encoder::initRelativeZero(){ + long angle_offset = -pulse_counter; + pulse_counter = 0; + pulse_timestamp = _micros(); + return _2PI * (angle_offset) / ((float)cpr); +} +// initialize index to zero +float Encoder::initAbsoluteZero(){ + pulse_counter -= index_pulse_counter; + prev_pulse_counter = pulse_counter; + return (index_pulse_counter) / ((float)cpr) * (_2PI); +} +// private function used to determine if encoder has index +int Encoder::hasIndex(){ + return index_pin != 0; +} + + +// encoder initialisation of the hardware pins +// and calculation variables +void Encoder::init(){ + + // Encoder - check if pullup needed for your encoder + if(pullup == Pullup::INTERN){ + pinMode(pinA, INPUT_PULLUP); + pinMode(pinB, INPUT_PULLUP); + if(hasIndex()) pinMode(index_pin,INPUT_PULLUP); + }else{ + pinMode(pinA, INPUT); + pinMode(pinB, INPUT); + if(hasIndex()) pinMode(index_pin,INPUT); + } + + // counter setup + pulse_counter = 0; + pulse_timestamp = _micros(); + // velocity calculation variables + prev_Th = 0; + pulse_per_second = 0; + prev_pulse_counter = 0; + prev_timestamp_us = _micros(); + + // initial cpr = PPR + // change it if the mode is quadrature + if(quadrature == Quadrature::ON) cpr = 4*cpr; + +} + +// function enabling hardware interrupts of the for the callback provided +// if callback is not provided then the interrupt is not enabled +void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){ + // attach interrupt if functions provided + switch(quadrature){ + case Quadrature::ON: + // A callback and B callback + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); + break; + case Quadrature::OFF: + // A callback and B callback + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); + break; + } + + // if index used initialize the index interrupt + if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE); +} + diff --git a/src/Encoder.h b/src/Encoder.h new file mode 100644 index 00000000..fc65a7a9 --- /dev/null +++ b/src/Encoder.h @@ -0,0 +1,112 @@ +#ifndef ENCODER_LIB_H +#define ENCODER_LIB_H + +#include "Arduino.h" +#include "FOCutils.h" +#include "Sensor.h" + + +/** + * Pullup configuration structure + */ +enum Pullup{ + INTERN, //!< Use internal pullups + EXTERN //!< Use external pullups +}; + +/** + * Quadrature mode configuration structure + */ +enum Quadrature{ + ON, //!< Enable quadrature mode CPR = 4xPPR + OFF //!< Disable quadrature mode / CPR = PPR +}; + +class Encoder: public Sensor{ + public: + /** + Encoder class constructor + @param encA encoder B pin + @param encB encoder B pin + @param ppr impulses per rotation (cpr=ppr*4) + @param index index pin number (optional input) + */ + Encoder(int encA, int encB , float ppr, int index = 0); + + /** encoder initialise pins */ + void init(); + /** + * function enabling hardware interrupts for the encoder channels with provided callback functions + * if callback is not provided then the interrupt is not enabled + * + * @param doA pointer to the A channel interrupt handler function + * @param doB pointer to the B channel interrupt handler function + * @param doIndex pointer to the Index channel interrupt handler function + * + */ + void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr); + + // Encoder interrupt callback functions + /** A channel callback function */ + void handleA(); + /** B channel callback function */ + void handleB(); + /** Index channel callback function */ + void handleIndex(); + + + // pins A and B + int pinA; //!< encoder hardware pin A + int pinB; //!< encoder hardware pin B + int index_pin; //!< index pin + + // Encoder configuration + Pullup pullup; //!< Configuration parameter internal or external pullups + Quadrature quadrature;//!< Configuration parameter enable or disable quadrature mode + float cpr;//!< encoder cpr number + + // Abstract functions of the Sensor class implementation + /** get current angle (rad) */ + float getAngle(); + /** get current angular velocity (rad/s) */ + float getVelocity(); + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + float initRelativeZero(); + /** + * set index angle as zero angle + * return the angle [rad] difference + */ + float initAbsoluteZero(); + /** + * returns 0 if it has no index + * 0 - encoder without index + * 1 - encoder with index + */ + int hasAbsoluteZero(); + /** + * returns 0 if it does need search for absolute zero + * 0 - encoder without index + * 1 - ecoder with index + */ + int needsAbsoluteZeroSearch(); + + private: + int hasIndex(); //!< function returning 1 if encoder has index pin and 0 if not. + + volatile long pulse_counter;//!< current pulse counter + volatile long pulse_timestamp;//!< last impulse timestamp in us + volatile int A_active; //!< current active states of A channel + volatile int B_active; //!< current active states of B channel + volatile int I_active; //!< current active states of Index channel + volatile long index_pulse_counter; //!< impulse counter number upon first index interrupt + + // velocity calculation variables + float prev_Th, pulse_per_second; + volatile long prev_pulse_counter, prev_timestamp_us; +}; + + +#endif diff --git a/src/FOCutils.cpp b/src/FOCutils.cpp new file mode 100644 index 00000000..04c6cfbf --- /dev/null +++ b/src/FOCutils.cpp @@ -0,0 +1,101 @@ +#include "FOCutils.h" + + +void _setPwmFrequency(int pin) { +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other atmega328p chips +// High PWM frequency +// https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pin == 5 || pin == 6 || pin == 9 || pin == 10) { + if (pin == 5 || pin == 6) { + // configure the pwm phase-corrected mode + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); + // set prescaler to 1 + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); + } else { + // set prescaler to 1 + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); + } + } + else if (pin == 3 || pin == 11) { + // set prescaler to 1 + TCCR2B = ((TCCR2B & 0b11111000) | 0x01); + } +#elif defined(_STM32_DEF_) // if stm chips + analogWrite(pin,0); + analogWriteFrequency(50000); // la valeur par défaut est 20000 Hz +#endif +} + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // return the value based on the prescaler + long t = _micros(); + while((_micros() - t)/1000 < ms){}; +#else + // regular micros + return delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} + + +// lookup table for sine calculation in between 0 and 90 degrees +//float sine_array[200] = {0.0000,0.0079,0.0158,0.0237,0.0316,0.0395,0.0473,0.0552,0.0631,0.0710,0.0789,0.0867,0.0946,0.1024,0.1103,0.1181,0.1260,0.1338,0.1416,0.1494,0.1572,0.1650,0.1728,0.1806,0.1883,0.1961,0.2038,0.2115,0.2192,0.2269,0.2346,0.2423,0.2499,0.2575,0.2652,0.2728,0.2804,0.2879,0.2955,0.3030,0.3105,0.3180,0.3255,0.3329,0.3404,0.3478,0.3552,0.3625,0.3699,0.3772,0.3845,0.3918,0.3990,0.4063,0.4135,0.4206,0.4278,0.4349,0.4420,0.4491,0.4561,0.4631,0.4701,0.4770,0.4840,0.4909,0.4977,0.5046,0.5113,0.5181,0.5249,0.5316,0.5382,0.5449,0.5515,0.5580,0.5646,0.5711,0.5775,0.5839,0.5903,0.5967,0.6030,0.6093,0.6155,0.6217,0.6279,0.6340,0.6401,0.6461,0.6521,0.6581,0.6640,0.6699,0.6758,0.6815,0.6873,0.6930,0.6987,0.7043,0.7099,0.7154,0.7209,0.7264,0.7318,0.7371,0.7424,0.7477,0.7529,0.7581,0.7632,0.7683,0.7733,0.7783,0.7832,0.7881,0.7930,0.7977,0.8025,0.8072,0.8118,0.8164,0.8209,0.8254,0.8298,0.8342,0.8385,0.8428,0.8470,0.8512,0.8553,0.8594,0.8634,0.8673,0.8712,0.8751,0.8789,0.8826,0.8863,0.8899,0.8935,0.8970,0.9005,0.9039,0.9072,0.9105,0.9138,0.9169,0.9201,0.9231,0.9261,0.9291,0.9320,0.9348,0.9376,0.9403,0.9429,0.9455,0.9481,0.9506,0.9530,0.9554,0.9577,0.9599,0.9621,0.9642,0.9663,0.9683,0.9702,0.9721,0.9739,0.9757,0.9774,0.9790,0.9806,0.9821,0.9836,0.9850,0.9863,0.9876,0.9888,0.9899,0.9910,0.9920,0.9930,0.9939,0.9947,0.9955,0.9962,0.9969,0.9975,0.9980,0.9985,0.9989,0.9992,0.9995,0.9997,0.9999,1.0000,1.0000}; + +// int array instead of float array +// 2x storage save (int 2Byte float 4 Byte ) +// sin*10000 +int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,1103,1181,1260,1338,1416,1494,1572,1650,1728,1806,1883,1961,2038,2115,2192,2269,2346,2423,2499,2575,2652,2728,2804,2879,2955,3030,3105,3180,3255,3329,3404,3478,3552,3625,3699,3772,3845,3918,3990,4063,4135,4206,4278,4349,4420,4491,4561,4631,4701,4770,4840,4909,4977,5046,5113,5181,5249,5316,5382,5449,5515,5580,5646,5711,5775,5839,5903,5967,6030,6093,6155,6217,6279,6340,6401,6461,6521,6581,6640,6699,6758,6815,6873,6930,6987,7043,7099,7154,7209,7264,7318,7371,7424,7477,7529,7581,7632,7683,7733,7783,7832,7881,7930,7977,8025,8072,8118,8164,8209,8254,8298,8342,8385,8428,8470,8512,8553,8594,8634,8673,8712,8751,8789,8826,8863,8899,8935,8970,9005,9039,9072,9105,9138,9169,9201,9231,9261,9291,9320,9348,9376,9403,9429,9455,9481,9506,9530,9554,9577,9599,9621,9642,9663,9683,9702,9721,9739,9757,9774,9790,9806,9821,9836,9850,9863,9876,9888,9899,9910,9920,9930,9939,9947,9955,9962,9969,9975,9980,9985,9989,9992,9995,9997,9999,10000,10000}; + +// function approximating the sine calculation by using fixed size array +// ~40us (float array) +// ~50us (int array) +// precision +-0.005 +// it has to receive an angle in between 0 and 2PI +float _sin(float a){ + if(a < _PI_2){ + //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; + //return sine_array[(int)(126.6873* a)]; // float array optimised + return 0.0001*sine_array[_round(126.6873* a)]; // int array optimised + }else if(a < _PI){ + // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; + //return sine_array[398 - (int)(126.6873*a)]; // float array optimised + return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimised + }else if(a < _3PI_2){ + // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; + //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimised + return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimised + } else { + // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; + //return -sine_array[796 - (int)(126.6873*a)]; // float array optimised + return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimised + } +} + +// function approfimating cosine calculaiton by using fixed size array +// ~55us (float array) +// ~56us (int array) +// precision +-0.005 +// it has to receive an angle in between 0 and 2PI +float _cos(float a){ + float a_sin = a + _PI_2; + a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} diff --git a/src/FOCutils.h b/src/FOCutils.h new file mode 100644 index 00000000..b60978b3 --- /dev/null +++ b/src/FOCutils.h @@ -0,0 +1,61 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + +// sign function +#define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + +// utility defines +#define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI 3.14159265359 +#define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + +/** + * High PWM frequency setting function + * - hardware specific + * + * @param pin pin number to configure + */ +void _setPwmFrequency(int pin); + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + * + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _sin(float a); +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _cos(float a); + +#endif \ No newline at end of file diff --git a/arduino_foc_minimal_magnetic/MagneticSensor.cpp b/src/MagneticSensor.cpp similarity index 100% rename from arduino_foc_minimal_magnetic/MagneticSensor.cpp rename to src/MagneticSensor.cpp diff --git a/arduino_foc_minimal_magnetic/MagneticSensor.h b/src/MagneticSensor.h similarity index 100% rename from arduino_foc_minimal_magnetic/MagneticSensor.h rename to src/MagneticSensor.h diff --git a/src/MagneticSensorI2C.cpp b/src/MagneticSensorI2C.cpp new file mode 100644 index 00000000..52778025 --- /dev/null +++ b/src/MagneticSensorI2C.cpp @@ -0,0 +1,153 @@ +#include "MagneticSensorI2C.h" + +// MagneticSensorI2C(uint8_t _chip_address, float _cpr, uint8_t _angle_register_msb) +// @param _chip_address I2C chip address +// @param _bit_resolution bit resolution of the sensor +// @param _angle_register_msb angle read register +// @param _bits_used_msb number of used bits in msb +MagneticSensorI2C::MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _bits_used_msb){ + // chip I2C address + chip_address = _chip_address; + // angle read register of the magnetic sensor + angle_register_msb = _angle_register_msb; + // register maximum value (counts per revolution) + cpr = pow(2,_bit_resolution); + + // depending on the sensor architecture there are different combinations of + // LSB and MSB register used bits + // AS5600 uses 0..7 LSB and 8..11 MSB + // AS5048 uses 0..5 LSB and 6..13 MSB + // used bits in LSB + lsb_used = _bit_resolution - _bits_used_msb; + // extraction masks + lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); + msb_mask = (uint8_t)( (2 << _bits_used_msb) - 1 ); +} + + +void MagneticSensorI2C::init(){ + + //I2C communication begin + Wire.begin(); + + // velocity calculation init + angle_prev = 0; + velocity_calc_timestamp = _micros(); + + // full rotations tracking number + full_rotation_offset = 0; + angle_data_prev = getRawCount(); + zero_offset = 0; +} + +// Shaft angle calculation +// angle is in radians [rad] +float MagneticSensorI2C::getAngle(){ + // raw data from the sensor + float angle_data = getRawCount(); + + // tracking the number of rotations + // in order to expand angle range form [0,2PI] + // to basically infinity + float d_angle = angle_data - angle_data_prev; + // if overflow happened track it as full rotation + if(abs(d_angle) > (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; + // save the current angle value for the next steps + // in order to know if overflow happened + angle_data_prev = angle_data; + + // zero offset adding + angle_data -= (int)zero_offset; + // return the full angle + // (number of full rotations)*2PI + current sensor angle + return full_rotation_offset + ( angle_data / (float)cpr) * _2PI; +} + +// Shaft velocity calculation +float MagneticSensorI2C::getVelocity(){ + // calculate sample time + float Ts = (_micros() - velocity_calc_timestamp)*1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // current angle + float angle_c = getAngle(); + // velocity calculation + float vel = (angle_c - angle_prev)/Ts; + + // save variables for future pass + angle_prev = angle_c; + velocity_calc_timestamp = _micros(); + return vel; +} + +// set current angle as zero angle +// return the angle [rad] difference +float MagneticSensorI2C::initRelativeZero(){ + float angle_offset = -getAngle(); + zero_offset = getRawCount(); + + // angle tracking variables + full_rotation_offset = 0; + return angle_offset; +} +// set absolute zero angle as zero angle +// return the angle [rad] difference +float MagneticSensorI2C::initAbsoluteZero(){ + float rotation = -(int)zero_offset; + // init absolute zero + zero_offset = 0; + + // angle tracking variables + full_rotation_offset = 0; + // return offset in radians + return rotation / (float)cpr * _2PI; +} +// returns 0 if it has no absolute 0 measurement +// 0 - incremental encoder without index +// 1 - encoder with index & magnetic sensors +int MagneticSensorI2C::hasAbsoluteZero(){ + return 1; +} +// returns 0 if it does need search for absolute zero +// 0 - magnetic sensor +// 1 - ecoder with index +int MagneticSensorI2C::needsAbsoluteZeroSearch(){ + return 0; +} + + +// function reading the raw counter of the magnetic sensor +int MagneticSensorI2C::getRawCount(){ + return (int)MagneticSensorI2C::read(angle_register_msb); +} + +// I2C functions +/* +* Read a register from the sensor +* Takes the address of the register as a uint8_t +* Returns the value of the register +*/ +int MagneticSensorI2C::read(uint8_t angle_reg_msb) { + // read the angle register first MSB then LSB + byte readArray[2]; + uint16_t readValue = 0; + // notify the device that is aboout to be read + Wire.beginTransmission(chip_address); + Wire.write(angle_reg_msb); + Wire.endTransmission(false); + + // read the data msb and lsb + Wire.requestFrom(chip_address, (uint8_t)2); + for (byte i=0; i < 2; i++) { + readArray[i] = Wire.read(); + } + + // depending on the sensor architecture there are different combinations of + // LSB and MSB register used bits + // AS5600 uses 0..7 LSB and 8..11 MSB + // AS5048 uses 0..5 LSB and 6..13 MSB + readValue = ( readArray[1] & lsb_mask ); + readValue += ( ( readArray[0] & msb_mask ) << lsb_used ); + return readValue; +} diff --git a/src/MagneticSensorI2C.h b/src/MagneticSensorI2C.h new file mode 100644 index 00000000..c5dc3489 --- /dev/null +++ b/src/MagneticSensorI2C.h @@ -0,0 +1,78 @@ +#ifndef MAGNETICSENSORI2C_LIB_H +#define MAGNETICSENSORI2C_LIB_H + +#include "Arduino.h" +#include +#include "FOCutils.h" +#include "Sensor.h" + + +class MagneticSensorI2C: public Sensor{ + public: + /** + * MagneticSensorI2C class constructor + * @param chip_address I2C chip address + * @param bits number of bits of the sensor resolution + * @param angle_register_msb angle read register msb + * @param _bits_used_msb number of used bits in msb + */ + MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _msb_bits_used); + + + /** sensor initialise pins */ + void init(); + + // implementation of abstract functions of the Sensor class + /** get current angle (rad) */ + float getAngle(); + /** get current angular velocity (rad/s) **/ + float getVelocity(); + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + float initRelativeZero(); + /** + * set absolute zero angle as zero angle + * return the angle [rad] difference + */ + float initAbsoluteZero(); + /** returns 1 because it is the absolute sensor */ + int hasAbsoluteZero(); + /** returns 0 maning it doesn't need search for absolute zero */ + int needsAbsoluteZeroSearch(); + + + private: + float cpr; //!< Maximum range of the magnetic sensor + uint16_t lsb_used; //!< Number of bits used in LSB register + uint8_t lsb_mask; + uint8_t msb_mask; + + // I2C variables + uint8_t angle_register_msb; //!< I2C angle register to read + uint8_t chip_address; //!< I2C chip select pins + + // I2C functions + /** Read one I2C register value */ + int read(uint8_t angle_register_msb); + + word zero_offset; //!< user defined zero offset + /** + * Function getting current angle register value + * it uses angle_register variable + */ + int getRawCount(); + + // total angle tracking variables + float full_rotation_offset; //! (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; + // save the current angle value for the next steps + // in order to know if overflow happened + angle_data_prev = angle_data; + + // zero offset adding + angle_data -= (int)zero_offset; + // return the full angle + // (number of full rotations)*2PI + current sensor angle + return full_rotation_offset + ( angle_data / (float)cpr) * _2PI; +} + +// Shaft velocity calculation +float MagneticSensorSPI::getVelocity(){ + // calculate sample time + float Ts = (_micros() - velocity_calc_timestamp)*1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // current angle + float angle_c = getAngle(); + // velocity calculation + float vel = (angle_c - angle_prev)/Ts; + + // save variables for future pass + angle_prev = angle_c; + velocity_calc_timestamp = _micros(); + return vel; +} + +// set current angle as zero angle +// return the angle [rad] difference +float MagneticSensorSPI::initRelativeZero(){ + float angle_offset = -getAngle(); + zero_offset = getRawCount(); + + // angle tracking variables + full_rotation_offset = 0; + return angle_offset; +} +// set absolute zero angle as zero angle +// return the angle [rad] difference +float MagneticSensorSPI::initAbsoluteZero(){ + float rotation = -(int)zero_offset; + // init absolute zero + zero_offset = 0; + + // angle tracking variables + full_rotation_offset = 0; + // return offset in radians + return rotation / (float)cpr * _2PI; +} +// returns 0 if it has no absolute 0 measurement +// 0 - incremental encoder without index +// 1 - encoder with index & magnetic sensors +int MagneticSensorSPI::hasAbsoluteZero(){ + return 1; +} +// returns 0 if it does need search for absolute zero +// 0 - magnetic sensor +// 1 - ecoder with index +int MagneticSensorSPI::needsAbsoluteZeroSearch(){ + return 0; +} + + +// function reading the raw counter of the magnetic sensor +int MagneticSensorSPI::getRawCount(){ + return (int)MagneticSensorSPI::read(angle_register); +} + +// SPI functions +/** + * Utility function used to calculate even parity of word + */ +byte MagneticSensorSPI::spiCalcEvenParity(word value){ + byte cnt = 0; + byte i; + + for (i = 0; i < 16; i++) + { + if (value & 0x1) cnt++; + value >>= 1; + } + return cnt & 0x1; +} + + /* + * Read a register from the sensor + * Takes the address of the register as a 16 bit word + * Returns the value of the register + */ +word MagneticSensorSPI::read(word angle_register){ + word command = 0b0100000000000000; // PAR=0 R/W=R + command = command | angle_register; + + //Add a parity bit on the the MSB + command |= ((word)spiCalcEvenParity(command)<<15); + + //Split the command into two bytes + byte right_byte = command & 0xFF; + byte left_byte = ( command >> 8 ) & 0xFF; + + +#if !defined(_STM32_DEF_) // if not stm chips + //SPI - begin transaction + SPI.beginTransaction(settings); +#endif + //SPI - begin transaction + //SPI.beginTransaction(settings); + + //Send the command + digitalWrite(chip_select_pin, LOW); + digitalWrite(chip_select_pin, LOW); + SPI.transfer(left_byte); + SPI.transfer(right_byte); + digitalWrite(chip_select_pin,HIGH); + digitalWrite(chip_select_pin,HIGH); + + delayMicroseconds(10); + + //Now read the response + digitalWrite(chip_select_pin, LOW); + digitalWrite(chip_select_pin, LOW); + left_byte = SPI.transfer(0x00); + right_byte = SPI.transfer(0x00); + digitalWrite(chip_select_pin, HIGH); + digitalWrite(chip_select_pin,HIGH); + +#if !defined(_STM32_DEF_) // if not stm chips + //SPI - end transaction + SPI.endTransaction(); +#endif + + // Return the data, stripping the parity and error bits + return (( ( left_byte & 0xFF ) << 8 ) | ( right_byte & 0xFF )) & ~0xC000; +} + +/** + * Closes the SPI connection + * SPI has an internal SPI-device counter, for each init()-call the close() function must be called exactly 1 time + */ +void MagneticSensorSPI::close(){ + SPI.end(); +} diff --git a/src/MagneticSensorSPI.h b/src/MagneticSensorSPI.h new file mode 100644 index 00000000..da70c0c4 --- /dev/null +++ b/src/MagneticSensorSPI.h @@ -0,0 +1,79 @@ +#ifndef MAGNETICSENSORSPI_LIB_H +#define MAGNETICSENSORSPI_LIB_H + +#include "Arduino.h" +#include +#include "FOCutils.h" +#include "Sensor.h" + +#define DEF_ANGLE_REGISTAR 0x3FFF + +class MagneticSensorSPI: public Sensor{ + public: + /** + * MagneticSensorSPI class constructor + * @param cs SPI chip select pin + * @param bit_resolution sensor resolution bit number + * @param angle_register (optional) angle read register - default 0x3FFF + */ + MagneticSensorSPI(int cs, float bit_resolution, int angle_register = 0); + + + /** sensor initialise pins */ + void init(); + + // implementation of abstract functions of the Sensor class + /** get current angle (rad) */ + float getAngle(); + /** get current angular velocity (rad/s) **/ + float getVelocity(); + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + float initRelativeZero(); + /** + * set absolute zero angle as zero angle + * return the angle [rad] difference + */ + float initAbsoluteZero(); + /** returns 1 because it is the absolute sensor */ + int hasAbsoluteZero(); + /** returns 0 maning it doesn't need search for absolute zero */ + int needsAbsoluteZeroSearch(); + + + private: + float cpr; //!< Maximum range of the magnetic sensor + // spi variables + int angle_register; //!< SPI angle register to read + int chip_select_pin; //!< SPI chip select pin + SPISettings settings; //!< SPI settings variable + // spi functions + /** Stop SPI communication */ + void close(); + /** Read one SPI register value */ + word read(word angle_register); + /** Calculate parity value */ + byte spiCalcEvenParity(word value); + + + word zero_offset; //!< user defined zero offset + /** + * Function getting current angle register value + * it uses angle_register variable + */ + int getRawCount(); + + // total angle tracking variables + float full_rotation_offset; //! Even harder to find is a stable and simple FOC algorithm code capable of running on Arduino devices. Therefore this is an attempt to: + * - Demystify FOC algorithm and make a robust but simple Arduino library: Arduino SimpleFOC library + * - Develop a modular BLDC driver board: Arduino SimpleFOC shield. + * + * @section features Features + * - Arduino compatible: Arduino library code + * - Easy to setup and configure: + * - Easy hardware configuration + * - Easy tuning the control loops + * - Modular: + * - Supports as many sensors , BLDC motors and driver boards as possible + * - Supports as many application requirements as possible + * - Plug & play: Arduino SimpleFOC shield + * + * @section dependencies Supported Hardware + * + * This library supports any arduino device and it is especially optimized for Arduino UNO boards and + * other Atmega328 boards. But it supports Arrduinio MEGA boards and similar. + * + * From the version 1.3.0 it will support the STM32 boards such as Bluepill and Nucelo devices.
+ * The programming is done the same way as for the Arduino UNO but stm32 devices require STM32Duino package.
+ * You can download it directly from library manager. + * + * @section example_code Example code + * @code +#include + +// initialize the motor +BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); +// initialize the encoder +Encoder encoder = Encoder(2, 3, 2048); +// channel A and B callbacks +void doA(){encoder.handleA();} +void doB(){encoder.handleB();} + + +void setup() { + // initialize encoder hardware + encoder.init(); + // hardware interrupt enable + encoder.enableInterrupts(doA, doB); + + // set control loop type to be used + motor.controller = ControlType::velocity; + + // use monitoring with the BLDCMotor + Serial.begin(115200); + // monitoring port + motor.useMonitoring(Serial); + + // link the motor to the sensor + motor.linkSensor(&encoder); + + // initialize motor + motor.init(); + // align encoder and start FOC + motor.initFOC(); +} + +void loop() { + // FOC algorithm function + motor.loopFOC(); + + // velocity control loop function + // setting the target velocity or 2rad/s + motor.move(2); + + // monitoring function outputting motor variables to the serial terminal + motor.monitor(); +} + * @endcode + * + * @section license License + * + * MIT license, all text here must be included in any redistribution. + * + */ + +#ifndef SIMPLEFOC_H +#define SIMPLEFOC_H + +#include "FOCutils.h" +#include "Sensor.h" +#include "Encoder.h" +#include "MagneticSensorSPI.h" +#include "MagneticSensorI2C.h" +#include "BLDCMotor.h" + +#endif diff --git a/src/defaults.h b/src/defaults.h new file mode 100644 index 00000000..5bcb0118 --- /dev/null +++ b/src/defaults.h @@ -0,0 +1,17 @@ +// default configuration values +// change this file to optimal values for your application + +#define DEF_POWER_SUPPLY 12.0 //!< default power supply voltage +// velocity PI controller params +#define DEF_PI_VEL_P 0.5 //!< default PI controller P value +#define DEF_PI_VEL_I 10 //!< default PI controller I value +#define DEF_PI_VEL_U_RAMP 1000 //!< default PI controller voltage ramp value +// angle P params +#define DEF_P_ANGLE_P 20 //!< default P controller P value +#define DEF_P_ANGLE_VEL_LIM 20 //!< angle velocity limit default +// index search +#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 //!< default index search velocity +// align voltage +#define DEF_VOLTAGE_SENSOR_ALIGN 6.0 //!< default voltage for sensor and motor zero alignemt +// low pass filter velocity +#define DEF_VEL_FILTER_Tf 0.005 //!< default velocity filter time constant \ No newline at end of file From e745a35fd8962cff44d92918e901245ba5919818 Mon Sep 17 00:00:00 2001 From: askuric Date: Sat, 1 Aug 2020 08:57:34 +0200 Subject: [PATCH 50/65] FEAT support for 1.4.0 --- README.md | 1 - src/BLDCMotor.cpp | 589 -------------------------------------- src/BLDCMotor.h | 277 ------------------ src/Encoder.cpp | 229 --------------- src/Encoder.h | 112 -------- src/FOCutils.cpp | 101 ------- src/FOCutils.h | 61 ---- src/MagneticSensor.cpp | 198 ------------- src/MagneticSensor.h | 79 ----- src/MagneticSensorI2C.cpp | 153 ---------- src/MagneticSensorI2C.h | 78 ----- src/MagneticSensorSPI.cpp | 198 ------------- src/MagneticSensorSPI.h | 79 ----- src/Sensor.h | 39 --- src/SimpleFOC.h | 96 ------- src/defaults.h | 17 -- 16 files changed, 2307 deletions(-) delete mode 100644 src/BLDCMotor.cpp delete mode 100644 src/BLDCMotor.h delete mode 100644 src/Encoder.cpp delete mode 100644 src/Encoder.h delete mode 100644 src/FOCutils.cpp delete mode 100644 src/FOCutils.h delete mode 100644 src/MagneticSensor.cpp delete mode 100644 src/MagneticSensor.h delete mode 100644 src/MagneticSensorI2C.cpp delete mode 100644 src/MagneticSensorI2C.h delete mode 100644 src/MagneticSensorSPI.cpp delete mode 100644 src/MagneticSensorSPI.h delete mode 100644 src/Sensor.h delete mode 100644 src/SimpleFOC.h delete mode 100644 src/defaults.h diff --git a/README.md b/README.md index 5ce98606..09ab0cb9 100644 --- a/README.md +++ b/README.md @@ -11,7 +11,6 @@ This is the minimal Arduino example of the [Simple FOC](https://github.com/askur ├───arduino_foc_minimal_encoder # Arduino minimal code for running a motor with Encoder │ └───arduino_foc_minimal_magnetic # Arduino minimal code for running a motor with magnetic sensor - # AS5048/47 ``` Each of the examples will give you the opportunity to change the PI velocity parameters `P` and `I`, Low pass filter time constant `Tf`, change the control loop in real time and check the average loop execution time, all from the serial terminal. diff --git a/src/BLDCMotor.cpp b/src/BLDCMotor.cpp deleted file mode 100644 index a826a366..00000000 --- a/src/BLDCMotor.cpp +++ /dev/null @@ -1,589 +0,0 @@ -#include "BLDCMotor.h" - -// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) -// - phA, phB, phC - motor A,B,C phase pwm pins -// - pp - pole pair number -// - cpr - counts per rotation number (cpm=ppm*4) -// - enable pin - (optional input) -BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) -{ - // Pin initialization - pwmA = phA; - pwmB = phB; - pwmC = phC; - pole_pairs = pp; - - // enable_pin pin - enable_pin = en; - - // Power supply voltage - voltage_power_supply = DEF_POWER_SUPPLY; - - // Velocity loop config - // PI controller constant - PI_velocity.P = DEF_PI_VEL_P; - PI_velocity.I = DEF_PI_VEL_I; - PI_velocity.timestamp = _micros(); - PI_velocity.voltage_limit = voltage_power_supply; - PI_velocity.voltage_ramp = DEF_PI_VEL_U_RAMP; - PI_velocity.voltage_prev = 0; - PI_velocity.tracking_error_prev = 0; - - // velocity low pass filter - LPF_velocity.Tf = DEF_VEL_FILTER_Tf; - LPF_velocity.timestamp = _micros(); - LPF_velocity.prev = 0; - - // position loop config - // P controller constant - P_angle.P = DEF_P_ANGLE_P; - // maximum angular velocity to be used for positioning - P_angle.velocity_limit = DEF_P_ANGLE_VEL_LIM; - - // index search velocity - velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; - // sensor and motor align voltage - voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; - - // electric angle of the zero angle - zero_electric_angle = 0; - - // default modulation is SinePWM - foc_modulation = FOCModulationType::SinePWM; - - // default target value - target = 0; - - //monitor_port - monitor_port = nullptr; -} - -// init hardware pins -void BLDCMotor::init() { - if(monitor_port) monitor_port->println("MONITOR: Initialize the motor pins."); - // PWM pins - pinMode(pwmA, OUTPUT); - pinMode(pwmB, OUTPUT); - pinMode(pwmC, OUTPUT); - if(hasEnable()) pinMode(enable_pin, OUTPUT); - - if(monitor_port) monitor_port->println("MONITOR: Set high frequency PWM."); - // Increase PWM frequency to 32 kHz - // make silent - _setPwmFrequency(pwmA); - _setPwmFrequency(pwmB); - _setPwmFrequency(pwmC); - - // sanity check for the voltage limit configuration - if(PI_velocity.voltage_limit > voltage_power_supply) PI_velocity.voltage_limit = voltage_power_supply; - - _delay(500); - // enable motor - if(monitor_port) monitor_port->println("MONITOR: Enabling motor."); - enable(); - _delay(500); - -} - - -// disable motor driver -void BLDCMotor::disable() -{ - // disable the driver - if enable_pin pin available - if (hasEnable()) digitalWrite(enable_pin, LOW); - // set zero to PWM - setPwm(pwmA, 0); - setPwm(pwmB, 0); - setPwm(pwmC, 0); -} -// enable motor driver -void BLDCMotor::enable() -{ - // set zero to PWM - setPwm(pwmA, 0); - setPwm(pwmB, 0); - setPwm(pwmC, 0); - // enable_pin the driver - if enable_pin pin available - if (hasEnable()) digitalWrite(enable_pin, HIGH); - -} - -void BLDCMotor::linkSensor(Sensor* _sensor) { - sensor = _sensor; -} - - -// Encoder alignment to electrical 0 angle -int BLDCMotor::alignSensor() { - if(monitor_port) monitor_port->println("MONITOR: Align the sensor's and motor electrical 0 angle."); - // align the electrical phases of the motor and sensor - // set angle -90 degrees - setPhaseVoltage(voltage_sensor_align, _3PI_2); - // let the motor stabilize for 3 sec - _delay(3000); - // set sensor to zero - sensor->initRelativeZero(); - _delay(500); - setPhaseVoltage(0,0); - _delay(200); - - // find the index if available - int exit_flag = absoluteZeroAlign(); - _delay(500); - if(monitor_port){ - if(exit_flag< 0 ) monitor_port->println("MONITOR: Error: Absolute zero not found!"); - if(exit_flag> 0 ) monitor_port->println("MONITOR: Success: Absolute zero found!"); - else monitor_port->println("MONITOR: Absolute zero not available!"); - } - return exit_flag; -} - - -// Encoder alignment the absolute zero angle -// - to the index -int BLDCMotor::absoluteZeroAlign() { - // if no absolute zero return - if(!sensor->hasAbsoluteZero()) return 0; - - if(monitor_port) monitor_port->println("MONITOR: Aligning the absolute zero."); - - if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MONITOR: Searching for absolute zero."); - // search the absolute zero with small velocity - while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ - loopFOC(); - voltage_q = velocityPI(velocity_index_search - shaftVelocity()); - } - voltage_q = 0; - // disable motor - setPhaseVoltage(0,0); - - // align absolute zero if it has been found - if(!sensor->needsAbsoluteZeroSearch()){ - // align the sensor with the absolute zero - float zero_offset = sensor->initAbsoluteZero(); - // remember zero electric angle - zero_electric_angle = electricAngle(zero_offset); - } - // return bool if zero found - return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; -} - -/** - State calculation methods -*/ -// shaft angle calculation -float BLDCMotor::shaftAngle() { - return sensor->getAngle(); -} -// shaft velocity calculation -float BLDCMotor::shaftVelocity() { - float Ts = (_micros() - LPF_velocity.timestamp) * 1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - // calculate the filtering - float alpha = LPF_velocity.Tf/(LPF_velocity.Tf + Ts); - float vel = alpha*LPF_velocity.prev + (1-alpha)*sensor->getVelocity(); - // save the variables - LPF_velocity.prev = vel; - LPF_velocity.timestamp = _micros(); - return vel; -} -// Electrical angle calculation -float BLDCMotor::electricAngle(float shaftAngle) { - //return normalizeAngle(shaftAngle * pole_pairs); - return (shaftAngle * pole_pairs); -} - -/** - FOC functions -*/ -// FOC initialization function -int BLDCMotor::initFOC() { - // sensor and motor alignment - _delay(500); - int exit_flag = alignSensor(); - _delay(500); - - if(monitor_port) monitor_port->println("MONITOR: FOC init finished - motor ready."); - - return exit_flag; -} - -// Iterative function looping FOC algorithm, setting Uq on the Motor -// The faster it can be run the better -void BLDCMotor::loopFOC() { - // shaft angle - shaft_angle = shaftAngle(); - // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); -} - -// Iterative function running outer loop of the FOC algorithm -// Behavior of this function is determined by the motor.controller variable -// It runs either angle, velocity or voltage loop -// - needs to be called iteratively it is asynchronous function -// - if target is not set it uses motor.target value -void BLDCMotor::move(float new_target) { - // set internal target variable - if( new_target != NOT_SET ) target = new_target; - // get angular velocity - shaft_velocity = shaftVelocity(); - // choose control loop - switch (controller) { - case ControlType::voltage: - voltage_q = target; - break; - case ControlType::angle: - // angle set point - // include angle loop - shaft_angle_sp = target; - shaft_velocity_sp = positionP( shaft_angle_sp - shaft_angle ); - voltage_q = velocityPI(shaft_velocity_sp - shaft_velocity); - break; - case ControlType::velocity: - // velocity set point - // include velocity loop - shaft_velocity_sp = target; - voltage_q = velocityPI(shaft_velocity_sp - shaft_velocity); - break; - } -} - - -// Method using FOC to set Uq to the motor at the optimal angle -// Function implementing Space Vector PWM and Sine PWM algorithms -// -// Function using sine approximation -// regular sin + cos ~300us (no memory usaage) -// approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { - switch (foc_modulation) - { - case FOCModulationType::SinePWM : - // Sinusoidal PWM modulation - // Inverse Park + Clarke transformation - - // angle normalization in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - angle_el = normalizeAngle(angle_el + zero_electric_angle); - // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; - - // Clarke transform - Ua = Ualpha + voltage_power_supply/2; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; - break; - - case FOCModulationType::SpaceVectorPWM : - // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm - // https://www.youtube.com/watch?v=QMSWUMEAejg - - // if negative voltages change inverse the phase - // angle + 180degrees - if(Uq < 0) angle_el += _PI; - Uq = abs(Uq); - - // angle normalisation in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - angle_el = normalizeAngle(angle_el + zero_electric_angle + _PI_2); - - // find the sector we are in currently - int sector = floor(angle_el / _PI_3) + 1; - // calculate the duty cycles - float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el); - float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3); - // two versions possible - // centered around voltage_power_supply/2 - float T0 = 1 - T1 - T2; - // pulled to 0 - better for low power supply voltage - //T0 = 0; - - // calculate the duty cycles(times) - float Ta,Tb,Tc; - switch(sector){ - case 1: - Ta = T1 + T2 + T0/2; - Tb = T2 + T0/2; - Tc = T0/2; - break; - case 2: - Ta = T1 + T0/2; - Tb = T1 + T2 + T0/2; - Tc = T0/2; - break; - case 3: - Ta = T0/2; - Tb = T1 + T2 + T0/2; - Tc = T2 + T0/2; - break; - case 4: - Ta = T0/2; - Tb = T1+ T0/2; - Tc = T1 + T2 + T0/2; - break; - case 5: - Ta = T2 + T0/2; - Tb = T0/2; - Tc = T1 + T2 + T0/2; - break; - case 6: - Ta = T1 + T2 + T0/2; - Tb = T0/2; - Tc = T1 + T0/2; - break; - default: - // possible error state - Ta = 0; - Tb = 0; - Tc = 0; - } - - // calculate the phase voltages - Ua = Ta*Uq; - Ub = Tb*Uq; - Uc = Tc*Uq; - break; - } - - // set the voltages in hardware - setPwm(pwmA, Ua); - setPwm(pwmB, Ub); - setPwm(pwmC, Uc); -} - - - - -// Set voltage to the pwm pin -// - function a bit optimized to get better performance -void BLDCMotor::setPwm(int pinPwm, float U) { - // max value - float U_max = voltage_power_supply; - - // sets the voltage [0,12V(U_max)] to pwm [0,255] - // - U_max you can set in header file - default 12V - int U_pwm = 255.0 * U / U_max; - - // limit the values between 0 and 255 - U_pwm = (U_pwm < 0) ? 0 : (U_pwm >= 255) ? 255 : U_pwm; - - analogWrite(pinPwm, U_pwm); -} - -/** - Utility functions -*/ -// normalizing radian angle to [0,2PI] -float BLDCMotor::normalizeAngle(float angle){ - float a = fmod(angle, _2PI); - return a >= 0 ? a : (a + _2PI); -} -// determining if the enable pin has been provided -int BLDCMotor::hasEnable(){ - return enable_pin != NOT_SET; -} - - -/** - Motor control functions -*/ -// PI controller function -float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){ - float Ts = (_micros() - cont.timestamp) * 1e-6; - - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // u(s) = (P + I/s)e(s) - // Tustin transform of the PI controller ( a bit optimized ) - // uk = uk_1 + (I*Ts/2 + P)*ek + (I*Ts/2 - P)*ek_1 - float tmp = cont.I*Ts*0.5; - float voltage = cont.voltage_prev + (tmp + cont.P) * tracking_error + (tmp - cont.P) * cont.tracking_error_prev; - - // antiwindup - limit the output voltage_q - if (abs(voltage) > cont.voltage_limit) voltage = voltage > 0 ? cont.voltage_limit : -cont.voltage_limit; - // limit the acceleration by ramping the the voltage - float d_voltage = voltage - cont.voltage_prev; - if (abs(d_voltage)/Ts > cont.voltage_ramp) voltage = d_voltage > 0 ? cont.voltage_prev + cont.voltage_ramp*Ts : cont.voltage_prev - cont.voltage_ramp*Ts; - - - cont.voltage_prev = voltage; - cont.tracking_error_prev = tracking_error; - cont.timestamp = _micros(); - return voltage; -} -// velocity control loop PI controller -float BLDCMotor::velocityPI(float tracking_error) { - return controllerPI(tracking_error, PI_velocity); -} - -// P controller for position control loop -float BLDCMotor::positionP(float ek) { - // calculate the target velocity from the position error - float velocity_target = P_angle.P * ek; - // constrain velocity target value - if (abs(velocity_target) > P_angle.velocity_limit) velocity_target = velocity_target > 0 ? P_angle.velocity_limit : -P_angle.velocity_limit; - return velocity_target; -} - -/** - * Monitoring functions - */ -// function implementing the monitor_port setter -void BLDCMotor::useMonitoring(Print &print){ - monitor_port = &print; //operate on the address of print - if(monitor_port ) monitor_port->println("MONITOR: Serial monitor enabled!"); -} -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void BLDCMotor::monitor() { - if(!monitor_port) return; - switch (controller) { - case ControlType::velocity: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_velocity_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - case ControlType::angle: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_angle); - break; - case ControlType::voltage: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - } -} - -int BLDCMotor::command(String user_command) { - // error flag - int errorFlag = 1; - // if empty string - if(user_command.length() < 1) return errorFlag; - - // parse command letter - char cmd = user_command.charAt(0); - // check if get command - char GET = user_command.charAt(1) == '\n'; - // parse command values - float value = user_command.substring(1).toFloat(); - - // apply the the command - switch(cmd){ - case 'P': // velocity P gain change - if(monitor_port) monitor_port->print("PI velocity P: "); - if(!GET) PI_velocity.P = value; - if(monitor_port) monitor_port->println(PI_velocity.P); - break; - case 'I': // velocity I gain change - if(monitor_port) monitor_port->print("PI velocity I: "); - if(!GET) PI_velocity.I = value; - if(monitor_port) monitor_port->println(PI_velocity.I); - break; - case 'L': // velocity voltage limit change - if(monitor_port) monitor_port->print("PI velocity voltage limit: "); - if(!GET)PI_velocity.voltage_limit = value; - if(monitor_port) monitor_port->println(PI_velocity.voltage_limit); - break; - case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print("PI velocity voltage ramp: "); - if(!GET) PI_velocity.voltage_ramp = value; - if(monitor_port) monitor_port->println(PI_velocity.voltage_ramp); - break; - case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print("LPF velocity time constant: "); - if(!GET) LPF_velocity.Tf = value; - if(monitor_port) monitor_port->println(LPF_velocity.Tf); - break; - case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print("P angle P value: "); - if(!GET) P_angle.P = value; - if(monitor_port) monitor_port->println(P_angle.P); - break; - case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print("P angle velocity limit: "); - if(!GET) P_angle.velocity_limit = value; - if(monitor_port) monitor_port->println(P_angle.velocity_limit); - break; - case 'T': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print("P angle velocity limit: "); - if(!GET) P_angle.velocity_limit = value; - if(monitor_port) monitor_port->println(P_angle.velocity_limit); - break; - case 'C': - // change control type - if(monitor_port) monitor_port->print("Contoller type: "); - - if(GET){ // if get commang - switch(controller){ - case ControlType::voltage: - if(monitor_port) monitor_port->println("voltage"); - break; - case ControlType::velocity: - if(monitor_port) monitor_port->println("velocity"); - break; - case ControlType::angle: - if(monitor_port) monitor_port->println("angle"); - break; - } - }else{ // if set command - switch((int)value){ - case 0: - if(monitor_port) monitor_port->println("voltage"); - controller = ControlType::voltage; - break; - case 1: - if(monitor_port) monitor_port->println("velocity"); - controller = ControlType::velocity; - break; - case 2: - if(monitor_port) monitor_port->println("angle"); - controller = ControlType::angle; - break; - default: // not valid command - errorFlag = 0; - } - } - break; - case 'V': // get current values of the state variables - switch((int)value){ - case 0: // get voltage - if(monitor_port) monitor_port->print("Uq: "); - if(monitor_port) monitor_port->println(voltage_q); - break; - case 1: // get velocity - if(monitor_port) monitor_port->print("Velocity: "); - if(monitor_port) monitor_port->println(shaft_velocity); - break; - case 2: // get angle - if(monitor_port) monitor_port->print("Angle: "); - if(monitor_port) monitor_port->println(shaft_angle); - break; - case 3: // get angle - if(monitor_port) monitor_port->print("Target: "); - if(monitor_port) monitor_port->println(target); - break; - default: // not valid command - errorFlag = 0; - } - break; - default: // target change - if(monitor_port) monitor_port->print("Target : "); - target = user_command.toFloat(); - if(monitor_port) monitor_port->println(target); - } - // return 0 if error and 1 if ok - return errorFlag; -} - - diff --git a/src/BLDCMotor.h b/src/BLDCMotor.h deleted file mode 100644 index df95445d..00000000 --- a/src/BLDCMotor.h +++ /dev/null @@ -1,277 +0,0 @@ -/** - * @file BLDCMotor.h - * - */ - -#ifndef BLDCMotor_h -#define BLDCMotor_h - -#include "Arduino.h" -#include "FOCutils.h" -#include "Sensor.h" -#include "defaults.h" - - -#define NOT_SET -12345.0 - -/** - * Motiron control type - */ -enum ControlType{ - voltage,//!< Torque control using voltage - velocity,//!< Velocity motion control - angle//!< Position/angle motion control -}; - -/** - * FOC modulation type - */ -enum FOCModulationType{ - SinePWM, //!< Sinusoidal PWM modulation - SpaceVectorPWM //!< Space vector modulation method -}; - -/** - * PI controller structure - */ -struct PI_s{ - float P; //!< Proportional gain - float I; //!< Integral gain - float voltage_limit; //!< Voltage limit of the controller output - float voltage_ramp; //!< Maximum speed of change of the output value - long timestamp; //!< Last execution timestamp - float voltage_prev; //!< last controller output value - float tracking_error_prev; //!< last tracking error value -}; - -// P controller structure -struct P_s{ - float P; //!< Proportional gain - long timestamp; //!< Last execution timestamp - float velocity_limit; //!< Velocity limit of the controller output -}; - -/** - * Low pass filter structure - */ -struct LPF_s{ - float Tf; //!< Low pass filter time constant - long timestamp; //!< Last execution timestamp - float prev; //!< filtered value in previous execution step -}; - - - - -/** - BLDC motor class -*/ -class BLDCMotor -{ - public: - /** - BLDCMotor class constructor - @param phA A phase pwm pin - @param phB B phase pwm pin - @param phC C phase pwm pin - @param pp pole pair number - @param cpr counts per rotation number (cpm=ppm*4) - @param en enable pin (optional input) - */ - BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); - - /** Motor hardware init function */ - void init(); - /** Motor disable function */ - void disable(); - /** Motor enable function */ - void enable(); - - /** - * Function linking a motor and a sensor - * - * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity - */ - void linkSensor(Sensor* sensor); - - /** - * Function initializing FOC algorithm - * and aligning sensor's and motors' zero position - */ - int initFOC(); - /** - * Function running FOC algorithm in real-time - * it calculates the gets motor angle and sets the appropriate voltages - * to the phase pwm signals - * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us - */ - void loopFOC(); - /** - * Function executing the control loops set by the controller parameter of the BLDCMotor. - * - * @param target Either voltage, angle or velocity based on the motor.controller - * If it is not set the motor will use the target set in its variable motor.target - * - * This function doesn't need to be run upon each loop execution - depends of the use case - */ - void move(float target = NOT_SET); - - - // hardware variables - int pwmA; //!< phase A pwm pin number - int pwmB; //!< phase B pwm pin number - int pwmC; //!< phase C pwm pin number - int enable_pin; //!< enable pin number - - - - - // State calculation methods - /** Shaft angle calculation in radians [rad] */ - float shaftAngle(); - /** - * Shaft angle calculation function in radian per second [rad/s] - * It implements low pass filtering - */ - float shaftVelocity(); - - // state variables - float target; //!< current target value - depends of the controller - float shaft_angle;//!< current motor angle - float shaft_velocity;//!< current motor velocity - float shaft_velocity_sp;//!< current target velocity - float shaft_angle_sp;//!< current target angle - float voltage_q;//!< current voltage u_q set - float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor - - // motor configuration parameters - float voltage_power_supply;//!< Power supply voltage - float voltage_sensor_align;//!< sensor and motor align voltage parameter - float velocity_index_search;//!< target velocity for index search - int pole_pairs;//!< Motor pole pairs number - - // configuration structures - ControlType controller; //!< parameter determining the control loop to be used - FOCModulationType foc_modulation;//!< parameter derterniming modulation algorithm - PI_s PI_velocity;//!< parameter determining the velocity PI configuration - P_s P_angle; //!< parameter determining the position P configuration - LPF_s LPF_velocity;//!< parameter determining the velocity Lpw pass filter configuration - - /** - * Sensor link: - * - Encoder - * - MagneticSensor - */ - Sensor* sensor; - - float zero_electric_angle;//! 0.5) Ts = 1e-3; - - // time from last impulse - float Th = (timestamp_us - pulse_timestamp) * 1e-6; - long dN = pulse_counter - prev_pulse_counter; - - // Pulse per second calculation (Eq.3.) - // dN - impulses received - // Ts - sampling time - time in between function calls - // Th - time from last impulse - // Th_1 - time form last impulse of the previous call - // only increment if some impulses received - float dt = Ts + prev_Th - Th; - pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second; - - // if more than 0.05 passed in between impulses - if ( Th > 0.1) pulse_per_second = 0; - - // velocity calculation - float velocity = pulse_per_second / ((float)cpr) * (_2PI); - - // save variables for next pass - prev_timestamp_us = timestamp_us; - // save velocity calculation variables - prev_Th = Th; - prev_pulse_counter = pulse_counter; - return (velocity); -} - -// getter for index pin -// return -1 if no index -int Encoder::needsAbsoluteZeroSearch(){ - return index_pulse_counter == 0; -} -// getter for index pin -int Encoder::hasAbsoluteZero(){ - return hasIndex(); -} -// initialize counter to zero -float Encoder::initRelativeZero(){ - long angle_offset = -pulse_counter; - pulse_counter = 0; - pulse_timestamp = _micros(); - return _2PI * (angle_offset) / ((float)cpr); -} -// initialize index to zero -float Encoder::initAbsoluteZero(){ - pulse_counter -= index_pulse_counter; - prev_pulse_counter = pulse_counter; - return (index_pulse_counter) / ((float)cpr) * (_2PI); -} -// private function used to determine if encoder has index -int Encoder::hasIndex(){ - return index_pin != 0; -} - - -// encoder initialisation of the hardware pins -// and calculation variables -void Encoder::init(){ - - // Encoder - check if pullup needed for your encoder - if(pullup == Pullup::INTERN){ - pinMode(pinA, INPUT_PULLUP); - pinMode(pinB, INPUT_PULLUP); - if(hasIndex()) pinMode(index_pin,INPUT_PULLUP); - }else{ - pinMode(pinA, INPUT); - pinMode(pinB, INPUT); - if(hasIndex()) pinMode(index_pin,INPUT); - } - - // counter setup - pulse_counter = 0; - pulse_timestamp = _micros(); - // velocity calculation variables - prev_Th = 0; - pulse_per_second = 0; - prev_pulse_counter = 0; - prev_timestamp_us = _micros(); - - // initial cpr = PPR - // change it if the mode is quadrature - if(quadrature == Quadrature::ON) cpr = 4*cpr; - -} - -// function enabling hardware interrupts of the for the callback provided -// if callback is not provided then the interrupt is not enabled -void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){ - // attach interrupt if functions provided - switch(quadrature){ - case Quadrature::ON: - // A callback and B callback - if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); - if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); - break; - case Quadrature::OFF: - // A callback and B callback - if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING); - if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); - break; - } - - // if index used initialize the index interrupt - if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE); -} - diff --git a/src/Encoder.h b/src/Encoder.h deleted file mode 100644 index fc65a7a9..00000000 --- a/src/Encoder.h +++ /dev/null @@ -1,112 +0,0 @@ -#ifndef ENCODER_LIB_H -#define ENCODER_LIB_H - -#include "Arduino.h" -#include "FOCutils.h" -#include "Sensor.h" - - -/** - * Pullup configuration structure - */ -enum Pullup{ - INTERN, //!< Use internal pullups - EXTERN //!< Use external pullups -}; - -/** - * Quadrature mode configuration structure - */ -enum Quadrature{ - ON, //!< Enable quadrature mode CPR = 4xPPR - OFF //!< Disable quadrature mode / CPR = PPR -}; - -class Encoder: public Sensor{ - public: - /** - Encoder class constructor - @param encA encoder B pin - @param encB encoder B pin - @param ppr impulses per rotation (cpr=ppr*4) - @param index index pin number (optional input) - */ - Encoder(int encA, int encB , float ppr, int index = 0); - - /** encoder initialise pins */ - void init(); - /** - * function enabling hardware interrupts for the encoder channels with provided callback functions - * if callback is not provided then the interrupt is not enabled - * - * @param doA pointer to the A channel interrupt handler function - * @param doB pointer to the B channel interrupt handler function - * @param doIndex pointer to the Index channel interrupt handler function - * - */ - void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr); - - // Encoder interrupt callback functions - /** A channel callback function */ - void handleA(); - /** B channel callback function */ - void handleB(); - /** Index channel callback function */ - void handleIndex(); - - - // pins A and B - int pinA; //!< encoder hardware pin A - int pinB; //!< encoder hardware pin B - int index_pin; //!< index pin - - // Encoder configuration - Pullup pullup; //!< Configuration parameter internal or external pullups - Quadrature quadrature;//!< Configuration parameter enable or disable quadrature mode - float cpr;//!< encoder cpr number - - // Abstract functions of the Sensor class implementation - /** get current angle (rad) */ - float getAngle(); - /** get current angular velocity (rad/s) */ - float getVelocity(); - /** - * set current angle as zero angle - * return the angle [rad] difference - */ - float initRelativeZero(); - /** - * set index angle as zero angle - * return the angle [rad] difference - */ - float initAbsoluteZero(); - /** - * returns 0 if it has no index - * 0 - encoder without index - * 1 - encoder with index - */ - int hasAbsoluteZero(); - /** - * returns 0 if it does need search for absolute zero - * 0 - encoder without index - * 1 - ecoder with index - */ - int needsAbsoluteZeroSearch(); - - private: - int hasIndex(); //!< function returning 1 if encoder has index pin and 0 if not. - - volatile long pulse_counter;//!< current pulse counter - volatile long pulse_timestamp;//!< last impulse timestamp in us - volatile int A_active; //!< current active states of A channel - volatile int B_active; //!< current active states of B channel - volatile int I_active; //!< current active states of Index channel - volatile long index_pulse_counter; //!< impulse counter number upon first index interrupt - - // velocity calculation variables - float prev_Th, pulse_per_second; - volatile long prev_pulse_counter, prev_timestamp_us; -}; - - -#endif diff --git a/src/FOCutils.cpp b/src/FOCutils.cpp deleted file mode 100644 index 04c6cfbf..00000000 --- a/src/FOCutils.cpp +++ /dev/null @@ -1,101 +0,0 @@ -#include "FOCutils.h" - - -void _setPwmFrequency(int pin) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other atmega328p chips -// High PWM frequency -// https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pin == 5 || pin == 6 || pin == 9 || pin == 10) { - if (pin == 5 || pin == 6) { - // configure the pwm phase-corrected mode - TCCR0A = ((TCCR0A & 0b11111100) | 0x01); - // set prescaler to 1 - TCCR0B = ((TCCR0B & 0b11110000) | 0x01); - } else { - // set prescaler to 1 - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); - } - } - else if (pin == 3 || pin == 11) { - // set prescaler to 1 - TCCR2B = ((TCCR2B & 0b11111000) | 0x01); - } -#elif defined(_STM32_DEF_) // if stm chips - analogWrite(pin,0); - analogWriteFrequency(50000); // la valeur par défaut est 20000 Hz -#endif -} - -// function buffering delay() -// arduino uno function doesn't work well with interrupts -void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) - // if arduino uno and other atmega328p chips - // return the value based on the prescaler - long t = _micros(); - while((_micros() - t)/1000 < ms){}; -#else - // regular micros - return delay(ms); -#endif -} - - -// function buffering _micros() -// arduino function doesn't work well with interrupts -unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) -// if arduino uno and other atmega328p chips - //return the value based on the prescaler - if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); - else return (micros()); -#else - // regular micros - return micros(); -#endif -} - - -// lookup table for sine calculation in between 0 and 90 degrees -//float sine_array[200] = {0.0000,0.0079,0.0158,0.0237,0.0316,0.0395,0.0473,0.0552,0.0631,0.0710,0.0789,0.0867,0.0946,0.1024,0.1103,0.1181,0.1260,0.1338,0.1416,0.1494,0.1572,0.1650,0.1728,0.1806,0.1883,0.1961,0.2038,0.2115,0.2192,0.2269,0.2346,0.2423,0.2499,0.2575,0.2652,0.2728,0.2804,0.2879,0.2955,0.3030,0.3105,0.3180,0.3255,0.3329,0.3404,0.3478,0.3552,0.3625,0.3699,0.3772,0.3845,0.3918,0.3990,0.4063,0.4135,0.4206,0.4278,0.4349,0.4420,0.4491,0.4561,0.4631,0.4701,0.4770,0.4840,0.4909,0.4977,0.5046,0.5113,0.5181,0.5249,0.5316,0.5382,0.5449,0.5515,0.5580,0.5646,0.5711,0.5775,0.5839,0.5903,0.5967,0.6030,0.6093,0.6155,0.6217,0.6279,0.6340,0.6401,0.6461,0.6521,0.6581,0.6640,0.6699,0.6758,0.6815,0.6873,0.6930,0.6987,0.7043,0.7099,0.7154,0.7209,0.7264,0.7318,0.7371,0.7424,0.7477,0.7529,0.7581,0.7632,0.7683,0.7733,0.7783,0.7832,0.7881,0.7930,0.7977,0.8025,0.8072,0.8118,0.8164,0.8209,0.8254,0.8298,0.8342,0.8385,0.8428,0.8470,0.8512,0.8553,0.8594,0.8634,0.8673,0.8712,0.8751,0.8789,0.8826,0.8863,0.8899,0.8935,0.8970,0.9005,0.9039,0.9072,0.9105,0.9138,0.9169,0.9201,0.9231,0.9261,0.9291,0.9320,0.9348,0.9376,0.9403,0.9429,0.9455,0.9481,0.9506,0.9530,0.9554,0.9577,0.9599,0.9621,0.9642,0.9663,0.9683,0.9702,0.9721,0.9739,0.9757,0.9774,0.9790,0.9806,0.9821,0.9836,0.9850,0.9863,0.9876,0.9888,0.9899,0.9910,0.9920,0.9930,0.9939,0.9947,0.9955,0.9962,0.9969,0.9975,0.9980,0.9985,0.9989,0.9992,0.9995,0.9997,0.9999,1.0000,1.0000}; - -// int array instead of float array -// 2x storage save (int 2Byte float 4 Byte ) -// sin*10000 -int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,1103,1181,1260,1338,1416,1494,1572,1650,1728,1806,1883,1961,2038,2115,2192,2269,2346,2423,2499,2575,2652,2728,2804,2879,2955,3030,3105,3180,3255,3329,3404,3478,3552,3625,3699,3772,3845,3918,3990,4063,4135,4206,4278,4349,4420,4491,4561,4631,4701,4770,4840,4909,4977,5046,5113,5181,5249,5316,5382,5449,5515,5580,5646,5711,5775,5839,5903,5967,6030,6093,6155,6217,6279,6340,6401,6461,6521,6581,6640,6699,6758,6815,6873,6930,6987,7043,7099,7154,7209,7264,7318,7371,7424,7477,7529,7581,7632,7683,7733,7783,7832,7881,7930,7977,8025,8072,8118,8164,8209,8254,8298,8342,8385,8428,8470,8512,8553,8594,8634,8673,8712,8751,8789,8826,8863,8899,8935,8970,9005,9039,9072,9105,9138,9169,9201,9231,9261,9291,9320,9348,9376,9403,9429,9455,9481,9506,9530,9554,9577,9599,9621,9642,9663,9683,9702,9721,9739,9757,9774,9790,9806,9821,9836,9850,9863,9876,9888,9899,9910,9920,9930,9939,9947,9955,9962,9969,9975,9980,9985,9989,9992,9995,9997,9999,10000,10000}; - -// function approximating the sine calculation by using fixed size array -// ~40us (float array) -// ~50us (int array) -// precision +-0.005 -// it has to receive an angle in between 0 and 2PI -float _sin(float a){ - if(a < _PI_2){ - //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; - //return sine_array[(int)(126.6873* a)]; // float array optimised - return 0.0001*sine_array[_round(126.6873* a)]; // int array optimised - }else if(a < _PI){ - // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; - //return sine_array[398 - (int)(126.6873*a)]; // float array optimised - return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimised - }else if(a < _3PI_2){ - // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; - //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimised - return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimised - } else { - // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; - //return -sine_array[796 - (int)(126.6873*a)]; // float array optimised - return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimised - } -} - -// function approfimating cosine calculaiton by using fixed size array -// ~55us (float array) -// ~56us (int array) -// precision +-0.005 -// it has to receive an angle in between 0 and 2PI -float _cos(float a){ - float a_sin = a + _PI_2; - a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin; - return _sin(a_sin); -} diff --git a/src/FOCutils.h b/src/FOCutils.h deleted file mode 100644 index b60978b3..00000000 --- a/src/FOCutils.h +++ /dev/null @@ -1,61 +0,0 @@ -#ifndef FOCUTILS_LIB_H -#define FOCUTILS_LIB_H - -#include "Arduino.h" - -// sign function -#define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) -#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) - -// utility defines -#define _2_SQRT3 1.15470053838 -#define _SQRT3 1.73205080757 -#define _1_SQRT3 0.57735026919 -#define _SQRT3_2 0.86602540378 -#define _SQRT2 1.41421356237 -#define _120_D2R 2.09439510239 -#define _PI 3.14159265359 -#define _PI_2 1.57079632679 -#define _PI_3 1.0471975512 -#define _2PI 6.28318530718 -#define _3PI_2 4.71238898038 - -/** - * High PWM frequency setting function - * - hardware specific - * - * @param pin pin number to configure - */ -void _setPwmFrequency(int pin); - -/** - * Function implementing delay() function in milliseconds - * - blocking function - * - hardware specific - * - * @param ms number of milliseconds to wait - */ -void _delay(unsigned long ms); - -/** - * Function implementing timestamp getting function in microseconds - * hardware specific - */ -unsigned long _micros(); - -/** - * Function approximating the sine calculation by using fixed size array - * - execution time ~40us (Arduino UNO) - * - * @param a angle in between 0 and 2PI - */ -float _sin(float a); -/** - * Function approximating cosine calculation by using fixed size array - * - execution time ~50us (Arduino UNO) - * - * @param a angle in between 0 and 2PI - */ -float _cos(float a); - -#endif \ No newline at end of file diff --git a/src/MagneticSensor.cpp b/src/MagneticSensor.cpp deleted file mode 100644 index 4cb78bb2..00000000 --- a/src/MagneticSensor.cpp +++ /dev/null @@ -1,198 +0,0 @@ -#include "MagneticSensor.h" - -// MagneticSensor(int cs, float _cpr, int _angle_register) -// cs - SPI chip select pin -// _cpr - count per revolution -// _angle_register - (optional) angle read register - default 0x3FFF -MagneticSensor::MagneticSensor(int cs, float _cpr, int _angle_register){ - // chip select pin - chip_select_pin = cs; - // angle read register of the magnetic sensor - angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTAR; - // register maximum value (counts per revolution) - cpr = _cpr; - -} - - -void MagneticSensor::init(){ - // 1MHz clock (AMS should be able to accept up to 10MHz) - settings = SPISettings(1000000, MSBFIRST, SPI_MODE1); - - //setup pins - pinMode(chip_select_pin, OUTPUT); - - - //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices - SPI.begin(); - SPI.setBitOrder(MSBFIRST); // Set the SPI_1 bit order - SPI.setDataMode(SPI_MODE1) ; - SPI.setClockDivider(SPI_CLOCK_DIV8); - - digitalWrite(chip_select_pin, HIGH); - // velocity calculation init - angle_prev = 0; - velocity_calc_timestamp = _micros(); - - // full rotations tracking number - full_rotation_offset = 0; - angle_data_prev = getRawCount(); - zero_offset = 0; -} - -// Shaft angle calculation -// angle is in radians [rad] -float MagneticSensor::getAngle(){ - // raw data from the sensor - float angle_data = getRawCount(); - - // tracking the number of rotations - // in order to expand angle range form [0,2PI] - // to basically infinity - float d_angle = angle_data - angle_data_prev; - // if overflow happened track it as full rotation - if(abs(d_angle) > (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; - // save the current angle value for the next steps - // in order to know if overflow happened - angle_data_prev = angle_data; - - // zero offset adding - angle_data -= (int)zero_offset; - // return the full angle - // (number of full rotations)*2PI + current sensor angle - return full_rotation_offset + ( angle_data / (float)cpr) * _2PI; -} - -// Shaft velocity calculation -float MagneticSensor::getVelocity(){ - // calculate sample time - float Ts = (_micros() - velocity_calc_timestamp)*1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // current angle - float angle_c = getAngle(); - // velocity calculation - float vel = (angle_c - angle_prev)/Ts; - - // save variables for future pass - angle_prev = angle_c; - velocity_calc_timestamp = _micros(); - return vel; -} - -// set current angle as zero angle -// return the angle [rad] difference -float MagneticSensor::initRelativeZero(){ - float angle_offset = -getAngle(); - zero_offset = getRawCount(); - - // angle tracking variables - full_rotation_offset = 0; - return angle_offset; -} -// set absolute zero angle as zero angle -// return the angle [rad] difference -float MagneticSensor::initAbsoluteZero(){ - float rotation = -(int)zero_offset; - // init absolute zero - zero_offset = 0; - - // angle tracking variables - full_rotation_offset = 0; - // return offset in radians - return rotation / (float)cpr * _2PI; -} -// returns 0 if it has no absolute 0 measurement -// 0 - incremental encoder without index -// 1 - encoder with index & magnetic sensors -int MagneticSensor::hasAbsoluteZero(){ - return 1; -} -// returns 0 if it does need search for absolute zero -// 0 - magnetic sensor -// 1 - ecoder with index -int MagneticSensor::needsAbsoluteZeroSearch(){ - return 0; -} - - -// function reading the raw counter of the magnetic sensor -int MagneticSensor::getRawCount(){ - return (int)MagneticSensor::read(angle_register); -} - -// SPI functions -/** - * Utility function used to calculate even parity of word - */ -byte MagneticSensor::spiCalcEvenParity(word value){ - byte cnt = 0; - byte i; - - for (i = 0; i < 16; i++) - { - if (value & 0x1) cnt++; - value >>= 1; - } - return cnt & 0x1; -} - - /* - * Read a register from the sensor - * Takes the address of the register as a 16 bit word - * Returns the value of the register - */ -word MagneticSensor::read(word angle_register){ - word command = 0b0100000000000000; // PAR=0 R/W=R - command = command | angle_register; - - //Add a parity bit on the the MSB - command |= ((word)spiCalcEvenParity(command)<<15); - - //Split the command into two bytes - byte right_byte = command & 0xFF; - byte left_byte = ( command >> 8 ) & 0xFF; - - -#if !defined(_STM32_DEF_) // if not stm chips - //SPI - begin transaction - SPI.beginTransaction(settings); -#endif - //SPI - begin transaction - //SPI.beginTransaction(settings); - - //Send the command - digitalWrite(chip_select_pin, LOW); - digitalWrite(chip_select_pin, LOW); - SPI.transfer(left_byte); - SPI.transfer(right_byte); - digitalWrite(chip_select_pin,HIGH); - digitalWrite(chip_select_pin,HIGH); - - delayMicroseconds(10); - - //Now read the response - digitalWrite(chip_select_pin, LOW); - digitalWrite(chip_select_pin, LOW); - left_byte = SPI.transfer(0x00); - right_byte = SPI.transfer(0x00); - digitalWrite(chip_select_pin, HIGH); - digitalWrite(chip_select_pin,HIGH); - -#if !defined(_STM32_DEF_) // if not stm chips - //SPI - end transaction - SPI.endTransaction(); -#endif - - // Return the data, stripping the parity and error bits - return (( ( left_byte & 0xFF ) << 8 ) | ( right_byte & 0xFF )) & ~0xC000; -} - -/** - * Closes the SPI connection - * SPI has an internal SPI-device counter, for each init()-call the close() function must be called exactly 1 time - */ -void MagneticSensor::close(){ - SPI.end(); -} diff --git a/src/MagneticSensor.h b/src/MagneticSensor.h deleted file mode 100644 index 90b6b291..00000000 --- a/src/MagneticSensor.h +++ /dev/null @@ -1,79 +0,0 @@ -#ifndef MAGNETICSENSOR_LIB_H -#define MAGNETICSENSOR_LIB_H - -#include "Arduino.h" -#include -#include "FOCutils.h" -#include "Sensor.h" - -#define DEF_ANGLE_REGISTAR 0x3FFF - -class MagneticSensor: public Sensor{ - public: - /** - * MagneticSensor class constructor - * @param cs SPI chip select pin - * @param cpr counts per revolution - * @param angle_register (optional) angle read register - default 0x3FFF - */ - MagneticSensor(int cs, float cpr, int angle_register = 0); - - - /** sensor initialise pins */ - void init(); - - // implementation of abstract functions of the Sensor class - /** get current angle (rad) */ - float getAngle(); - /** get current angular velocity (rad/s) **/ - float getVelocity(); - /** - * set current angle as zero angle - * return the angle [rad] difference - */ - float initRelativeZero(); - /** - * set absolute zero angle as zero angle - * return the angle [rad] difference - */ - float initAbsoluteZero(); - /** returns 1 because it is the absolute sensor */ - int hasAbsoluteZero(); - /** returns 0 maning it doesn't need search for absolute zero */ - int needsAbsoluteZeroSearch(); - - - private: - float cpr; //!< Maximum range of the magnetic sensor - // spi variables - int angle_register; //!< SPI angle register to read - int chip_select_pin; //!< SPI chip select pin - SPISettings settings; //!< SPI settings variable - // spi functions - /** Stop SPI communication */ - void close(); - /** Read one SPI register value */ - word read(word angle_register); - /** Calculate parity value */ - byte spiCalcEvenParity(word value); - - - word zero_offset; //!< user defined zero offset - /** - * Function getting current angle register value - * it uses angle_register variable - */ - int getRawCount(); - - // total angle tracking variables - float full_rotation_offset; //! (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; - // save the current angle value for the next steps - // in order to know if overflow happened - angle_data_prev = angle_data; - - // zero offset adding - angle_data -= (int)zero_offset; - // return the full angle - // (number of full rotations)*2PI + current sensor angle - return full_rotation_offset + ( angle_data / (float)cpr) * _2PI; -} - -// Shaft velocity calculation -float MagneticSensorI2C::getVelocity(){ - // calculate sample time - float Ts = (_micros() - velocity_calc_timestamp)*1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // current angle - float angle_c = getAngle(); - // velocity calculation - float vel = (angle_c - angle_prev)/Ts; - - // save variables for future pass - angle_prev = angle_c; - velocity_calc_timestamp = _micros(); - return vel; -} - -// set current angle as zero angle -// return the angle [rad] difference -float MagneticSensorI2C::initRelativeZero(){ - float angle_offset = -getAngle(); - zero_offset = getRawCount(); - - // angle tracking variables - full_rotation_offset = 0; - return angle_offset; -} -// set absolute zero angle as zero angle -// return the angle [rad] difference -float MagneticSensorI2C::initAbsoluteZero(){ - float rotation = -(int)zero_offset; - // init absolute zero - zero_offset = 0; - - // angle tracking variables - full_rotation_offset = 0; - // return offset in radians - return rotation / (float)cpr * _2PI; -} -// returns 0 if it has no absolute 0 measurement -// 0 - incremental encoder without index -// 1 - encoder with index & magnetic sensors -int MagneticSensorI2C::hasAbsoluteZero(){ - return 1; -} -// returns 0 if it does need search for absolute zero -// 0 - magnetic sensor -// 1 - ecoder with index -int MagneticSensorI2C::needsAbsoluteZeroSearch(){ - return 0; -} - - -// function reading the raw counter of the magnetic sensor -int MagneticSensorI2C::getRawCount(){ - return (int)MagneticSensorI2C::read(angle_register_msb); -} - -// I2C functions -/* -* Read a register from the sensor -* Takes the address of the register as a uint8_t -* Returns the value of the register -*/ -int MagneticSensorI2C::read(uint8_t angle_reg_msb) { - // read the angle register first MSB then LSB - byte readArray[2]; - uint16_t readValue = 0; - // notify the device that is aboout to be read - Wire.beginTransmission(chip_address); - Wire.write(angle_reg_msb); - Wire.endTransmission(false); - - // read the data msb and lsb - Wire.requestFrom(chip_address, (uint8_t)2); - for (byte i=0; i < 2; i++) { - readArray[i] = Wire.read(); - } - - // depending on the sensor architecture there are different combinations of - // LSB and MSB register used bits - // AS5600 uses 0..7 LSB and 8..11 MSB - // AS5048 uses 0..5 LSB and 6..13 MSB - readValue = ( readArray[1] & lsb_mask ); - readValue += ( ( readArray[0] & msb_mask ) << lsb_used ); - return readValue; -} diff --git a/src/MagneticSensorI2C.h b/src/MagneticSensorI2C.h deleted file mode 100644 index c5dc3489..00000000 --- a/src/MagneticSensorI2C.h +++ /dev/null @@ -1,78 +0,0 @@ -#ifndef MAGNETICSENSORI2C_LIB_H -#define MAGNETICSENSORI2C_LIB_H - -#include "Arduino.h" -#include -#include "FOCutils.h" -#include "Sensor.h" - - -class MagneticSensorI2C: public Sensor{ - public: - /** - * MagneticSensorI2C class constructor - * @param chip_address I2C chip address - * @param bits number of bits of the sensor resolution - * @param angle_register_msb angle read register msb - * @param _bits_used_msb number of used bits in msb - */ - MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _msb_bits_used); - - - /** sensor initialise pins */ - void init(); - - // implementation of abstract functions of the Sensor class - /** get current angle (rad) */ - float getAngle(); - /** get current angular velocity (rad/s) **/ - float getVelocity(); - /** - * set current angle as zero angle - * return the angle [rad] difference - */ - float initRelativeZero(); - /** - * set absolute zero angle as zero angle - * return the angle [rad] difference - */ - float initAbsoluteZero(); - /** returns 1 because it is the absolute sensor */ - int hasAbsoluteZero(); - /** returns 0 maning it doesn't need search for absolute zero */ - int needsAbsoluteZeroSearch(); - - - private: - float cpr; //!< Maximum range of the magnetic sensor - uint16_t lsb_used; //!< Number of bits used in LSB register - uint8_t lsb_mask; - uint8_t msb_mask; - - // I2C variables - uint8_t angle_register_msb; //!< I2C angle register to read - uint8_t chip_address; //!< I2C chip select pins - - // I2C functions - /** Read one I2C register value */ - int read(uint8_t angle_register_msb); - - word zero_offset; //!< user defined zero offset - /** - * Function getting current angle register value - * it uses angle_register variable - */ - int getRawCount(); - - // total angle tracking variables - float full_rotation_offset; //! (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; - // save the current angle value for the next steps - // in order to know if overflow happened - angle_data_prev = angle_data; - - // zero offset adding - angle_data -= (int)zero_offset; - // return the full angle - // (number of full rotations)*2PI + current sensor angle - return full_rotation_offset + ( angle_data / (float)cpr) * _2PI; -} - -// Shaft velocity calculation -float MagneticSensorSPI::getVelocity(){ - // calculate sample time - float Ts = (_micros() - velocity_calc_timestamp)*1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // current angle - float angle_c = getAngle(); - // velocity calculation - float vel = (angle_c - angle_prev)/Ts; - - // save variables for future pass - angle_prev = angle_c; - velocity_calc_timestamp = _micros(); - return vel; -} - -// set current angle as zero angle -// return the angle [rad] difference -float MagneticSensorSPI::initRelativeZero(){ - float angle_offset = -getAngle(); - zero_offset = getRawCount(); - - // angle tracking variables - full_rotation_offset = 0; - return angle_offset; -} -// set absolute zero angle as zero angle -// return the angle [rad] difference -float MagneticSensorSPI::initAbsoluteZero(){ - float rotation = -(int)zero_offset; - // init absolute zero - zero_offset = 0; - - // angle tracking variables - full_rotation_offset = 0; - // return offset in radians - return rotation / (float)cpr * _2PI; -} -// returns 0 if it has no absolute 0 measurement -// 0 - incremental encoder without index -// 1 - encoder with index & magnetic sensors -int MagneticSensorSPI::hasAbsoluteZero(){ - return 1; -} -// returns 0 if it does need search for absolute zero -// 0 - magnetic sensor -// 1 - ecoder with index -int MagneticSensorSPI::needsAbsoluteZeroSearch(){ - return 0; -} - - -// function reading the raw counter of the magnetic sensor -int MagneticSensorSPI::getRawCount(){ - return (int)MagneticSensorSPI::read(angle_register); -} - -// SPI functions -/** - * Utility function used to calculate even parity of word - */ -byte MagneticSensorSPI::spiCalcEvenParity(word value){ - byte cnt = 0; - byte i; - - for (i = 0; i < 16; i++) - { - if (value & 0x1) cnt++; - value >>= 1; - } - return cnt & 0x1; -} - - /* - * Read a register from the sensor - * Takes the address of the register as a 16 bit word - * Returns the value of the register - */ -word MagneticSensorSPI::read(word angle_register){ - word command = 0b0100000000000000; // PAR=0 R/W=R - command = command | angle_register; - - //Add a parity bit on the the MSB - command |= ((word)spiCalcEvenParity(command)<<15); - - //Split the command into two bytes - byte right_byte = command & 0xFF; - byte left_byte = ( command >> 8 ) & 0xFF; - - -#if !defined(_STM32_DEF_) // if not stm chips - //SPI - begin transaction - SPI.beginTransaction(settings); -#endif - //SPI - begin transaction - //SPI.beginTransaction(settings); - - //Send the command - digitalWrite(chip_select_pin, LOW); - digitalWrite(chip_select_pin, LOW); - SPI.transfer(left_byte); - SPI.transfer(right_byte); - digitalWrite(chip_select_pin,HIGH); - digitalWrite(chip_select_pin,HIGH); - - delayMicroseconds(10); - - //Now read the response - digitalWrite(chip_select_pin, LOW); - digitalWrite(chip_select_pin, LOW); - left_byte = SPI.transfer(0x00); - right_byte = SPI.transfer(0x00); - digitalWrite(chip_select_pin, HIGH); - digitalWrite(chip_select_pin,HIGH); - -#if !defined(_STM32_DEF_) // if not stm chips - //SPI - end transaction - SPI.endTransaction(); -#endif - - // Return the data, stripping the parity and error bits - return (( ( left_byte & 0xFF ) << 8 ) | ( right_byte & 0xFF )) & ~0xC000; -} - -/** - * Closes the SPI connection - * SPI has an internal SPI-device counter, for each init()-call the close() function must be called exactly 1 time - */ -void MagneticSensorSPI::close(){ - SPI.end(); -} diff --git a/src/MagneticSensorSPI.h b/src/MagneticSensorSPI.h deleted file mode 100644 index da70c0c4..00000000 --- a/src/MagneticSensorSPI.h +++ /dev/null @@ -1,79 +0,0 @@ -#ifndef MAGNETICSENSORSPI_LIB_H -#define MAGNETICSENSORSPI_LIB_H - -#include "Arduino.h" -#include -#include "FOCutils.h" -#include "Sensor.h" - -#define DEF_ANGLE_REGISTAR 0x3FFF - -class MagneticSensorSPI: public Sensor{ - public: - /** - * MagneticSensorSPI class constructor - * @param cs SPI chip select pin - * @param bit_resolution sensor resolution bit number - * @param angle_register (optional) angle read register - default 0x3FFF - */ - MagneticSensorSPI(int cs, float bit_resolution, int angle_register = 0); - - - /** sensor initialise pins */ - void init(); - - // implementation of abstract functions of the Sensor class - /** get current angle (rad) */ - float getAngle(); - /** get current angular velocity (rad/s) **/ - float getVelocity(); - /** - * set current angle as zero angle - * return the angle [rad] difference - */ - float initRelativeZero(); - /** - * set absolute zero angle as zero angle - * return the angle [rad] difference - */ - float initAbsoluteZero(); - /** returns 1 because it is the absolute sensor */ - int hasAbsoluteZero(); - /** returns 0 maning it doesn't need search for absolute zero */ - int needsAbsoluteZeroSearch(); - - - private: - float cpr; //!< Maximum range of the magnetic sensor - // spi variables - int angle_register; //!< SPI angle register to read - int chip_select_pin; //!< SPI chip select pin - SPISettings settings; //!< SPI settings variable - // spi functions - /** Stop SPI communication */ - void close(); - /** Read one SPI register value */ - word read(word angle_register); - /** Calculate parity value */ - byte spiCalcEvenParity(word value); - - - word zero_offset; //!< user defined zero offset - /** - * Function getting current angle register value - * it uses angle_register variable - */ - int getRawCount(); - - // total angle tracking variables - float full_rotation_offset; //! Even harder to find is a stable and simple FOC algorithm code capable of running on Arduino devices. Therefore this is an attempt to: - * - Demystify FOC algorithm and make a robust but simple Arduino library: Arduino SimpleFOC library - * - Develop a modular BLDC driver board: Arduino SimpleFOC shield. - * - * @section features Features - * - Arduino compatible: Arduino library code - * - Easy to setup and configure: - * - Easy hardware configuration - * - Easy tuning the control loops - * - Modular: - * - Supports as many sensors , BLDC motors and driver boards as possible - * - Supports as many application requirements as possible - * - Plug & play: Arduino SimpleFOC shield - * - * @section dependencies Supported Hardware - * - * This library supports any arduino device and it is especially optimized for Arduino UNO boards and - * other Atmega328 boards. But it supports Arrduinio MEGA boards and similar. - * - * From the version 1.3.0 it will support the STM32 boards such as Bluepill and Nucelo devices.
- * The programming is done the same way as for the Arduino UNO but stm32 devices require STM32Duino package.
- * You can download it directly from library manager. - * - * @section example_code Example code - * @code -#include - -// initialize the motor -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); -// initialize the encoder -Encoder encoder = Encoder(2, 3, 2048); -// channel A and B callbacks -void doA(){encoder.handleA();} -void doB(){encoder.handleB();} - - -void setup() { - // initialize encoder hardware - encoder.init(); - // hardware interrupt enable - encoder.enableInterrupts(doA, doB); - - // set control loop type to be used - motor.controller = ControlType::velocity; - - // use monitoring with the BLDCMotor - Serial.begin(115200); - // monitoring port - motor.useMonitoring(Serial); - - // link the motor to the sensor - motor.linkSensor(&encoder); - - // initialize motor - motor.init(); - // align encoder and start FOC - motor.initFOC(); -} - -void loop() { - // FOC algorithm function - motor.loopFOC(); - - // velocity control loop function - // setting the target velocity or 2rad/s - motor.move(2); - - // monitoring function outputting motor variables to the serial terminal - motor.monitor(); -} - * @endcode - * - * @section license License - * - * MIT license, all text here must be included in any redistribution. - * - */ - -#ifndef SIMPLEFOC_H -#define SIMPLEFOC_H - -#include "FOCutils.h" -#include "Sensor.h" -#include "Encoder.h" -#include "MagneticSensorSPI.h" -#include "MagneticSensorI2C.h" -#include "BLDCMotor.h" - -#endif diff --git a/src/defaults.h b/src/defaults.h deleted file mode 100644 index 5bcb0118..00000000 --- a/src/defaults.h +++ /dev/null @@ -1,17 +0,0 @@ -// default configuration values -// change this file to optimal values for your application - -#define DEF_POWER_SUPPLY 12.0 //!< default power supply voltage -// velocity PI controller params -#define DEF_PI_VEL_P 0.5 //!< default PI controller P value -#define DEF_PI_VEL_I 10 //!< default PI controller I value -#define DEF_PI_VEL_U_RAMP 1000 //!< default PI controller voltage ramp value -// angle P params -#define DEF_P_ANGLE_P 20 //!< default P controller P value -#define DEF_P_ANGLE_VEL_LIM 20 //!< angle velocity limit default -// index search -#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 //!< default index search velocity -// align voltage -#define DEF_VOLTAGE_SENSOR_ALIGN 6.0 //!< default voltage for sensor and motor zero alignemt -// low pass filter velocity -#define DEF_VEL_FILTER_Tf 0.005 //!< default velocity filter time constant \ No newline at end of file From 82a365a153c87184432724605569c72ee581eb04 Mon Sep 17 00:00:00 2001 From: askuric Date: Sat, 1 Aug 2020 09:04:36 +0200 Subject: [PATCH 51/65] FIX forgotten BLDCMotor.cpp --- arduino_foc_minimal_encoder/BLDCMotor.cpp | 589 ++++++++++++++++++ .../arduino_foc_minimal_encoder.ino | 3 +- 2 files changed, 590 insertions(+), 2 deletions(-) create mode 100644 arduino_foc_minimal_encoder/BLDCMotor.cpp diff --git a/arduino_foc_minimal_encoder/BLDCMotor.cpp b/arduino_foc_minimal_encoder/BLDCMotor.cpp new file mode 100644 index 00000000..a826a366 --- /dev/null +++ b/arduino_foc_minimal_encoder/BLDCMotor.cpp @@ -0,0 +1,589 @@ +#include "BLDCMotor.h" + +// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - phA, phB, phC - motor A,B,C phase pwm pins +// - pp - pole pair number +// - cpr - counts per rotation number (cpm=ppm*4) +// - enable pin - (optional input) +BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +{ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + pole_pairs = pp; + + // enable_pin pin + enable_pin = en; + + // Power supply voltage + voltage_power_supply = DEF_POWER_SUPPLY; + + // Velocity loop config + // PI controller constant + PI_velocity.P = DEF_PI_VEL_P; + PI_velocity.I = DEF_PI_VEL_I; + PI_velocity.timestamp = _micros(); + PI_velocity.voltage_limit = voltage_power_supply; + PI_velocity.voltage_ramp = DEF_PI_VEL_U_RAMP; + PI_velocity.voltage_prev = 0; + PI_velocity.tracking_error_prev = 0; + + // velocity low pass filter + LPF_velocity.Tf = DEF_VEL_FILTER_Tf; + LPF_velocity.timestamp = _micros(); + LPF_velocity.prev = 0; + + // position loop config + // P controller constant + P_angle.P = DEF_P_ANGLE_P; + // maximum angular velocity to be used for positioning + P_angle.velocity_limit = DEF_P_ANGLE_VEL_LIM; + + // index search velocity + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; + + // electric angle of the zero angle + zero_electric_angle = 0; + + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + + // default target value + target = 0; + + //monitor_port + monitor_port = nullptr; +} + +// init hardware pins +void BLDCMotor::init() { + if(monitor_port) monitor_port->println("MONITOR: Initialize the motor pins."); + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(hasEnable()) pinMode(enable_pin, OUTPUT); + + if(monitor_port) monitor_port->println("MONITOR: Set high frequency PWM."); + // Increase PWM frequency to 32 kHz + // make silent + _setPwmFrequency(pwmA); + _setPwmFrequency(pwmB); + _setPwmFrequency(pwmC); + + // sanity check for the voltage limit configuration + if(PI_velocity.voltage_limit > voltage_power_supply) PI_velocity.voltage_limit = voltage_power_supply; + + _delay(500); + // enable motor + if(monitor_port) monitor_port->println("MONITOR: Enabling motor."); + enable(); + _delay(500); + +} + + +// disable motor driver +void BLDCMotor::disable() +{ + // disable the driver - if enable_pin pin available + if (hasEnable()) digitalWrite(enable_pin, LOW); + // set zero to PWM + setPwm(pwmA, 0); + setPwm(pwmB, 0); + setPwm(pwmC, 0); +} +// enable motor driver +void BLDCMotor::enable() +{ + // set zero to PWM + setPwm(pwmA, 0); + setPwm(pwmB, 0); + setPwm(pwmC, 0); + // enable_pin the driver - if enable_pin pin available + if (hasEnable()) digitalWrite(enable_pin, HIGH); + +} + +void BLDCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} + + +// Encoder alignment to electrical 0 angle +int BLDCMotor::alignSensor() { + if(monitor_port) monitor_port->println("MONITOR: Align the sensor's and motor electrical 0 angle."); + // align the electrical phases of the motor and sensor + // set angle -90 degrees + setPhaseVoltage(voltage_sensor_align, _3PI_2); + // let the motor stabilize for 3 sec + _delay(3000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0,0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MONITOR: Error: Absolute zero not found!"); + if(exit_flag> 0 ) monitor_port->println("MONITOR: Success: Absolute zero found!"); + else monitor_port->println("MONITOR: Absolute zero not available!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int BLDCMotor::absoluteZeroAlign() { + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + if(monitor_port) monitor_port->println("MONITOR: Aligning the absolute zero."); + + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MONITOR: Searching for absolute zero."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = velocityPI(velocity_index_search - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); + + // align absolute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = electricAngle(zero_offset); + } + // return bool if zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +/** + State calculation methods +*/ +// shaft angle calculation +float BLDCMotor::shaftAngle() { + return sensor->getAngle(); +} +// shaft velocity calculation +float BLDCMotor::shaftVelocity() { + float Ts = (_micros() - LPF_velocity.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + // calculate the filtering + float alpha = LPF_velocity.Tf/(LPF_velocity.Tf + Ts); + float vel = alpha*LPF_velocity.prev + (1-alpha)*sensor->getVelocity(); + // save the variables + LPF_velocity.prev = vel; + LPF_velocity.timestamp = _micros(); + return vel; +} +// Electrical angle calculation +float BLDCMotor::electricAngle(float shaftAngle) { + //return normalizeAngle(shaftAngle * pole_pairs); + return (shaftAngle * pole_pairs); +} + +/** + FOC functions +*/ +// FOC initialization function +int BLDCMotor::initFOC() { + // sensor and motor alignment + _delay(500); + int exit_flag = alignSensor(); + _delay(500); + + if(monitor_port) monitor_port->println("MONITOR: FOC init finished - motor ready."); + + return exit_flag; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void BLDCMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); +} + +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function +// - if target is not set it uses motor.target value +void BLDCMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; + // get angular velocity + shaft_velocity = shaftVelocity(); + // choose control loop + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = positionP( shaft_angle_sp - shaft_angle ); + voltage_q = velocityPI(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // include velocity loop + shaft_velocity_sp = target; + voltage_q = velocityPI(shaft_velocity_sp - shaft_velocity); + break; + } +} + + +// Method using FOC to set Uq to the motor at the optimal angle +// Function implementing Space Vector PWM and Sine PWM algorithms +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) +void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { + switch (foc_modulation) + { + case FOCModulationType::SinePWM : + // Sinusoidal PWM modulation + // Inverse Park + Clarke transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + + // Clarke transform + Ua = Ualpha + voltage_power_supply/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + break; + + case FOCModulationType::SpaceVectorPWM : + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // https://www.youtube.com/watch?v=QMSWUMEAejg + + // if negative voltages change inverse the phase + // angle + 180degrees + if(Uq < 0) angle_el += _PI; + Uq = abs(Uq); + + // angle normalisation in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = normalizeAngle(angle_el + zero_electric_angle + _PI_2); + + // find the sector we are in currently + int sector = floor(angle_el / _PI_3) + 1; + // calculate the duty cycles + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el); + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3); + // two versions possible + // centered around voltage_power_supply/2 + float T0 = 1 - T1 - T2; + // pulled to 0 - better for low power supply voltage + //T0 = 0; + + // calculate the duty cycles(times) + float Ta,Tb,Tc; + switch(sector){ + case 1: + Ta = T1 + T2 + T0/2; + Tb = T2 + T0/2; + Tc = T0/2; + break; + case 2: + Ta = T1 + T0/2; + Tb = T1 + T2 + T0/2; + Tc = T0/2; + break; + case 3: + Ta = T0/2; + Tb = T1 + T2 + T0/2; + Tc = T2 + T0/2; + break; + case 4: + Ta = T0/2; + Tb = T1+ T0/2; + Tc = T1 + T2 + T0/2; + break; + case 5: + Ta = T2 + T0/2; + Tb = T0/2; + Tc = T1 + T2 + T0/2; + break; + case 6: + Ta = T1 + T2 + T0/2; + Tb = T0/2; + Tc = T1 + T0/2; + break; + default: + // possible error state + Ta = 0; + Tb = 0; + Tc = 0; + } + + // calculate the phase voltages + Ua = Ta*Uq; + Ub = Tb*Uq; + Uc = Tc*Uq; + break; + } + + // set the voltages in hardware + setPwm(pwmA, Ua); + setPwm(pwmB, Ub); + setPwm(pwmC, Uc); +} + + + + +// Set voltage to the pwm pin +// - function a bit optimized to get better performance +void BLDCMotor::setPwm(int pinPwm, float U) { + // max value + float U_max = voltage_power_supply; + + // sets the voltage [0,12V(U_max)] to pwm [0,255] + // - U_max you can set in header file - default 12V + int U_pwm = 255.0 * U / U_max; + + // limit the values between 0 and 255 + U_pwm = (U_pwm < 0) ? 0 : (U_pwm >= 255) ? 255 : U_pwm; + + analogWrite(pinPwm, U_pwm); +} + +/** + Utility functions +*/ +// normalizing radian angle to [0,2PI] +float BLDCMotor::normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} +// determining if the enable pin has been provided +int BLDCMotor::hasEnable(){ + return enable_pin != NOT_SET; +} + + +/** + Motor control functions +*/ +// PI controller function +float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){ + float Ts = (_micros() - cont.timestamp) * 1e-6; + + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s)e(s) + // Tustin transform of the PI controller ( a bit optimized ) + // uk = uk_1 + (I*Ts/2 + P)*ek + (I*Ts/2 - P)*ek_1 + float tmp = cont.I*Ts*0.5; + float voltage = cont.voltage_prev + (tmp + cont.P) * tracking_error + (tmp - cont.P) * cont.tracking_error_prev; + + // antiwindup - limit the output voltage_q + if (abs(voltage) > cont.voltage_limit) voltage = voltage > 0 ? cont.voltage_limit : -cont.voltage_limit; + // limit the acceleration by ramping the the voltage + float d_voltage = voltage - cont.voltage_prev; + if (abs(d_voltage)/Ts > cont.voltage_ramp) voltage = d_voltage > 0 ? cont.voltage_prev + cont.voltage_ramp*Ts : cont.voltage_prev - cont.voltage_ramp*Ts; + + + cont.voltage_prev = voltage; + cont.tracking_error_prev = tracking_error; + cont.timestamp = _micros(); + return voltage; +} +// velocity control loop PI controller +float BLDCMotor::velocityPI(float tracking_error) { + return controllerPI(tracking_error, PI_velocity); +} + +// P controller for position control loop +float BLDCMotor::positionP(float ek) { + // calculate the target velocity from the position error + float velocity_target = P_angle.P * ek; + // constrain velocity target value + if (abs(velocity_target) > P_angle.velocity_limit) velocity_target = velocity_target > 0 ? P_angle.velocity_limit : -P_angle.velocity_limit; + return velocity_target; +} + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void BLDCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MONITOR: Serial monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void BLDCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int BLDCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("PI velocity P: "); + if(!GET) PI_velocity.P = value; + if(monitor_port) monitor_port->println(PI_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("PI velocity I: "); + if(!GET) PI_velocity.I = value; + if(monitor_port) monitor_port->println(PI_velocity.I); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("PI velocity voltage limit: "); + if(!GET)PI_velocity.voltage_limit = value; + if(monitor_port) monitor_port->println(PI_velocity.voltage_limit); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("PI velocity voltage ramp: "); + if(!GET) PI_velocity.voltage_ramp = value; + if(monitor_port) monitor_port->println(PI_velocity.voltage_ramp); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("LPF velocity time constant: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print("P angle P value: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("P angle velocity limit: "); + if(!GET) P_angle.velocity_limit = value; + if(monitor_port) monitor_port->println(P_angle.velocity_limit); + break; + case 'T': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("P angle velocity limit: "); + if(!GET) P_angle.velocity_limit = value; + if(monitor_port) monitor_port->println(P_angle.velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Contoller type: "); + + if(GET){ // if get commang + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} + + diff --git a/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino b/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino index 41e29569..4f06a4a1 100644 --- a/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino +++ b/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino @@ -38,7 +38,6 @@ * - 3: current target value * */ - #include "BLDCMotor.h" #include "Encoder.h" @@ -46,7 +45,7 @@ // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11,8); +BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); //Encoder(int encA, int encB , int cpr, int index) // - encA, encB - encoder A and B pins From e628c61f700e0bd2e259352556a8a5915a455ad7 Mon Sep 17 00:00:00 2001 From: askuric Date: Mon, 10 Aug 2020 18:57:57 +0200 Subject: [PATCH 52/65] FEAT updated to the version 1.4.1. - recolved memory issues + support for esp32 --- arduino_foc_minimal_encoder/BLDCMotor.cpp | 104 +++++----- arduino_foc_minimal_encoder/BLDCMotor.h | 11 +- arduino_foc_minimal_encoder/FOCutils.cpp | 184 ++++++++++++++---- arduino_foc_minimal_encoder/FOCutils.h | 31 ++- arduino_foc_minimal_magnetic/BLDCMotor.cpp | 104 +++++----- arduino_foc_minimal_magnetic/BLDCMotor.h | 11 +- arduino_foc_minimal_magnetic/FOCutils.cpp | 184 ++++++++++++++---- arduino_foc_minimal_magnetic/FOCutils.h | 31 ++- .../MagneticSensorI2C.cpp | 153 --------------- 9 files changed, 474 insertions(+), 339 deletions(-) delete mode 100644 arduino_foc_minimal_magnetic/MagneticSensorI2C.cpp diff --git a/arduino_foc_minimal_encoder/BLDCMotor.cpp b/arduino_foc_minimal_encoder/BLDCMotor.cpp index a826a366..fd574804 100644 --- a/arduino_foc_minimal_encoder/BLDCMotor.cpp +++ b/arduino_foc_minimal_encoder/BLDCMotor.cpp @@ -60,26 +60,24 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // init hardware pins void BLDCMotor::init() { - if(monitor_port) monitor_port->println("MONITOR: Initialize the motor pins."); + if(monitor_port) monitor_port->println("MOT: Init pins."); // PWM pins pinMode(pwmA, OUTPUT); pinMode(pwmB, OUTPUT); pinMode(pwmC, OUTPUT); if(hasEnable()) pinMode(enable_pin, OUTPUT); - if(monitor_port) monitor_port->println("MONITOR: Set high frequency PWM."); + if(monitor_port) monitor_port->println("MOT: PWM config."); // Increase PWM frequency to 32 kHz // make silent - _setPwmFrequency(pwmA); - _setPwmFrequency(pwmB); - _setPwmFrequency(pwmC); + _setPwmFrequency(pwmA, pwmB, pwmC); // sanity check for the voltage limit configuration if(PI_velocity.voltage_limit > voltage_power_supply) PI_velocity.voltage_limit = voltage_power_supply; _delay(500); // enable motor - if(monitor_port) monitor_port->println("MONITOR: Enabling motor."); + if(monitor_port) monitor_port->println("MOT: Enable."); enable(); _delay(500); @@ -92,17 +90,13 @@ void BLDCMotor::disable() // disable the driver - if enable_pin pin available if (hasEnable()) digitalWrite(enable_pin, LOW); // set zero to PWM - setPwm(pwmA, 0); - setPwm(pwmB, 0); - setPwm(pwmC, 0); + setPwm(0, 0, 0); } // enable motor driver void BLDCMotor::enable() { // set zero to PWM - setPwm(pwmA, 0); - setPwm(pwmB, 0); - setPwm(pwmC, 0); + setPwm(0, 0, 0); // enable_pin the driver - if enable_pin pin available if (hasEnable()) digitalWrite(enable_pin, HIGH); @@ -115,7 +109,7 @@ void BLDCMotor::linkSensor(Sensor* _sensor) { // Encoder alignment to electrical 0 angle int BLDCMotor::alignSensor() { - if(monitor_port) monitor_port->println("MONITOR: Align the sensor's and motor electrical 0 angle."); + if(monitor_port) monitor_port->println("MOT: Align sensor."); // align the electrical phases of the motor and sensor // set angle -90 degrees setPhaseVoltage(voltage_sensor_align, _3PI_2); @@ -131,9 +125,9 @@ int BLDCMotor::alignSensor() { int exit_flag = absoluteZeroAlign(); _delay(500); if(monitor_port){ - if(exit_flag< 0 ) monitor_port->println("MONITOR: Error: Absolute zero not found!"); - if(exit_flag> 0 ) monitor_port->println("MONITOR: Success: Absolute zero found!"); - else monitor_port->println("MONITOR: Absolute zero not available!"); + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); } return exit_flag; } @@ -142,12 +136,13 @@ int BLDCMotor::alignSensor() { // Encoder alignment the absolute zero angle // - to the index int BLDCMotor::absoluteZeroAlign() { - // if no absolute zero return + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return if(!sensor->hasAbsoluteZero()) return 0; - if(monitor_port) monitor_port->println("MONITOR: Aligning the absolute zero."); - if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MONITOR: Searching for absolute zero."); + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); // search the absolute zero with small velocity while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ loopFOC(); @@ -204,7 +199,7 @@ int BLDCMotor::initFOC() { int exit_flag = alignSensor(); _delay(500); - if(monitor_port) monitor_port->println("MONITOR: FOC init finished - motor ready."); + if(monitor_port) monitor_port->println("MOT: Motor ready."); return exit_flag; } @@ -348,28 +343,21 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { } // set the voltages in hardware - setPwm(pwmA, Ua); - setPwm(pwmB, Ub); - setPwm(pwmC, Uc); + setPwm(Ua, Ub, Uc); } // Set voltage to the pwm pin -// - function a bit optimized to get better performance -void BLDCMotor::setPwm(int pinPwm, float U) { - // max value - float U_max = voltage_power_supply; - - // sets the voltage [0,12V(U_max)] to pwm [0,255] - // - U_max you can set in header file - default 12V - int U_pwm = 255.0 * U / U_max; - - // limit the values between 0 and 255 - U_pwm = (U_pwm < 0) ? 0 : (U_pwm >= 255) ? 255 : U_pwm; - - analogWrite(pinPwm, U_pwm); +void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { + // calculate duty cycle + // limited in [0,1] + float dc_a = (Ua < 0) ? 0 : (Ua >= voltage_power_supply) ? 1 : Ua / voltage_power_supply; + float dc_b = (Ub < 0) ? 0 : (Ub >= voltage_power_supply) ? 1 : Ub / voltage_power_supply; + float dc_c = (Uc < 0) ? 0 : (Uc >= voltage_power_supply) ? 1 : Uc / voltage_power_supply; + // hardware specific writing + _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); } /** @@ -434,7 +422,7 @@ float BLDCMotor::positionP(float ek) { // function implementing the monitor_port setter void BLDCMotor::useMonitoring(Print &print){ monitor_port = &print; //operate on the address of print - if(monitor_port ) monitor_port->println("MONITOR: Serial monitor enabled!"); + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); } // utility function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! @@ -478,51 +466,63 @@ int BLDCMotor::command(String user_command) { // parse command values float value = user_command.substring(1).toFloat(); + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'L': // velocity voltage limit change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PI velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" P angle| "); + break; + } + // apply the the command switch(cmd){ case 'P': // velocity P gain change - if(monitor_port) monitor_port->print("PI velocity P: "); + if(monitor_port) monitor_port->print("P: "); if(!GET) PI_velocity.P = value; if(monitor_port) monitor_port->println(PI_velocity.P); break; case 'I': // velocity I gain change - if(monitor_port) monitor_port->print("PI velocity I: "); + if(monitor_port) monitor_port->print("I: "); if(!GET) PI_velocity.I = value; if(monitor_port) monitor_port->println(PI_velocity.I); break; case 'L': // velocity voltage limit change - if(monitor_port) monitor_port->print("PI velocity voltage limit: "); + if(monitor_port) monitor_port->print("volt_limit: "); if(!GET)PI_velocity.voltage_limit = value; if(monitor_port) monitor_port->println(PI_velocity.voltage_limit); break; case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print("PI velocity voltage ramp: "); + if(monitor_port) monitor_port->print("volt_ramp: "); if(!GET) PI_velocity.voltage_ramp = value; if(monitor_port) monitor_port->println(PI_velocity.voltage_ramp); break; case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print("LPF velocity time constant: "); + if(monitor_port) monitor_port->print("Tf: "); if(!GET) LPF_velocity.Tf = value; if(monitor_port) monitor_port->println(LPF_velocity.Tf); break; case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print("P angle P value: "); + if(monitor_port) monitor_port->print(" P: "); if(!GET) P_angle.P = value; if(monitor_port) monitor_port->println(P_angle.P); break; case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print("P angle velocity limit: "); - if(!GET) P_angle.velocity_limit = value; - if(monitor_port) monitor_port->println(P_angle.velocity_limit); - break; - case 'T': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print("P angle velocity limit: "); + if(monitor_port) monitor_port->print("vel_limit: "); if(!GET) P_angle.velocity_limit = value; if(monitor_port) monitor_port->println(P_angle.velocity_limit); break; case 'C': // change control type - if(monitor_port) monitor_port->print("Contoller type: "); + if(monitor_port) monitor_port->print("Control: "); if(GET){ // if get commang switch(controller){ @@ -584,6 +584,4 @@ int BLDCMotor::command(String user_command) { } // return 0 if error and 1 if ok return errorFlag; -} - - +} \ No newline at end of file diff --git a/arduino_foc_minimal_encoder/BLDCMotor.h b/arduino_foc_minimal_encoder/BLDCMotor.h index df95445d..d01ea717 100644 --- a/arduino_foc_minimal_encoder/BLDCMotor.h +++ b/arduino_foc_minimal_encoder/BLDCMotor.h @@ -245,8 +245,15 @@ class BLDCMotor /** Electrical angle calculation */ float electricAngle(float shaftAngle); - /** Set phase voltaget to pwm output */ - void setPwm(int pinPwm, float U); + + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + * @param Uc phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc); // Utility functions /** normalizing radian angle to [0,2PI] */ diff --git a/arduino_foc_minimal_encoder/FOCutils.cpp b/arduino_foc_minimal_encoder/FOCutils.cpp index 04c6cfbf..653c7191 100644 --- a/arduino_foc_minimal_encoder/FOCutils.cpp +++ b/arduino_foc_minimal_encoder/FOCutils.cpp @@ -1,42 +1,159 @@ #include "FOCutils.h" +#if defined(ESP_H) // if ESP32 board +// empty motor slot +#define _EMPTY_SLOT -20 -void _setPwmFrequency(int pin) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other atmega328p chips -// High PWM frequency -// https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pin == 5 || pin == 6 || pin == 9 || pin == 10) { - if (pin == 5 || pin == 6) { - // configure the pwm phase-corrected mode - TCCR0A = ((TCCR0A & 0b11111100) | 0x01); - // set prescaler to 1 - TCCR0B = ((TCCR0B & 0b11110000) | 0x01); - } else { - // set prescaler to 1 - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); +// structure containing motor slot configuration +// this library supports up to 4 motors +typedef struct { + int pinA; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; + mcpwm_io_signals_t mcpwm_c; + +} motor_slots_t; + +// define motor slots array +motor_slots_t esp32_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B + }; + +#endif + + +// function setting the high pwm frequency to the supplied pins +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _setPwmFrequency(const int pinA, const int pinB, const int pinC) { +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pinA == 5 || pinA == 6 || pinB == 5 || pinB == 6 || pinC == 5 || pinC == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pinA == 9 || pinA == 10 || pinB == 9 || pinB == 10 || pinC == 9 || pinC == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pinA == 3 || pinA == 11 || pinB == 3 || pinB == 11 || pinC == 3 || pinC == 11 ) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +#elif defined(_STM32_DEF_) // if stm chips + + analogWrite(pinA, 0); + analogWriteFrequency(50000); // set 50kHz + analogWrite(pinB, 0); + analogWriteFrequency(50000); // set 50kHz + analogWrite(pinC, 0); + analogWriteFrequency(50000); // set 50kHz + +#elif defined(ESP_H) // if esp32 boards + + motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 4; i++){ + if(esp32_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_motor_slots[i].pinA = pinA; + m_slot = esp32_motor_slots[i]; + break; } } - else if (pin == 3 || pin == 11) { - // set prescaler to 1 - TCCR2B = ((TCCR2B & 0b11111000) | 0x01); + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); + + mcpwm_config_t pwm_config; + pwm_config.frequency = 4000000; //frequency = 20000Hz + pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% + pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + _delay(100); + + mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_0); + mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_1); + mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_2); + m_slot.mcpwm_num->clk_cfg.prescale = 0; + + m_slot.mcpwm_num->timer[0].period.prescale = 4; + m_slot.mcpwm_num->timer[1].period.prescale = 4; + m_slot.mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + m_slot.mcpwm_num->timer[0].period.period = 2048; + m_slot.mcpwm_num->timer[1].period.period = 2048; + m_slot.mcpwm_num->timer[2].period.period = 2048; + _delay(1); + m_slot.mcpwm_num->timer[0].period.upmethod = 0; + m_slot.mcpwm_num->timer[1].period.upmethod = 0; + m_slot.mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + m_slot.mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + m_slot.mcpwm_num->timer[0].sync.out_sel = 0; +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + break; + } } -#elif defined(_STM32_DEF_) // if stm chips - analogWrite(pin,0); - analogWriteFrequency(50000); // la valeur par défaut est 20000 Hz +#else // Arduino & STM32 devices + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255*dc_a); + analogWrite(pinB, 255*dc_b); + analogWrite(pinC, 255*dc_c); #endif } + // function buffering delay() // arduino uno function doesn't work well with interrupts void _delay(unsigned long ms){ #if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other atmega328p chips - // return the value based on the prescaler - long t = _micros(); - while((_micros() - t)/1000 < ms){}; + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; #else // regular micros - return delay(ms); + delay(ms); #endif } @@ -56,9 +173,6 @@ unsigned long _micros(){ } -// lookup table for sine calculation in between 0 and 90 degrees -//float sine_array[200] = {0.0000,0.0079,0.0158,0.0237,0.0316,0.0395,0.0473,0.0552,0.0631,0.0710,0.0789,0.0867,0.0946,0.1024,0.1103,0.1181,0.1260,0.1338,0.1416,0.1494,0.1572,0.1650,0.1728,0.1806,0.1883,0.1961,0.2038,0.2115,0.2192,0.2269,0.2346,0.2423,0.2499,0.2575,0.2652,0.2728,0.2804,0.2879,0.2955,0.3030,0.3105,0.3180,0.3255,0.3329,0.3404,0.3478,0.3552,0.3625,0.3699,0.3772,0.3845,0.3918,0.3990,0.4063,0.4135,0.4206,0.4278,0.4349,0.4420,0.4491,0.4561,0.4631,0.4701,0.4770,0.4840,0.4909,0.4977,0.5046,0.5113,0.5181,0.5249,0.5316,0.5382,0.5449,0.5515,0.5580,0.5646,0.5711,0.5775,0.5839,0.5903,0.5967,0.6030,0.6093,0.6155,0.6217,0.6279,0.6340,0.6401,0.6461,0.6521,0.6581,0.6640,0.6699,0.6758,0.6815,0.6873,0.6930,0.6987,0.7043,0.7099,0.7154,0.7209,0.7264,0.7318,0.7371,0.7424,0.7477,0.7529,0.7581,0.7632,0.7683,0.7733,0.7783,0.7832,0.7881,0.7930,0.7977,0.8025,0.8072,0.8118,0.8164,0.8209,0.8254,0.8298,0.8342,0.8385,0.8428,0.8470,0.8512,0.8553,0.8594,0.8634,0.8673,0.8712,0.8751,0.8789,0.8826,0.8863,0.8899,0.8935,0.8970,0.9005,0.9039,0.9072,0.9105,0.9138,0.9169,0.9201,0.9231,0.9261,0.9291,0.9320,0.9348,0.9376,0.9403,0.9429,0.9455,0.9481,0.9506,0.9530,0.9554,0.9577,0.9599,0.9621,0.9642,0.9663,0.9683,0.9702,0.9721,0.9739,0.9757,0.9774,0.9790,0.9806,0.9821,0.9836,0.9850,0.9863,0.9876,0.9888,0.9899,0.9910,0.9920,0.9930,0.9939,0.9947,0.9955,0.9962,0.9969,0.9975,0.9980,0.9985,0.9989,0.9992,0.9995,0.9997,0.9999,1.0000,1.0000}; - // int array instead of float array // 2x storage save (int 2Byte float 4 Byte ) // sin*10000 @@ -72,24 +186,24 @@ int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,110 float _sin(float a){ if(a < _PI_2){ //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; - //return sine_array[(int)(126.6873* a)]; // float array optimised - return 0.0001*sine_array[_round(126.6873* a)]; // int array optimised + //return sine_array[(int)(126.6873* a)]; // float array optimized + return 0.0001*sine_array[_round(126.6873* a)]; // int array optimized }else if(a < _PI){ // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; - //return sine_array[398 - (int)(126.6873*a)]; // float array optimised - return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimised + //return sine_array[398 - (int)(126.6873*a)]; // float array optimized + return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimized }else if(a < _3PI_2){ // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; - //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimised - return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimised + //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimized + return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimized } else { // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; - //return -sine_array[796 - (int)(126.6873*a)]; // float array optimised - return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimised + //return -sine_array[796 - (int)(126.6873*a)]; // float array optimized + return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimized } } -// function approfimating cosine calculaiton by using fixed size array +// function approximating cosine calculation by using fixed size array // ~55us (float array) // ~56us (int array) // precision +-0.005 diff --git a/arduino_foc_minimal_encoder/FOCutils.h b/arduino_foc_minimal_encoder/FOCutils.h index b60978b3..110d1dcc 100644 --- a/arduino_foc_minimal_encoder/FOCutils.h +++ b/arduino_foc_minimal_encoder/FOCutils.h @@ -3,6 +3,15 @@ #include "Arduino.h" + +#if defined(ESP_H) // if esp32 boards + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +#endif + // sign function #define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) #define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) @@ -24,15 +33,17 @@ * High PWM frequency setting function * - hardware specific * - * @param pin pin number to configure + * @param pinA pinA number to configure + * @param pinB pinB number to configure + * @param pinC pinC number to configure */ -void _setPwmFrequency(int pin); +void _setPwmFrequency(int pinA, int pinB, int pinC); /** * Function implementing delay() function in milliseconds * - blocking function * - hardware specific - * + * @param ms number of milliseconds to wait */ void _delay(unsigned long ms); @@ -43,6 +54,20 @@ void _delay(unsigned long ms); */ unsigned long _micros(); +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); + + /** * Function approximating the sine calculation by using fixed size array * - execution time ~40us (Arduino UNO) diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.cpp b/arduino_foc_minimal_magnetic/BLDCMotor.cpp index a826a366..fd574804 100644 --- a/arduino_foc_minimal_magnetic/BLDCMotor.cpp +++ b/arduino_foc_minimal_magnetic/BLDCMotor.cpp @@ -60,26 +60,24 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // init hardware pins void BLDCMotor::init() { - if(monitor_port) monitor_port->println("MONITOR: Initialize the motor pins."); + if(monitor_port) monitor_port->println("MOT: Init pins."); // PWM pins pinMode(pwmA, OUTPUT); pinMode(pwmB, OUTPUT); pinMode(pwmC, OUTPUT); if(hasEnable()) pinMode(enable_pin, OUTPUT); - if(monitor_port) monitor_port->println("MONITOR: Set high frequency PWM."); + if(monitor_port) monitor_port->println("MOT: PWM config."); // Increase PWM frequency to 32 kHz // make silent - _setPwmFrequency(pwmA); - _setPwmFrequency(pwmB); - _setPwmFrequency(pwmC); + _setPwmFrequency(pwmA, pwmB, pwmC); // sanity check for the voltage limit configuration if(PI_velocity.voltage_limit > voltage_power_supply) PI_velocity.voltage_limit = voltage_power_supply; _delay(500); // enable motor - if(monitor_port) monitor_port->println("MONITOR: Enabling motor."); + if(monitor_port) monitor_port->println("MOT: Enable."); enable(); _delay(500); @@ -92,17 +90,13 @@ void BLDCMotor::disable() // disable the driver - if enable_pin pin available if (hasEnable()) digitalWrite(enable_pin, LOW); // set zero to PWM - setPwm(pwmA, 0); - setPwm(pwmB, 0); - setPwm(pwmC, 0); + setPwm(0, 0, 0); } // enable motor driver void BLDCMotor::enable() { // set zero to PWM - setPwm(pwmA, 0); - setPwm(pwmB, 0); - setPwm(pwmC, 0); + setPwm(0, 0, 0); // enable_pin the driver - if enable_pin pin available if (hasEnable()) digitalWrite(enable_pin, HIGH); @@ -115,7 +109,7 @@ void BLDCMotor::linkSensor(Sensor* _sensor) { // Encoder alignment to electrical 0 angle int BLDCMotor::alignSensor() { - if(monitor_port) monitor_port->println("MONITOR: Align the sensor's and motor electrical 0 angle."); + if(monitor_port) monitor_port->println("MOT: Align sensor."); // align the electrical phases of the motor and sensor // set angle -90 degrees setPhaseVoltage(voltage_sensor_align, _3PI_2); @@ -131,9 +125,9 @@ int BLDCMotor::alignSensor() { int exit_flag = absoluteZeroAlign(); _delay(500); if(monitor_port){ - if(exit_flag< 0 ) monitor_port->println("MONITOR: Error: Absolute zero not found!"); - if(exit_flag> 0 ) monitor_port->println("MONITOR: Success: Absolute zero found!"); - else monitor_port->println("MONITOR: Absolute zero not available!"); + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); } return exit_flag; } @@ -142,12 +136,13 @@ int BLDCMotor::alignSensor() { // Encoder alignment the absolute zero angle // - to the index int BLDCMotor::absoluteZeroAlign() { - // if no absolute zero return + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return if(!sensor->hasAbsoluteZero()) return 0; - if(monitor_port) monitor_port->println("MONITOR: Aligning the absolute zero."); - if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MONITOR: Searching for absolute zero."); + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); // search the absolute zero with small velocity while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ loopFOC(); @@ -204,7 +199,7 @@ int BLDCMotor::initFOC() { int exit_flag = alignSensor(); _delay(500); - if(monitor_port) monitor_port->println("MONITOR: FOC init finished - motor ready."); + if(monitor_port) monitor_port->println("MOT: Motor ready."); return exit_flag; } @@ -348,28 +343,21 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { } // set the voltages in hardware - setPwm(pwmA, Ua); - setPwm(pwmB, Ub); - setPwm(pwmC, Uc); + setPwm(Ua, Ub, Uc); } // Set voltage to the pwm pin -// - function a bit optimized to get better performance -void BLDCMotor::setPwm(int pinPwm, float U) { - // max value - float U_max = voltage_power_supply; - - // sets the voltage [0,12V(U_max)] to pwm [0,255] - // - U_max you can set in header file - default 12V - int U_pwm = 255.0 * U / U_max; - - // limit the values between 0 and 255 - U_pwm = (U_pwm < 0) ? 0 : (U_pwm >= 255) ? 255 : U_pwm; - - analogWrite(pinPwm, U_pwm); +void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { + // calculate duty cycle + // limited in [0,1] + float dc_a = (Ua < 0) ? 0 : (Ua >= voltage_power_supply) ? 1 : Ua / voltage_power_supply; + float dc_b = (Ub < 0) ? 0 : (Ub >= voltage_power_supply) ? 1 : Ub / voltage_power_supply; + float dc_c = (Uc < 0) ? 0 : (Uc >= voltage_power_supply) ? 1 : Uc / voltage_power_supply; + // hardware specific writing + _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); } /** @@ -434,7 +422,7 @@ float BLDCMotor::positionP(float ek) { // function implementing the monitor_port setter void BLDCMotor::useMonitoring(Print &print){ monitor_port = &print; //operate on the address of print - if(monitor_port ) monitor_port->println("MONITOR: Serial monitor enabled!"); + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); } // utility function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! @@ -478,51 +466,63 @@ int BLDCMotor::command(String user_command) { // parse command values float value = user_command.substring(1).toFloat(); + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'L': // velocity voltage limit change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PI velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" P angle| "); + break; + } + // apply the the command switch(cmd){ case 'P': // velocity P gain change - if(monitor_port) monitor_port->print("PI velocity P: "); + if(monitor_port) monitor_port->print("P: "); if(!GET) PI_velocity.P = value; if(monitor_port) monitor_port->println(PI_velocity.P); break; case 'I': // velocity I gain change - if(monitor_port) monitor_port->print("PI velocity I: "); + if(monitor_port) monitor_port->print("I: "); if(!GET) PI_velocity.I = value; if(monitor_port) monitor_port->println(PI_velocity.I); break; case 'L': // velocity voltage limit change - if(monitor_port) monitor_port->print("PI velocity voltage limit: "); + if(monitor_port) monitor_port->print("volt_limit: "); if(!GET)PI_velocity.voltage_limit = value; if(monitor_port) monitor_port->println(PI_velocity.voltage_limit); break; case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print("PI velocity voltage ramp: "); + if(monitor_port) monitor_port->print("volt_ramp: "); if(!GET) PI_velocity.voltage_ramp = value; if(monitor_port) monitor_port->println(PI_velocity.voltage_ramp); break; case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print("LPF velocity time constant: "); + if(monitor_port) monitor_port->print("Tf: "); if(!GET) LPF_velocity.Tf = value; if(monitor_port) monitor_port->println(LPF_velocity.Tf); break; case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print("P angle P value: "); + if(monitor_port) monitor_port->print(" P: "); if(!GET) P_angle.P = value; if(monitor_port) monitor_port->println(P_angle.P); break; case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print("P angle velocity limit: "); - if(!GET) P_angle.velocity_limit = value; - if(monitor_port) monitor_port->println(P_angle.velocity_limit); - break; - case 'T': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print("P angle velocity limit: "); + if(monitor_port) monitor_port->print("vel_limit: "); if(!GET) P_angle.velocity_limit = value; if(monitor_port) monitor_port->println(P_angle.velocity_limit); break; case 'C': // change control type - if(monitor_port) monitor_port->print("Contoller type: "); + if(monitor_port) monitor_port->print("Control: "); if(GET){ // if get commang switch(controller){ @@ -584,6 +584,4 @@ int BLDCMotor::command(String user_command) { } // return 0 if error and 1 if ok return errorFlag; -} - - +} \ No newline at end of file diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.h b/arduino_foc_minimal_magnetic/BLDCMotor.h index df95445d..d01ea717 100644 --- a/arduino_foc_minimal_magnetic/BLDCMotor.h +++ b/arduino_foc_minimal_magnetic/BLDCMotor.h @@ -245,8 +245,15 @@ class BLDCMotor /** Electrical angle calculation */ float electricAngle(float shaftAngle); - /** Set phase voltaget to pwm output */ - void setPwm(int pinPwm, float U); + + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + * @param Uc phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc); // Utility functions /** normalizing radian angle to [0,2PI] */ diff --git a/arduino_foc_minimal_magnetic/FOCutils.cpp b/arduino_foc_minimal_magnetic/FOCutils.cpp index 04c6cfbf..653c7191 100644 --- a/arduino_foc_minimal_magnetic/FOCutils.cpp +++ b/arduino_foc_minimal_magnetic/FOCutils.cpp @@ -1,42 +1,159 @@ #include "FOCutils.h" +#if defined(ESP_H) // if ESP32 board +// empty motor slot +#define _EMPTY_SLOT -20 -void _setPwmFrequency(int pin) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other atmega328p chips -// High PWM frequency -// https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pin == 5 || pin == 6 || pin == 9 || pin == 10) { - if (pin == 5 || pin == 6) { - // configure the pwm phase-corrected mode - TCCR0A = ((TCCR0A & 0b11111100) | 0x01); - // set prescaler to 1 - TCCR0B = ((TCCR0B & 0b11110000) | 0x01); - } else { - // set prescaler to 1 - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); +// structure containing motor slot configuration +// this library supports up to 4 motors +typedef struct { + int pinA; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; + mcpwm_io_signals_t mcpwm_c; + +} motor_slots_t; + +// define motor slots array +motor_slots_t esp32_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B + }; + +#endif + + +// function setting the high pwm frequency to the supplied pins +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _setPwmFrequency(const int pinA, const int pinB, const int pinC) { +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pinA == 5 || pinA == 6 || pinB == 5 || pinB == 6 || pinC == 5 || pinC == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pinA == 9 || pinA == 10 || pinB == 9 || pinB == 10 || pinC == 9 || pinC == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pinA == 3 || pinA == 11 || pinB == 3 || pinB == 11 || pinC == 3 || pinC == 11 ) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +#elif defined(_STM32_DEF_) // if stm chips + + analogWrite(pinA, 0); + analogWriteFrequency(50000); // set 50kHz + analogWrite(pinB, 0); + analogWriteFrequency(50000); // set 50kHz + analogWrite(pinC, 0); + analogWriteFrequency(50000); // set 50kHz + +#elif defined(ESP_H) // if esp32 boards + + motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 4; i++){ + if(esp32_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_motor_slots[i].pinA = pinA; + m_slot = esp32_motor_slots[i]; + break; } } - else if (pin == 3 || pin == 11) { - // set prescaler to 1 - TCCR2B = ((TCCR2B & 0b11111000) | 0x01); + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); + + mcpwm_config_t pwm_config; + pwm_config.frequency = 4000000; //frequency = 20000Hz + pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% + pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + _delay(100); + + mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_0); + mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_1); + mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_2); + m_slot.mcpwm_num->clk_cfg.prescale = 0; + + m_slot.mcpwm_num->timer[0].period.prescale = 4; + m_slot.mcpwm_num->timer[1].period.prescale = 4; + m_slot.mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + m_slot.mcpwm_num->timer[0].period.period = 2048; + m_slot.mcpwm_num->timer[1].period.period = 2048; + m_slot.mcpwm_num->timer[2].period.period = 2048; + _delay(1); + m_slot.mcpwm_num->timer[0].period.upmethod = 0; + m_slot.mcpwm_num->timer[1].period.upmethod = 0; + m_slot.mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + m_slot.mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + m_slot.mcpwm_num->timer[0].sync.out_sel = 0; +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + break; + } } -#elif defined(_STM32_DEF_) // if stm chips - analogWrite(pin,0); - analogWriteFrequency(50000); // la valeur par défaut est 20000 Hz +#else // Arduino & STM32 devices + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255*dc_a); + analogWrite(pinB, 255*dc_b); + analogWrite(pinC, 255*dc_c); #endif } + // function buffering delay() // arduino uno function doesn't work well with interrupts void _delay(unsigned long ms){ #if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other atmega328p chips - // return the value based on the prescaler - long t = _micros(); - while((_micros() - t)/1000 < ms){}; + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; #else // regular micros - return delay(ms); + delay(ms); #endif } @@ -56,9 +173,6 @@ unsigned long _micros(){ } -// lookup table for sine calculation in between 0 and 90 degrees -//float sine_array[200] = {0.0000,0.0079,0.0158,0.0237,0.0316,0.0395,0.0473,0.0552,0.0631,0.0710,0.0789,0.0867,0.0946,0.1024,0.1103,0.1181,0.1260,0.1338,0.1416,0.1494,0.1572,0.1650,0.1728,0.1806,0.1883,0.1961,0.2038,0.2115,0.2192,0.2269,0.2346,0.2423,0.2499,0.2575,0.2652,0.2728,0.2804,0.2879,0.2955,0.3030,0.3105,0.3180,0.3255,0.3329,0.3404,0.3478,0.3552,0.3625,0.3699,0.3772,0.3845,0.3918,0.3990,0.4063,0.4135,0.4206,0.4278,0.4349,0.4420,0.4491,0.4561,0.4631,0.4701,0.4770,0.4840,0.4909,0.4977,0.5046,0.5113,0.5181,0.5249,0.5316,0.5382,0.5449,0.5515,0.5580,0.5646,0.5711,0.5775,0.5839,0.5903,0.5967,0.6030,0.6093,0.6155,0.6217,0.6279,0.6340,0.6401,0.6461,0.6521,0.6581,0.6640,0.6699,0.6758,0.6815,0.6873,0.6930,0.6987,0.7043,0.7099,0.7154,0.7209,0.7264,0.7318,0.7371,0.7424,0.7477,0.7529,0.7581,0.7632,0.7683,0.7733,0.7783,0.7832,0.7881,0.7930,0.7977,0.8025,0.8072,0.8118,0.8164,0.8209,0.8254,0.8298,0.8342,0.8385,0.8428,0.8470,0.8512,0.8553,0.8594,0.8634,0.8673,0.8712,0.8751,0.8789,0.8826,0.8863,0.8899,0.8935,0.8970,0.9005,0.9039,0.9072,0.9105,0.9138,0.9169,0.9201,0.9231,0.9261,0.9291,0.9320,0.9348,0.9376,0.9403,0.9429,0.9455,0.9481,0.9506,0.9530,0.9554,0.9577,0.9599,0.9621,0.9642,0.9663,0.9683,0.9702,0.9721,0.9739,0.9757,0.9774,0.9790,0.9806,0.9821,0.9836,0.9850,0.9863,0.9876,0.9888,0.9899,0.9910,0.9920,0.9930,0.9939,0.9947,0.9955,0.9962,0.9969,0.9975,0.9980,0.9985,0.9989,0.9992,0.9995,0.9997,0.9999,1.0000,1.0000}; - // int array instead of float array // 2x storage save (int 2Byte float 4 Byte ) // sin*10000 @@ -72,24 +186,24 @@ int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,110 float _sin(float a){ if(a < _PI_2){ //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; - //return sine_array[(int)(126.6873* a)]; // float array optimised - return 0.0001*sine_array[_round(126.6873* a)]; // int array optimised + //return sine_array[(int)(126.6873* a)]; // float array optimized + return 0.0001*sine_array[_round(126.6873* a)]; // int array optimized }else if(a < _PI){ // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; - //return sine_array[398 - (int)(126.6873*a)]; // float array optimised - return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimised + //return sine_array[398 - (int)(126.6873*a)]; // float array optimized + return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimized }else if(a < _3PI_2){ // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; - //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimised - return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimised + //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimized + return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimized } else { // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; - //return -sine_array[796 - (int)(126.6873*a)]; // float array optimised - return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimised + //return -sine_array[796 - (int)(126.6873*a)]; // float array optimized + return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimized } } -// function approfimating cosine calculaiton by using fixed size array +// function approximating cosine calculation by using fixed size array // ~55us (float array) // ~56us (int array) // precision +-0.005 diff --git a/arduino_foc_minimal_magnetic/FOCutils.h b/arduino_foc_minimal_magnetic/FOCutils.h index b60978b3..110d1dcc 100644 --- a/arduino_foc_minimal_magnetic/FOCutils.h +++ b/arduino_foc_minimal_magnetic/FOCutils.h @@ -3,6 +3,15 @@ #include "Arduino.h" + +#if defined(ESP_H) // if esp32 boards + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +#endif + // sign function #define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) #define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) @@ -24,15 +33,17 @@ * High PWM frequency setting function * - hardware specific * - * @param pin pin number to configure + * @param pinA pinA number to configure + * @param pinB pinB number to configure + * @param pinC pinC number to configure */ -void _setPwmFrequency(int pin); +void _setPwmFrequency(int pinA, int pinB, int pinC); /** * Function implementing delay() function in milliseconds * - blocking function * - hardware specific - * + * @param ms number of milliseconds to wait */ void _delay(unsigned long ms); @@ -43,6 +54,20 @@ void _delay(unsigned long ms); */ unsigned long _micros(); +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); + + /** * Function approximating the sine calculation by using fixed size array * - execution time ~40us (Arduino UNO) diff --git a/arduino_foc_minimal_magnetic/MagneticSensorI2C.cpp b/arduino_foc_minimal_magnetic/MagneticSensorI2C.cpp deleted file mode 100644 index 52778025..00000000 --- a/arduino_foc_minimal_magnetic/MagneticSensorI2C.cpp +++ /dev/null @@ -1,153 +0,0 @@ -#include "MagneticSensorI2C.h" - -// MagneticSensorI2C(uint8_t _chip_address, float _cpr, uint8_t _angle_register_msb) -// @param _chip_address I2C chip address -// @param _bit_resolution bit resolution of the sensor -// @param _angle_register_msb angle read register -// @param _bits_used_msb number of used bits in msb -MagneticSensorI2C::MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _bits_used_msb){ - // chip I2C address - chip_address = _chip_address; - // angle read register of the magnetic sensor - angle_register_msb = _angle_register_msb; - // register maximum value (counts per revolution) - cpr = pow(2,_bit_resolution); - - // depending on the sensor architecture there are different combinations of - // LSB and MSB register used bits - // AS5600 uses 0..7 LSB and 8..11 MSB - // AS5048 uses 0..5 LSB and 6..13 MSB - // used bits in LSB - lsb_used = _bit_resolution - _bits_used_msb; - // extraction masks - lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); - msb_mask = (uint8_t)( (2 << _bits_used_msb) - 1 ); -} - - -void MagneticSensorI2C::init(){ - - //I2C communication begin - Wire.begin(); - - // velocity calculation init - angle_prev = 0; - velocity_calc_timestamp = _micros(); - - // full rotations tracking number - full_rotation_offset = 0; - angle_data_prev = getRawCount(); - zero_offset = 0; -} - -// Shaft angle calculation -// angle is in radians [rad] -float MagneticSensorI2C::getAngle(){ - // raw data from the sensor - float angle_data = getRawCount(); - - // tracking the number of rotations - // in order to expand angle range form [0,2PI] - // to basically infinity - float d_angle = angle_data - angle_data_prev; - // if overflow happened track it as full rotation - if(abs(d_angle) > (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; - // save the current angle value for the next steps - // in order to know if overflow happened - angle_data_prev = angle_data; - - // zero offset adding - angle_data -= (int)zero_offset; - // return the full angle - // (number of full rotations)*2PI + current sensor angle - return full_rotation_offset + ( angle_data / (float)cpr) * _2PI; -} - -// Shaft velocity calculation -float MagneticSensorI2C::getVelocity(){ - // calculate sample time - float Ts = (_micros() - velocity_calc_timestamp)*1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // current angle - float angle_c = getAngle(); - // velocity calculation - float vel = (angle_c - angle_prev)/Ts; - - // save variables for future pass - angle_prev = angle_c; - velocity_calc_timestamp = _micros(); - return vel; -} - -// set current angle as zero angle -// return the angle [rad] difference -float MagneticSensorI2C::initRelativeZero(){ - float angle_offset = -getAngle(); - zero_offset = getRawCount(); - - // angle tracking variables - full_rotation_offset = 0; - return angle_offset; -} -// set absolute zero angle as zero angle -// return the angle [rad] difference -float MagneticSensorI2C::initAbsoluteZero(){ - float rotation = -(int)zero_offset; - // init absolute zero - zero_offset = 0; - - // angle tracking variables - full_rotation_offset = 0; - // return offset in radians - return rotation / (float)cpr * _2PI; -} -// returns 0 if it has no absolute 0 measurement -// 0 - incremental encoder without index -// 1 - encoder with index & magnetic sensors -int MagneticSensorI2C::hasAbsoluteZero(){ - return 1; -} -// returns 0 if it does need search for absolute zero -// 0 - magnetic sensor -// 1 - ecoder with index -int MagneticSensorI2C::needsAbsoluteZeroSearch(){ - return 0; -} - - -// function reading the raw counter of the magnetic sensor -int MagneticSensorI2C::getRawCount(){ - return (int)MagneticSensorI2C::read(angle_register_msb); -} - -// I2C functions -/* -* Read a register from the sensor -* Takes the address of the register as a uint8_t -* Returns the value of the register -*/ -int MagneticSensorI2C::read(uint8_t angle_reg_msb) { - // read the angle register first MSB then LSB - byte readArray[2]; - uint16_t readValue = 0; - // notify the device that is aboout to be read - Wire.beginTransmission(chip_address); - Wire.write(angle_reg_msb); - Wire.endTransmission(false); - - // read the data msb and lsb - Wire.requestFrom(chip_address, (uint8_t)2); - for (byte i=0; i < 2; i++) { - readArray[i] = Wire.read(); - } - - // depending on the sensor architecture there are different combinations of - // LSB and MSB register used bits - // AS5600 uses 0..7 LSB and 8..11 MSB - // AS5048 uses 0..5 LSB and 6..13 MSB - readValue = ( readArray[1] & lsb_mask ); - readValue += ( ( readArray[0] & msb_mask ) << lsb_used ); - return readValue; -} From 037322f702e94168009818dd0355f004bca5c90a Mon Sep 17 00:00:00 2001 From: askuric Date: Wed, 9 Sep 2020 10:25:25 +0200 Subject: [PATCH 53/65] FEAT version 1.5.0 --- README.md | 161 +++- .../BLDCMotor.cpp | 283 +++++-- .../BLDCMotor.h | 67 +- .../Encoder.cpp | 4 +- .../Encoder.h | 8 - .../FOCutils.cpp | 0 .../FOCutils.h | 2 +- library_source/HallSensor.cpp | 186 +++++ library_source/HallSensor.h | 107 +++ library_source/MagneticSensorAnalog.cpp | 109 +++ library_source/MagneticSensorAnalog.h | 82 ++ library_source/MagneticSensorI2C.cpp | 154 ++++ .../MagneticSensorI2C.h | 0 .../MagneticSensorSPI.cpp | 19 +- .../MagneticSensorSPI.h | 0 .../Sensor.h | 20 + .../defaults.h | 9 +- .../BLDCMotor.cpp | 283 +++++-- .../arduino_foc_minimal_encoder}/BLDCMotor.h | 67 +- .../arduino_foc_minimal_encoder/Encoder.cpp | 229 ++++++ .../arduino_foc_minimal_encoder/Encoder.h | 104 +++ .../arduino_foc_minimal_encoder}/FOCutils.cpp | 0 .../arduino_foc_minimal_encoder}/FOCutils.h | 2 +- .../arduino_foc_minimal_encoder}/Sensor.h | 20 + .../arduino_foc_minimal_encoder.ino | 94 +-- .../arduino_foc_minimal_encoder}/defaults.h | 9 +- .../arduino_foc_minimal_hall/BLDCMotor.cpp | 716 ++++++++++++++++++ .../arduino_foc_minimal_hall/BLDCMotor.h | 323 ++++++++ .../arduino_foc_minimal_hall/FOCutils.cpp | 215 ++++++ .../arduino_foc_minimal_hall/FOCutils.h | 86 +++ .../arduino_foc_minimal_hall/HallSensor.cpp | 186 +++++ .../arduino_foc_minimal_hall/HallSensor.h | 107 +++ .../arduino_foc_minimal_hall/Sensor.h | 59 ++ .../arduino_foc_minimal_hall.ino | 155 ++++ .../arduino_foc_minimal_hall/defaults.h | 18 + .../BLDCMotor.cpp | 716 ++++++++++++++++++ .../BLDCMotor.h | 323 ++++++++ .../FOCutils.cpp | 215 ++++++ .../FOCutils.h | 86 +++ .../MagneticSensorI2C.cpp | 154 ++++ .../MagneticSensorI2C.h | 78 ++ .../arduino_foc_minimal_magnetic_i2c/Sensor.h | 59 ++ .../arduino_foc_minimal_magnetic_i2c.ino | 139 ++++ .../defaults.h | 18 + .../BLDCMotor.cpp | 716 ++++++++++++++++++ .../BLDCMotor.h | 323 ++++++++ .../FOCutils.cpp | 215 ++++++ .../FOCutils.h | 86 +++ .../MagneticSensorSPI.cpp | 209 +++++ .../MagneticSensorSPI.h | 79 ++ .../arduino_foc_minimal_magnetic_spi/Sensor.h | 59 ++ .../arduino_foc_minimal_magnetic_spi.ino | 102 +-- .../defaults.h | 18 + .../BLDCMotor.cpp | 716 ++++++++++++++++++ .../arduino_foc_minimal_openloop/BLDCMotor.h | 323 ++++++++ .../arduino_foc_minimal_openloop/FOCutils.cpp | 215 ++++++ .../arduino_foc_minimal_openloop/FOCutils.h | 86 +++ .../arduino_foc_minimal_openloop/Sensor.h | 59 ++ .../arduino_foc_minimal_openloop.ino | 62 ++ .../arduino_foc_minimal_openloop/defaults.h | 18 + 60 files changed, 8585 insertions(+), 373 deletions(-) rename {arduino_foc_minimal_encoder => library_source}/BLDCMotor.cpp (66%) rename {arduino_foc_minimal_encoder => library_source}/BLDCMotor.h (79%) rename {arduino_foc_minimal_encoder => library_source}/Encoder.cpp (98%) rename {arduino_foc_minimal_encoder => library_source}/Encoder.h (95%) rename {arduino_foc_minimal_encoder => library_source}/FOCutils.cpp (100%) rename {arduino_foc_minimal_encoder => library_source}/FOCutils.h (97%) create mode 100644 library_source/HallSensor.cpp create mode 100644 library_source/HallSensor.h create mode 100644 library_source/MagneticSensorAnalog.cpp create mode 100644 library_source/MagneticSensorAnalog.h create mode 100644 library_source/MagneticSensorI2C.cpp rename {arduino_foc_minimal_magnetic => library_source}/MagneticSensorI2C.h (100%) rename {arduino_foc_minimal_magnetic => library_source}/MagneticSensorSPI.cpp (91%) rename {arduino_foc_minimal_magnetic => library_source}/MagneticSensorSPI.h (100%) rename {arduino_foc_minimal_encoder => library_source}/Sensor.h (72%) rename {arduino_foc_minimal_encoder => library_source}/defaults.h (64%) rename {arduino_foc_minimal_magnetic => minimal_project_examples/arduino_foc_minimal_encoder}/BLDCMotor.cpp (66%) rename {arduino_foc_minimal_magnetic => minimal_project_examples/arduino_foc_minimal_encoder}/BLDCMotor.h (79%) create mode 100644 minimal_project_examples/arduino_foc_minimal_encoder/Encoder.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_encoder/Encoder.h rename {arduino_foc_minimal_magnetic => minimal_project_examples/arduino_foc_minimal_encoder}/FOCutils.cpp (100%) rename {arduino_foc_minimal_magnetic => minimal_project_examples/arduino_foc_minimal_encoder}/FOCutils.h (97%) rename {arduino_foc_minimal_magnetic => minimal_project_examples/arduino_foc_minimal_encoder}/Sensor.h (72%) rename {arduino_foc_minimal_encoder => minimal_project_examples/arduino_foc_minimal_encoder}/arduino_foc_minimal_encoder.ino (55%) rename {arduino_foc_minimal_magnetic => minimal_project_examples/arduino_foc_minimal_encoder}/defaults.h (64%) create mode 100644 minimal_project_examples/arduino_foc_minimal_hall/BLDCMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_hall/BLDCMotor.h create mode 100644 minimal_project_examples/arduino_foc_minimal_hall/FOCutils.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_hall/FOCutils.h create mode 100644 minimal_project_examples/arduino_foc_minimal_hall/HallSensor.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_hall/HallSensor.h create mode 100644 minimal_project_examples/arduino_foc_minimal_hall/Sensor.h create mode 100644 minimal_project_examples/arduino_foc_minimal_hall/arduino_foc_minimal_hall.ino create mode 100644 minimal_project_examples/arduino_foc_minimal_hall/defaults.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/BLDCMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/BLDCMotor.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/FOCutils.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/FOCutils.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/MagneticSensorI2C.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/MagneticSensorI2C.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/Sensor.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/arduino_foc_minimal_magnetic_i2c.ino create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/defaults.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_spi/BLDCMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_spi/BLDCMotor.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_spi/FOCutils.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_spi/FOCutils.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorSPI.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorSPI.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_spi/Sensor.h rename arduino_foc_minimal_magnetic/arduino_foc_minimal_magnetic.ino => minimal_project_examples/arduino_foc_minimal_magnetic_spi/arduino_foc_minimal_magnetic_spi.ino (53%) create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_spi/defaults.h create mode 100644 minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.h create mode 100644 minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.h create mode 100644 minimal_project_examples/arduino_foc_minimal_openloop/Sensor.h create mode 100644 minimal_project_examples/arduino_foc_minimal_openloop/arduino_foc_minimal_openloop.ino create mode 100644 minimal_project_examples/arduino_foc_minimal_openloop/defaults.h diff --git a/README.md b/README.md index 09ab0cb9..c17367b8 100644 --- a/README.md +++ b/README.md @@ -4,46 +4,38 @@ [![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT) [![arduino-library-badge](https://www.ardu-badge.com/badge/Simple%20FOC.svg?)](https://www.ardu-badge.com/badge/Simple%20FOC.svg) -This is the minimal Arduino example of the [Simple FOC](https://github.com/askuric/Arduino-FOC) arduino library intended for mostly for easier experimentation and modification! +This is the repository of the [*SimpleFOClibrary*](https://github.com/askuric/Arduino-FOC) intended to be used to crete the projects with minimal code possible which is specific for certain **motor+sensor+driver** combination. -### Minimal repository structure +### Repository structure ```shell -├───arduino_foc_minimal_encoder # Arduino minimal code for running a motor with Encoder -│ -└───arduino_foc_minimal_magnetic # Arduino minimal code for running a motor with magnetic sensor +├─── library_source +| | +| ├─ BLDCMotor.cpp/h # BLDCMotor class implementing all the FOC operation +| ├─ FOCutils.cpp/h # Utility functions +| ├─ defaults.h # Default configuration values +│ ├─ Sensor.h # Abstract Sensor class that all the sensors implement +│ │ +│ ├─ Encoder.cpp/h # Encoder class implementing the Quadrature encoder operations +│ ├─ MagneticSensorSPI.cpp/h # class implementing SPI communication for Magnetic sensors +│ ├─ MagneticSensorI2C.cpp/h # class implementing I2C communication for Magnetic sensors +│ ├─ MagneticSensorAnalog.cpp/h # class implementing Analog output for Magnetic sensors +│ └─ HallSensor.cpp/h # class implementing Hall sensor +| +└─── minimal_project_examples + ├─ arduino_foc_minimal_openloop # Arduino minimal code for running a motor in the open loop + ├─ arduino_foc_minimal_encoder # Arduino minimal code for running a motor with Encoder + ├─ arduino_foc_minimal_hall # Arduino minimal code for running a motor with Hall sensors + ├─ arduino_foc_minimal_magnetic_i2c # Arduino minimal code for running a motor with I2C magnetic sensor + └─ arduino_foc_minimal_magnetic_spi # Arduino minimal code for running a motor with SPI magnetic sensor ``` -Each of the examples will give you the opportunity to change the PI velocity parameters `P` and `I`, Low pass filter time constant `Tf`, change the control loop in real time and check the average loop execution time, all from the serial terminal. - -List of commands: -- **P**: velocity PI controller P gain -- **I**: velocity PI controller I gain -- **L**: velocity PI controller voltage limit -- **R**: velocity PI controller voltage ramp -- **F**: velocity Low pass filter time constant -- **K**: angle P controller P gain -- **N**: angle P controller velocity limit -- **C**: control loop - - **0**: voltage - - **1**: velocity - - **2**: angle -- **V**: get motor variables - - **0**: currently set voltage - - **1**: current velocity - - **2**: current angle - - **3**: current target value - - -Find more information about the **motor commands** in the [docs.simplefoc.com](https://docs.simplefoc.com/communication) - -### Installation -For those willing to experiment and to modify the code I suggest using the [minimal version](https://github.com/askuric/Arduino-FOC/tree/minimal) of the code. - > This code is completely independent and you can run it as any other Arduino Sketch without the need for any libraries. +# Creating your own minimal project +First you need to download this repository to your computer. #### Github website download - Make sure you are in [minimal branch](https://github.com/askuric/Arduino-FOC/tree/minimal) - Download the code by clicking on the `Clone or Download > Download ZIP`. -- Unzip it and open the sketch in Arduino IDE. +- Unzip it #### Using terminal - Open the terminal: @@ -51,15 +43,110 @@ For those willing to experiment and to modify the code I suggest using the [mini cd *to you desired directory* git clone -b minimal https://github.com/askuric/Arduino-FOC.git ``` -- Then you just open it with the Arduino IDE and run it. + +After this step you will be able to open the example projects directly with Arduino IDE. This code is completely independent and you can run it as any other Arduino Sketch without the need for any libraries. + +> **BEWARE** In some cases this minimal version of the code will produce conflicts with the *Simple FOC* library if it is installed through Arduino library manager. So you might need to uninstall the library to run minimal projects. + +## BLDC motor support code + +In the `library_source` folder you will find all *SimpleFOClibrary* source files. From those files you will choose just the ones you need for your own project. + +In each Arduino project using the *SimpleFOClibrary* you will need to copy these six files into your project directory. + +```shell +├─── my_arduino_project +| ├─ my_arduino_project.ino +| | +| ├─ BLDCMotor.cpp/h # BLDCMotor class implementing all the FOC operation +| ├─ FOCutils.cpp/h # Utility functions +| ├─ defaults.h # Default configuration values + └─ Sensor.h # Abstract Sensor class that all the sensors implement +``` + +And in your arduino code you need to add the include: +```cpp +#include "BLDCMotor.h" +``` + +If you wish to run your motor in the open loop mode these are all the files that you will need. See the `arduino_foc_minimal_openloop.ino` project example. + +## Sensor support +In order to support the different position sensors you will have to add their `*.cpp` and `*.h` files into the directory. All you need to do is copy the header files from the `library_source` directory. + + +### Example: Encoder sensor +For example if you wish to use encoder, your arduino project will have structure: + +```shell +├─── my_arduino_project +| ├─ my_arduino_project.ino +| | +| ├─ BLDCMotor.cpp/h # BLDCMotor class implementing all the FOC operation +| ├─ FOCutils.cpp/h # Utility functions +│ ├─ defaults.h # Default configuration values +│ ├─ Sensor.h # Abstract Sensor class that all the sensors implement +│ | + └─ Encoder.cpp/h # Encoder class implementing the Quadrature encoder operations +``` +And your includes will be: +```cpp +#include "BLDCMotor.h" +#include "Encoder.h" +``` +See `arduino_foc_minimal_encoder.ino`. + +### Example: SPI Magnetic sensor +If you wish to use SPI magnetic sensor with your project, your folder structure will be: + +```shell +├─── my_arduino_project +| ├─ my_arduino_project.ino +| | +| ├─ BLDCMotor.cpp/h # BLDCMotor class implementing all the FOC operation +| ├─ FOCutils.cpp/h # Utility functions +│ ├─ defaults.h # Default configuration values +│ ├─ Sensor.h # Abstract Sensor class that all the sensors implement +│ | + └─ MagneticSensorSPI.cpp/h # class implementing SPI communication for Magnetic sensors +``` +And your includes will be: +```cpp +#include "BLDCMotor.h" +#include "MagneticSensorSPI.h" +``` +See `arduino_foc_minimal_magnetic_spi.ino`. + + +### Example: Analog magnetic sensor and encoder +For example if you wish to use magnetic sensor with SPI communication, your arduino project will have structure: + +```shell +├─── my_arduino_project +| ├─ my_arduino_project.ino +| | +| ├─ BLDCMotor.cpp/h # BLDCMotor class implementing all the FOC operation +| ├─ FOCutils.cpp/h # Utility functions +│ ├─ defaults.h # Default configuration values +│ ├─ Sensor.h # Abstract Sensor class that all the sensors implement +│ | +│ ├─ Encoder.cpp/h # Encoder class implementing the Quadrature encoder operations + └─ MagneticSensorAnalog.cpp/h # class implementing Analog output for Magnetic sensors +``` +And your includes will be: +```cpp +#include "BLDCMotor.h" +#include "MagneticSensorAnalog.h" +#include "Encoder.h" +``` ## Documentation -Find out more information about the Arduino SimpleFOC project in [docs website](https://askuric.github.io/Arduino-FOC/) +Find out more information about the Arduino *SimpleFOCproject* in [docs website](https://docs.simplefoc.com/) ## Arduino FOC repo structure Branch | Description | Status ------------ | ------------- | ------------ -[master](https://github.com/askuric/Arduino-FOC) | Stable and tested library version | ![Library Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Compile/badge.svg) -[dev](https://github.com/askuric/Arduino-FOC/tree/dev) | Development library version | ![Library Dev Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Dev%20Compile/badge.svg?branch=dev) -[minimal](https://github.com/askuric/Arduino-FOC/tree/minimal) | Minimal Arduino example with integrated library | ![MinimalBuild](https://github.com/askuric/Arduino-FOC/workflows/MinimalBuild/badge.svg?branch=minimal) +[master](https://github.com/simplefoc/Arduino-FOC) | Stable and tested library version | ![Library Compile](https://github.com/simplefoc/Arduino-FOC/workflows/Library%20Compile/badge.svg) +[dev](https://github.com/simplefoc/Arduino-FOC/tree/dev) | Development library version | ![Library Dev Compile](https://github.com/simplefoc/Arduino-FOC/workflows/Library%20Dev%20Compile/badge.svg?branch=dev) +[minimal](https://github.com/simplefoc/Arduino-FOC/tree/minimal) | Minimal Arduino example with integrated library | ![MinimalBuild](https://github.com/simplefoc/Arduino-FOC/workflows/MinimalBuild/badge.svg?branch=minimal) diff --git a/arduino_foc_minimal_encoder/BLDCMotor.cpp b/library_source/BLDCMotor.cpp similarity index 66% rename from arduino_foc_minimal_encoder/BLDCMotor.cpp rename to library_source/BLDCMotor.cpp index fd574804..f31e818a 100644 --- a/arduino_foc_minimal_encoder/BLDCMotor.cpp +++ b/library_source/BLDCMotor.cpp @@ -21,13 +21,14 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // Velocity loop config // PI controller constant - PI_velocity.P = DEF_PI_VEL_P; - PI_velocity.I = DEF_PI_VEL_I; - PI_velocity.timestamp = _micros(); - PI_velocity.voltage_limit = voltage_power_supply; - PI_velocity.voltage_ramp = DEF_PI_VEL_U_RAMP; - PI_velocity.voltage_prev = 0; - PI_velocity.tracking_error_prev = 0; + PID_velocity.P = DEF_PID_VEL_P; + PID_velocity.I = DEF_PID_VEL_I; + PID_velocity.D = DEF_PID_VEL_D; + PID_velocity.output_ramp = DEF_PID_VEL_U_RAMP; + PID_velocity.timestamp = _micros(); + PID_velocity.integral_prev = 0; + PID_velocity.output_prev = 0; + PID_velocity.tracking_error_prev = 0; // velocity low pass filter LPF_velocity.Tf = DEF_VEL_FILTER_Tf; @@ -37,8 +38,11 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // position loop config // P controller constant P_angle.P = DEF_P_ANGLE_P; + // maximum angular velocity to be used for positioning - P_angle.velocity_limit = DEF_P_ANGLE_VEL_LIM; + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = voltage_power_supply; // index search velocity velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; @@ -56,6 +60,8 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) //monitor_port monitor_port = nullptr; + //sensor + sensor = nullptr; } // init hardware pins @@ -73,7 +79,9 @@ void BLDCMotor::init() { _setPwmFrequency(pwmA, pwmB, pwmC); // sanity check for the voltage limit configuration - if(PI_velocity.voltage_limit > voltage_power_supply) PI_velocity.voltage_limit = voltage_power_supply; + if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; _delay(500); // enable motor @@ -112,9 +120,28 @@ int BLDCMotor::alignSensor() { if(monitor_port) monitor_port->println("MOT: Align sensor."); // align the electrical phases of the motor and sensor // set angle -90 degrees - setPhaseVoltage(voltage_sensor_align, _3PI_2); - // let the motor stabilize for 3 sec - _delay(3000); + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } + + // let the motor stabilize for 2 sec + _delay(2000); // set sensor to zero sensor->initRelativeZero(); _delay(500); @@ -146,7 +173,7 @@ int BLDCMotor::absoluteZeroAlign() { // search the absolute zero with small velocity while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ loopFOC(); - voltage_q = velocityPI(velocity_index_search - shaftVelocity()); + voltage_q = velocityPID(velocity_index_search - shaftVelocity()); } voltage_q = 0; // disable motor @@ -157,7 +184,7 @@ int BLDCMotor::absoluteZeroAlign() { // align the sensor with the absolute zero float zero_offset = sensor->initAbsoluteZero(); // remember zero electric angle - zero_electric_angle = electricAngle(zero_offset); + zero_electric_angle = normalizeAngle(electricAngle(zero_offset)); } // return bool if zero found return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; @@ -168,20 +195,15 @@ int BLDCMotor::absoluteZeroAlign() { */ // shaft angle calculation float BLDCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return 0; return sensor->getAngle(); } // shaft velocity calculation float BLDCMotor::shaftVelocity() { - float Ts = (_micros() - LPF_velocity.timestamp) * 1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - // calculate the filtering - float alpha = LPF_velocity.Tf/(LPF_velocity.Tf + Ts); - float vel = alpha*LPF_velocity.prev + (1-alpha)*sensor->getVelocity(); - // save the variables - LPF_velocity.prev = vel; - LPF_velocity.timestamp = _micros(); - return vel; + // if no sensor linked return 0 + if(!sensor) return 0; + return lowPassFilter(sensor->getVelocity(), LPF_velocity); } // Electrical angle calculation float BLDCMotor::electricAngle(float shaftAngle) { @@ -193,12 +215,21 @@ float BLDCMotor::electricAngle(float shaftAngle) { FOC functions */ // FOC initialization function -int BLDCMotor::initFOC() { - // sensor and motor alignment - _delay(500); - int exit_flag = alignSensor(); - _delay(500); - +int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } if(monitor_port) monitor_port->println("MOT: Motor ready."); return exit_flag; @@ -233,13 +264,25 @@ void BLDCMotor::move(float new_target) { // include angle loop shaft_angle_sp = target; shaft_velocity_sp = positionP( shaft_angle_sp - shaft_angle ); - voltage_q = velocityPI(shaft_velocity_sp - shaft_velocity); + voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); break; case ControlType::velocity: // velocity set point // include velocity loop shaft_velocity_sp = target; - voltage_q = velocityPI(shaft_velocity_sp - shaft_velocity); + voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); break; } } @@ -287,13 +330,13 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // find the sector we are in currently int sector = floor(angle_el / _PI_3) + 1; // calculate the duty cycles - float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el); - float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3); + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; // two versions possible // centered around voltage_power_supply/2 float T0 = 1 - T1 - T2; // pulled to 0 - better for low power supply voltage - //T0 = 0; + //float T0 = 0; // calculate the duty cycles(times) float Ta,Tb,Tc; @@ -335,10 +378,10 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { Tc = 0; } - // calculate the phase voltages - Ua = Ta*Uq; - Ub = Tb*Uq; - Uc = Tc*Uq; + // calculate the phase voltages and center + Ua = Ta*voltage_power_supply; + Ub = Tb*voltage_power_supply; + Uc = Tc*voltage_power_supply; break; } @@ -348,14 +391,13 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { - // Set voltage to the pwm pin void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { // calculate duty cycle // limited in [0,1] - float dc_a = (Ua < 0) ? 0 : (Ua >= voltage_power_supply) ? 1 : Ua / voltage_power_supply; - float dc_b = (Ub < 0) ? 0 : (Ub >= voltage_power_supply) ? 1 : Ub / voltage_power_supply; - float dc_c = (Uc < 0) ? 0 : (Uc >= voltage_power_supply) ? 1 : Uc / voltage_power_supply; + float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); // hardware specific writing _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); } @@ -373,38 +415,70 @@ int BLDCMotor::hasEnable(){ return enable_pin != NOT_SET; } +// low pass filter function +// - input -singal to be filtered +// - lpf -LPF_s structure with filter parameters +float BLDCMotor::lowPassFilter(float input, LPF_s& lpf){ + unsigned long now_us = _micros(); + float Ts = (now_us - lpf.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // calculate the filtering + float alpha = lpf.Tf/(lpf.Tf + Ts); + float out = alpha*lpf.prev + (1-alpha)*input; + + // save the variables + lpf.prev = out; + lpf.timestamp = now_us; + return out; +} + /** Motor control functions */ -// PI controller function -float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){ - float Ts = (_micros() - cont.timestamp) * 1e-6; - +// PID controller function +float BLDCMotor::controllerPID(float tracking_error, PID_s& cont){ + // calculate the time from the last call + unsigned long now_us = _micros(); + float Ts = (now_us - cont.timestamp) * 1e-6; // quick fix for strange cases (micros overflow) if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - // u(s) = (P + I/s)e(s) - // Tustin transform of the PI controller ( a bit optimized ) - // uk = uk_1 + (I*Ts/2 + P)*ek + (I*Ts/2 - P)*ek_1 - float tmp = cont.I*Ts*0.5; - float voltage = cont.voltage_prev + (tmp + cont.P) * tracking_error + (tmp - cont.P) * cont.tracking_error_prev; + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = cont.P * tracking_error; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = cont.integral_prev + cont.I*Ts*0.5*(tracking_error + cont.tracking_error_prev); + // antiwindup - limit the output voltage_q + integral = constrain(integral, -voltage_limit, voltage_limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = cont.D*(tracking_error - cont.tracking_error_prev)/Ts; + // sum all the components + float voltage = proportional + integral + derivative; // antiwindup - limit the output voltage_q - if (abs(voltage) > cont.voltage_limit) voltage = voltage > 0 ? cont.voltage_limit : -cont.voltage_limit; - // limit the acceleration by ramping the the voltage - float d_voltage = voltage - cont.voltage_prev; - if (abs(d_voltage)/Ts > cont.voltage_ramp) voltage = d_voltage > 0 ? cont.voltage_prev + cont.voltage_ramp*Ts : cont.voltage_prev - cont.voltage_ramp*Ts; + voltage = constrain(voltage, -voltage_limit, voltage_limit); + // limit the acceleration by ramping the the voltage + float d_voltage = voltage - cont.output_prev; + if (abs(d_voltage)/Ts > cont.output_ramp) voltage = d_voltage > 0 ? cont.output_prev + cont.output_ramp*Ts : cont.output_prev - cont.output_ramp*Ts; - cont.voltage_prev = voltage; + // saving for the next pass + cont.integral_prev = integral; + cont.output_prev = voltage; cont.tracking_error_prev = tracking_error; - cont.timestamp = _micros(); + cont.timestamp = now_us; return voltage; } // velocity control loop PI controller -float BLDCMotor::velocityPI(float tracking_error) { - return controllerPI(tracking_error, PI_velocity); +float BLDCMotor::velocityPID(float tracking_error) { + return controllerPID(tracking_error, PID_velocity); } // P controller for position control loop @@ -412,10 +486,52 @@ float BLDCMotor::positionP(float ek) { // calculate the target velocity from the position error float velocity_target = P_angle.P * ek; // constrain velocity target value - if (abs(velocity_target) > P_angle.velocity_limit) velocity_target = velocity_target > 0 ? P_angle.velocity_limit : -P_angle.velocity_limit; + velocity_target = constrain(velocity_target, -velocity_limit, velocity_limit); return velocity_target; } +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void BLDCMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void BLDCMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + /** * Monitoring functions */ @@ -429,6 +545,7 @@ void BLDCMotor::useMonitoring(Print &print){ void BLDCMotor::monitor() { if(!monitor_port) return; switch (controller) { + case ControlType::velocity_openloop: case ControlType::velocity: monitor_port->print(voltage_q); monitor_port->print("\t"); @@ -436,6 +553,7 @@ void BLDCMotor::monitor() { monitor_port->print("\t"); monitor_port->println(shaft_velocity); break; + case ControlType::angle_openloop: case ControlType::angle: monitor_port->print(voltage_q); monitor_port->print("\t"); @@ -470,40 +588,49 @@ int BLDCMotor::command(String user_command) { switch(cmd){ case 'P': // velocity P gain change case 'I': // velocity I gain change - case 'L': // velocity voltage limit change + case 'D': // velocity D gain change case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print(" PI velocity| "); + if(monitor_port) monitor_port->print(" PID velocity| "); break; case 'F': // velocity Tf low pass filter change if(monitor_port) monitor_port->print(" LPF velocity| "); break; case 'K': // angle loop gain P change - case 'N': // angle loop gain velocity_limit change if(monitor_port) monitor_port->print(" P angle| "); break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + } // apply the the command switch(cmd){ case 'P': // velocity P gain change if(monitor_port) monitor_port->print("P: "); - if(!GET) PI_velocity.P = value; - if(monitor_port) monitor_port->println(PI_velocity.P); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); break; case 'I': // velocity I gain change if(monitor_port) monitor_port->print("I: "); - if(!GET) PI_velocity.I = value; - if(monitor_port) monitor_port->println(PI_velocity.I); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); break; - case 'L': // velocity voltage limit change - if(monitor_port) monitor_port->print("volt_limit: "); - if(!GET)PI_velocity.voltage_limit = value; - if(monitor_port) monitor_port->println(PI_velocity.voltage_limit); + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); break; case 'R': // velocity voltage ramp change if(monitor_port) monitor_port->print("volt_ramp: "); - if(!GET) PI_velocity.voltage_ramp = value; - if(monitor_port) monitor_port->println(PI_velocity.voltage_ramp); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET)voltage_limit = value; + if(monitor_port) monitor_port->println(voltage_limit); break; case 'F': // velocity Tf low pass filter change if(monitor_port) monitor_port->print("Tf: "); @@ -517,14 +644,14 @@ int BLDCMotor::command(String user_command) { break; case 'N': // angle loop gain velocity_limit change if(monitor_port) monitor_port->print("vel_limit: "); - if(!GET) P_angle.velocity_limit = value; - if(monitor_port) monitor_port->println(P_angle.velocity_limit); + if(!GET) velocity_limit = value; + if(monitor_port) monitor_port->println(velocity_limit); break; case 'C': // change control type if(monitor_port) monitor_port->print("Control: "); - if(GET){ // if get commang + if(GET){ // if get command switch(controller){ case ControlType::voltage: if(monitor_port) monitor_port->println("voltage"); @@ -535,6 +662,8 @@ int BLDCMotor::command(String user_command) { case ControlType::angle: if(monitor_port) monitor_port->println("angle"); break; + default: + if(monitor_port) monitor_port->println("open loop"); } }else{ // if set command switch((int)value){ diff --git a/arduino_foc_minimal_encoder/BLDCMotor.h b/library_source/BLDCMotor.h similarity index 79% rename from arduino_foc_minimal_encoder/BLDCMotor.h rename to library_source/BLDCMotor.h index d01ea717..95ca9472 100644 --- a/arduino_foc_minimal_encoder/BLDCMotor.h +++ b/library_source/BLDCMotor.h @@ -20,7 +20,9 @@ enum ControlType{ voltage,//!< Torque control using voltage velocity,//!< Velocity motion control - angle//!< Position/angle motion control + angle,//!< Position/angle motion control + velocity_openloop, + angle_openloop }; /** @@ -32,15 +34,16 @@ enum FOCModulationType{ }; /** - * PI controller structure + * PID controller structure */ -struct PI_s{ +struct PID_s{ float P; //!< Proportional gain float I; //!< Integral gain - float voltage_limit; //!< Voltage limit of the controller output - float voltage_ramp; //!< Maximum speed of change of the output value + float D; //!< Derivative gain long timestamp; //!< Last execution timestamp - float voltage_prev; //!< last controller output value + float integral_prev; //!< last integral component value + float output_prev; //!< last pid output value + float output_ramp; //!< Maximum speed of change of the output value float tracking_error_prev; //!< last tracking error value }; @@ -48,7 +51,6 @@ struct PI_s{ struct P_s{ float P; //!< Proportional gain long timestamp; //!< Last execution timestamp - float velocity_limit; //!< Velocity limit of the controller output }; /** @@ -97,8 +99,14 @@ class BLDCMotor /** * Function initializing FOC algorithm * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * */ - int initFOC(); + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); /** * Function running FOC algorithm in real-time * it calculates the gets motor angle and sets the appropriate voltages @@ -115,7 +123,6 @@ class BLDCMotor * This function doesn't need to be run upon each loop execution - depends of the use case */ void move(float target = NOT_SET); - // hardware variables int pwmA; //!< phase A pwm pin number @@ -150,10 +157,14 @@ class BLDCMotor float velocity_index_search;//!< target velocity for index search int pole_pairs;//!< Motor pole pairs number + // limiting variables + float voltage_limit; //!< Voltage limitting variable - global limit + float velocity_limit; //!< Velocity limitting variable - global limit + // configuration structures ControlType controller; //!< parameter determining the control loop to be used FOCModulationType foc_modulation;//!< parameter derterniming modulation algorithm - PI_s PI_velocity;//!< parameter determining the velocity PI configuration + PID_s PID_velocity;//!< parameter determining the velocity PI configuration P_s P_angle; //!< parameter determining the position P configuration LPF_s LPF_velocity;//!< parameter determining the velocity Lpw pass filter configuration @@ -261,23 +272,51 @@ class BLDCMotor /** determining if the enable pin has been provided */ int hasEnable(); + /** + * Low pass filter function - iterative + * @param input - singal to be filtered + * @param lpf - LPF_s structure with filter parameters + */ + float lowPassFilter(float input, LPF_s& lpf); + // Motion control functions /** * Generic PI controller function executing one step of a controller - * receives tracking error and PI_s structure and outputs the control signal + * receives tracking error and PID_s structure and outputs the control signal * * @param tracking_error Current error in between target value and mesasured value - * @param controller PI_s structure containing all the necessary PI controller config and variables + * @param controller PID_s structure containing all the necessary PI controller config and variables */ - float controllerPI(float tracking_error, PI_s &controller); + float controllerPID(float tracking_error, PID_s &controller); /** Velocity PI controller implementation */ - float velocityPI(float tracking_error); + float velocityPID(float tracking_error); /** Position P controller implementation */ float positionP(float ek); + + // Open loop motion control + /** + * Function (iterative) generating open loop movement for target velocity + * it uses voltage_limit variable + * + * @param target_velocity - rad/s + */ + void velocityOpenloop(float target_velocity); + /** + * Function (iterative) generating open loop movement towards the target angle + * it uses voltage_limit and velocity_limit variables + * + * @param target_angle - rad + */ + void angleOpenloop(float target_angle); + // phase voltages float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform + + // open loop variables + long open_loop_timestamp; + }; diff --git a/arduino_foc_minimal_encoder/Encoder.cpp b/library_source/Encoder.cpp similarity index 98% rename from arduino_foc_minimal_encoder/Encoder.cpp rename to library_source/Encoder.cpp index ddd0a07d..77631345 100644 --- a/arduino_foc_minimal_encoder/Encoder.cpp +++ b/library_source/Encoder.cpp @@ -107,7 +107,7 @@ void Encoder::handleIndex() { Shaft angle calculation */ float Encoder::getAngle(){ - return _2PI * (pulse_counter) / ((float)cpr); + return natural_direction * _2PI * (pulse_counter) / ((float)cpr); } /* Shaft velocity calculation @@ -145,7 +145,7 @@ float Encoder::getVelocity(){ // save velocity calculation variables prev_Th = Th; prev_pulse_counter = pulse_counter; - return (velocity); + return natural_direction * (velocity); } // getter for index pin diff --git a/arduino_foc_minimal_encoder/Encoder.h b/library_source/Encoder.h similarity index 95% rename from arduino_foc_minimal_encoder/Encoder.h rename to library_source/Encoder.h index fc65a7a9..19aafc94 100644 --- a/arduino_foc_minimal_encoder/Encoder.h +++ b/library_source/Encoder.h @@ -6,14 +6,6 @@ #include "Sensor.h" -/** - * Pullup configuration structure - */ -enum Pullup{ - INTERN, //!< Use internal pullups - EXTERN //!< Use external pullups -}; - /** * Quadrature mode configuration structure */ diff --git a/arduino_foc_minimal_encoder/FOCutils.cpp b/library_source/FOCutils.cpp similarity index 100% rename from arduino_foc_minimal_encoder/FOCutils.cpp rename to library_source/FOCutils.cpp diff --git a/arduino_foc_minimal_encoder/FOCutils.h b/library_source/FOCutils.h similarity index 97% rename from arduino_foc_minimal_encoder/FOCutils.h rename to library_source/FOCutils.h index 110d1dcc..4c347a12 100644 --- a/arduino_foc_minimal_encoder/FOCutils.h +++ b/library_source/FOCutils.h @@ -13,7 +13,7 @@ #endif // sign function -#define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) #define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) // utility defines diff --git a/library_source/HallSensor.cpp b/library_source/HallSensor.cpp new file mode 100644 index 00000000..7072a97a --- /dev/null +++ b/library_source/HallSensor.cpp @@ -0,0 +1,186 @@ +#include "HallSensor.h" + + +/* + HallSensor(int hallA, int hallB , int cpr, int index) + - hallA, hallB, hallC - HallSensor A, B and C pins + - pp - pole pairs +*/ + +HallSensor::HallSensor(int _hallA, int _hallB, int _hallC, int _pp){ + + // HallSensor measurement structure init + // hardware pins + pinA = _hallA; + pinB = _hallB; + pinC = _hallC; + // counter setup + pulse_counter = 0; + pulse_timestamp = 0; + + cpr = _pp * 6; // hall has 6 segments per electrical revolution + A_active = 0; + B_active = 0; + C_active = 0; + + // velocity calculation variables + + prev_pulse_counter = 0; + prev_timestamp_us = _micros(); + + // extern pullup as default + pullup = Pullup::EXTERN; +} + +// HallSensor interrupt callback functions +// A channel +void HallSensor::handleA() { + A_active= digitalRead(pinA); + updateState(); +} +// B channel +void HallSensor::handleB() { + B_active = digitalRead(pinB); + updateState(); +} + +// C channel +void HallSensor::handleC() { + C_active = digitalRead(pinC); + updateState(); +} + +void HallSensor::updateState() { + int newState = C_active + (B_active << 1) + (A_active << 2); + Direction direction = decodeDirection(state, newState); + state = newState; + + pulse_counter += direction; + pulse_timestamp = _micros(); +} + +// determines whether the hallsensr state transition means that it has moved one step CW (+1), CCW (-1) or state transition is invalid (0) +// states are 3bits, one for each hall sensor +Direction HallSensor::decodeDirection(int oldState, int newState) +{ + // here are expected state transitions (oldState > newState). + // CW state transitions are: ( 6 > 2 > 3 > 1 > 5 > 4 > 6 ) + // CCW state transitions are: ( 6 > 4 > 5 > 1 > 3 > 2 > 6 ) + // invalid state transitions are oldState == newState or if newState or oldState == 0 | 7 as hallsensors can't be all on or all off + + int rawDirection; + + if ( + (oldState == 6 && newState == 2) || \ + (oldState == 2 && newState == 3) || \ + (oldState == 3 && newState == 1) || \ + (oldState == 1 && newState == 5) || \ + (oldState == 5 && newState == 4) || \ + (oldState == 4 && newState == 6) + ) { + rawDirection = Direction::CW; + } else if( + (oldState == 6 && newState == 4) || \ + (oldState == 4 && newState == 5) || \ + (oldState == 5 && newState == 1) || \ + (oldState == 1 && newState == 3) || \ + (oldState == 3 && newState == 2) || \ + (oldState == 2 && newState == 6) + ) { + rawDirection = Direction::CCW; + } else { + rawDirection = Direction::UNKNOWN; + } + + direction = static_cast(rawDirection * natural_direction); + return direction; // * goofy; +} + +/* + Shaft angle calculation +*/ +float HallSensor::getAngle(){ + + long dN = pulse_counter - prev_pulse_counter; + + if (dN != 0) + { + + // time from last impulse + float Th = (pulse_timestamp - prev_timestamp_us) * 1e-6; + if (Th <= 0 || Th > 0.5) + Th = 1e-3; + // save variables for next pass + prev_timestamp_us = pulse_timestamp; + prev_pulse_counter = pulse_counter; + velocity = (float) _2PI * dN / (cpr * Th); + } + angle = (float) _2PI * pulse_counter / cpr; + + return angle; +} +/* + Shaft velocity calculation + function using mixed time and frequency measurement technique +*/ +float HallSensor::getVelocity(){ + // this is calculated during the last call to getAngle(); + return velocity; +} + +// getter for index pin +// return -1 if no index +int HallSensor::needsAbsoluteZeroSearch(){ + return 0; +} +// getter for index pin +int HallSensor::hasAbsoluteZero(){ + return 0; +} +// initialize counter to zero +float HallSensor::initRelativeZero(){ + + pulse_counter = 0; + pulse_timestamp = _micros(); + velocity = 0; + return 0.0; +} +// initialize index to zero +float HallSensor::initAbsoluteZero(){ + return 0.0; +} + +// HallSensor initialisation of the hardware pins +// and calculation variables +void HallSensor::init(){ + + // HallSensor - check if pullup needed for your HallSensor + if(pullup == Pullup::INTERN){ + pinMode(pinA, INPUT_PULLUP); + pinMode(pinB, INPUT_PULLUP); + pinMode(pinC, INPUT_PULLUP); + }else{ + pinMode(pinA, INPUT); + pinMode(pinB, INPUT); + pinMode(pinC, INPUT); + } + + // counter setup + pulse_counter = 0; + pulse_timestamp = _micros(); + prev_pulse_counter = 0; + prev_timestamp_us = _micros(); + +} + +// function enabling hardware interrupts for the callback provided +// if callback is not provided then the interrupt is not enabled +void HallSensor::enableInterrupts(void (*doA)(), void(*doB)(), void(*doC)()){ + // attach interrupt if functions provided + + // A, B and C callback + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); + if(doC != nullptr) attachInterrupt(digitalPinToInterrupt(pinC), doC, CHANGE); +} + diff --git a/library_source/HallSensor.h b/library_source/HallSensor.h new file mode 100644 index 00000000..018426f9 --- /dev/null +++ b/library_source/HallSensor.h @@ -0,0 +1,107 @@ +#ifndef HALL_SENSOR_LIB_H +#define HALL_SENSOR_LIB_H + +#include "Arduino.h" +#include "FOCutils.h" +#include "Sensor.h" + + +class HallSensor: public Sensor{ + public: + /** + HallSensor class constructor + @param encA HallSensor B pin + @param encB HallSensor B pin + @param encC HallSensor B pin + @param pp pole pairs (e.g hoverboard motor has 15pp and small gimbals often have 7pp) + @param index index pin number (optional input) + */ + HallSensor(int encA, int encB, int encC, int pp); + + /** HallSensor initialise pins */ + void init(); + /** + * function enabling hardware interrupts for the HallSensor channels with provided callback functions + * if callback is not provided then the interrupt is not enabled + * + * @param doA pointer to the A channel interrupt handler function + * @param doB pointer to the B channel interrupt handler function + * @param doIndex pointer to the Index channel interrupt handler function + * + */ + void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doC)() = nullptr); + + // HallSensor interrupt callback functions + /** A channel callback function */ + void handleA(); + /** B channel callback function */ + void handleB(); + /** C channel callback function */ + void handleC(); + + + // pins A and B + int pinA; //!< HallSensor hardware pin A + int pinB; //!< HallSensor hardware pin B + int pinC; //!< HallSensor hardware pin C + + // HallSensor configuration + Pullup pullup; //!< Configuration parameter internal or external pullups + float cpr;//!< HallSensor cpr number + + // Abstract functions of the Sensor class implementation + /** get current angle (rad) */ + float getAngle(); + /** get current angular velocity (rad/s) */ + float getVelocity(); + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + float initRelativeZero(); + /** + * set index angle as zero angle + * return the angle [rad] difference + */ + float initAbsoluteZero(); + /** + * returns 0 if it has no index + * 0 - HallSensor without index + * 1 - HallSensor with index + */ + int hasAbsoluteZero(); + /** + * returns 0 if it does need search for absolute zero + * 0 - HallSensor without index + * 1 - ecoder with index + */ + int needsAbsoluteZeroSearch(); + + // whether last step was CW (+1) or CCW (-1) direction + Direction direction; + + // the current 3bit state of the hall sensors + int state; + + volatile float angle; // rad/s + volatile float velocity; // rad/s + + private: + + Direction decodeDirection(int oldState, int newState); + void updateState(); + + volatile long pulse_counter;//!< current pulse counter + volatile long pulse_timestamp;//!< last impulse timestamp in us + volatile int A_active; //!< current active states of A channel + volatile int B_active; //!< current active states of B channel + volatile int C_active; //!< current active states of C channel + + // velocity calculation variables + // float prev_Th, pulse_per_second; + volatile long prev_pulse_counter, prev_timestamp_us; + +}; + + +#endif diff --git a/library_source/MagneticSensorAnalog.cpp b/library_source/MagneticSensorAnalog.cpp new file mode 100644 index 00000000..ed112a94 --- /dev/null +++ b/library_source/MagneticSensorAnalog.cpp @@ -0,0 +1,109 @@ +#include "MagneticSensorAnalog.h" + +/** MagneticSensorAnalog(uint8_t _pinAnalog, int _min, int _max) + * @param _pinAnalog the pin that is reading the pwm from magnetic sensor + * @param _min_raw_count the smallest expected reading. Whilst you might expect it to be 0 it is often ~15. Getting this wrong results in a small click once per revolution + * @param _max_raw_count the largest value read. whilst you might expect it to be 2^10 = 1023 it is often ~ 1020. Note: For ESP32 (with 12bit ADC the value will be nearer 4096) + */ +MagneticSensorAnalog::MagneticSensorAnalog(uint8_t _pinAnalog, int _min_raw_count, int _max_raw_count){ + + pinAnalog = _pinAnalog; + + cpr = _max_raw_count - _min_raw_count; + min_raw_count = _min_raw_count; + max_raw_count = _max_raw_count; + + if(pullup == Pullup::INTERN){ + pinMode(pinAnalog, INPUT_PULLUP); + }else{ + pinMode(pinAnalog, INPUT); + } + +} + + +void MagneticSensorAnalog::init(){ + + // velocity calculation init + angle_prev = 0; + velocity_calc_timestamp = _micros(); + + // full rotations tracking number + full_rotation_offset = 0; + raw_count_prev = getRawCount(); + zero_offset = 0; +} + +// Shaft angle calculation +// angle is in radians [rad] +float MagneticSensorAnalog::getAngle(){ + // raw data from the sensor + raw_count = getRawCount(); + + int delta = raw_count - raw_count_prev; + // if overflow happened track it as full rotation + if(abs(delta) > (0.8*cpr) ) full_rotation_offset += delta > 0 ? -_2PI : _2PI; + + float angle = natural_direction * (full_rotation_offset + ( (float) (raw_count - zero_offset) / (float)cpr) * _2PI); + + // calculate velocity here + long now = _micros(); + float Ts = ( now - velocity_calc_timestamp)*1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + velocity = (angle - angle_prev)/Ts; + + // save variables for future pass + raw_count_prev = raw_count; + angle_prev = angle; + velocity_calc_timestamp = now; + + return angle; +} + +// Shaft velocity calculation +float MagneticSensorAnalog::getVelocity(){ + // TODO: Refactor?: to avoid angle being called twice, velocity is pre-calculted during getAngle + return velocity; +} + +// set current angle as zero angle +// return the angle [rad] difference +float MagneticSensorAnalog::initRelativeZero(){ + + float angle_offset = -getAngle(); + zero_offset = natural_direction * getRawCount(); + + // angle tracking variables + full_rotation_offset = 0; + return angle_offset; +} +// set absolute zero angle as zero angle +// return the angle [rad] difference +float MagneticSensorAnalog::initAbsoluteZero(){ + float rotation = -(int)zero_offset; + // init absolute zero + zero_offset = 0; + + // angle tracking variables + full_rotation_offset = 0; + // return offset in radians + return rotation / (float)cpr * _2PI; +} +// returns 0 if it has no absolute 0 measurement +// 0 - incremental encoder without index +// 1 - encoder with index & magnetic sensors +int MagneticSensorAnalog::hasAbsoluteZero(){ + return 1; +} +// returns 0 if it does need search for absolute zero +// 0 - magnetic sensor +// 1 - ecoder with index +int MagneticSensorAnalog::needsAbsoluteZeroSearch(){ + return 0; +} + +// function reading the raw counter of the magnetic sensor +int MagneticSensorAnalog::getRawCount(){ + return analogRead(pinAnalog); +} diff --git a/library_source/MagneticSensorAnalog.h b/library_source/MagneticSensorAnalog.h new file mode 100644 index 00000000..e0095b64 --- /dev/null +++ b/library_source/MagneticSensorAnalog.h @@ -0,0 +1,82 @@ +#ifndef MAGNETICSENSORANALOG_LIB_H +#define MAGNETICSENSORANALOG_LIB_H + +#include "Arduino.h" +#include +#include "FOCutils.h" +#include "Sensor.h" + +/** + * This sensor has been tested with AS5600 running in 'analog mode'. This is where output pin of AS6000 is connected to an analog pin on your microcontroller. + * This approach is very simple but you may more accurate results with MagneticSensorI2C if that is also supported as its skips the DAC -> ADC conversion (ADC supports MagneticSensorI2C) + */ +class MagneticSensorAnalog: public Sensor{ + public: + /** + * MagneticSensorAnalog class constructor + * @param _pinAnalog the pin to read the PWM signal + * @param _pinAnalog the pin to read the PWM signal + */ + MagneticSensorAnalog(uint8_t _pinAnalog, int _min = 0, int _max = 0); + + + /** sensor initialise pins */ + void init(); + + int pinAnalog; //!< encoder hardware pin A + + // Encoder configuration + Pullup pullup; + + // implementation of abstract functions of the Sensor class + /** get current angle (rad) */ + float getAngle(); + /** get current angular velocity (rad/s) **/ + float getVelocity(); + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + float initRelativeZero(); + /** + * set absolute zero angle as zero angle + * return the angle [rad] difference + */ + float initAbsoluteZero(); + /** returns 1 because it is the absolute sensor */ + int hasAbsoluteZero(); + /** returns 0 maning it doesn't need search for absolute zero */ + int needsAbsoluteZeroSearch(); + /** raw count (typically in range of 0-1023), useful for debugging resolution issues */ + int raw_count; + int min_raw_count; + int max_raw_count; + int cpr; + + private: + // float cpr; //!< Maximum range of the magnetic sensor + + + int read(); + + int zero_offset; //!< user defined zero offset + /** + * Function getting current angle register value + * it uses angle_register variable + */ + int getRawCount(); + + // total angle tracking variables + float full_rotation_offset; //! (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; + // save the current angle value for the next steps + // in order to know if overflow happened + angle_data_prev = angle_data; + + // zero offset adding + angle_data -= (int)zero_offset; + // return the full angle + // (number of full rotations)*2PI + current sensor angle + return natural_direction * (full_rotation_offset + ( angle_data / (float)cpr) * _2PI); +} + +// Shaft velocity calculation +float MagneticSensorI2C::getVelocity(){ + // calculate sample time + unsigned long now_us = _micros(); + float Ts = (now_us - velocity_calc_timestamp)*1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // current angle + float angle_c = getAngle(); + // velocity calculation + float vel = (angle_c - angle_prev)/Ts; + + // save variables for future pass + angle_prev = angle_c; + velocity_calc_timestamp = now_us; + return vel; +} + +// set current angle as zero angle +// return the angle [rad] difference +float MagneticSensorI2C::initRelativeZero(){ + float angle_offset = -getAngle(); + zero_offset = natural_direction * getRawCount(); + + // angle tracking variables + full_rotation_offset = 0; + return angle_offset; +} +// set absolute zero angle as zero angle +// return the angle [rad] difference +float MagneticSensorI2C::initAbsoluteZero(){ + float rotation = -(int)zero_offset; + // init absolute zero + zero_offset = 0; + + // angle tracking variables + full_rotation_offset = 0; + // return offset in radians + return rotation / (float)cpr * _2PI; +} +// returns 0 if it has no absolute 0 measurement +// 0 - incremental encoder without index +// 1 - encoder with index & magnetic sensors +int MagneticSensorI2C::hasAbsoluteZero(){ + return 1; +} +// returns 0 if it does need search for absolute zero +// 0 - magnetic sensor +// 1 - ecoder with index +int MagneticSensorI2C::needsAbsoluteZeroSearch(){ + return 0; +} + + +// function reading the raw counter of the magnetic sensor +int MagneticSensorI2C::getRawCount(){ + return (int)MagneticSensorI2C::read(angle_register_msb); +} + +// I2C functions +/* +* Read a register from the sensor +* Takes the address of the register as a uint8_t +* Returns the value of the register +*/ +int MagneticSensorI2C::read(uint8_t angle_reg_msb) { + // read the angle register first MSB then LSB + byte readArray[2]; + uint16_t readValue = 0; + // notify the device that is aboout to be read + Wire.beginTransmission(chip_address); + Wire.write(angle_reg_msb); + Wire.endTransmission(false); + + // read the data msb and lsb + Wire.requestFrom(chip_address, (uint8_t)2); + for (byte i=0; i < 2; i++) { + readArray[i] = Wire.read(); + } + + // depending on the sensor architecture there are different combinations of + // LSB and MSB register used bits + // AS5600 uses 0..7 LSB and 8..11 MSB + // AS5048 uses 0..5 LSB and 6..13 MSB + readValue = ( readArray[1] & lsb_mask ); + readValue += ( ( readArray[0] & msb_mask ) << lsb_used ); + return readValue; +} diff --git a/arduino_foc_minimal_magnetic/MagneticSensorI2C.h b/library_source/MagneticSensorI2C.h similarity index 100% rename from arduino_foc_minimal_magnetic/MagneticSensorI2C.h rename to library_source/MagneticSensorI2C.h diff --git a/arduino_foc_minimal_magnetic/MagneticSensorSPI.cpp b/library_source/MagneticSensorSPI.cpp similarity index 91% rename from arduino_foc_minimal_magnetic/MagneticSensorSPI.cpp rename to library_source/MagneticSensorSPI.cpp index d75204ee..79430b13 100644 --- a/arduino_foc_minimal_magnetic/MagneticSensorSPI.cpp +++ b/library_source/MagneticSensorSPI.cpp @@ -25,9 +25,11 @@ void MagneticSensorSPI::init(){ //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices SPI.begin(); +#ifndef ESP_H // if not ESP32 board SPI.setBitOrder(MSBFIRST); // Set the SPI_1 bit order SPI.setDataMode(SPI_MODE1) ; SPI.setClockDivider(SPI_CLOCK_DIV8); +#endif digitalWrite(chip_select_pin, HIGH); // velocity calculation init @@ -60,13 +62,14 @@ float MagneticSensorSPI::getAngle(){ angle_data -= (int)zero_offset; // return the full angle // (number of full rotations)*2PI + current sensor angle - return full_rotation_offset + ( angle_data / (float)cpr) * _2PI; + return natural_direction * (full_rotation_offset + ( angle_data / (float)cpr) * _2PI); } // Shaft velocity calculation float MagneticSensorSPI::getVelocity(){ // calculate sample time - float Ts = (_micros() - velocity_calc_timestamp)*1e-6; + unsigned long now_us = _micros(); + float Ts = (now_us - velocity_calc_timestamp)*1e-6; // quick fix for strange cases (micros overflow) if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; @@ -77,7 +80,7 @@ float MagneticSensorSPI::getVelocity(){ // save variables for future pass angle_prev = angle_c; - velocity_calc_timestamp = _micros(); + velocity_calc_timestamp = now_us; return vel; } @@ -85,7 +88,7 @@ float MagneticSensorSPI::getVelocity(){ // return the angle [rad] difference float MagneticSensorSPI::initRelativeZero(){ float angle_offset = -getAngle(); - zero_offset = getRawCount(); + zero_offset = natural_direction * getRawCount(); // angle tracking variables full_rotation_offset = 0; @@ -164,13 +167,21 @@ word MagneticSensorSPI::read(word angle_register){ //Send the command digitalWrite(chip_select_pin, LOW); +#ifndef ESP_H // if not ESP32 board digitalWrite(chip_select_pin, LOW); +#endif SPI.transfer(left_byte); SPI.transfer(right_byte); digitalWrite(chip_select_pin,HIGH); +#ifndef ESP_H // if not ESP32 board digitalWrite(chip_select_pin,HIGH); +#endif +#if defined( ESP_H ) // if ESP32 board + delayMicroseconds(50); +#else delayMicroseconds(10); +#endif //Now read the response digitalWrite(chip_select_pin, LOW); diff --git a/arduino_foc_minimal_magnetic/MagneticSensorSPI.h b/library_source/MagneticSensorSPI.h similarity index 100% rename from arduino_foc_minimal_magnetic/MagneticSensorSPI.h rename to library_source/MagneticSensorSPI.h diff --git a/arduino_foc_minimal_encoder/Sensor.h b/library_source/Sensor.h similarity index 72% rename from arduino_foc_minimal_encoder/Sensor.h rename to library_source/Sensor.h index 56e4d286..7370c38f 100644 --- a/arduino_foc_minimal_encoder/Sensor.h +++ b/library_source/Sensor.h @@ -1,6 +1,23 @@ #ifndef SENSOR_H #define SENSOR_H +/** + * Direction structure + */ +enum Direction{ + CW = 1, //clockwise + CCW = -1, // counter clockwise + UNKNOWN = 0 //not yet known or invalid state +}; + +/** + * Pullup configuration structure + */ +enum Pullup{ + INTERN, //!< Use internal pullups + EXTERN //!< Use external pullups +}; + /** * Sensor abstract class defintion * Each sensor needs to have these functions implemented @@ -22,6 +39,9 @@ class Sensor{ */ virtual float initAbsoluteZero(); + // if natural_direction == Direction::CCW then direction will be flipped to CW + int natural_direction = Direction::CW; + /** * returns 0 if it has no absolute 0 measurement * 0 - incremental encoder without index diff --git a/arduino_foc_minimal_encoder/defaults.h b/library_source/defaults.h similarity index 64% rename from arduino_foc_minimal_encoder/defaults.h rename to library_source/defaults.h index 5bcb0118..bbb48c6e 100644 --- a/arduino_foc_minimal_encoder/defaults.h +++ b/library_source/defaults.h @@ -3,12 +3,13 @@ #define DEF_POWER_SUPPLY 12.0 //!< default power supply voltage // velocity PI controller params -#define DEF_PI_VEL_P 0.5 //!< default PI controller P value -#define DEF_PI_VEL_I 10 //!< default PI controller I value -#define DEF_PI_VEL_U_RAMP 1000 //!< default PI controller voltage ramp value +#define DEF_PID_VEL_P 0.5 //!< default PID controller P value +#define DEF_PID_VEL_I 10 //!< default PID controller I value +#define DEF_PID_VEL_D 0 //!< default PID controller D value +#define DEF_PID_VEL_U_RAMP 1000 //!< default PID controller voltage ramp value // angle P params #define DEF_P_ANGLE_P 20 //!< default P controller P value -#define DEF_P_ANGLE_VEL_LIM 20 //!< angle velocity limit default +#define DEF_VEL_LIM 20 //!< angle velocity limit default // index search #define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 //!< default index search velocity // align voltage diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_minimal_encoder/BLDCMotor.cpp similarity index 66% rename from arduino_foc_minimal_magnetic/BLDCMotor.cpp rename to minimal_project_examples/arduino_foc_minimal_encoder/BLDCMotor.cpp index fd574804..f31e818a 100644 --- a/arduino_foc_minimal_magnetic/BLDCMotor.cpp +++ b/minimal_project_examples/arduino_foc_minimal_encoder/BLDCMotor.cpp @@ -21,13 +21,14 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // Velocity loop config // PI controller constant - PI_velocity.P = DEF_PI_VEL_P; - PI_velocity.I = DEF_PI_VEL_I; - PI_velocity.timestamp = _micros(); - PI_velocity.voltage_limit = voltage_power_supply; - PI_velocity.voltage_ramp = DEF_PI_VEL_U_RAMP; - PI_velocity.voltage_prev = 0; - PI_velocity.tracking_error_prev = 0; + PID_velocity.P = DEF_PID_VEL_P; + PID_velocity.I = DEF_PID_VEL_I; + PID_velocity.D = DEF_PID_VEL_D; + PID_velocity.output_ramp = DEF_PID_VEL_U_RAMP; + PID_velocity.timestamp = _micros(); + PID_velocity.integral_prev = 0; + PID_velocity.output_prev = 0; + PID_velocity.tracking_error_prev = 0; // velocity low pass filter LPF_velocity.Tf = DEF_VEL_FILTER_Tf; @@ -37,8 +38,11 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // position loop config // P controller constant P_angle.P = DEF_P_ANGLE_P; + // maximum angular velocity to be used for positioning - P_angle.velocity_limit = DEF_P_ANGLE_VEL_LIM; + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = voltage_power_supply; // index search velocity velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; @@ -56,6 +60,8 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) //monitor_port monitor_port = nullptr; + //sensor + sensor = nullptr; } // init hardware pins @@ -73,7 +79,9 @@ void BLDCMotor::init() { _setPwmFrequency(pwmA, pwmB, pwmC); // sanity check for the voltage limit configuration - if(PI_velocity.voltage_limit > voltage_power_supply) PI_velocity.voltage_limit = voltage_power_supply; + if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; _delay(500); // enable motor @@ -112,9 +120,28 @@ int BLDCMotor::alignSensor() { if(monitor_port) monitor_port->println("MOT: Align sensor."); // align the electrical phases of the motor and sensor // set angle -90 degrees - setPhaseVoltage(voltage_sensor_align, _3PI_2); - // let the motor stabilize for 3 sec - _delay(3000); + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } + + // let the motor stabilize for 2 sec + _delay(2000); // set sensor to zero sensor->initRelativeZero(); _delay(500); @@ -146,7 +173,7 @@ int BLDCMotor::absoluteZeroAlign() { // search the absolute zero with small velocity while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ loopFOC(); - voltage_q = velocityPI(velocity_index_search - shaftVelocity()); + voltage_q = velocityPID(velocity_index_search - shaftVelocity()); } voltage_q = 0; // disable motor @@ -157,7 +184,7 @@ int BLDCMotor::absoluteZeroAlign() { // align the sensor with the absolute zero float zero_offset = sensor->initAbsoluteZero(); // remember zero electric angle - zero_electric_angle = electricAngle(zero_offset); + zero_electric_angle = normalizeAngle(electricAngle(zero_offset)); } // return bool if zero found return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; @@ -168,20 +195,15 @@ int BLDCMotor::absoluteZeroAlign() { */ // shaft angle calculation float BLDCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return 0; return sensor->getAngle(); } // shaft velocity calculation float BLDCMotor::shaftVelocity() { - float Ts = (_micros() - LPF_velocity.timestamp) * 1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - // calculate the filtering - float alpha = LPF_velocity.Tf/(LPF_velocity.Tf + Ts); - float vel = alpha*LPF_velocity.prev + (1-alpha)*sensor->getVelocity(); - // save the variables - LPF_velocity.prev = vel; - LPF_velocity.timestamp = _micros(); - return vel; + // if no sensor linked return 0 + if(!sensor) return 0; + return lowPassFilter(sensor->getVelocity(), LPF_velocity); } // Electrical angle calculation float BLDCMotor::electricAngle(float shaftAngle) { @@ -193,12 +215,21 @@ float BLDCMotor::electricAngle(float shaftAngle) { FOC functions */ // FOC initialization function -int BLDCMotor::initFOC() { - // sensor and motor alignment - _delay(500); - int exit_flag = alignSensor(); - _delay(500); - +int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } if(monitor_port) monitor_port->println("MOT: Motor ready."); return exit_flag; @@ -233,13 +264,25 @@ void BLDCMotor::move(float new_target) { // include angle loop shaft_angle_sp = target; shaft_velocity_sp = positionP( shaft_angle_sp - shaft_angle ); - voltage_q = velocityPI(shaft_velocity_sp - shaft_velocity); + voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); break; case ControlType::velocity: // velocity set point // include velocity loop shaft_velocity_sp = target; - voltage_q = velocityPI(shaft_velocity_sp - shaft_velocity); + voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); break; } } @@ -287,13 +330,13 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // find the sector we are in currently int sector = floor(angle_el / _PI_3) + 1; // calculate the duty cycles - float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el); - float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3); + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; // two versions possible // centered around voltage_power_supply/2 float T0 = 1 - T1 - T2; // pulled to 0 - better for low power supply voltage - //T0 = 0; + //float T0 = 0; // calculate the duty cycles(times) float Ta,Tb,Tc; @@ -335,10 +378,10 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { Tc = 0; } - // calculate the phase voltages - Ua = Ta*Uq; - Ub = Tb*Uq; - Uc = Tc*Uq; + // calculate the phase voltages and center + Ua = Ta*voltage_power_supply; + Ub = Tb*voltage_power_supply; + Uc = Tc*voltage_power_supply; break; } @@ -348,14 +391,13 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { - // Set voltage to the pwm pin void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { // calculate duty cycle // limited in [0,1] - float dc_a = (Ua < 0) ? 0 : (Ua >= voltage_power_supply) ? 1 : Ua / voltage_power_supply; - float dc_b = (Ub < 0) ? 0 : (Ub >= voltage_power_supply) ? 1 : Ub / voltage_power_supply; - float dc_c = (Uc < 0) ? 0 : (Uc >= voltage_power_supply) ? 1 : Uc / voltage_power_supply; + float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); // hardware specific writing _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); } @@ -373,38 +415,70 @@ int BLDCMotor::hasEnable(){ return enable_pin != NOT_SET; } +// low pass filter function +// - input -singal to be filtered +// - lpf -LPF_s structure with filter parameters +float BLDCMotor::lowPassFilter(float input, LPF_s& lpf){ + unsigned long now_us = _micros(); + float Ts = (now_us - lpf.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // calculate the filtering + float alpha = lpf.Tf/(lpf.Tf + Ts); + float out = alpha*lpf.prev + (1-alpha)*input; + + // save the variables + lpf.prev = out; + lpf.timestamp = now_us; + return out; +} + /** Motor control functions */ -// PI controller function -float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){ - float Ts = (_micros() - cont.timestamp) * 1e-6; - +// PID controller function +float BLDCMotor::controllerPID(float tracking_error, PID_s& cont){ + // calculate the time from the last call + unsigned long now_us = _micros(); + float Ts = (now_us - cont.timestamp) * 1e-6; // quick fix for strange cases (micros overflow) if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - // u(s) = (P + I/s)e(s) - // Tustin transform of the PI controller ( a bit optimized ) - // uk = uk_1 + (I*Ts/2 + P)*ek + (I*Ts/2 - P)*ek_1 - float tmp = cont.I*Ts*0.5; - float voltage = cont.voltage_prev + (tmp + cont.P) * tracking_error + (tmp - cont.P) * cont.tracking_error_prev; + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = cont.P * tracking_error; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = cont.integral_prev + cont.I*Ts*0.5*(tracking_error + cont.tracking_error_prev); + // antiwindup - limit the output voltage_q + integral = constrain(integral, -voltage_limit, voltage_limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = cont.D*(tracking_error - cont.tracking_error_prev)/Ts; + // sum all the components + float voltage = proportional + integral + derivative; // antiwindup - limit the output voltage_q - if (abs(voltage) > cont.voltage_limit) voltage = voltage > 0 ? cont.voltage_limit : -cont.voltage_limit; - // limit the acceleration by ramping the the voltage - float d_voltage = voltage - cont.voltage_prev; - if (abs(d_voltage)/Ts > cont.voltage_ramp) voltage = d_voltage > 0 ? cont.voltage_prev + cont.voltage_ramp*Ts : cont.voltage_prev - cont.voltage_ramp*Ts; + voltage = constrain(voltage, -voltage_limit, voltage_limit); + // limit the acceleration by ramping the the voltage + float d_voltage = voltage - cont.output_prev; + if (abs(d_voltage)/Ts > cont.output_ramp) voltage = d_voltage > 0 ? cont.output_prev + cont.output_ramp*Ts : cont.output_prev - cont.output_ramp*Ts; - cont.voltage_prev = voltage; + // saving for the next pass + cont.integral_prev = integral; + cont.output_prev = voltage; cont.tracking_error_prev = tracking_error; - cont.timestamp = _micros(); + cont.timestamp = now_us; return voltage; } // velocity control loop PI controller -float BLDCMotor::velocityPI(float tracking_error) { - return controllerPI(tracking_error, PI_velocity); +float BLDCMotor::velocityPID(float tracking_error) { + return controllerPID(tracking_error, PID_velocity); } // P controller for position control loop @@ -412,10 +486,52 @@ float BLDCMotor::positionP(float ek) { // calculate the target velocity from the position error float velocity_target = P_angle.P * ek; // constrain velocity target value - if (abs(velocity_target) > P_angle.velocity_limit) velocity_target = velocity_target > 0 ? P_angle.velocity_limit : -P_angle.velocity_limit; + velocity_target = constrain(velocity_target, -velocity_limit, velocity_limit); return velocity_target; } +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void BLDCMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void BLDCMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + /** * Monitoring functions */ @@ -429,6 +545,7 @@ void BLDCMotor::useMonitoring(Print &print){ void BLDCMotor::monitor() { if(!monitor_port) return; switch (controller) { + case ControlType::velocity_openloop: case ControlType::velocity: monitor_port->print(voltage_q); monitor_port->print("\t"); @@ -436,6 +553,7 @@ void BLDCMotor::monitor() { monitor_port->print("\t"); monitor_port->println(shaft_velocity); break; + case ControlType::angle_openloop: case ControlType::angle: monitor_port->print(voltage_q); monitor_port->print("\t"); @@ -470,40 +588,49 @@ int BLDCMotor::command(String user_command) { switch(cmd){ case 'P': // velocity P gain change case 'I': // velocity I gain change - case 'L': // velocity voltage limit change + case 'D': // velocity D gain change case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print(" PI velocity| "); + if(monitor_port) monitor_port->print(" PID velocity| "); break; case 'F': // velocity Tf low pass filter change if(monitor_port) monitor_port->print(" LPF velocity| "); break; case 'K': // angle loop gain P change - case 'N': // angle loop gain velocity_limit change if(monitor_port) monitor_port->print(" P angle| "); break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + } // apply the the command switch(cmd){ case 'P': // velocity P gain change if(monitor_port) monitor_port->print("P: "); - if(!GET) PI_velocity.P = value; - if(monitor_port) monitor_port->println(PI_velocity.P); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); break; case 'I': // velocity I gain change if(monitor_port) monitor_port->print("I: "); - if(!GET) PI_velocity.I = value; - if(monitor_port) monitor_port->println(PI_velocity.I); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); break; - case 'L': // velocity voltage limit change - if(monitor_port) monitor_port->print("volt_limit: "); - if(!GET)PI_velocity.voltage_limit = value; - if(monitor_port) monitor_port->println(PI_velocity.voltage_limit); + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); break; case 'R': // velocity voltage ramp change if(monitor_port) monitor_port->print("volt_ramp: "); - if(!GET) PI_velocity.voltage_ramp = value; - if(monitor_port) monitor_port->println(PI_velocity.voltage_ramp); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET)voltage_limit = value; + if(monitor_port) monitor_port->println(voltage_limit); break; case 'F': // velocity Tf low pass filter change if(monitor_port) monitor_port->print("Tf: "); @@ -517,14 +644,14 @@ int BLDCMotor::command(String user_command) { break; case 'N': // angle loop gain velocity_limit change if(monitor_port) monitor_port->print("vel_limit: "); - if(!GET) P_angle.velocity_limit = value; - if(monitor_port) monitor_port->println(P_angle.velocity_limit); + if(!GET) velocity_limit = value; + if(monitor_port) monitor_port->println(velocity_limit); break; case 'C': // change control type if(monitor_port) monitor_port->print("Control: "); - if(GET){ // if get commang + if(GET){ // if get command switch(controller){ case ControlType::voltage: if(monitor_port) monitor_port->println("voltage"); @@ -535,6 +662,8 @@ int BLDCMotor::command(String user_command) { case ControlType::angle: if(monitor_port) monitor_port->println("angle"); break; + default: + if(monitor_port) monitor_port->println("open loop"); } }else{ // if set command switch((int)value){ diff --git a/arduino_foc_minimal_magnetic/BLDCMotor.h b/minimal_project_examples/arduino_foc_minimal_encoder/BLDCMotor.h similarity index 79% rename from arduino_foc_minimal_magnetic/BLDCMotor.h rename to minimal_project_examples/arduino_foc_minimal_encoder/BLDCMotor.h index d01ea717..95ca9472 100644 --- a/arduino_foc_minimal_magnetic/BLDCMotor.h +++ b/minimal_project_examples/arduino_foc_minimal_encoder/BLDCMotor.h @@ -20,7 +20,9 @@ enum ControlType{ voltage,//!< Torque control using voltage velocity,//!< Velocity motion control - angle//!< Position/angle motion control + angle,//!< Position/angle motion control + velocity_openloop, + angle_openloop }; /** @@ -32,15 +34,16 @@ enum FOCModulationType{ }; /** - * PI controller structure + * PID controller structure */ -struct PI_s{ +struct PID_s{ float P; //!< Proportional gain float I; //!< Integral gain - float voltage_limit; //!< Voltage limit of the controller output - float voltage_ramp; //!< Maximum speed of change of the output value + float D; //!< Derivative gain long timestamp; //!< Last execution timestamp - float voltage_prev; //!< last controller output value + float integral_prev; //!< last integral component value + float output_prev; //!< last pid output value + float output_ramp; //!< Maximum speed of change of the output value float tracking_error_prev; //!< last tracking error value }; @@ -48,7 +51,6 @@ struct PI_s{ struct P_s{ float P; //!< Proportional gain long timestamp; //!< Last execution timestamp - float velocity_limit; //!< Velocity limit of the controller output }; /** @@ -97,8 +99,14 @@ class BLDCMotor /** * Function initializing FOC algorithm * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * */ - int initFOC(); + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); /** * Function running FOC algorithm in real-time * it calculates the gets motor angle and sets the appropriate voltages @@ -115,7 +123,6 @@ class BLDCMotor * This function doesn't need to be run upon each loop execution - depends of the use case */ void move(float target = NOT_SET); - // hardware variables int pwmA; //!< phase A pwm pin number @@ -150,10 +157,14 @@ class BLDCMotor float velocity_index_search;//!< target velocity for index search int pole_pairs;//!< Motor pole pairs number + // limiting variables + float voltage_limit; //!< Voltage limitting variable - global limit + float velocity_limit; //!< Velocity limitting variable - global limit + // configuration structures ControlType controller; //!< parameter determining the control loop to be used FOCModulationType foc_modulation;//!< parameter derterniming modulation algorithm - PI_s PI_velocity;//!< parameter determining the velocity PI configuration + PID_s PID_velocity;//!< parameter determining the velocity PI configuration P_s P_angle; //!< parameter determining the position P configuration LPF_s LPF_velocity;//!< parameter determining the velocity Lpw pass filter configuration @@ -261,23 +272,51 @@ class BLDCMotor /** determining if the enable pin has been provided */ int hasEnable(); + /** + * Low pass filter function - iterative + * @param input - singal to be filtered + * @param lpf - LPF_s structure with filter parameters + */ + float lowPassFilter(float input, LPF_s& lpf); + // Motion control functions /** * Generic PI controller function executing one step of a controller - * receives tracking error and PI_s structure and outputs the control signal + * receives tracking error and PID_s structure and outputs the control signal * * @param tracking_error Current error in between target value and mesasured value - * @param controller PI_s structure containing all the necessary PI controller config and variables + * @param controller PID_s structure containing all the necessary PI controller config and variables */ - float controllerPI(float tracking_error, PI_s &controller); + float controllerPID(float tracking_error, PID_s &controller); /** Velocity PI controller implementation */ - float velocityPI(float tracking_error); + float velocityPID(float tracking_error); /** Position P controller implementation */ float positionP(float ek); + + // Open loop motion control + /** + * Function (iterative) generating open loop movement for target velocity + * it uses voltage_limit variable + * + * @param target_velocity - rad/s + */ + void velocityOpenloop(float target_velocity); + /** + * Function (iterative) generating open loop movement towards the target angle + * it uses voltage_limit and velocity_limit variables + * + * @param target_angle - rad + */ + void angleOpenloop(float target_angle); + // phase voltages float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform + + // open loop variables + long open_loop_timestamp; + }; diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/Encoder.cpp b/minimal_project_examples/arduino_foc_minimal_encoder/Encoder.cpp new file mode 100644 index 00000000..77631345 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_encoder/Encoder.cpp @@ -0,0 +1,229 @@ +#include "Encoder.h" + + +/* + Encoder(int encA, int encB , int cpr, int index) + - encA, encB - encoder A and B pins + - cpr - counts per rotation number (cpm=ppm*4) + - index pin - (optional input) +*/ + +Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ + + // Encoder measurement structure init + // hardware pins + pinA = _encA; + pinB = _encB; + // counter setup + pulse_counter = 0; + pulse_timestamp = 0; + + cpr = _ppr; + A_active = 0; + B_active = 0; + I_active = 0; + // index pin + index_pin = _index; // its 0 if not used + index_pulse_counter = 0; + + // velocity calculation variables + prev_Th = 0; + pulse_per_second = 0; + prev_pulse_counter = 0; + prev_timestamp_us = _micros(); + + // extern pullup as default + pullup = Pullup::EXTERN; + // enable quadrature encoder by default + quadrature = Quadrature::ON; +} + +// Encoder interrupt callback functions +// A channel +void Encoder::handleA() { + int A = digitalRead(pinA); + switch (quadrature){ + case Quadrature::ON: + // CPR = 4xPPR + if ( A != A_active ) { + pulse_counter += (A_active == B_active) ? 1 : -1; + pulse_timestamp = _micros(); + A_active = A; + } + break; + case Quadrature::OFF: + // CPR = PPR + if(A && !digitalRead(pinB)){ + pulse_counter++; + pulse_timestamp = _micros(); + } + break; + } +} +// B channel +void Encoder::handleB() { + int B = digitalRead(pinB); + switch (quadrature){ + case Quadrature::ON: + // // CPR = 4xPPR + if ( B != B_active ) { + pulse_counter += (A_active != B_active) ? 1 : -1; + pulse_timestamp = _micros(); + B_active = B; + } + break; + case Quadrature::OFF: + // CPR = PPR + if(B && !digitalRead(pinA)){ + pulse_counter--; + pulse_timestamp = _micros(); + } + break; + } +} + +// Index channel +void Encoder::handleIndex() { + if(hasIndex()){ + int I = digitalRead(index_pin); + if(I && !I_active){ + // align encoder on each index + if(index_pulse_counter){ + long tmp = pulse_counter; + // corrent the counter value + pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; + // preserve relative speed + prev_pulse_counter += pulse_counter - tmp; + } else { + // initial offset + index_pulse_counter = pulse_counter; + } + } + I_active = I; + } +} + +/* + Shaft angle calculation +*/ +float Encoder::getAngle(){ + return natural_direction * _2PI * (pulse_counter) / ((float)cpr); +} +/* + Shaft velocity calculation + function using mixed time and frequency measurement technique +*/ +float Encoder::getVelocity(){ + // timestamp + long timestamp_us = _micros(); + // sampling time calculation + float Ts = (timestamp_us - prev_timestamp_us) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // time from last impulse + float Th = (timestamp_us - pulse_timestamp) * 1e-6; + long dN = pulse_counter - prev_pulse_counter; + + // Pulse per second calculation (Eq.3.) + // dN - impulses received + // Ts - sampling time - time in between function calls + // Th - time from last impulse + // Th_1 - time form last impulse of the previous call + // only increment if some impulses received + float dt = Ts + prev_Th - Th; + pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second; + + // if more than 0.05 passed in between impulses + if ( Th > 0.1) pulse_per_second = 0; + + // velocity calculation + float velocity = pulse_per_second / ((float)cpr) * (_2PI); + + // save variables for next pass + prev_timestamp_us = timestamp_us; + // save velocity calculation variables + prev_Th = Th; + prev_pulse_counter = pulse_counter; + return natural_direction * (velocity); +} + +// getter for index pin +// return -1 if no index +int Encoder::needsAbsoluteZeroSearch(){ + return index_pulse_counter == 0; +} +// getter for index pin +int Encoder::hasAbsoluteZero(){ + return hasIndex(); +} +// initialize counter to zero +float Encoder::initRelativeZero(){ + long angle_offset = -pulse_counter; + pulse_counter = 0; + pulse_timestamp = _micros(); + return _2PI * (angle_offset) / ((float)cpr); +} +// initialize index to zero +float Encoder::initAbsoluteZero(){ + pulse_counter -= index_pulse_counter; + prev_pulse_counter = pulse_counter; + return (index_pulse_counter) / ((float)cpr) * (_2PI); +} +// private function used to determine if encoder has index +int Encoder::hasIndex(){ + return index_pin != 0; +} + + +// encoder initialisation of the hardware pins +// and calculation variables +void Encoder::init(){ + + // Encoder - check if pullup needed for your encoder + if(pullup == Pullup::INTERN){ + pinMode(pinA, INPUT_PULLUP); + pinMode(pinB, INPUT_PULLUP); + if(hasIndex()) pinMode(index_pin,INPUT_PULLUP); + }else{ + pinMode(pinA, INPUT); + pinMode(pinB, INPUT); + if(hasIndex()) pinMode(index_pin,INPUT); + } + + // counter setup + pulse_counter = 0; + pulse_timestamp = _micros(); + // velocity calculation variables + prev_Th = 0; + pulse_per_second = 0; + prev_pulse_counter = 0; + prev_timestamp_us = _micros(); + + // initial cpr = PPR + // change it if the mode is quadrature + if(quadrature == Quadrature::ON) cpr = 4*cpr; + +} + +// function enabling hardware interrupts of the for the callback provided +// if callback is not provided then the interrupt is not enabled +void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){ + // attach interrupt if functions provided + switch(quadrature){ + case Quadrature::ON: + // A callback and B callback + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); + break; + case Quadrature::OFF: + // A callback and B callback + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); + break; + } + + // if index used initialize the index interrupt + if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE); +} + diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/Encoder.h b/minimal_project_examples/arduino_foc_minimal_encoder/Encoder.h new file mode 100644 index 00000000..19aafc94 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_encoder/Encoder.h @@ -0,0 +1,104 @@ +#ifndef ENCODER_LIB_H +#define ENCODER_LIB_H + +#include "Arduino.h" +#include "FOCutils.h" +#include "Sensor.h" + + +/** + * Quadrature mode configuration structure + */ +enum Quadrature{ + ON, //!< Enable quadrature mode CPR = 4xPPR + OFF //!< Disable quadrature mode / CPR = PPR +}; + +class Encoder: public Sensor{ + public: + /** + Encoder class constructor + @param encA encoder B pin + @param encB encoder B pin + @param ppr impulses per rotation (cpr=ppr*4) + @param index index pin number (optional input) + */ + Encoder(int encA, int encB , float ppr, int index = 0); + + /** encoder initialise pins */ + void init(); + /** + * function enabling hardware interrupts for the encoder channels with provided callback functions + * if callback is not provided then the interrupt is not enabled + * + * @param doA pointer to the A channel interrupt handler function + * @param doB pointer to the B channel interrupt handler function + * @param doIndex pointer to the Index channel interrupt handler function + * + */ + void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr); + + // Encoder interrupt callback functions + /** A channel callback function */ + void handleA(); + /** B channel callback function */ + void handleB(); + /** Index channel callback function */ + void handleIndex(); + + + // pins A and B + int pinA; //!< encoder hardware pin A + int pinB; //!< encoder hardware pin B + int index_pin; //!< index pin + + // Encoder configuration + Pullup pullup; //!< Configuration parameter internal or external pullups + Quadrature quadrature;//!< Configuration parameter enable or disable quadrature mode + float cpr;//!< encoder cpr number + + // Abstract functions of the Sensor class implementation + /** get current angle (rad) */ + float getAngle(); + /** get current angular velocity (rad/s) */ + float getVelocity(); + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + float initRelativeZero(); + /** + * set index angle as zero angle + * return the angle [rad] difference + */ + float initAbsoluteZero(); + /** + * returns 0 if it has no index + * 0 - encoder without index + * 1 - encoder with index + */ + int hasAbsoluteZero(); + /** + * returns 0 if it does need search for absolute zero + * 0 - encoder without index + * 1 - ecoder with index + */ + int needsAbsoluteZeroSearch(); + + private: + int hasIndex(); //!< function returning 1 if encoder has index pin and 0 if not. + + volatile long pulse_counter;//!< current pulse counter + volatile long pulse_timestamp;//!< last impulse timestamp in us + volatile int A_active; //!< current active states of A channel + volatile int B_active; //!< current active states of B channel + volatile int I_active; //!< current active states of Index channel + volatile long index_pulse_counter; //!< impulse counter number upon first index interrupt + + // velocity calculation variables + float prev_Th, pulse_per_second; + volatile long prev_pulse_counter, prev_timestamp_us; +}; + + +#endif diff --git a/arduino_foc_minimal_magnetic/FOCutils.cpp b/minimal_project_examples/arduino_foc_minimal_encoder/FOCutils.cpp similarity index 100% rename from arduino_foc_minimal_magnetic/FOCutils.cpp rename to minimal_project_examples/arduino_foc_minimal_encoder/FOCutils.cpp diff --git a/arduino_foc_minimal_magnetic/FOCutils.h b/minimal_project_examples/arduino_foc_minimal_encoder/FOCutils.h similarity index 97% rename from arduino_foc_minimal_magnetic/FOCutils.h rename to minimal_project_examples/arduino_foc_minimal_encoder/FOCutils.h index 110d1dcc..4c347a12 100644 --- a/arduino_foc_minimal_magnetic/FOCutils.h +++ b/minimal_project_examples/arduino_foc_minimal_encoder/FOCutils.h @@ -13,7 +13,7 @@ #endif // sign function -#define sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) #define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) // utility defines diff --git a/arduino_foc_minimal_magnetic/Sensor.h b/minimal_project_examples/arduino_foc_minimal_encoder/Sensor.h similarity index 72% rename from arduino_foc_minimal_magnetic/Sensor.h rename to minimal_project_examples/arduino_foc_minimal_encoder/Sensor.h index 56e4d286..7370c38f 100644 --- a/arduino_foc_minimal_magnetic/Sensor.h +++ b/minimal_project_examples/arduino_foc_minimal_encoder/Sensor.h @@ -1,6 +1,23 @@ #ifndef SENSOR_H #define SENSOR_H +/** + * Direction structure + */ +enum Direction{ + CW = 1, //clockwise + CCW = -1, // counter clockwise + UNKNOWN = 0 //not yet known or invalid state +}; + +/** + * Pullup configuration structure + */ +enum Pullup{ + INTERN, //!< Use internal pullups + EXTERN //!< Use external pullups +}; + /** * Sensor abstract class defintion * Each sensor needs to have these functions implemented @@ -22,6 +39,9 @@ class Sensor{ */ virtual float initAbsoluteZero(); + // if natural_direction == Direction::CCW then direction will be flipped to CW + int natural_direction = Direction::CW; + /** * returns 0 if it has no absolute 0 measurement * 0 - incremental encoder without index diff --git a/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino b/minimal_project_examples/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino similarity index 55% rename from arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino rename to minimal_project_examples/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino index 4f06a4a1..8951768f 100644 --- a/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino +++ b/minimal_project_examples/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino @@ -1,8 +1,5 @@ /** - * Comprehensive BLDC motor control example using encoder and the minimal version off the SimpleFOC library - * - THis code is completely stand alone and you dont need to have SimpleFOClibary installed to run it - * - * Check the docs.simplefoc.com for more information + * Comprehensive BLDC motor control example using encoder * * Using serial terminal user can send motor commands and configure the motor and FOC in real-time: * - configure PID controller constants @@ -20,13 +17,14 @@ * - to get the current target value enter: V3 * * List of commands: - * - P: velocity PI controller P gain - * - I: velocity PI controller I gain - * - L: velocity PI controller voltage limit - * - R: velocity PI controller voltage ramp + * - P: velocity PID controller P gain + * - I: velocity PID controller I gain + * - D: velocity PID controller D gain + * - R: velocity PID controller voltage ramp * - F: velocity Low pass filter time constant * - K: angle P controller P gain * - N: angle P controller velocity limit + * - L: system voltage limit * - C: control loop * - 0: voltage * - 1: velocity @@ -41,70 +39,53 @@ #include "BLDCMotor.h" #include "Encoder.h" -// BLDCMotor( int phA, int phB, int phC, int pp, int en) -// - phA, phB, phC - motor A,B,C phase pwm pins -// - pp - pole pair number -// - enable pin - (optional input) -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); - -//Encoder(int encA, int encB , int cpr, int index) -// - encA, encB - encoder A and B pins -// - ppr - impulses per rotation (cpr=ppr*4) -// - index pin - (optional input) -Encoder encoder = Encoder(2, 3, 8196); -// interrupt routine intialisation +// motor instance +BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 7); + +// encoder instance +Encoder encoder = Encoder(2, 3, 8192); + +// Interrupt routine intialisation +// channel A and B callbacks void doA(){encoder.handleA();} void doB(){encoder.handleB();} -void setup() { +void setup() { // initialize encoder sensor hardware encoder.init(); - encoder.enableInterrupts(doA,doB); + encoder.enableInterrupts(doA, doB); // link the motor to the sensor motor.linkSensor(&encoder); - // choose FOC algorithm to be used: - // FOCModulationType::SinePWM (default) - // FOCModulationType::SpaceVectorPWM + // choose FOC modulation motor.foc_modulation = FOCModulationType::SpaceVectorPWM; // power supply voltage [V] - // default 12V motor.voltage_power_supply = 12; - // motor and sensor aligning voltage [V] - // default 6V - motor.voltage_sensor_align = 3; - + // set control loop type to be used - // ControlType::voltage - // ControlType::velocity - // ControlType::angle motor.controller = ControlType::voltage; - // controller configuration based on the control type - // velocity PI controller parameters - motor.PI_velocity.P = 0.2; - motor.PI_velocity.I = 20; - // default voltage_power_supply/2 - motor.PI_velocity.voltage_limit = 6; - // jerk control using voltage voltage ramp - // default value is 300 volts per sec ~ 0.3V per millisecond - motor.PI_velocity.voltage_ramp = 1000; - - // velocity low pass filtering - // default 10ms - try different values to see what is the best. - // the lower the less filtered - motor.LPF_velocity.Tf = 0.0; + // contoller configuration based on the controll type + motor.PID_velocity.P = 0.2; + motor.PID_velocity.I = 20; + motor.PID_velocity.D = 0; + // default voltage_power_supply + motor.voltage_limit = 12; + + // velocity low pass filtering time constant + motor.LPF_velocity.Tf = 0.01; // angle loop controller - motor.P_angle.P = 3; - motor.P_angle.velocity_limit = 10; + motor.P_angle.P = 20; + // angle loop velocity limit + motor.velocity_limit = 50; // use monitoring with serial for motor init // monitoring port Serial.begin(115200); - // enable monitoring + // comment out if not needed motor.useMonitoring(Serial); // initialise motor @@ -115,18 +96,13 @@ void setup() { // set the inital target value motor.target = 2; - Serial.println("Full control example: "); - Serial.println("Voltage control target 2V."); + + // Run user commands to configure and the motor (find the full command list in docs.simplefoc.com) + Serial.println("Motor commands sketch | Initial motion control > torque/voltage : target 2V."); _delay(1000); - } -// target velocity variable -float target = 0; -// loop stats variables -unsigned long t = 0; -long timestamp = _micros(); void loop() { // iterative setting FOC phase voltage @@ -166,4 +142,4 @@ String serialReceiveUserCommand() { } } return command; -} +} \ No newline at end of file diff --git a/arduino_foc_minimal_magnetic/defaults.h b/minimal_project_examples/arduino_foc_minimal_encoder/defaults.h similarity index 64% rename from arduino_foc_minimal_magnetic/defaults.h rename to minimal_project_examples/arduino_foc_minimal_encoder/defaults.h index 5bcb0118..bbb48c6e 100644 --- a/arduino_foc_minimal_magnetic/defaults.h +++ b/minimal_project_examples/arduino_foc_minimal_encoder/defaults.h @@ -3,12 +3,13 @@ #define DEF_POWER_SUPPLY 12.0 //!< default power supply voltage // velocity PI controller params -#define DEF_PI_VEL_P 0.5 //!< default PI controller P value -#define DEF_PI_VEL_I 10 //!< default PI controller I value -#define DEF_PI_VEL_U_RAMP 1000 //!< default PI controller voltage ramp value +#define DEF_PID_VEL_P 0.5 //!< default PID controller P value +#define DEF_PID_VEL_I 10 //!< default PID controller I value +#define DEF_PID_VEL_D 0 //!< default PID controller D value +#define DEF_PID_VEL_U_RAMP 1000 //!< default PID controller voltage ramp value // angle P params #define DEF_P_ANGLE_P 20 //!< default P controller P value -#define DEF_P_ANGLE_VEL_LIM 20 //!< angle velocity limit default +#define DEF_VEL_LIM 20 //!< angle velocity limit default // index search #define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 //!< default index search velocity // align voltage diff --git a/minimal_project_examples/arduino_foc_minimal_hall/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_minimal_hall/BLDCMotor.cpp new file mode 100644 index 00000000..f31e818a --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_hall/BLDCMotor.cpp @@ -0,0 +1,716 @@ +#include "BLDCMotor.h" + +// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - phA, phB, phC - motor A,B,C phase pwm pins +// - pp - pole pair number +// - cpr - counts per rotation number (cpm=ppm*4) +// - enable pin - (optional input) +BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +{ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + pole_pairs = pp; + + // enable_pin pin + enable_pin = en; + + // Power supply voltage + voltage_power_supply = DEF_POWER_SUPPLY; + + // Velocity loop config + // PI controller constant + PID_velocity.P = DEF_PID_VEL_P; + PID_velocity.I = DEF_PID_VEL_I; + PID_velocity.D = DEF_PID_VEL_D; + PID_velocity.output_ramp = DEF_PID_VEL_U_RAMP; + PID_velocity.timestamp = _micros(); + PID_velocity.integral_prev = 0; + PID_velocity.output_prev = 0; + PID_velocity.tracking_error_prev = 0; + + // velocity low pass filter + LPF_velocity.Tf = DEF_VEL_FILTER_Tf; + LPF_velocity.timestamp = _micros(); + LPF_velocity.prev = 0; + + // position loop config + // P controller constant + P_angle.P = DEF_P_ANGLE_P; + + // maximum angular velocity to be used for positioning + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = voltage_power_supply; + + // index search velocity + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; + + // electric angle of the zero angle + zero_electric_angle = 0; + + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + + // default target value + target = 0; + + //monitor_port + monitor_port = nullptr; + //sensor + sensor = nullptr; +} + +// init hardware pins +void BLDCMotor::init() { + if(monitor_port) monitor_port->println("MOT: Init pins."); + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(hasEnable()) pinMode(enable_pin, OUTPUT); + + if(monitor_port) monitor_port->println("MOT: PWM config."); + // Increase PWM frequency to 32 kHz + // make silent + _setPwmFrequency(pwmA, pwmB, pwmC); + + // sanity check for the voltage limit configuration + if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + + _delay(500); + // enable motor + if(monitor_port) monitor_port->println("MOT: Enable."); + enable(); + _delay(500); + +} + + +// disable motor driver +void BLDCMotor::disable() +{ + // disable the driver - if enable_pin pin available + if (hasEnable()) digitalWrite(enable_pin, LOW); + // set zero to PWM + setPwm(0, 0, 0); +} +// enable motor driver +void BLDCMotor::enable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // enable_pin the driver - if enable_pin pin available + if (hasEnable()) digitalWrite(enable_pin, HIGH); + +} + +void BLDCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} + + +// Encoder alignment to electrical 0 angle +int BLDCMotor::alignSensor() { + if(monitor_port) monitor_port->println("MOT: Align sensor."); + // align the electrical phases of the motor and sensor + // set angle -90 degrees + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } + + // let the motor stabilize for 2 sec + _delay(2000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0,0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int BLDCMotor::absoluteZeroAlign() { + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = velocityPID(velocity_index_search - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); + + // align absolute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = normalizeAngle(electricAngle(zero_offset)); + } + // return bool if zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +/** + State calculation methods +*/ +// shaft angle calculation +float BLDCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return 0; + return sensor->getAngle(); +} +// shaft velocity calculation +float BLDCMotor::shaftVelocity() { + // if no sensor linked return 0 + if(!sensor) return 0; + return lowPassFilter(sensor->getVelocity(), LPF_velocity); +} +// Electrical angle calculation +float BLDCMotor::electricAngle(float shaftAngle) { + //return normalizeAngle(shaftAngle * pole_pairs); + return (shaftAngle * pole_pairs); +} + +/** + FOC functions +*/ +// FOC initialization function +int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } + if(monitor_port) monitor_port->println("MOT: Motor ready."); + + return exit_flag; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void BLDCMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); +} + +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function +// - if target is not set it uses motor.target value +void BLDCMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; + // get angular velocity + shaft_velocity = shaftVelocity(); + // choose control loop + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = positionP( shaft_angle_sp - shaft_angle ); + voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // include velocity loop + shaft_velocity_sp = target; + voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); + break; + } +} + + +// Method using FOC to set Uq to the motor at the optimal angle +// Function implementing Space Vector PWM and Sine PWM algorithms +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) +void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { + switch (foc_modulation) + { + case FOCModulationType::SinePWM : + // Sinusoidal PWM modulation + // Inverse Park + Clarke transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + + // Clarke transform + Ua = Ualpha + voltage_power_supply/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + break; + + case FOCModulationType::SpaceVectorPWM : + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // https://www.youtube.com/watch?v=QMSWUMEAejg + + // if negative voltages change inverse the phase + // angle + 180degrees + if(Uq < 0) angle_el += _PI; + Uq = abs(Uq); + + // angle normalisation in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = normalizeAngle(angle_el + zero_electric_angle + _PI_2); + + // find the sector we are in currently + int sector = floor(angle_el / _PI_3) + 1; + // calculate the duty cycles + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; + // two versions possible + // centered around voltage_power_supply/2 + float T0 = 1 - T1 - T2; + // pulled to 0 - better for low power supply voltage + //float T0 = 0; + + // calculate the duty cycles(times) + float Ta,Tb,Tc; + switch(sector){ + case 1: + Ta = T1 + T2 + T0/2; + Tb = T2 + T0/2; + Tc = T0/2; + break; + case 2: + Ta = T1 + T0/2; + Tb = T1 + T2 + T0/2; + Tc = T0/2; + break; + case 3: + Ta = T0/2; + Tb = T1 + T2 + T0/2; + Tc = T2 + T0/2; + break; + case 4: + Ta = T0/2; + Tb = T1+ T0/2; + Tc = T1 + T2 + T0/2; + break; + case 5: + Ta = T2 + T0/2; + Tb = T0/2; + Tc = T1 + T2 + T0/2; + break; + case 6: + Ta = T1 + T2 + T0/2; + Tb = T0/2; + Tc = T1 + T0/2; + break; + default: + // possible error state + Ta = 0; + Tb = 0; + Tc = 0; + } + + // calculate the phase voltages and center + Ua = Ta*voltage_power_supply; + Ub = Tb*voltage_power_supply; + Uc = Tc*voltage_power_supply; + break; + } + + // set the voltages in hardware + setPwm(Ua, Ub, Uc); +} + + + +// Set voltage to the pwm pin +void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { + // calculate duty cycle + // limited in [0,1] + float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); + // hardware specific writing + _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); +} + +/** + Utility functions +*/ +// normalizing radian angle to [0,2PI] +float BLDCMotor::normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} +// determining if the enable pin has been provided +int BLDCMotor::hasEnable(){ + return enable_pin != NOT_SET; +} + +// low pass filter function +// - input -singal to be filtered +// - lpf -LPF_s structure with filter parameters +float BLDCMotor::lowPassFilter(float input, LPF_s& lpf){ + unsigned long now_us = _micros(); + float Ts = (now_us - lpf.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // calculate the filtering + float alpha = lpf.Tf/(lpf.Tf + Ts); + float out = alpha*lpf.prev + (1-alpha)*input; + + // save the variables + lpf.prev = out; + lpf.timestamp = now_us; + return out; +} + + +/** + Motor control functions +*/ +// PID controller function +float BLDCMotor::controllerPID(float tracking_error, PID_s& cont){ + // calculate the time from the last call + unsigned long now_us = _micros(); + float Ts = (now_us - cont.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = cont.P * tracking_error; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = cont.integral_prev + cont.I*Ts*0.5*(tracking_error + cont.tracking_error_prev); + // antiwindup - limit the output voltage_q + integral = constrain(integral, -voltage_limit, voltage_limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = cont.D*(tracking_error - cont.tracking_error_prev)/Ts; + // sum all the components + float voltage = proportional + integral + derivative; + + // antiwindup - limit the output voltage_q + voltage = constrain(voltage, -voltage_limit, voltage_limit); + + // limit the acceleration by ramping the the voltage + float d_voltage = voltage - cont.output_prev; + if (abs(d_voltage)/Ts > cont.output_ramp) voltage = d_voltage > 0 ? cont.output_prev + cont.output_ramp*Ts : cont.output_prev - cont.output_ramp*Ts; + + // saving for the next pass + cont.integral_prev = integral; + cont.output_prev = voltage; + cont.tracking_error_prev = tracking_error; + cont.timestamp = now_us; + return voltage; +} +// velocity control loop PI controller +float BLDCMotor::velocityPID(float tracking_error) { + return controllerPID(tracking_error, PID_velocity); +} + +// P controller for position control loop +float BLDCMotor::positionP(float ek) { + // calculate the target velocity from the position error + float velocity_target = P_angle.P * ek; + // constrain velocity target value + velocity_target = constrain(velocity_target, -velocity_limit, velocity_limit); + return velocity_target; +} + +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void BLDCMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void BLDCMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void BLDCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void BLDCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity_openloop: + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle_openloop: + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int BLDCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'D': // velocity D gain change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PID velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P angle| "); + break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + + } + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("P: "); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("I: "); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); + break; + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("volt_ramp: "); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET)voltage_limit = value; + if(monitor_port) monitor_port->println(voltage_limit); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("Tf: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("vel_limit: "); + if(!GET) velocity_limit = value; + if(monitor_port) monitor_port->println(velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Control: "); + + if(GET){ // if get command + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + default: + if(monitor_port) monitor_port->println("open loop"); + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_hall/BLDCMotor.h b/minimal_project_examples/arduino_foc_minimal_hall/BLDCMotor.h new file mode 100644 index 00000000..95ca9472 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_hall/BLDCMotor.h @@ -0,0 +1,323 @@ +/** + * @file BLDCMotor.h + * + */ + +#ifndef BLDCMotor_h +#define BLDCMotor_h + +#include "Arduino.h" +#include "FOCutils.h" +#include "Sensor.h" +#include "defaults.h" + + +#define NOT_SET -12345.0 + +/** + * Motiron control type + */ +enum ControlType{ + voltage,//!< Torque control using voltage + velocity,//!< Velocity motion control + angle,//!< Position/angle motion control + velocity_openloop, + angle_openloop +}; + +/** + * FOC modulation type + */ +enum FOCModulationType{ + SinePWM, //!< Sinusoidal PWM modulation + SpaceVectorPWM //!< Space vector modulation method +}; + +/** + * PID controller structure + */ +struct PID_s{ + float P; //!< Proportional gain + float I; //!< Integral gain + float D; //!< Derivative gain + long timestamp; //!< Last execution timestamp + float integral_prev; //!< last integral component value + float output_prev; //!< last pid output value + float output_ramp; //!< Maximum speed of change of the output value + float tracking_error_prev; //!< last tracking error value +}; + +// P controller structure +struct P_s{ + float P; //!< Proportional gain + long timestamp; //!< Last execution timestamp +}; + +/** + * Low pass filter structure + */ +struct LPF_s{ + float Tf; //!< Low pass filter time constant + long timestamp; //!< Last execution timestamp + float prev; //!< filtered value in previous execution step +}; + + + + +/** + BLDC motor class +*/ +class BLDCMotor +{ + public: + /** + BLDCMotor class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param pp pole pair number + @param cpr counts per rotation number (cpm=ppm*4) + @param en enable pin (optional input) + */ + BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + + /** Motor hardware init function */ + void init(); + /** Motor disable function */ + void disable(); + /** Motor enable function */ + void enable(); + + /** + * Function linking a motor and a sensor + * + * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity + */ + void linkSensor(Sensor* sensor); + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + void loopFOC(); + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET); + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + + + + // State calculation methods + /** Shaft angle calculation in radians [rad] */ + float shaftAngle(); + /** + * Shaft angle calculation function in radian per second [rad/s] + * It implements low pass filtering + */ + float shaftVelocity(); + + // state variables + float target; //!< current target value - depends of the controller + float shaft_angle;//!< current motor angle + float shaft_velocity;//!< current motor velocity + float shaft_velocity_sp;//!< current target velocity + float shaft_angle_sp;//!< current target angle + float voltage_q;//!< current voltage u_q set + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + + // motor configuration parameters + float voltage_power_supply;//!< Power supply voltage + float voltage_sensor_align;//!< sensor and motor align voltage parameter + float velocity_index_search;//!< target velocity for index search + int pole_pairs;//!< Motor pole pairs number + + // limiting variables + float voltage_limit; //!< Voltage limitting variable - global limit + float velocity_limit; //!< Velocity limitting variable - global limit + + // configuration structures + ControlType controller; //!< parameter determining the control loop to be used + FOCModulationType foc_modulation;//!< parameter derterniming modulation algorithm + PID_s PID_velocity;//!< parameter determining the velocity PI configuration + P_s P_angle; //!< parameter determining the position P configuration + LPF_s LPF_velocity;//!< parameter determining the velocity Lpw pass filter configuration + + /** + * Sensor link: + * - Encoder + * - MagneticSensor + */ + Sensor* sensor; + + float zero_electric_angle;//!clk_cfg.prescale = 0; + + m_slot.mcpwm_num->timer[0].period.prescale = 4; + m_slot.mcpwm_num->timer[1].period.prescale = 4; + m_slot.mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + m_slot.mcpwm_num->timer[0].period.period = 2048; + m_slot.mcpwm_num->timer[1].period.period = 2048; + m_slot.mcpwm_num->timer[2].period.period = 2048; + _delay(1); + m_slot.mcpwm_num->timer[0].period.upmethod = 0; + m_slot.mcpwm_num->timer[1].period.upmethod = 0; + m_slot.mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + m_slot.mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + m_slot.mcpwm_num->timer[0].sync.out_sel = 0; +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + break; + } + } +#else // Arduino & STM32 devices + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255*dc_a); + analogWrite(pinB, 255*dc_b); + analogWrite(pinC, 255*dc_c); +#endif +} + + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} + + +// int array instead of float array +// 2x storage save (int 2Byte float 4 Byte ) +// sin*10000 +int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,1103,1181,1260,1338,1416,1494,1572,1650,1728,1806,1883,1961,2038,2115,2192,2269,2346,2423,2499,2575,2652,2728,2804,2879,2955,3030,3105,3180,3255,3329,3404,3478,3552,3625,3699,3772,3845,3918,3990,4063,4135,4206,4278,4349,4420,4491,4561,4631,4701,4770,4840,4909,4977,5046,5113,5181,5249,5316,5382,5449,5515,5580,5646,5711,5775,5839,5903,5967,6030,6093,6155,6217,6279,6340,6401,6461,6521,6581,6640,6699,6758,6815,6873,6930,6987,7043,7099,7154,7209,7264,7318,7371,7424,7477,7529,7581,7632,7683,7733,7783,7832,7881,7930,7977,8025,8072,8118,8164,8209,8254,8298,8342,8385,8428,8470,8512,8553,8594,8634,8673,8712,8751,8789,8826,8863,8899,8935,8970,9005,9039,9072,9105,9138,9169,9201,9231,9261,9291,9320,9348,9376,9403,9429,9455,9481,9506,9530,9554,9577,9599,9621,9642,9663,9683,9702,9721,9739,9757,9774,9790,9806,9821,9836,9850,9863,9876,9888,9899,9910,9920,9930,9939,9947,9955,9962,9969,9975,9980,9985,9989,9992,9995,9997,9999,10000,10000}; + +// function approximating the sine calculation by using fixed size array +// ~40us (float array) +// ~50us (int array) +// precision +-0.005 +// it has to receive an angle in between 0 and 2PI +float _sin(float a){ + if(a < _PI_2){ + //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; + //return sine_array[(int)(126.6873* a)]; // float array optimized + return 0.0001*sine_array[_round(126.6873* a)]; // int array optimized + }else if(a < _PI){ + // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; + //return sine_array[398 - (int)(126.6873*a)]; // float array optimized + return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimized + }else if(a < _3PI_2){ + // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; + //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimized + return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimized + } else { + // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; + //return -sine_array[796 - (int)(126.6873*a)]; // float array optimized + return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimized + } +} + +// function approximating cosine calculation by using fixed size array +// ~55us (float array) +// ~56us (int array) +// precision +-0.005 +// it has to receive an angle in between 0 and 2PI +float _cos(float a){ + float a_sin = a + _PI_2; + a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} diff --git a/minimal_project_examples/arduino_foc_minimal_hall/FOCutils.h b/minimal_project_examples/arduino_foc_minimal_hall/FOCutils.h new file mode 100644 index 00000000..4c347a12 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_hall/FOCutils.h @@ -0,0 +1,86 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + + +#if defined(ESP_H) // if esp32 boards + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +#endif + +// sign function +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + +// utility defines +#define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI 3.14159265359 +#define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + +/** + * High PWM frequency setting function + * - hardware specific + * + * @param pinA pinA number to configure + * @param pinB pinB number to configure + * @param pinC pinC number to configure + */ +void _setPwmFrequency(int pinA, int pinB, int pinC); + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); + + +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _sin(float a); +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _cos(float a); + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_hall/HallSensor.cpp b/minimal_project_examples/arduino_foc_minimal_hall/HallSensor.cpp new file mode 100644 index 00000000..7072a97a --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_hall/HallSensor.cpp @@ -0,0 +1,186 @@ +#include "HallSensor.h" + + +/* + HallSensor(int hallA, int hallB , int cpr, int index) + - hallA, hallB, hallC - HallSensor A, B and C pins + - pp - pole pairs +*/ + +HallSensor::HallSensor(int _hallA, int _hallB, int _hallC, int _pp){ + + // HallSensor measurement structure init + // hardware pins + pinA = _hallA; + pinB = _hallB; + pinC = _hallC; + // counter setup + pulse_counter = 0; + pulse_timestamp = 0; + + cpr = _pp * 6; // hall has 6 segments per electrical revolution + A_active = 0; + B_active = 0; + C_active = 0; + + // velocity calculation variables + + prev_pulse_counter = 0; + prev_timestamp_us = _micros(); + + // extern pullup as default + pullup = Pullup::EXTERN; +} + +// HallSensor interrupt callback functions +// A channel +void HallSensor::handleA() { + A_active= digitalRead(pinA); + updateState(); +} +// B channel +void HallSensor::handleB() { + B_active = digitalRead(pinB); + updateState(); +} + +// C channel +void HallSensor::handleC() { + C_active = digitalRead(pinC); + updateState(); +} + +void HallSensor::updateState() { + int newState = C_active + (B_active << 1) + (A_active << 2); + Direction direction = decodeDirection(state, newState); + state = newState; + + pulse_counter += direction; + pulse_timestamp = _micros(); +} + +// determines whether the hallsensr state transition means that it has moved one step CW (+1), CCW (-1) or state transition is invalid (0) +// states are 3bits, one for each hall sensor +Direction HallSensor::decodeDirection(int oldState, int newState) +{ + // here are expected state transitions (oldState > newState). + // CW state transitions are: ( 6 > 2 > 3 > 1 > 5 > 4 > 6 ) + // CCW state transitions are: ( 6 > 4 > 5 > 1 > 3 > 2 > 6 ) + // invalid state transitions are oldState == newState or if newState or oldState == 0 | 7 as hallsensors can't be all on or all off + + int rawDirection; + + if ( + (oldState == 6 && newState == 2) || \ + (oldState == 2 && newState == 3) || \ + (oldState == 3 && newState == 1) || \ + (oldState == 1 && newState == 5) || \ + (oldState == 5 && newState == 4) || \ + (oldState == 4 && newState == 6) + ) { + rawDirection = Direction::CW; + } else if( + (oldState == 6 && newState == 4) || \ + (oldState == 4 && newState == 5) || \ + (oldState == 5 && newState == 1) || \ + (oldState == 1 && newState == 3) || \ + (oldState == 3 && newState == 2) || \ + (oldState == 2 && newState == 6) + ) { + rawDirection = Direction::CCW; + } else { + rawDirection = Direction::UNKNOWN; + } + + direction = static_cast(rawDirection * natural_direction); + return direction; // * goofy; +} + +/* + Shaft angle calculation +*/ +float HallSensor::getAngle(){ + + long dN = pulse_counter - prev_pulse_counter; + + if (dN != 0) + { + + // time from last impulse + float Th = (pulse_timestamp - prev_timestamp_us) * 1e-6; + if (Th <= 0 || Th > 0.5) + Th = 1e-3; + // save variables for next pass + prev_timestamp_us = pulse_timestamp; + prev_pulse_counter = pulse_counter; + velocity = (float) _2PI * dN / (cpr * Th); + } + angle = (float) _2PI * pulse_counter / cpr; + + return angle; +} +/* + Shaft velocity calculation + function using mixed time and frequency measurement technique +*/ +float HallSensor::getVelocity(){ + // this is calculated during the last call to getAngle(); + return velocity; +} + +// getter for index pin +// return -1 if no index +int HallSensor::needsAbsoluteZeroSearch(){ + return 0; +} +// getter for index pin +int HallSensor::hasAbsoluteZero(){ + return 0; +} +// initialize counter to zero +float HallSensor::initRelativeZero(){ + + pulse_counter = 0; + pulse_timestamp = _micros(); + velocity = 0; + return 0.0; +} +// initialize index to zero +float HallSensor::initAbsoluteZero(){ + return 0.0; +} + +// HallSensor initialisation of the hardware pins +// and calculation variables +void HallSensor::init(){ + + // HallSensor - check if pullup needed for your HallSensor + if(pullup == Pullup::INTERN){ + pinMode(pinA, INPUT_PULLUP); + pinMode(pinB, INPUT_PULLUP); + pinMode(pinC, INPUT_PULLUP); + }else{ + pinMode(pinA, INPUT); + pinMode(pinB, INPUT); + pinMode(pinC, INPUT); + } + + // counter setup + pulse_counter = 0; + pulse_timestamp = _micros(); + prev_pulse_counter = 0; + prev_timestamp_us = _micros(); + +} + +// function enabling hardware interrupts for the callback provided +// if callback is not provided then the interrupt is not enabled +void HallSensor::enableInterrupts(void (*doA)(), void(*doB)(), void(*doC)()){ + // attach interrupt if functions provided + + // A, B and C callback + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); + if(doC != nullptr) attachInterrupt(digitalPinToInterrupt(pinC), doC, CHANGE); +} + diff --git a/minimal_project_examples/arduino_foc_minimal_hall/HallSensor.h b/minimal_project_examples/arduino_foc_minimal_hall/HallSensor.h new file mode 100644 index 00000000..018426f9 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_hall/HallSensor.h @@ -0,0 +1,107 @@ +#ifndef HALL_SENSOR_LIB_H +#define HALL_SENSOR_LIB_H + +#include "Arduino.h" +#include "FOCutils.h" +#include "Sensor.h" + + +class HallSensor: public Sensor{ + public: + /** + HallSensor class constructor + @param encA HallSensor B pin + @param encB HallSensor B pin + @param encC HallSensor B pin + @param pp pole pairs (e.g hoverboard motor has 15pp and small gimbals often have 7pp) + @param index index pin number (optional input) + */ + HallSensor(int encA, int encB, int encC, int pp); + + /** HallSensor initialise pins */ + void init(); + /** + * function enabling hardware interrupts for the HallSensor channels with provided callback functions + * if callback is not provided then the interrupt is not enabled + * + * @param doA pointer to the A channel interrupt handler function + * @param doB pointer to the B channel interrupt handler function + * @param doIndex pointer to the Index channel interrupt handler function + * + */ + void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doC)() = nullptr); + + // HallSensor interrupt callback functions + /** A channel callback function */ + void handleA(); + /** B channel callback function */ + void handleB(); + /** C channel callback function */ + void handleC(); + + + // pins A and B + int pinA; //!< HallSensor hardware pin A + int pinB; //!< HallSensor hardware pin B + int pinC; //!< HallSensor hardware pin C + + // HallSensor configuration + Pullup pullup; //!< Configuration parameter internal or external pullups + float cpr;//!< HallSensor cpr number + + // Abstract functions of the Sensor class implementation + /** get current angle (rad) */ + float getAngle(); + /** get current angular velocity (rad/s) */ + float getVelocity(); + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + float initRelativeZero(); + /** + * set index angle as zero angle + * return the angle [rad] difference + */ + float initAbsoluteZero(); + /** + * returns 0 if it has no index + * 0 - HallSensor without index + * 1 - HallSensor with index + */ + int hasAbsoluteZero(); + /** + * returns 0 if it does need search for absolute zero + * 0 - HallSensor without index + * 1 - ecoder with index + */ + int needsAbsoluteZeroSearch(); + + // whether last step was CW (+1) or CCW (-1) direction + Direction direction; + + // the current 3bit state of the hall sensors + int state; + + volatile float angle; // rad/s + volatile float velocity; // rad/s + + private: + + Direction decodeDirection(int oldState, int newState); + void updateState(); + + volatile long pulse_counter;//!< current pulse counter + volatile long pulse_timestamp;//!< last impulse timestamp in us + volatile int A_active; //!< current active states of A channel + volatile int B_active; //!< current active states of B channel + volatile int C_active; //!< current active states of C channel + + // velocity calculation variables + // float prev_Th, pulse_per_second; + volatile long prev_pulse_counter, prev_timestamp_us; + +}; + + +#endif diff --git a/minimal_project_examples/arduino_foc_minimal_hall/Sensor.h b/minimal_project_examples/arduino_foc_minimal_hall/Sensor.h new file mode 100644 index 00000000..7370c38f --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_hall/Sensor.h @@ -0,0 +1,59 @@ +#ifndef SENSOR_H +#define SENSOR_H + +/** + * Direction structure + */ +enum Direction{ + CW = 1, //clockwise + CCW = -1, // counter clockwise + UNKNOWN = 0 //not yet known or invalid state +}; + +/** + * Pullup configuration structure + */ +enum Pullup{ + INTERN, //!< Use internal pullups + EXTERN //!< Use external pullups +}; + +/** + * Sensor abstract class defintion + * Each sensor needs to have these functions implemented + */ +class Sensor{ + public: + /** get current angle (rad) */ + virtual float getAngle(); + /** get current angular velocity (rad/s)*/ + virtual float getVelocity(); + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + virtual float initRelativeZero(); + /** + * set absolute zero angle as zero angle + * return the angle [rad] difference + */ + virtual float initAbsoluteZero(); + + // if natural_direction == Direction::CCW then direction will be flipped to CW + int natural_direction = Direction::CW; + + /** + * returns 0 if it has no absolute 0 measurement + * 0 - incremental encoder without index + * 1 - encoder with index & magnetic sensors + */ + virtual int hasAbsoluteZero(); + /** + * returns 0 if it does need search for absolute zero + * 0 - magnetic sensor (& encoder with index which is found) + * 1 - ecoder with index (with index not found yet) + */ + virtual int needsAbsoluteZeroSearch(); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_hall/arduino_foc_minimal_hall.ino b/minimal_project_examples/arduino_foc_minimal_hall/arduino_foc_minimal_hall.ino new file mode 100644 index 00000000..d06cb7a3 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_hall/arduino_foc_minimal_hall.ino @@ -0,0 +1,155 @@ +/** + * Comprehensive BLDC motor control example using Hall sensor + * + * Using serial terminal user can send motor commands and configure the motor and FOC in real-time: + * - configure PID controller constants + * - change motion control loops + * - monitor motor variabels + * - set target values + * - check all the configuration values + * + * To check the config value just enter the command letter. + * For example: - to read velocity PI controller P gain run: P + * - to set velocity PI controller P gain to 1.2 run: P1.2 + * + * To change the target value just enter a number in the terminal: + * For example: - to change the target value to -0.1453 enter: -0.1453 + * - to get the current target value enter: V3 + * + * List of commands: + * - P: velocity PID controller P gain + * - I: velocity PID controller I gain + * - D: velocity PID controller D gain + * - R: velocity PID controller voltage ramp + * - F: velocity Low pass filter time constant + * - K: angle P controller P gain + * - N: angle P controller velocity limit + * - L: system voltage limit + * - C: control loop + * - 0: voltage + * - 1: velocity + * - 2: angle + * - V: get motor variables + * - 0: currently set voltage + * - 1: current velocity + * - 2: current angle + * - 3: current target value + * + */ +#include "BLDCMotor.h" +#include "HallSensor.h" + +// software interrupt library +#include +#include + +// motor instance +BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 7); + +// hall sensor instance +HallSensor sensor = HallSensor(2, 3, 4, 11); + +// Interrupt routine intialisation +// channel A, B and C callbacks +void doA(){sensor.handleA();} +void doB(){sensor.handleB();} +void doC(){sensor.handleC();} +// If no available hadware interrupt pins use the software interrupt +PciListenerImp listenC(sensor.pinC, doC); + +void setup() { + + // initialize encoder sensor hardware + sensor.init(); + sensor.enableInterrupts(doA, doB); //, doC); + // software interrupts + PciManager.registerListener(&listenC); + + // link the motor to the sensor + motor.linkSensor(&sensor); + + // choose FOC modulation + motor.foc_modulation = FOCModulationType::SpaceVectorPWM; + + // power supply voltage [V] + motor.voltage_power_supply = 12; + + // set control loop type to be used + motor.controller = ControlType::voltage; + + // contoller configuration based on the controll type + motor.PID_velocity.P = 0.2; + motor.PID_velocity.I = 20; + motor.PID_velocity.D = 0; + // default voltage_power_supply + motor.voltage_limit = 12; + + // velocity low pass filtering time constant + motor.LPF_velocity.Tf = 0.01; + + // angle loop controller + motor.P_angle.P = 20; + // angle loop velocity limit + motor.velocity_limit = 50; + + // use monitoring with serial for motor init + // monitoring port + Serial.begin(115200); + // comment out if not needed + motor.useMonitoring(Serial); + + // initialise motor + motor.init(); + // align encoder and start FOC + motor.initFOC(); + + // set the inital target value + motor.target = 2; + + + // Run user commands to configure and the motor (find the full command list in docs.simplefoc.com) + Serial.println("Motor commands sketch | Initial motion control > torque/voltage : target 2V."); + + _delay(1000); +} + + +void loop() { + // iterative setting FOC phase voltage + motor.loopFOC(); + + // iterative function setting the outter loop target + // velocity, position or voltage + // if tatget not set in parameter uses motor.target variable + motor.move(); + + // user communication + motor.command(serialReceiveUserCommand()); +} + +// utility function enabling serial communication the user +String serialReceiveUserCommand() { + + // a string to hold incoming data + static String received_chars; + + String command = ""; + + while (Serial.available()) { + // get the new byte: + char inChar = (char)Serial.read(); + // add it to the string buffer: + received_chars += inChar; + + // end of user input + if (inChar == '\n') { + + // execute the user command + command = received_chars; + + // reset the command buffer + received_chars = ""; + } + } + return command; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_hall/defaults.h b/minimal_project_examples/arduino_foc_minimal_hall/defaults.h new file mode 100644 index 00000000..bbb48c6e --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_hall/defaults.h @@ -0,0 +1,18 @@ +// default configuration values +// change this file to optimal values for your application + +#define DEF_POWER_SUPPLY 12.0 //!< default power supply voltage +// velocity PI controller params +#define DEF_PID_VEL_P 0.5 //!< default PID controller P value +#define DEF_PID_VEL_I 10 //!< default PID controller I value +#define DEF_PID_VEL_D 0 //!< default PID controller D value +#define DEF_PID_VEL_U_RAMP 1000 //!< default PID controller voltage ramp value +// angle P params +#define DEF_P_ANGLE_P 20 //!< default P controller P value +#define DEF_VEL_LIM 20 //!< angle velocity limit default +// index search +#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 //!< default index search velocity +// align voltage +#define DEF_VOLTAGE_SENSOR_ALIGN 6.0 //!< default voltage for sensor and motor zero alignemt +// low pass filter velocity +#define DEF_VEL_FILTER_Tf 0.005 //!< default velocity filter time constant \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/BLDCMotor.cpp new file mode 100644 index 00000000..f31e818a --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/BLDCMotor.cpp @@ -0,0 +1,716 @@ +#include "BLDCMotor.h" + +// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - phA, phB, phC - motor A,B,C phase pwm pins +// - pp - pole pair number +// - cpr - counts per rotation number (cpm=ppm*4) +// - enable pin - (optional input) +BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +{ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + pole_pairs = pp; + + // enable_pin pin + enable_pin = en; + + // Power supply voltage + voltage_power_supply = DEF_POWER_SUPPLY; + + // Velocity loop config + // PI controller constant + PID_velocity.P = DEF_PID_VEL_P; + PID_velocity.I = DEF_PID_VEL_I; + PID_velocity.D = DEF_PID_VEL_D; + PID_velocity.output_ramp = DEF_PID_VEL_U_RAMP; + PID_velocity.timestamp = _micros(); + PID_velocity.integral_prev = 0; + PID_velocity.output_prev = 0; + PID_velocity.tracking_error_prev = 0; + + // velocity low pass filter + LPF_velocity.Tf = DEF_VEL_FILTER_Tf; + LPF_velocity.timestamp = _micros(); + LPF_velocity.prev = 0; + + // position loop config + // P controller constant + P_angle.P = DEF_P_ANGLE_P; + + // maximum angular velocity to be used for positioning + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = voltage_power_supply; + + // index search velocity + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; + + // electric angle of the zero angle + zero_electric_angle = 0; + + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + + // default target value + target = 0; + + //monitor_port + monitor_port = nullptr; + //sensor + sensor = nullptr; +} + +// init hardware pins +void BLDCMotor::init() { + if(monitor_port) monitor_port->println("MOT: Init pins."); + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(hasEnable()) pinMode(enable_pin, OUTPUT); + + if(monitor_port) monitor_port->println("MOT: PWM config."); + // Increase PWM frequency to 32 kHz + // make silent + _setPwmFrequency(pwmA, pwmB, pwmC); + + // sanity check for the voltage limit configuration + if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + + _delay(500); + // enable motor + if(monitor_port) monitor_port->println("MOT: Enable."); + enable(); + _delay(500); + +} + + +// disable motor driver +void BLDCMotor::disable() +{ + // disable the driver - if enable_pin pin available + if (hasEnable()) digitalWrite(enable_pin, LOW); + // set zero to PWM + setPwm(0, 0, 0); +} +// enable motor driver +void BLDCMotor::enable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // enable_pin the driver - if enable_pin pin available + if (hasEnable()) digitalWrite(enable_pin, HIGH); + +} + +void BLDCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} + + +// Encoder alignment to electrical 0 angle +int BLDCMotor::alignSensor() { + if(monitor_port) monitor_port->println("MOT: Align sensor."); + // align the electrical phases of the motor and sensor + // set angle -90 degrees + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } + + // let the motor stabilize for 2 sec + _delay(2000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0,0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int BLDCMotor::absoluteZeroAlign() { + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = velocityPID(velocity_index_search - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); + + // align absolute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = normalizeAngle(electricAngle(zero_offset)); + } + // return bool if zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +/** + State calculation methods +*/ +// shaft angle calculation +float BLDCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return 0; + return sensor->getAngle(); +} +// shaft velocity calculation +float BLDCMotor::shaftVelocity() { + // if no sensor linked return 0 + if(!sensor) return 0; + return lowPassFilter(sensor->getVelocity(), LPF_velocity); +} +// Electrical angle calculation +float BLDCMotor::electricAngle(float shaftAngle) { + //return normalizeAngle(shaftAngle * pole_pairs); + return (shaftAngle * pole_pairs); +} + +/** + FOC functions +*/ +// FOC initialization function +int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } + if(monitor_port) monitor_port->println("MOT: Motor ready."); + + return exit_flag; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void BLDCMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); +} + +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function +// - if target is not set it uses motor.target value +void BLDCMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; + // get angular velocity + shaft_velocity = shaftVelocity(); + // choose control loop + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = positionP( shaft_angle_sp - shaft_angle ); + voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // include velocity loop + shaft_velocity_sp = target; + voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); + break; + } +} + + +// Method using FOC to set Uq to the motor at the optimal angle +// Function implementing Space Vector PWM and Sine PWM algorithms +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) +void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { + switch (foc_modulation) + { + case FOCModulationType::SinePWM : + // Sinusoidal PWM modulation + // Inverse Park + Clarke transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + + // Clarke transform + Ua = Ualpha + voltage_power_supply/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + break; + + case FOCModulationType::SpaceVectorPWM : + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // https://www.youtube.com/watch?v=QMSWUMEAejg + + // if negative voltages change inverse the phase + // angle + 180degrees + if(Uq < 0) angle_el += _PI; + Uq = abs(Uq); + + // angle normalisation in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = normalizeAngle(angle_el + zero_electric_angle + _PI_2); + + // find the sector we are in currently + int sector = floor(angle_el / _PI_3) + 1; + // calculate the duty cycles + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; + // two versions possible + // centered around voltage_power_supply/2 + float T0 = 1 - T1 - T2; + // pulled to 0 - better for low power supply voltage + //float T0 = 0; + + // calculate the duty cycles(times) + float Ta,Tb,Tc; + switch(sector){ + case 1: + Ta = T1 + T2 + T0/2; + Tb = T2 + T0/2; + Tc = T0/2; + break; + case 2: + Ta = T1 + T0/2; + Tb = T1 + T2 + T0/2; + Tc = T0/2; + break; + case 3: + Ta = T0/2; + Tb = T1 + T2 + T0/2; + Tc = T2 + T0/2; + break; + case 4: + Ta = T0/2; + Tb = T1+ T0/2; + Tc = T1 + T2 + T0/2; + break; + case 5: + Ta = T2 + T0/2; + Tb = T0/2; + Tc = T1 + T2 + T0/2; + break; + case 6: + Ta = T1 + T2 + T0/2; + Tb = T0/2; + Tc = T1 + T0/2; + break; + default: + // possible error state + Ta = 0; + Tb = 0; + Tc = 0; + } + + // calculate the phase voltages and center + Ua = Ta*voltage_power_supply; + Ub = Tb*voltage_power_supply; + Uc = Tc*voltage_power_supply; + break; + } + + // set the voltages in hardware + setPwm(Ua, Ub, Uc); +} + + + +// Set voltage to the pwm pin +void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { + // calculate duty cycle + // limited in [0,1] + float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); + // hardware specific writing + _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); +} + +/** + Utility functions +*/ +// normalizing radian angle to [0,2PI] +float BLDCMotor::normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} +// determining if the enable pin has been provided +int BLDCMotor::hasEnable(){ + return enable_pin != NOT_SET; +} + +// low pass filter function +// - input -singal to be filtered +// - lpf -LPF_s structure with filter parameters +float BLDCMotor::lowPassFilter(float input, LPF_s& lpf){ + unsigned long now_us = _micros(); + float Ts = (now_us - lpf.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // calculate the filtering + float alpha = lpf.Tf/(lpf.Tf + Ts); + float out = alpha*lpf.prev + (1-alpha)*input; + + // save the variables + lpf.prev = out; + lpf.timestamp = now_us; + return out; +} + + +/** + Motor control functions +*/ +// PID controller function +float BLDCMotor::controllerPID(float tracking_error, PID_s& cont){ + // calculate the time from the last call + unsigned long now_us = _micros(); + float Ts = (now_us - cont.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = cont.P * tracking_error; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = cont.integral_prev + cont.I*Ts*0.5*(tracking_error + cont.tracking_error_prev); + // antiwindup - limit the output voltage_q + integral = constrain(integral, -voltage_limit, voltage_limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = cont.D*(tracking_error - cont.tracking_error_prev)/Ts; + // sum all the components + float voltage = proportional + integral + derivative; + + // antiwindup - limit the output voltage_q + voltage = constrain(voltage, -voltage_limit, voltage_limit); + + // limit the acceleration by ramping the the voltage + float d_voltage = voltage - cont.output_prev; + if (abs(d_voltage)/Ts > cont.output_ramp) voltage = d_voltage > 0 ? cont.output_prev + cont.output_ramp*Ts : cont.output_prev - cont.output_ramp*Ts; + + // saving for the next pass + cont.integral_prev = integral; + cont.output_prev = voltage; + cont.tracking_error_prev = tracking_error; + cont.timestamp = now_us; + return voltage; +} +// velocity control loop PI controller +float BLDCMotor::velocityPID(float tracking_error) { + return controllerPID(tracking_error, PID_velocity); +} + +// P controller for position control loop +float BLDCMotor::positionP(float ek) { + // calculate the target velocity from the position error + float velocity_target = P_angle.P * ek; + // constrain velocity target value + velocity_target = constrain(velocity_target, -velocity_limit, velocity_limit); + return velocity_target; +} + +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void BLDCMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void BLDCMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void BLDCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void BLDCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity_openloop: + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle_openloop: + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int BLDCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'D': // velocity D gain change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PID velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P angle| "); + break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + + } + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("P: "); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("I: "); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); + break; + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("volt_ramp: "); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET)voltage_limit = value; + if(monitor_port) monitor_port->println(voltage_limit); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("Tf: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("vel_limit: "); + if(!GET) velocity_limit = value; + if(monitor_port) monitor_port->println(velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Control: "); + + if(GET){ // if get command + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + default: + if(monitor_port) monitor_port->println("open loop"); + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/BLDCMotor.h b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/BLDCMotor.h new file mode 100644 index 00000000..95ca9472 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/BLDCMotor.h @@ -0,0 +1,323 @@ +/** + * @file BLDCMotor.h + * + */ + +#ifndef BLDCMotor_h +#define BLDCMotor_h + +#include "Arduino.h" +#include "FOCutils.h" +#include "Sensor.h" +#include "defaults.h" + + +#define NOT_SET -12345.0 + +/** + * Motiron control type + */ +enum ControlType{ + voltage,//!< Torque control using voltage + velocity,//!< Velocity motion control + angle,//!< Position/angle motion control + velocity_openloop, + angle_openloop +}; + +/** + * FOC modulation type + */ +enum FOCModulationType{ + SinePWM, //!< Sinusoidal PWM modulation + SpaceVectorPWM //!< Space vector modulation method +}; + +/** + * PID controller structure + */ +struct PID_s{ + float P; //!< Proportional gain + float I; //!< Integral gain + float D; //!< Derivative gain + long timestamp; //!< Last execution timestamp + float integral_prev; //!< last integral component value + float output_prev; //!< last pid output value + float output_ramp; //!< Maximum speed of change of the output value + float tracking_error_prev; //!< last tracking error value +}; + +// P controller structure +struct P_s{ + float P; //!< Proportional gain + long timestamp; //!< Last execution timestamp +}; + +/** + * Low pass filter structure + */ +struct LPF_s{ + float Tf; //!< Low pass filter time constant + long timestamp; //!< Last execution timestamp + float prev; //!< filtered value in previous execution step +}; + + + + +/** + BLDC motor class +*/ +class BLDCMotor +{ + public: + /** + BLDCMotor class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param pp pole pair number + @param cpr counts per rotation number (cpm=ppm*4) + @param en enable pin (optional input) + */ + BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + + /** Motor hardware init function */ + void init(); + /** Motor disable function */ + void disable(); + /** Motor enable function */ + void enable(); + + /** + * Function linking a motor and a sensor + * + * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity + */ + void linkSensor(Sensor* sensor); + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + void loopFOC(); + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET); + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + + + + // State calculation methods + /** Shaft angle calculation in radians [rad] */ + float shaftAngle(); + /** + * Shaft angle calculation function in radian per second [rad/s] + * It implements low pass filtering + */ + float shaftVelocity(); + + // state variables + float target; //!< current target value - depends of the controller + float shaft_angle;//!< current motor angle + float shaft_velocity;//!< current motor velocity + float shaft_velocity_sp;//!< current target velocity + float shaft_angle_sp;//!< current target angle + float voltage_q;//!< current voltage u_q set + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + + // motor configuration parameters + float voltage_power_supply;//!< Power supply voltage + float voltage_sensor_align;//!< sensor and motor align voltage parameter + float velocity_index_search;//!< target velocity for index search + int pole_pairs;//!< Motor pole pairs number + + // limiting variables + float voltage_limit; //!< Voltage limitting variable - global limit + float velocity_limit; //!< Velocity limitting variable - global limit + + // configuration structures + ControlType controller; //!< parameter determining the control loop to be used + FOCModulationType foc_modulation;//!< parameter derterniming modulation algorithm + PID_s PID_velocity;//!< parameter determining the velocity PI configuration + P_s P_angle; //!< parameter determining the position P configuration + LPF_s LPF_velocity;//!< parameter determining the velocity Lpw pass filter configuration + + /** + * Sensor link: + * - Encoder + * - MagneticSensor + */ + Sensor* sensor; + + float zero_electric_angle;//!clk_cfg.prescale = 0; + + m_slot.mcpwm_num->timer[0].period.prescale = 4; + m_slot.mcpwm_num->timer[1].period.prescale = 4; + m_slot.mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + m_slot.mcpwm_num->timer[0].period.period = 2048; + m_slot.mcpwm_num->timer[1].period.period = 2048; + m_slot.mcpwm_num->timer[2].period.period = 2048; + _delay(1); + m_slot.mcpwm_num->timer[0].period.upmethod = 0; + m_slot.mcpwm_num->timer[1].period.upmethod = 0; + m_slot.mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + m_slot.mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + m_slot.mcpwm_num->timer[0].sync.out_sel = 0; +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + break; + } + } +#else // Arduino & STM32 devices + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255*dc_a); + analogWrite(pinB, 255*dc_b); + analogWrite(pinC, 255*dc_c); +#endif +} + + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} + + +// int array instead of float array +// 2x storage save (int 2Byte float 4 Byte ) +// sin*10000 +int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,1103,1181,1260,1338,1416,1494,1572,1650,1728,1806,1883,1961,2038,2115,2192,2269,2346,2423,2499,2575,2652,2728,2804,2879,2955,3030,3105,3180,3255,3329,3404,3478,3552,3625,3699,3772,3845,3918,3990,4063,4135,4206,4278,4349,4420,4491,4561,4631,4701,4770,4840,4909,4977,5046,5113,5181,5249,5316,5382,5449,5515,5580,5646,5711,5775,5839,5903,5967,6030,6093,6155,6217,6279,6340,6401,6461,6521,6581,6640,6699,6758,6815,6873,6930,6987,7043,7099,7154,7209,7264,7318,7371,7424,7477,7529,7581,7632,7683,7733,7783,7832,7881,7930,7977,8025,8072,8118,8164,8209,8254,8298,8342,8385,8428,8470,8512,8553,8594,8634,8673,8712,8751,8789,8826,8863,8899,8935,8970,9005,9039,9072,9105,9138,9169,9201,9231,9261,9291,9320,9348,9376,9403,9429,9455,9481,9506,9530,9554,9577,9599,9621,9642,9663,9683,9702,9721,9739,9757,9774,9790,9806,9821,9836,9850,9863,9876,9888,9899,9910,9920,9930,9939,9947,9955,9962,9969,9975,9980,9985,9989,9992,9995,9997,9999,10000,10000}; + +// function approximating the sine calculation by using fixed size array +// ~40us (float array) +// ~50us (int array) +// precision +-0.005 +// it has to receive an angle in between 0 and 2PI +float _sin(float a){ + if(a < _PI_2){ + //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; + //return sine_array[(int)(126.6873* a)]; // float array optimized + return 0.0001*sine_array[_round(126.6873* a)]; // int array optimized + }else if(a < _PI){ + // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; + //return sine_array[398 - (int)(126.6873*a)]; // float array optimized + return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimized + }else if(a < _3PI_2){ + // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; + //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimized + return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimized + } else { + // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; + //return -sine_array[796 - (int)(126.6873*a)]; // float array optimized + return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimized + } +} + +// function approximating cosine calculation by using fixed size array +// ~55us (float array) +// ~56us (int array) +// precision +-0.005 +// it has to receive an angle in between 0 and 2PI +float _cos(float a){ + float a_sin = a + _PI_2; + a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/FOCutils.h b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/FOCutils.h new file mode 100644 index 00000000..4c347a12 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/FOCutils.h @@ -0,0 +1,86 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + + +#if defined(ESP_H) // if esp32 boards + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +#endif + +// sign function +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + +// utility defines +#define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI 3.14159265359 +#define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + +/** + * High PWM frequency setting function + * - hardware specific + * + * @param pinA pinA number to configure + * @param pinB pinB number to configure + * @param pinC pinC number to configure + */ +void _setPwmFrequency(int pinA, int pinB, int pinC); + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); + + +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _sin(float a); +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _cos(float a); + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/MagneticSensorI2C.cpp b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/MagneticSensorI2C.cpp new file mode 100644 index 00000000..eb94a753 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/MagneticSensorI2C.cpp @@ -0,0 +1,154 @@ +#include "MagneticSensorI2C.h" + +// MagneticSensorI2C(uint8_t _chip_address, float _cpr, uint8_t _angle_register_msb) +// @param _chip_address I2C chip address +// @param _bit_resolution bit resolution of the sensor +// @param _angle_register_msb angle read register +// @param _bits_used_msb number of used bits in msb +MagneticSensorI2C::MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _bits_used_msb){ + // chip I2C address + chip_address = _chip_address; + // angle read register of the magnetic sensor + angle_register_msb = _angle_register_msb; + // register maximum value (counts per revolution) + cpr = pow(2, _bit_resolution); + + // depending on the sensor architecture there are different combinations of + // LSB and MSB register used bits + // AS5600 uses 0..7 LSB and 8..11 MSB + // AS5048 uses 0..5 LSB and 6..13 MSB + // used bits in LSB + lsb_used = _bit_resolution - _bits_used_msb; + // extraction masks + lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); + msb_mask = (uint8_t)( (2 << _bits_used_msb) - 1 ); +} + + +void MagneticSensorI2C::init(){ + + //I2C communication begin + Wire.begin(); + + // velocity calculation init + angle_prev = 0; + velocity_calc_timestamp = _micros(); + + // full rotations tracking number + full_rotation_offset = 0; + angle_data_prev = getRawCount(); + zero_offset = 0; +} + +// Shaft angle calculation +// angle is in radians [rad] +float MagneticSensorI2C::getAngle(){ + // raw data from the sensor + float angle_data = getRawCount(); + + // tracking the number of rotations + // in order to expand angle range form [0,2PI] + // to basically infinity + float d_angle = angle_data - angle_data_prev; + // if overflow happened track it as full rotation + if(abs(d_angle) > (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; + // save the current angle value for the next steps + // in order to know if overflow happened + angle_data_prev = angle_data; + + // zero offset adding + angle_data -= (int)zero_offset; + // return the full angle + // (number of full rotations)*2PI + current sensor angle + return natural_direction * (full_rotation_offset + ( angle_data / (float)cpr) * _2PI); +} + +// Shaft velocity calculation +float MagneticSensorI2C::getVelocity(){ + // calculate sample time + unsigned long now_us = _micros(); + float Ts = (now_us - velocity_calc_timestamp)*1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // current angle + float angle_c = getAngle(); + // velocity calculation + float vel = (angle_c - angle_prev)/Ts; + + // save variables for future pass + angle_prev = angle_c; + velocity_calc_timestamp = now_us; + return vel; +} + +// set current angle as zero angle +// return the angle [rad] difference +float MagneticSensorI2C::initRelativeZero(){ + float angle_offset = -getAngle(); + zero_offset = natural_direction * getRawCount(); + + // angle tracking variables + full_rotation_offset = 0; + return angle_offset; +} +// set absolute zero angle as zero angle +// return the angle [rad] difference +float MagneticSensorI2C::initAbsoluteZero(){ + float rotation = -(int)zero_offset; + // init absolute zero + zero_offset = 0; + + // angle tracking variables + full_rotation_offset = 0; + // return offset in radians + return rotation / (float)cpr * _2PI; +} +// returns 0 if it has no absolute 0 measurement +// 0 - incremental encoder without index +// 1 - encoder with index & magnetic sensors +int MagneticSensorI2C::hasAbsoluteZero(){ + return 1; +} +// returns 0 if it does need search for absolute zero +// 0 - magnetic sensor +// 1 - ecoder with index +int MagneticSensorI2C::needsAbsoluteZeroSearch(){ + return 0; +} + + +// function reading the raw counter of the magnetic sensor +int MagneticSensorI2C::getRawCount(){ + return (int)MagneticSensorI2C::read(angle_register_msb); +} + +// I2C functions +/* +* Read a register from the sensor +* Takes the address of the register as a uint8_t +* Returns the value of the register +*/ +int MagneticSensorI2C::read(uint8_t angle_reg_msb) { + // read the angle register first MSB then LSB + byte readArray[2]; + uint16_t readValue = 0; + // notify the device that is aboout to be read + Wire.beginTransmission(chip_address); + Wire.write(angle_reg_msb); + Wire.endTransmission(false); + + // read the data msb and lsb + Wire.requestFrom(chip_address, (uint8_t)2); + for (byte i=0; i < 2; i++) { + readArray[i] = Wire.read(); + } + + // depending on the sensor architecture there are different combinations of + // LSB and MSB register used bits + // AS5600 uses 0..7 LSB and 8..11 MSB + // AS5048 uses 0..5 LSB and 6..13 MSB + readValue = ( readArray[1] & lsb_mask ); + readValue += ( ( readArray[0] & msb_mask ) << lsb_used ); + return readValue; +} diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/MagneticSensorI2C.h b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/MagneticSensorI2C.h new file mode 100644 index 00000000..c5dc3489 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/MagneticSensorI2C.h @@ -0,0 +1,78 @@ +#ifndef MAGNETICSENSORI2C_LIB_H +#define MAGNETICSENSORI2C_LIB_H + +#include "Arduino.h" +#include +#include "FOCutils.h" +#include "Sensor.h" + + +class MagneticSensorI2C: public Sensor{ + public: + /** + * MagneticSensorI2C class constructor + * @param chip_address I2C chip address + * @param bits number of bits of the sensor resolution + * @param angle_register_msb angle read register msb + * @param _bits_used_msb number of used bits in msb + */ + MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _msb_bits_used); + + + /** sensor initialise pins */ + void init(); + + // implementation of abstract functions of the Sensor class + /** get current angle (rad) */ + float getAngle(); + /** get current angular velocity (rad/s) **/ + float getVelocity(); + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + float initRelativeZero(); + /** + * set absolute zero angle as zero angle + * return the angle [rad] difference + */ + float initAbsoluteZero(); + /** returns 1 because it is the absolute sensor */ + int hasAbsoluteZero(); + /** returns 0 maning it doesn't need search for absolute zero */ + int needsAbsoluteZeroSearch(); + + + private: + float cpr; //!< Maximum range of the magnetic sensor + uint16_t lsb_used; //!< Number of bits used in LSB register + uint8_t lsb_mask; + uint8_t msb_mask; + + // I2C variables + uint8_t angle_register_msb; //!< I2C angle register to read + uint8_t chip_address; //!< I2C chip select pins + + // I2C functions + /** Read one I2C register value */ + int read(uint8_t angle_register_msb); + + word zero_offset; //!< user defined zero offset + /** + * Function getting current angle register value + * it uses angle_register variable + */ + int getRawCount(); + + // total angle tracking variables + float full_rotation_offset; //! torque/voltage : target 2V."); + + _delay(1000); +} + + +void loop() { + // iterative setting FOC phase voltage + motor.loopFOC(); + + // iterative function setting the outter loop target + // velocity, position or voltage + // if tatget not set in parameter uses motor.target variable + motor.move(); + + // user communication + motor.command(serialReceiveUserCommand()); +} + +// utility function enabling serial communication the user +String serialReceiveUserCommand() { + + // a string to hold incoming data + static String received_chars; + + String command = ""; + + while (Serial.available()) { + // get the new byte: + char inChar = (char)Serial.read(); + // add it to the string buffer: + received_chars += inChar; + + // end of user input + if (inChar == '\n') { + + // execute the user command + command = received_chars; + + // reset the command buffer + received_chars = ""; + } + } + return command; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/defaults.h b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/defaults.h new file mode 100644 index 00000000..bbb48c6e --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/defaults.h @@ -0,0 +1,18 @@ +// default configuration values +// change this file to optimal values for your application + +#define DEF_POWER_SUPPLY 12.0 //!< default power supply voltage +// velocity PI controller params +#define DEF_PID_VEL_P 0.5 //!< default PID controller P value +#define DEF_PID_VEL_I 10 //!< default PID controller I value +#define DEF_PID_VEL_D 0 //!< default PID controller D value +#define DEF_PID_VEL_U_RAMP 1000 //!< default PID controller voltage ramp value +// angle P params +#define DEF_P_ANGLE_P 20 //!< default P controller P value +#define DEF_VEL_LIM 20 //!< angle velocity limit default +// index search +#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 //!< default index search velocity +// align voltage +#define DEF_VOLTAGE_SENSOR_ALIGN 6.0 //!< default voltage for sensor and motor zero alignemt +// low pass filter velocity +#define DEF_VEL_FILTER_Tf 0.005 //!< default velocity filter time constant \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/BLDCMotor.cpp new file mode 100644 index 00000000..f31e818a --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/BLDCMotor.cpp @@ -0,0 +1,716 @@ +#include "BLDCMotor.h" + +// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - phA, phB, phC - motor A,B,C phase pwm pins +// - pp - pole pair number +// - cpr - counts per rotation number (cpm=ppm*4) +// - enable pin - (optional input) +BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +{ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + pole_pairs = pp; + + // enable_pin pin + enable_pin = en; + + // Power supply voltage + voltage_power_supply = DEF_POWER_SUPPLY; + + // Velocity loop config + // PI controller constant + PID_velocity.P = DEF_PID_VEL_P; + PID_velocity.I = DEF_PID_VEL_I; + PID_velocity.D = DEF_PID_VEL_D; + PID_velocity.output_ramp = DEF_PID_VEL_U_RAMP; + PID_velocity.timestamp = _micros(); + PID_velocity.integral_prev = 0; + PID_velocity.output_prev = 0; + PID_velocity.tracking_error_prev = 0; + + // velocity low pass filter + LPF_velocity.Tf = DEF_VEL_FILTER_Tf; + LPF_velocity.timestamp = _micros(); + LPF_velocity.prev = 0; + + // position loop config + // P controller constant + P_angle.P = DEF_P_ANGLE_P; + + // maximum angular velocity to be used for positioning + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = voltage_power_supply; + + // index search velocity + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; + + // electric angle of the zero angle + zero_electric_angle = 0; + + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + + // default target value + target = 0; + + //monitor_port + monitor_port = nullptr; + //sensor + sensor = nullptr; +} + +// init hardware pins +void BLDCMotor::init() { + if(monitor_port) monitor_port->println("MOT: Init pins."); + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(hasEnable()) pinMode(enable_pin, OUTPUT); + + if(monitor_port) monitor_port->println("MOT: PWM config."); + // Increase PWM frequency to 32 kHz + // make silent + _setPwmFrequency(pwmA, pwmB, pwmC); + + // sanity check for the voltage limit configuration + if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + + _delay(500); + // enable motor + if(monitor_port) monitor_port->println("MOT: Enable."); + enable(); + _delay(500); + +} + + +// disable motor driver +void BLDCMotor::disable() +{ + // disable the driver - if enable_pin pin available + if (hasEnable()) digitalWrite(enable_pin, LOW); + // set zero to PWM + setPwm(0, 0, 0); +} +// enable motor driver +void BLDCMotor::enable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // enable_pin the driver - if enable_pin pin available + if (hasEnable()) digitalWrite(enable_pin, HIGH); + +} + +void BLDCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} + + +// Encoder alignment to electrical 0 angle +int BLDCMotor::alignSensor() { + if(monitor_port) monitor_port->println("MOT: Align sensor."); + // align the electrical phases of the motor and sensor + // set angle -90 degrees + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } + + // let the motor stabilize for 2 sec + _delay(2000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0,0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int BLDCMotor::absoluteZeroAlign() { + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = velocityPID(velocity_index_search - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); + + // align absolute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = normalizeAngle(electricAngle(zero_offset)); + } + // return bool if zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +/** + State calculation methods +*/ +// shaft angle calculation +float BLDCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return 0; + return sensor->getAngle(); +} +// shaft velocity calculation +float BLDCMotor::shaftVelocity() { + // if no sensor linked return 0 + if(!sensor) return 0; + return lowPassFilter(sensor->getVelocity(), LPF_velocity); +} +// Electrical angle calculation +float BLDCMotor::electricAngle(float shaftAngle) { + //return normalizeAngle(shaftAngle * pole_pairs); + return (shaftAngle * pole_pairs); +} + +/** + FOC functions +*/ +// FOC initialization function +int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } + if(monitor_port) monitor_port->println("MOT: Motor ready."); + + return exit_flag; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void BLDCMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); +} + +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function +// - if target is not set it uses motor.target value +void BLDCMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; + // get angular velocity + shaft_velocity = shaftVelocity(); + // choose control loop + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = positionP( shaft_angle_sp - shaft_angle ); + voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // include velocity loop + shaft_velocity_sp = target; + voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); + break; + } +} + + +// Method using FOC to set Uq to the motor at the optimal angle +// Function implementing Space Vector PWM and Sine PWM algorithms +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) +void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { + switch (foc_modulation) + { + case FOCModulationType::SinePWM : + // Sinusoidal PWM modulation + // Inverse Park + Clarke transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + + // Clarke transform + Ua = Ualpha + voltage_power_supply/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + break; + + case FOCModulationType::SpaceVectorPWM : + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // https://www.youtube.com/watch?v=QMSWUMEAejg + + // if negative voltages change inverse the phase + // angle + 180degrees + if(Uq < 0) angle_el += _PI; + Uq = abs(Uq); + + // angle normalisation in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = normalizeAngle(angle_el + zero_electric_angle + _PI_2); + + // find the sector we are in currently + int sector = floor(angle_el / _PI_3) + 1; + // calculate the duty cycles + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; + // two versions possible + // centered around voltage_power_supply/2 + float T0 = 1 - T1 - T2; + // pulled to 0 - better for low power supply voltage + //float T0 = 0; + + // calculate the duty cycles(times) + float Ta,Tb,Tc; + switch(sector){ + case 1: + Ta = T1 + T2 + T0/2; + Tb = T2 + T0/2; + Tc = T0/2; + break; + case 2: + Ta = T1 + T0/2; + Tb = T1 + T2 + T0/2; + Tc = T0/2; + break; + case 3: + Ta = T0/2; + Tb = T1 + T2 + T0/2; + Tc = T2 + T0/2; + break; + case 4: + Ta = T0/2; + Tb = T1+ T0/2; + Tc = T1 + T2 + T0/2; + break; + case 5: + Ta = T2 + T0/2; + Tb = T0/2; + Tc = T1 + T2 + T0/2; + break; + case 6: + Ta = T1 + T2 + T0/2; + Tb = T0/2; + Tc = T1 + T0/2; + break; + default: + // possible error state + Ta = 0; + Tb = 0; + Tc = 0; + } + + // calculate the phase voltages and center + Ua = Ta*voltage_power_supply; + Ub = Tb*voltage_power_supply; + Uc = Tc*voltage_power_supply; + break; + } + + // set the voltages in hardware + setPwm(Ua, Ub, Uc); +} + + + +// Set voltage to the pwm pin +void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { + // calculate duty cycle + // limited in [0,1] + float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); + // hardware specific writing + _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); +} + +/** + Utility functions +*/ +// normalizing radian angle to [0,2PI] +float BLDCMotor::normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} +// determining if the enable pin has been provided +int BLDCMotor::hasEnable(){ + return enable_pin != NOT_SET; +} + +// low pass filter function +// - input -singal to be filtered +// - lpf -LPF_s structure with filter parameters +float BLDCMotor::lowPassFilter(float input, LPF_s& lpf){ + unsigned long now_us = _micros(); + float Ts = (now_us - lpf.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // calculate the filtering + float alpha = lpf.Tf/(lpf.Tf + Ts); + float out = alpha*lpf.prev + (1-alpha)*input; + + // save the variables + lpf.prev = out; + lpf.timestamp = now_us; + return out; +} + + +/** + Motor control functions +*/ +// PID controller function +float BLDCMotor::controllerPID(float tracking_error, PID_s& cont){ + // calculate the time from the last call + unsigned long now_us = _micros(); + float Ts = (now_us - cont.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = cont.P * tracking_error; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = cont.integral_prev + cont.I*Ts*0.5*(tracking_error + cont.tracking_error_prev); + // antiwindup - limit the output voltage_q + integral = constrain(integral, -voltage_limit, voltage_limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = cont.D*(tracking_error - cont.tracking_error_prev)/Ts; + // sum all the components + float voltage = proportional + integral + derivative; + + // antiwindup - limit the output voltage_q + voltage = constrain(voltage, -voltage_limit, voltage_limit); + + // limit the acceleration by ramping the the voltage + float d_voltage = voltage - cont.output_prev; + if (abs(d_voltage)/Ts > cont.output_ramp) voltage = d_voltage > 0 ? cont.output_prev + cont.output_ramp*Ts : cont.output_prev - cont.output_ramp*Ts; + + // saving for the next pass + cont.integral_prev = integral; + cont.output_prev = voltage; + cont.tracking_error_prev = tracking_error; + cont.timestamp = now_us; + return voltage; +} +// velocity control loop PI controller +float BLDCMotor::velocityPID(float tracking_error) { + return controllerPID(tracking_error, PID_velocity); +} + +// P controller for position control loop +float BLDCMotor::positionP(float ek) { + // calculate the target velocity from the position error + float velocity_target = P_angle.P * ek; + // constrain velocity target value + velocity_target = constrain(velocity_target, -velocity_limit, velocity_limit); + return velocity_target; +} + +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void BLDCMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void BLDCMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void BLDCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void BLDCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity_openloop: + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle_openloop: + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int BLDCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'D': // velocity D gain change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PID velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P angle| "); + break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + + } + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("P: "); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("I: "); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); + break; + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("volt_ramp: "); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET)voltage_limit = value; + if(monitor_port) monitor_port->println(voltage_limit); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("Tf: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("vel_limit: "); + if(!GET) velocity_limit = value; + if(monitor_port) monitor_port->println(velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Control: "); + + if(GET){ // if get command + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + default: + if(monitor_port) monitor_port->println("open loop"); + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/BLDCMotor.h b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/BLDCMotor.h new file mode 100644 index 00000000..95ca9472 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/BLDCMotor.h @@ -0,0 +1,323 @@ +/** + * @file BLDCMotor.h + * + */ + +#ifndef BLDCMotor_h +#define BLDCMotor_h + +#include "Arduino.h" +#include "FOCutils.h" +#include "Sensor.h" +#include "defaults.h" + + +#define NOT_SET -12345.0 + +/** + * Motiron control type + */ +enum ControlType{ + voltage,//!< Torque control using voltage + velocity,//!< Velocity motion control + angle,//!< Position/angle motion control + velocity_openloop, + angle_openloop +}; + +/** + * FOC modulation type + */ +enum FOCModulationType{ + SinePWM, //!< Sinusoidal PWM modulation + SpaceVectorPWM //!< Space vector modulation method +}; + +/** + * PID controller structure + */ +struct PID_s{ + float P; //!< Proportional gain + float I; //!< Integral gain + float D; //!< Derivative gain + long timestamp; //!< Last execution timestamp + float integral_prev; //!< last integral component value + float output_prev; //!< last pid output value + float output_ramp; //!< Maximum speed of change of the output value + float tracking_error_prev; //!< last tracking error value +}; + +// P controller structure +struct P_s{ + float P; //!< Proportional gain + long timestamp; //!< Last execution timestamp +}; + +/** + * Low pass filter structure + */ +struct LPF_s{ + float Tf; //!< Low pass filter time constant + long timestamp; //!< Last execution timestamp + float prev; //!< filtered value in previous execution step +}; + + + + +/** + BLDC motor class +*/ +class BLDCMotor +{ + public: + /** + BLDCMotor class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param pp pole pair number + @param cpr counts per rotation number (cpm=ppm*4) + @param en enable pin (optional input) + */ + BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + + /** Motor hardware init function */ + void init(); + /** Motor disable function */ + void disable(); + /** Motor enable function */ + void enable(); + + /** + * Function linking a motor and a sensor + * + * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity + */ + void linkSensor(Sensor* sensor); + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + void loopFOC(); + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET); + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + + + + // State calculation methods + /** Shaft angle calculation in radians [rad] */ + float shaftAngle(); + /** + * Shaft angle calculation function in radian per second [rad/s] + * It implements low pass filtering + */ + float shaftVelocity(); + + // state variables + float target; //!< current target value - depends of the controller + float shaft_angle;//!< current motor angle + float shaft_velocity;//!< current motor velocity + float shaft_velocity_sp;//!< current target velocity + float shaft_angle_sp;//!< current target angle + float voltage_q;//!< current voltage u_q set + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + + // motor configuration parameters + float voltage_power_supply;//!< Power supply voltage + float voltage_sensor_align;//!< sensor and motor align voltage parameter + float velocity_index_search;//!< target velocity for index search + int pole_pairs;//!< Motor pole pairs number + + // limiting variables + float voltage_limit; //!< Voltage limitting variable - global limit + float velocity_limit; //!< Velocity limitting variable - global limit + + // configuration structures + ControlType controller; //!< parameter determining the control loop to be used + FOCModulationType foc_modulation;//!< parameter derterniming modulation algorithm + PID_s PID_velocity;//!< parameter determining the velocity PI configuration + P_s P_angle; //!< parameter determining the position P configuration + LPF_s LPF_velocity;//!< parameter determining the velocity Lpw pass filter configuration + + /** + * Sensor link: + * - Encoder + * - MagneticSensor + */ + Sensor* sensor; + + float zero_electric_angle;//!clk_cfg.prescale = 0; + + m_slot.mcpwm_num->timer[0].period.prescale = 4; + m_slot.mcpwm_num->timer[1].period.prescale = 4; + m_slot.mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + m_slot.mcpwm_num->timer[0].period.period = 2048; + m_slot.mcpwm_num->timer[1].period.period = 2048; + m_slot.mcpwm_num->timer[2].period.period = 2048; + _delay(1); + m_slot.mcpwm_num->timer[0].period.upmethod = 0; + m_slot.mcpwm_num->timer[1].period.upmethod = 0; + m_slot.mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + m_slot.mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + m_slot.mcpwm_num->timer[0].sync.out_sel = 0; +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + break; + } + } +#else // Arduino & STM32 devices + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255*dc_a); + analogWrite(pinB, 255*dc_b); + analogWrite(pinC, 255*dc_c); +#endif +} + + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} + + +// int array instead of float array +// 2x storage save (int 2Byte float 4 Byte ) +// sin*10000 +int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,1103,1181,1260,1338,1416,1494,1572,1650,1728,1806,1883,1961,2038,2115,2192,2269,2346,2423,2499,2575,2652,2728,2804,2879,2955,3030,3105,3180,3255,3329,3404,3478,3552,3625,3699,3772,3845,3918,3990,4063,4135,4206,4278,4349,4420,4491,4561,4631,4701,4770,4840,4909,4977,5046,5113,5181,5249,5316,5382,5449,5515,5580,5646,5711,5775,5839,5903,5967,6030,6093,6155,6217,6279,6340,6401,6461,6521,6581,6640,6699,6758,6815,6873,6930,6987,7043,7099,7154,7209,7264,7318,7371,7424,7477,7529,7581,7632,7683,7733,7783,7832,7881,7930,7977,8025,8072,8118,8164,8209,8254,8298,8342,8385,8428,8470,8512,8553,8594,8634,8673,8712,8751,8789,8826,8863,8899,8935,8970,9005,9039,9072,9105,9138,9169,9201,9231,9261,9291,9320,9348,9376,9403,9429,9455,9481,9506,9530,9554,9577,9599,9621,9642,9663,9683,9702,9721,9739,9757,9774,9790,9806,9821,9836,9850,9863,9876,9888,9899,9910,9920,9930,9939,9947,9955,9962,9969,9975,9980,9985,9989,9992,9995,9997,9999,10000,10000}; + +// function approximating the sine calculation by using fixed size array +// ~40us (float array) +// ~50us (int array) +// precision +-0.005 +// it has to receive an angle in between 0 and 2PI +float _sin(float a){ + if(a < _PI_2){ + //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; + //return sine_array[(int)(126.6873* a)]; // float array optimized + return 0.0001*sine_array[_round(126.6873* a)]; // int array optimized + }else if(a < _PI){ + // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; + //return sine_array[398 - (int)(126.6873*a)]; // float array optimized + return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimized + }else if(a < _3PI_2){ + // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; + //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimized + return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimized + } else { + // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; + //return -sine_array[796 - (int)(126.6873*a)]; // float array optimized + return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimized + } +} + +// function approximating cosine calculation by using fixed size array +// ~55us (float array) +// ~56us (int array) +// precision +-0.005 +// it has to receive an angle in between 0 and 2PI +float _cos(float a){ + float a_sin = a + _PI_2; + a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/FOCutils.h b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/FOCutils.h new file mode 100644 index 00000000..4c347a12 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/FOCutils.h @@ -0,0 +1,86 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + + +#if defined(ESP_H) // if esp32 boards + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +#endif + +// sign function +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + +// utility defines +#define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI 3.14159265359 +#define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + +/** + * High PWM frequency setting function + * - hardware specific + * + * @param pinA pinA number to configure + * @param pinB pinB number to configure + * @param pinC pinC number to configure + */ +void _setPwmFrequency(int pinA, int pinB, int pinC); + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); + + +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _sin(float a); +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _cos(float a); + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorSPI.cpp b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorSPI.cpp new file mode 100644 index 00000000..79430b13 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorSPI.cpp @@ -0,0 +1,209 @@ +#include "MagneticSensorSPI.h" + +// MagneticSensorSPI(int cs, float _bit_resolution, int _angle_register) +// cs - SPI chip select pin +// _bit_resolution sensor resolution bit number +// _angle_register - (optional) angle read register - default 0x3FFF +MagneticSensorSPI::MagneticSensorSPI(int cs, float _bit_resolution, int _angle_register){ + // chip select pin + chip_select_pin = cs; + // angle read register of the magnetic sensor + angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTAR; + // register maximum value (counts per revolution) + cpr = pow(2,_bit_resolution); + +} + + +void MagneticSensorSPI::init(){ + // 1MHz clock (AMS should be able to accept up to 10MHz) + settings = SPISettings(1000000, MSBFIRST, SPI_MODE1); + + //setup pins + pinMode(chip_select_pin, OUTPUT); + + + //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices + SPI.begin(); +#ifndef ESP_H // if not ESP32 board + SPI.setBitOrder(MSBFIRST); // Set the SPI_1 bit order + SPI.setDataMode(SPI_MODE1) ; + SPI.setClockDivider(SPI_CLOCK_DIV8); +#endif + + digitalWrite(chip_select_pin, HIGH); + // velocity calculation init + angle_prev = 0; + velocity_calc_timestamp = _micros(); + + // full rotations tracking number + full_rotation_offset = 0; + angle_data_prev = getRawCount(); + zero_offset = 0; +} + +// Shaft angle calculation +// angle is in radians [rad] +float MagneticSensorSPI::getAngle(){ + // raw data from the sensor + float angle_data = getRawCount(); + + // tracking the number of rotations + // in order to expand angle range form [0,2PI] + // to basically infinity + float d_angle = angle_data - angle_data_prev; + // if overflow happened track it as full rotation + if(abs(d_angle) > (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; + // save the current angle value for the next steps + // in order to know if overflow happened + angle_data_prev = angle_data; + + // zero offset adding + angle_data -= (int)zero_offset; + // return the full angle + // (number of full rotations)*2PI + current sensor angle + return natural_direction * (full_rotation_offset + ( angle_data / (float)cpr) * _2PI); +} + +// Shaft velocity calculation +float MagneticSensorSPI::getVelocity(){ + // calculate sample time + unsigned long now_us = _micros(); + float Ts = (now_us - velocity_calc_timestamp)*1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // current angle + float angle_c = getAngle(); + // velocity calculation + float vel = (angle_c - angle_prev)/Ts; + + // save variables for future pass + angle_prev = angle_c; + velocity_calc_timestamp = now_us; + return vel; +} + +// set current angle as zero angle +// return the angle [rad] difference +float MagneticSensorSPI::initRelativeZero(){ + float angle_offset = -getAngle(); + zero_offset = natural_direction * getRawCount(); + + // angle tracking variables + full_rotation_offset = 0; + return angle_offset; +} +// set absolute zero angle as zero angle +// return the angle [rad] difference +float MagneticSensorSPI::initAbsoluteZero(){ + float rotation = -(int)zero_offset; + // init absolute zero + zero_offset = 0; + + // angle tracking variables + full_rotation_offset = 0; + // return offset in radians + return rotation / (float)cpr * _2PI; +} +// returns 0 if it has no absolute 0 measurement +// 0 - incremental encoder without index +// 1 - encoder with index & magnetic sensors +int MagneticSensorSPI::hasAbsoluteZero(){ + return 1; +} +// returns 0 if it does need search for absolute zero +// 0 - magnetic sensor +// 1 - ecoder with index +int MagneticSensorSPI::needsAbsoluteZeroSearch(){ + return 0; +} + + +// function reading the raw counter of the magnetic sensor +int MagneticSensorSPI::getRawCount(){ + return (int)MagneticSensorSPI::read(angle_register); +} + +// SPI functions +/** + * Utility function used to calculate even parity of word + */ +byte MagneticSensorSPI::spiCalcEvenParity(word value){ + byte cnt = 0; + byte i; + + for (i = 0; i < 16; i++) + { + if (value & 0x1) cnt++; + value >>= 1; + } + return cnt & 0x1; +} + + /* + * Read a register from the sensor + * Takes the address of the register as a 16 bit word + * Returns the value of the register + */ +word MagneticSensorSPI::read(word angle_register){ + word command = 0b0100000000000000; // PAR=0 R/W=R + command = command | angle_register; + + //Add a parity bit on the the MSB + command |= ((word)spiCalcEvenParity(command)<<15); + + //Split the command into two bytes + byte right_byte = command & 0xFF; + byte left_byte = ( command >> 8 ) & 0xFF; + + +#if !defined(_STM32_DEF_) // if not stm chips + //SPI - begin transaction + SPI.beginTransaction(settings); +#endif + //SPI - begin transaction + //SPI.beginTransaction(settings); + + //Send the command + digitalWrite(chip_select_pin, LOW); +#ifndef ESP_H // if not ESP32 board + digitalWrite(chip_select_pin, LOW); +#endif + SPI.transfer(left_byte); + SPI.transfer(right_byte); + digitalWrite(chip_select_pin,HIGH); +#ifndef ESP_H // if not ESP32 board + digitalWrite(chip_select_pin,HIGH); +#endif + +#if defined( ESP_H ) // if ESP32 board + delayMicroseconds(50); +#else + delayMicroseconds(10); +#endif + + //Now read the response + digitalWrite(chip_select_pin, LOW); + digitalWrite(chip_select_pin, LOW); + left_byte = SPI.transfer(0x00); + right_byte = SPI.transfer(0x00); + digitalWrite(chip_select_pin, HIGH); + digitalWrite(chip_select_pin,HIGH); + +#if !defined(_STM32_DEF_) // if not stm chips + //SPI - end transaction + SPI.endTransaction(); +#endif + + // Return the data, stripping the parity and error bits + return (( ( left_byte & 0xFF ) << 8 ) | ( right_byte & 0xFF )) & ~0xC000; +} + +/** + * Closes the SPI connection + * SPI has an internal SPI-device counter, for each init()-call the close() function must be called exactly 1 time + */ +void MagneticSensorSPI::close(){ + SPI.end(); +} diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorSPI.h b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorSPI.h new file mode 100644 index 00000000..da70c0c4 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorSPI.h @@ -0,0 +1,79 @@ +#ifndef MAGNETICSENSORSPI_LIB_H +#define MAGNETICSENSORSPI_LIB_H + +#include "Arduino.h" +#include +#include "FOCutils.h" +#include "Sensor.h" + +#define DEF_ANGLE_REGISTAR 0x3FFF + +class MagneticSensorSPI: public Sensor{ + public: + /** + * MagneticSensorSPI class constructor + * @param cs SPI chip select pin + * @param bit_resolution sensor resolution bit number + * @param angle_register (optional) angle read register - default 0x3FFF + */ + MagneticSensorSPI(int cs, float bit_resolution, int angle_register = 0); + + + /** sensor initialise pins */ + void init(); + + // implementation of abstract functions of the Sensor class + /** get current angle (rad) */ + float getAngle(); + /** get current angular velocity (rad/s) **/ + float getVelocity(); + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + float initRelativeZero(); + /** + * set absolute zero angle as zero angle + * return the angle [rad] difference + */ + float initAbsoluteZero(); + /** returns 1 because it is the absolute sensor */ + int hasAbsoluteZero(); + /** returns 0 maning it doesn't need search for absolute zero */ + int needsAbsoluteZeroSearch(); + + + private: + float cpr; //!< Maximum range of the magnetic sensor + // spi variables + int angle_register; //!< SPI angle register to read + int chip_select_pin; //!< SPI chip select pin + SPISettings settings; //!< SPI settings variable + // spi functions + /** Stop SPI communication */ + void close(); + /** Read one SPI register value */ + word read(word angle_register); + /** Calculate parity value */ + byte spiCalcEvenParity(word value); + + + word zero_offset; //!< user defined zero offset + /** + * Function getting current angle register value + * it uses angle_register variable + */ + int getRawCount(); + + // total angle tracking variables + float full_rotation_offset; //! torque/voltage : target 2V."); _delay(1000); - } -// target velocity variable -float target = 0; -// loop stats variables -unsigned long t = 0; -long timestamp = _micros(); void loop() { // iterative setting FOC phase voltage @@ -146,7 +106,7 @@ void loop() { // velocity, position or voltage // if tatget not set in parameter uses motor.target variable motor.move(); - + // user communication motor.command(serialReceiveUserCommand()); } @@ -176,4 +136,4 @@ String serialReceiveUserCommand() { } } return command; -} +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/defaults.h b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/defaults.h new file mode 100644 index 00000000..bbb48c6e --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/defaults.h @@ -0,0 +1,18 @@ +// default configuration values +// change this file to optimal values for your application + +#define DEF_POWER_SUPPLY 12.0 //!< default power supply voltage +// velocity PI controller params +#define DEF_PID_VEL_P 0.5 //!< default PID controller P value +#define DEF_PID_VEL_I 10 //!< default PID controller I value +#define DEF_PID_VEL_D 0 //!< default PID controller D value +#define DEF_PID_VEL_U_RAMP 1000 //!< default PID controller voltage ramp value +// angle P params +#define DEF_P_ANGLE_P 20 //!< default P controller P value +#define DEF_VEL_LIM 20 //!< angle velocity limit default +// index search +#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 //!< default index search velocity +// align voltage +#define DEF_VOLTAGE_SENSOR_ALIGN 6.0 //!< default voltage for sensor and motor zero alignemt +// low pass filter velocity +#define DEF_VEL_FILTER_Tf 0.005 //!< default velocity filter time constant \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.cpp new file mode 100644 index 00000000..f31e818a --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.cpp @@ -0,0 +1,716 @@ +#include "BLDCMotor.h" + +// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - phA, phB, phC - motor A,B,C phase pwm pins +// - pp - pole pair number +// - cpr - counts per rotation number (cpm=ppm*4) +// - enable pin - (optional input) +BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +{ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + pole_pairs = pp; + + // enable_pin pin + enable_pin = en; + + // Power supply voltage + voltage_power_supply = DEF_POWER_SUPPLY; + + // Velocity loop config + // PI controller constant + PID_velocity.P = DEF_PID_VEL_P; + PID_velocity.I = DEF_PID_VEL_I; + PID_velocity.D = DEF_PID_VEL_D; + PID_velocity.output_ramp = DEF_PID_VEL_U_RAMP; + PID_velocity.timestamp = _micros(); + PID_velocity.integral_prev = 0; + PID_velocity.output_prev = 0; + PID_velocity.tracking_error_prev = 0; + + // velocity low pass filter + LPF_velocity.Tf = DEF_VEL_FILTER_Tf; + LPF_velocity.timestamp = _micros(); + LPF_velocity.prev = 0; + + // position loop config + // P controller constant + P_angle.P = DEF_P_ANGLE_P; + + // maximum angular velocity to be used for positioning + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = voltage_power_supply; + + // index search velocity + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; + + // electric angle of the zero angle + zero_electric_angle = 0; + + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + + // default target value + target = 0; + + //monitor_port + monitor_port = nullptr; + //sensor + sensor = nullptr; +} + +// init hardware pins +void BLDCMotor::init() { + if(monitor_port) monitor_port->println("MOT: Init pins."); + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(hasEnable()) pinMode(enable_pin, OUTPUT); + + if(monitor_port) monitor_port->println("MOT: PWM config."); + // Increase PWM frequency to 32 kHz + // make silent + _setPwmFrequency(pwmA, pwmB, pwmC); + + // sanity check for the voltage limit configuration + if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + + _delay(500); + // enable motor + if(monitor_port) monitor_port->println("MOT: Enable."); + enable(); + _delay(500); + +} + + +// disable motor driver +void BLDCMotor::disable() +{ + // disable the driver - if enable_pin pin available + if (hasEnable()) digitalWrite(enable_pin, LOW); + // set zero to PWM + setPwm(0, 0, 0); +} +// enable motor driver +void BLDCMotor::enable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // enable_pin the driver - if enable_pin pin available + if (hasEnable()) digitalWrite(enable_pin, HIGH); + +} + +void BLDCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} + + +// Encoder alignment to electrical 0 angle +int BLDCMotor::alignSensor() { + if(monitor_port) monitor_port->println("MOT: Align sensor."); + // align the electrical phases of the motor and sensor + // set angle -90 degrees + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } + + // let the motor stabilize for 2 sec + _delay(2000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0,0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int BLDCMotor::absoluteZeroAlign() { + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = velocityPID(velocity_index_search - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); + + // align absolute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = normalizeAngle(electricAngle(zero_offset)); + } + // return bool if zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +/** + State calculation methods +*/ +// shaft angle calculation +float BLDCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return 0; + return sensor->getAngle(); +} +// shaft velocity calculation +float BLDCMotor::shaftVelocity() { + // if no sensor linked return 0 + if(!sensor) return 0; + return lowPassFilter(sensor->getVelocity(), LPF_velocity); +} +// Electrical angle calculation +float BLDCMotor::electricAngle(float shaftAngle) { + //return normalizeAngle(shaftAngle * pole_pairs); + return (shaftAngle * pole_pairs); +} + +/** + FOC functions +*/ +// FOC initialization function +int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } + if(monitor_port) monitor_port->println("MOT: Motor ready."); + + return exit_flag; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void BLDCMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); +} + +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function +// - if target is not set it uses motor.target value +void BLDCMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; + // get angular velocity + shaft_velocity = shaftVelocity(); + // choose control loop + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = positionP( shaft_angle_sp - shaft_angle ); + voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // include velocity loop + shaft_velocity_sp = target; + voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); + break; + } +} + + +// Method using FOC to set Uq to the motor at the optimal angle +// Function implementing Space Vector PWM and Sine PWM algorithms +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) +void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { + switch (foc_modulation) + { + case FOCModulationType::SinePWM : + // Sinusoidal PWM modulation + // Inverse Park + Clarke transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + + // Clarke transform + Ua = Ualpha + voltage_power_supply/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + break; + + case FOCModulationType::SpaceVectorPWM : + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // https://www.youtube.com/watch?v=QMSWUMEAejg + + // if negative voltages change inverse the phase + // angle + 180degrees + if(Uq < 0) angle_el += _PI; + Uq = abs(Uq); + + // angle normalisation in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = normalizeAngle(angle_el + zero_electric_angle + _PI_2); + + // find the sector we are in currently + int sector = floor(angle_el / _PI_3) + 1; + // calculate the duty cycles + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; + // two versions possible + // centered around voltage_power_supply/2 + float T0 = 1 - T1 - T2; + // pulled to 0 - better for low power supply voltage + //float T0 = 0; + + // calculate the duty cycles(times) + float Ta,Tb,Tc; + switch(sector){ + case 1: + Ta = T1 + T2 + T0/2; + Tb = T2 + T0/2; + Tc = T0/2; + break; + case 2: + Ta = T1 + T0/2; + Tb = T1 + T2 + T0/2; + Tc = T0/2; + break; + case 3: + Ta = T0/2; + Tb = T1 + T2 + T0/2; + Tc = T2 + T0/2; + break; + case 4: + Ta = T0/2; + Tb = T1+ T0/2; + Tc = T1 + T2 + T0/2; + break; + case 5: + Ta = T2 + T0/2; + Tb = T0/2; + Tc = T1 + T2 + T0/2; + break; + case 6: + Ta = T1 + T2 + T0/2; + Tb = T0/2; + Tc = T1 + T0/2; + break; + default: + // possible error state + Ta = 0; + Tb = 0; + Tc = 0; + } + + // calculate the phase voltages and center + Ua = Ta*voltage_power_supply; + Ub = Tb*voltage_power_supply; + Uc = Tc*voltage_power_supply; + break; + } + + // set the voltages in hardware + setPwm(Ua, Ub, Uc); +} + + + +// Set voltage to the pwm pin +void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { + // calculate duty cycle + // limited in [0,1] + float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); + // hardware specific writing + _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); +} + +/** + Utility functions +*/ +// normalizing radian angle to [0,2PI] +float BLDCMotor::normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} +// determining if the enable pin has been provided +int BLDCMotor::hasEnable(){ + return enable_pin != NOT_SET; +} + +// low pass filter function +// - input -singal to be filtered +// - lpf -LPF_s structure with filter parameters +float BLDCMotor::lowPassFilter(float input, LPF_s& lpf){ + unsigned long now_us = _micros(); + float Ts = (now_us - lpf.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // calculate the filtering + float alpha = lpf.Tf/(lpf.Tf + Ts); + float out = alpha*lpf.prev + (1-alpha)*input; + + // save the variables + lpf.prev = out; + lpf.timestamp = now_us; + return out; +} + + +/** + Motor control functions +*/ +// PID controller function +float BLDCMotor::controllerPID(float tracking_error, PID_s& cont){ + // calculate the time from the last call + unsigned long now_us = _micros(); + float Ts = (now_us - cont.timestamp) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = cont.P * tracking_error; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = cont.integral_prev + cont.I*Ts*0.5*(tracking_error + cont.tracking_error_prev); + // antiwindup - limit the output voltage_q + integral = constrain(integral, -voltage_limit, voltage_limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = cont.D*(tracking_error - cont.tracking_error_prev)/Ts; + // sum all the components + float voltage = proportional + integral + derivative; + + // antiwindup - limit the output voltage_q + voltage = constrain(voltage, -voltage_limit, voltage_limit); + + // limit the acceleration by ramping the the voltage + float d_voltage = voltage - cont.output_prev; + if (abs(d_voltage)/Ts > cont.output_ramp) voltage = d_voltage > 0 ? cont.output_prev + cont.output_ramp*Ts : cont.output_prev - cont.output_ramp*Ts; + + // saving for the next pass + cont.integral_prev = integral; + cont.output_prev = voltage; + cont.tracking_error_prev = tracking_error; + cont.timestamp = now_us; + return voltage; +} +// velocity control loop PI controller +float BLDCMotor::velocityPID(float tracking_error) { + return controllerPID(tracking_error, PID_velocity); +} + +// P controller for position control loop +float BLDCMotor::positionP(float ek) { + // calculate the target velocity from the position error + float velocity_target = P_angle.P * ek; + // constrain velocity target value + velocity_target = constrain(velocity_target, -velocity_limit, velocity_limit); + return velocity_target; +} + +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void BLDCMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void BLDCMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void BLDCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void BLDCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity_openloop: + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle_openloop: + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int BLDCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'D': // velocity D gain change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PID velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P angle| "); + break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + + } + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("P: "); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("I: "); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); + break; + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("volt_ramp: "); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET)voltage_limit = value; + if(monitor_port) monitor_port->println(voltage_limit); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("Tf: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("vel_limit: "); + if(!GET) velocity_limit = value; + if(monitor_port) monitor_port->println(velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Control: "); + + if(GET){ // if get command + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + default: + if(monitor_port) monitor_port->println("open loop"); + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.h b/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.h new file mode 100644 index 00000000..95ca9472 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.h @@ -0,0 +1,323 @@ +/** + * @file BLDCMotor.h + * + */ + +#ifndef BLDCMotor_h +#define BLDCMotor_h + +#include "Arduino.h" +#include "FOCutils.h" +#include "Sensor.h" +#include "defaults.h" + + +#define NOT_SET -12345.0 + +/** + * Motiron control type + */ +enum ControlType{ + voltage,//!< Torque control using voltage + velocity,//!< Velocity motion control + angle,//!< Position/angle motion control + velocity_openloop, + angle_openloop +}; + +/** + * FOC modulation type + */ +enum FOCModulationType{ + SinePWM, //!< Sinusoidal PWM modulation + SpaceVectorPWM //!< Space vector modulation method +}; + +/** + * PID controller structure + */ +struct PID_s{ + float P; //!< Proportional gain + float I; //!< Integral gain + float D; //!< Derivative gain + long timestamp; //!< Last execution timestamp + float integral_prev; //!< last integral component value + float output_prev; //!< last pid output value + float output_ramp; //!< Maximum speed of change of the output value + float tracking_error_prev; //!< last tracking error value +}; + +// P controller structure +struct P_s{ + float P; //!< Proportional gain + long timestamp; //!< Last execution timestamp +}; + +/** + * Low pass filter structure + */ +struct LPF_s{ + float Tf; //!< Low pass filter time constant + long timestamp; //!< Last execution timestamp + float prev; //!< filtered value in previous execution step +}; + + + + +/** + BLDC motor class +*/ +class BLDCMotor +{ + public: + /** + BLDCMotor class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param pp pole pair number + @param cpr counts per rotation number (cpm=ppm*4) + @param en enable pin (optional input) + */ + BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + + /** Motor hardware init function */ + void init(); + /** Motor disable function */ + void disable(); + /** Motor enable function */ + void enable(); + + /** + * Function linking a motor and a sensor + * + * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity + */ + void linkSensor(Sensor* sensor); + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + void loopFOC(); + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET); + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + + + + // State calculation methods + /** Shaft angle calculation in radians [rad] */ + float shaftAngle(); + /** + * Shaft angle calculation function in radian per second [rad/s] + * It implements low pass filtering + */ + float shaftVelocity(); + + // state variables + float target; //!< current target value - depends of the controller + float shaft_angle;//!< current motor angle + float shaft_velocity;//!< current motor velocity + float shaft_velocity_sp;//!< current target velocity + float shaft_angle_sp;//!< current target angle + float voltage_q;//!< current voltage u_q set + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + + // motor configuration parameters + float voltage_power_supply;//!< Power supply voltage + float voltage_sensor_align;//!< sensor and motor align voltage parameter + float velocity_index_search;//!< target velocity for index search + int pole_pairs;//!< Motor pole pairs number + + // limiting variables + float voltage_limit; //!< Voltage limitting variable - global limit + float velocity_limit; //!< Velocity limitting variable - global limit + + // configuration structures + ControlType controller; //!< parameter determining the control loop to be used + FOCModulationType foc_modulation;//!< parameter derterniming modulation algorithm + PID_s PID_velocity;//!< parameter determining the velocity PI configuration + P_s P_angle; //!< parameter determining the position P configuration + LPF_s LPF_velocity;//!< parameter determining the velocity Lpw pass filter configuration + + /** + * Sensor link: + * - Encoder + * - MagneticSensor + */ + Sensor* sensor; + + float zero_electric_angle;//!clk_cfg.prescale = 0; + + m_slot.mcpwm_num->timer[0].period.prescale = 4; + m_slot.mcpwm_num->timer[1].period.prescale = 4; + m_slot.mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + m_slot.mcpwm_num->timer[0].period.period = 2048; + m_slot.mcpwm_num->timer[1].period.period = 2048; + m_slot.mcpwm_num->timer[2].period.period = 2048; + _delay(1); + m_slot.mcpwm_num->timer[0].period.upmethod = 0; + m_slot.mcpwm_num->timer[1].period.upmethod = 0; + m_slot.mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + m_slot.mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + m_slot.mcpwm_num->timer[0].sync.out_sel = 0; +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + break; + } + } +#else // Arduino & STM32 devices + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255*dc_a); + analogWrite(pinB, 255*dc_b); + analogWrite(pinC, 255*dc_c); +#endif +} + + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} + + +// int array instead of float array +// 2x storage save (int 2Byte float 4 Byte ) +// sin*10000 +int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,1103,1181,1260,1338,1416,1494,1572,1650,1728,1806,1883,1961,2038,2115,2192,2269,2346,2423,2499,2575,2652,2728,2804,2879,2955,3030,3105,3180,3255,3329,3404,3478,3552,3625,3699,3772,3845,3918,3990,4063,4135,4206,4278,4349,4420,4491,4561,4631,4701,4770,4840,4909,4977,5046,5113,5181,5249,5316,5382,5449,5515,5580,5646,5711,5775,5839,5903,5967,6030,6093,6155,6217,6279,6340,6401,6461,6521,6581,6640,6699,6758,6815,6873,6930,6987,7043,7099,7154,7209,7264,7318,7371,7424,7477,7529,7581,7632,7683,7733,7783,7832,7881,7930,7977,8025,8072,8118,8164,8209,8254,8298,8342,8385,8428,8470,8512,8553,8594,8634,8673,8712,8751,8789,8826,8863,8899,8935,8970,9005,9039,9072,9105,9138,9169,9201,9231,9261,9291,9320,9348,9376,9403,9429,9455,9481,9506,9530,9554,9577,9599,9621,9642,9663,9683,9702,9721,9739,9757,9774,9790,9806,9821,9836,9850,9863,9876,9888,9899,9910,9920,9930,9939,9947,9955,9962,9969,9975,9980,9985,9989,9992,9995,9997,9999,10000,10000}; + +// function approximating the sine calculation by using fixed size array +// ~40us (float array) +// ~50us (int array) +// precision +-0.005 +// it has to receive an angle in between 0 and 2PI +float _sin(float a){ + if(a < _PI_2){ + //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; + //return sine_array[(int)(126.6873* a)]; // float array optimized + return 0.0001*sine_array[_round(126.6873* a)]; // int array optimized + }else if(a < _PI){ + // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; + //return sine_array[398 - (int)(126.6873*a)]; // float array optimized + return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimized + }else if(a < _3PI_2){ + // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; + //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimized + return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimized + } else { + // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; + //return -sine_array[796 - (int)(126.6873*a)]; // float array optimized + return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimized + } +} + +// function approximating cosine calculation by using fixed size array +// ~55us (float array) +// ~56us (int array) +// precision +-0.005 +// it has to receive an angle in between 0 and 2PI +float _cos(float a){ + float a_sin = a + _PI_2; + a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.h b/minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.h new file mode 100644 index 00000000..4c347a12 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.h @@ -0,0 +1,86 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + + +#if defined(ESP_H) // if esp32 boards + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +#endif + +// sign function +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + +// utility defines +#define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI 3.14159265359 +#define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + +/** + * High PWM frequency setting function + * - hardware specific + * + * @param pinA pinA number to configure + * @param pinB pinB number to configure + * @param pinC pinC number to configure + */ +void _setPwmFrequency(int pinA, int pinB, int pinC); + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); + + +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _sin(float a); +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _cos(float a); + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/Sensor.h b/minimal_project_examples/arduino_foc_minimal_openloop/Sensor.h new file mode 100644 index 00000000..7370c38f --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_openloop/Sensor.h @@ -0,0 +1,59 @@ +#ifndef SENSOR_H +#define SENSOR_H + +/** + * Direction structure + */ +enum Direction{ + CW = 1, //clockwise + CCW = -1, // counter clockwise + UNKNOWN = 0 //not yet known or invalid state +}; + +/** + * Pullup configuration structure + */ +enum Pullup{ + INTERN, //!< Use internal pullups + EXTERN //!< Use external pullups +}; + +/** + * Sensor abstract class defintion + * Each sensor needs to have these functions implemented + */ +class Sensor{ + public: + /** get current angle (rad) */ + virtual float getAngle(); + /** get current angular velocity (rad/s)*/ + virtual float getVelocity(); + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + virtual float initRelativeZero(); + /** + * set absolute zero angle as zero angle + * return the angle [rad] difference + */ + virtual float initAbsoluteZero(); + + // if natural_direction == Direction::CCW then direction will be flipped to CW + int natural_direction = Direction::CW; + + /** + * returns 0 if it has no absolute 0 measurement + * 0 - incremental encoder without index + * 1 - encoder with index & magnetic sensors + */ + virtual int hasAbsoluteZero(); + /** + * returns 0 if it does need search for absolute zero + * 0 - magnetic sensor (& encoder with index which is found) + * 1 - ecoder with index (with index not found yet) + */ + virtual int needsAbsoluteZeroSearch(); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/arduino_foc_minimal_openloop.ino b/minimal_project_examples/arduino_foc_minimal_openloop/arduino_foc_minimal_openloop.ino new file mode 100644 index 00000000..76193fbb --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_openloop/arduino_foc_minimal_openloop.ino @@ -0,0 +1,62 @@ +#include "BLDCMotor.h" + +// motor instance +BLDCMotor motor = BLDCMotor(3, 10, 6, 11, 7); + +void setup() { + + // power supply voltage + // default 12V + motor.voltage_power_supply = 12; + + // limiting motor movements + motor.voltage_limit = 3; // rad/s + motor.velocity_limit = 20; // rad/s + // open loop control config + motor.controller = ControlType::angle_openloop; + + // init motor hardware + motor.init(); + + + Serial.begin(115200); + Serial.println("Motor ready!"); + _delay(1000); +} + +float target_position = 0; // rad/s + +void loop() { + // open loop angle movements + // using motor.voltage_limit and motor.velocity_limit + motor.move(target_position); + + // receive the used commands from serial + serialReceiveUserCommand(); +} + +// utility function enabling serial communication with the user to set the target values +// this function can be implemented in serialEvent function as well +void serialReceiveUserCommand() { + + // a string to hold incoming data + static String received_chars; + + while (Serial.available()) { + // get the new byte: + char inChar = (char)Serial.read(); + // add it to the string buffer: + received_chars += inChar; + // end of user input + if (inChar == '\n') { + + // change the motor target + target_position = received_chars.toFloat(); + Serial.print("Target position: "); + Serial.println(target_position); + + // reset the command buffer + received_chars = ""; + } + } +} diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/defaults.h b/minimal_project_examples/arduino_foc_minimal_openloop/defaults.h new file mode 100644 index 00000000..bbb48c6e --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_openloop/defaults.h @@ -0,0 +1,18 @@ +// default configuration values +// change this file to optimal values for your application + +#define DEF_POWER_SUPPLY 12.0 //!< default power supply voltage +// velocity PI controller params +#define DEF_PID_VEL_P 0.5 //!< default PID controller P value +#define DEF_PID_VEL_I 10 //!< default PID controller I value +#define DEF_PID_VEL_D 0 //!< default PID controller D value +#define DEF_PID_VEL_U_RAMP 1000 //!< default PID controller voltage ramp value +// angle P params +#define DEF_P_ANGLE_P 20 //!< default P controller P value +#define DEF_VEL_LIM 20 //!< angle velocity limit default +// index search +#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 //!< default index search velocity +// align voltage +#define DEF_VOLTAGE_SENSOR_ALIGN 6.0 //!< default voltage for sensor and motor zero alignemt +// low pass filter velocity +#define DEF_VEL_FILTER_Tf 0.005 //!< default velocity filter time constant \ No newline at end of file From 376812cb94514ddf5803b5ed088c5c7daf37d76d Mon Sep 17 00:00:00 2001 From: Antun Skuric <36178713+askuric@users.noreply.github.com> Date: Wed, 9 Sep 2020 12:27:49 +0200 Subject: [PATCH 54/65] Update ccpp.yml --- .github/workflows/ccpp.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/ccpp.yml b/.github/workflows/ccpp.yml index 795e8be2..515bf90b 100644 --- a/.github/workflows/ccpp.yml +++ b/.github/workflows/ccpp.yml @@ -12,3 +12,5 @@ jobs: uses: actions/checkout@master - name: Compile all examples uses: ArminJo/arduino-test-compile@v2.1.0 + with: + libraries: PciManager From 5422dcb137c3b9ce311326695a0654a0cdfe11b3 Mon Sep 17 00:00:00 2001 From: Antun Skuric <36178713+askuric@users.noreply.github.com> Date: Wed, 9 Sep 2020 12:29:55 +0200 Subject: [PATCH 55/65] Update ccpp.yml --- .github/workflows/ccpp.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ccpp.yml b/.github/workflows/ccpp.yml index 515bf90b..0d9a5721 100644 --- a/.github/workflows/ccpp.yml +++ b/.github/workflows/ccpp.yml @@ -11,6 +11,6 @@ jobs: - name: Checkout uses: actions/checkout@master - name: Compile all examples - uses: ArminJo/arduino-test-compile@v2.1.0 + uses: ArminJo/arduino-test-compile@v1.0.0 with: libraries: PciManager From a5753973ce9fb008823e22a961b94f15dfa5f228 Mon Sep 17 00:00:00 2001 From: askuric Date: Sat, 12 Sep 2020 07:25:18 +0200 Subject: [PATCH 56/65] FIEAT Teensy suppor - Cristopher Parrot code --- library_source/FOCutils.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/library_source/FOCutils.cpp b/library_source/FOCutils.cpp index 653c7191..7c92b685 100644 --- a/library_source/FOCutils.cpp +++ b/library_source/FOCutils.cpp @@ -53,6 +53,14 @@ void _setPwmFrequency(const int pinA, const int pinB, const int pinC) { analogWrite(pinC, 0); analogWriteFrequency(50000); // set 50kHz +#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards + analogWrite(pinA, 0); + analogWriteFrequency(pinA, 50000); // set 50kHz + analogWrite(pinB, 0); + analogWriteFrequency(pinB, 50000); // set 50kHz + analogWrite(pinC, 0); + analogWriteFrequency(pinC, 50000); // set 50kHz + #elif defined(ESP_H) // if esp32 boards motor_slots_t m_slot = {}; @@ -133,7 +141,7 @@ void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, in break; } } -#else // Arduino & STM32 devices +#else // Arduino & STM32 devices & Teensy // transform duty cycle from [0,1] to [0,255] analogWrite(pinA, 255*dc_a); analogWrite(pinB, 255*dc_b); From c1c8b38322ebbd909742a069f50b44ad852fa306 Mon Sep 17 00:00:00 2001 From: askuric Date: Sun, 4 Oct 2020 02:52:47 +0200 Subject: [PATCH 57/65] library source updated with stepper motors --- library_source/BLDCMotor.cpp | 414 ++---------------- library_source/BLDCMotor.h | 226 +--------- library_source/Encoder.h | 5 +- library_source/HallSensor.h | 7 +- library_source/MagneticSensorAnalog.h | 9 +- library_source/MagneticSensorI2C.h | 5 +- library_source/MagneticSensorSPI.h | 5 +- library_source/StepperMotor.cpp | 305 +++++++++++++ library_source/StepperMotor.h | 122 ++++++ library_source/common/FOCMotor.cpp | 245 +++++++++++ library_source/common/FOCMotor.h | 195 +++++++++ library_source/{ => common}/Sensor.h | 0 library_source/{ => common}/defaults.h | 0 library_source/common/foc_utils.cpp | 54 +++ library_source/common/foc_utils.h | 55 +++ .../hardware_utils.cpp} | 96 ++-- .../{FOCutils.h => common/hardware_utils.h} | 79 ++-- library_source/common/lowpass_filter.cpp | 25 ++ library_source/common/lowpass_filter.h | 29 ++ library_source/common/pid.cpp | 56 +++ library_source/common/pid.h | 40 ++ 21 files changed, 1267 insertions(+), 705 deletions(-) create mode 100644 library_source/StepperMotor.cpp create mode 100644 library_source/StepperMotor.h create mode 100644 library_source/common/FOCMotor.cpp create mode 100644 library_source/common/FOCMotor.h rename library_source/{ => common}/Sensor.h (100%) rename library_source/{ => common}/defaults.h (100%) create mode 100644 library_source/common/foc_utils.cpp create mode 100644 library_source/common/foc_utils.h rename library_source/{FOCutils.cpp => common/hardware_utils.cpp} (70%) rename library_source/{FOCutils.h => common/hardware_utils.h} (54%) create mode 100644 library_source/common/lowpass_filter.cpp create mode 100644 library_source/common/lowpass_filter.h create mode 100644 library_source/common/pid.cpp create mode 100644 library_source/common/pid.h diff --git a/library_source/BLDCMotor.cpp b/library_source/BLDCMotor.cpp index f31e818a..893ac81a 100644 --- a/library_source/BLDCMotor.cpp +++ b/library_source/BLDCMotor.cpp @@ -6,6 +6,7 @@ // - cpr - counts per rotation number (cpm=ppm*4) // - enable pin - (optional input) BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +: FOCMotor() { // Pin initialization pwmA = phA; @@ -16,54 +17,9 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // enable_pin pin enable_pin = en; - // Power supply voltage - voltage_power_supply = DEF_POWER_SUPPLY; - - // Velocity loop config - // PI controller constant - PID_velocity.P = DEF_PID_VEL_P; - PID_velocity.I = DEF_PID_VEL_I; - PID_velocity.D = DEF_PID_VEL_D; - PID_velocity.output_ramp = DEF_PID_VEL_U_RAMP; - PID_velocity.timestamp = _micros(); - PID_velocity.integral_prev = 0; - PID_velocity.output_prev = 0; - PID_velocity.tracking_error_prev = 0; - - // velocity low pass filter - LPF_velocity.Tf = DEF_VEL_FILTER_Tf; - LPF_velocity.timestamp = _micros(); - LPF_velocity.prev = 0; - - // position loop config - // P controller constant - P_angle.P = DEF_P_ANGLE_P; - - // maximum angular velocity to be used for positioning - velocity_limit = DEF_VEL_LIM; - // maximum voltage to be set to the motor - voltage_limit = voltage_power_supply; - - // index search velocity - velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; - // sensor and motor align voltage - voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; - - // electric angle of the zero angle - zero_electric_angle = 0; - - // default modulation is SinePWM - foc_modulation = FOCModulationType::SinePWM; - - // default target value - target = 0; - - //monitor_port - monitor_port = nullptr; - //sensor - sensor = nullptr; } + // init hardware pins void BLDCMotor::init() { if(monitor_port) monitor_port->println("MOT: Init pins."); @@ -71,7 +27,7 @@ void BLDCMotor::init() { pinMode(pwmA, OUTPUT); pinMode(pwmB, OUTPUT); pinMode(pwmC, OUTPUT); - if(hasEnable()) pinMode(enable_pin, OUTPUT); + if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); if(monitor_port) monitor_port->println("MOT: PWM config."); // Increase PWM frequency to 32 kHz @@ -96,7 +52,7 @@ void BLDCMotor::init() { void BLDCMotor::disable() { // disable the driver - if enable_pin pin available - if (hasEnable()) digitalWrite(enable_pin, LOW); + if (enable_pin != NOT_SET) digitalWrite(enable_pin, LOW); // set zero to PWM setPwm(0, 0, 0); } @@ -106,15 +62,33 @@ void BLDCMotor::enable() // set zero to PWM setPwm(0, 0, 0); // enable_pin the driver - if enable_pin pin available - if (hasEnable()) digitalWrite(enable_pin, HIGH); - -} + if (enable_pin != NOT_SET) digitalWrite(enable_pin, HIGH); -void BLDCMotor::linkSensor(Sensor* _sensor) { - sensor = _sensor; } +/** + FOC functions +*/ +// FOC initialization function +int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } + if(monitor_port) monitor_port->println("MOT: Motor ready."); + return exit_flag; +} // Encoder alignment to electrical 0 angle int BLDCMotor::alignSensor() { if(monitor_port) monitor_port->println("MOT: Align sensor."); @@ -173,7 +147,7 @@ int BLDCMotor::absoluteZeroAlign() { // search the absolute zero with small velocity while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ loopFOC(); - voltage_q = velocityPID(velocity_index_search - shaftVelocity()); + voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); } voltage_q = 0; // disable motor @@ -184,64 +158,19 @@ int BLDCMotor::absoluteZeroAlign() { // align the sensor with the absolute zero float zero_offset = sensor->initAbsoluteZero(); // remember zero electric angle - zero_electric_angle = normalizeAngle(electricAngle(zero_offset)); + zero_electric_angle = _normalizeAngle(_electricalAngle(zero_offset, pole_pairs)); } // return bool if zero found return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; } -/** - State calculation methods -*/ -// shaft angle calculation -float BLDCMotor::shaftAngle() { - // if no sensor linked return 0 - if(!sensor) return 0; - return sensor->getAngle(); -} -// shaft velocity calculation -float BLDCMotor::shaftVelocity() { - // if no sensor linked return 0 - if(!sensor) return 0; - return lowPassFilter(sensor->getVelocity(), LPF_velocity); -} -// Electrical angle calculation -float BLDCMotor::electricAngle(float shaftAngle) { - //return normalizeAngle(shaftAngle * pole_pairs); - return (shaftAngle * pole_pairs); -} - -/** - FOC functions -*/ -// FOC initialization function -int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { - int exit_flag = 1; - // align motor if necessary - // alignment necessary for encoders! - if(zero_electric_offset != NOT_SET){ - // abosolute zero offset provided - no need to align - zero_electric_angle = zero_electric_offset; - // set the sensor direction - default CW - sensor->natural_direction = sensor_direction; - }else{ - // sensor and motor alignment - _delay(500); - exit_flag = alignSensor(); - _delay(500); - } - if(monitor_port) monitor_port->println("MOT: Motor ready."); - - return exit_flag; -} - // Iterative function looping FOC algorithm, setting Uq on the Motor // The faster it can be run the better void BLDCMotor::loopFOC() { // shaft angle shaft_angle = shaftAngle(); // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); + setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); } // Iterative function running outer loop of the FOC algorithm @@ -263,14 +192,14 @@ void BLDCMotor::move(float new_target) { // angle set point // include angle loop shaft_angle_sp = target; - shaft_velocity_sp = positionP( shaft_angle_sp - shaft_angle ); - voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); + shaft_velocity_sp = P_angle( shaft_angle_sp - shaft_angle ); + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); break; case ControlType::velocity: // velocity set point // include velocity loop shaft_velocity_sp = target; - voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); break; case ControlType::velocity_openloop: // velocity control in open loop @@ -303,7 +232,7 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // angle normalization in between 0 and 2pi // only necessary if using _sin and _cos - approximation functions - angle_el = normalizeAngle(angle_el + zero_electric_angle); + angle_el = _normalizeAngle(angle_el + zero_electric_angle); // Inverse park transform Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; @@ -325,7 +254,7 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // angle normalisation in between 0 and 2pi // only necessary if using _sin and _cos - approximation functions - angle_el = normalizeAngle(angle_el + zero_electric_angle + _PI_2); + angle_el = _normalizeAngle(angle_el + zero_electric_angle + _PI_2); // find the sector we are in currently int sector = floor(angle_el / _PI_3) + 1; @@ -402,94 +331,8 @@ void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); } -/** - Utility functions -*/ -// normalizing radian angle to [0,2PI] -float BLDCMotor::normalizeAngle(float angle){ - float a = fmod(angle, _2PI); - return a >= 0 ? a : (a + _2PI); -} -// determining if the enable pin has been provided -int BLDCMotor::hasEnable(){ - return enable_pin != NOT_SET; -} - -// low pass filter function -// - input -singal to be filtered -// - lpf -LPF_s structure with filter parameters -float BLDCMotor::lowPassFilter(float input, LPF_s& lpf){ - unsigned long now_us = _micros(); - float Ts = (now_us - lpf.timestamp) * 1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // calculate the filtering - float alpha = lpf.Tf/(lpf.Tf + Ts); - float out = alpha*lpf.prev + (1-alpha)*input; - - // save the variables - lpf.prev = out; - lpf.timestamp = now_us; - return out; -} -/** - Motor control functions -*/ -// PID controller function -float BLDCMotor::controllerPID(float tracking_error, PID_s& cont){ - // calculate the time from the last call - unsigned long now_us = _micros(); - float Ts = (now_us - cont.timestamp) * 1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // u(s) = (P + I/s + Ds)e(s) - // Discrete implementations - // proportional part - // u_p = P *e(k) - float proportional = cont.P * tracking_error; - // Tustin transform of the integral part - // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) - float integral = cont.integral_prev + cont.I*Ts*0.5*(tracking_error + cont.tracking_error_prev); - // antiwindup - limit the output voltage_q - integral = constrain(integral, -voltage_limit, voltage_limit); - // Discrete derivation - // u_dk = D(ek - ek_1)/Ts - float derivative = cont.D*(tracking_error - cont.tracking_error_prev)/Ts; - // sum all the components - float voltage = proportional + integral + derivative; - - // antiwindup - limit the output voltage_q - voltage = constrain(voltage, -voltage_limit, voltage_limit); - - // limit the acceleration by ramping the the voltage - float d_voltage = voltage - cont.output_prev; - if (abs(d_voltage)/Ts > cont.output_ramp) voltage = d_voltage > 0 ? cont.output_prev + cont.output_ramp*Ts : cont.output_prev - cont.output_ramp*Ts; - - // saving for the next pass - cont.integral_prev = integral; - cont.output_prev = voltage; - cont.tracking_error_prev = tracking_error; - cont.timestamp = now_us; - return voltage; -} -// velocity control loop PI controller -float BLDCMotor::velocityPID(float tracking_error) { - return controllerPID(tracking_error, PID_velocity); -} - -// P controller for position control loop -float BLDCMotor::positionP(float ek) { - // calculate the target velocity from the position error - float velocity_target = P_angle.P * ek; - // constrain velocity target value - velocity_target = constrain(velocity_target, -velocity_limit, velocity_limit); - return velocity_target; -} - // Function (iterative) generating open loop movement for target velocity // - target_velocity - rad/s // it uses voltage_limit variable @@ -503,7 +346,7 @@ void BLDCMotor::velocityOpenloop(float target_velocity){ shaft_angle += target_velocity*Ts; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; @@ -526,191 +369,8 @@ void BLDCMotor::angleOpenloop(float target_angle){ shaft_angle = target_angle; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; -} - -/** - * Monitoring functions - */ -// function implementing the monitor_port setter -void BLDCMotor::useMonitoring(Print &print){ - monitor_port = &print; //operate on the address of print - if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); -} -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void BLDCMotor::monitor() { - if(!monitor_port) return; - switch (controller) { - case ControlType::velocity_openloop: - case ControlType::velocity: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_velocity_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - case ControlType::angle_openloop: - case ControlType::angle: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_angle); - break; - case ControlType::voltage: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - } -} - -int BLDCMotor::command(String user_command) { - // error flag - int errorFlag = 1; - // if empty string - if(user_command.length() < 1) return errorFlag; - - // parse command letter - char cmd = user_command.charAt(0); - // check if get command - char GET = user_command.charAt(1) == '\n'; - // parse command values - float value = user_command.substring(1).toFloat(); - - // a bit of optimisation of variable memory for Arduino UNO (atmega328) - switch(cmd){ - case 'P': // velocity P gain change - case 'I': // velocity I gain change - case 'D': // velocity D gain change - case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print(" PID velocity| "); - break; - case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print(" LPF velocity| "); - break; - case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print(" P angle| "); - break; - case 'L': // velocity voltage limit change - case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print(" Limits| "); - break; - - } - - // apply the the command - switch(cmd){ - case 'P': // velocity P gain change - if(monitor_port) monitor_port->print("P: "); - if(!GET) PID_velocity.P = value; - if(monitor_port) monitor_port->println(PID_velocity.P); - break; - case 'I': // velocity I gain change - if(monitor_port) monitor_port->print("I: "); - if(!GET) PID_velocity.I = value; - if(monitor_port) monitor_port->println(PID_velocity.I); - break; - case 'D': // velocity D gain change - if(monitor_port) monitor_port->print("D: "); - if(!GET) PID_velocity.D = value; - if(monitor_port) monitor_port->println(PID_velocity.D); - break; - case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print("volt_ramp: "); - if(!GET) PID_velocity.output_ramp = value; - if(monitor_port) monitor_port->println(PID_velocity.output_ramp); - break; - case 'L': // velocity voltage limit change - if(monitor_port) monitor_port->print("volt_limit: "); - if(!GET)voltage_limit = value; - if(monitor_port) monitor_port->println(voltage_limit); - break; - case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print("Tf: "); - if(!GET) LPF_velocity.Tf = value; - if(monitor_port) monitor_port->println(LPF_velocity.Tf); - break; - case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print(" P: "); - if(!GET) P_angle.P = value; - if(monitor_port) monitor_port->println(P_angle.P); - break; - case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print("vel_limit: "); - if(!GET) velocity_limit = value; - if(monitor_port) monitor_port->println(velocity_limit); - break; - case 'C': - // change control type - if(monitor_port) monitor_port->print("Control: "); - - if(GET){ // if get command - switch(controller){ - case ControlType::voltage: - if(monitor_port) monitor_port->println("voltage"); - break; - case ControlType::velocity: - if(monitor_port) monitor_port->println("velocity"); - break; - case ControlType::angle: - if(monitor_port) monitor_port->println("angle"); - break; - default: - if(monitor_port) monitor_port->println("open loop"); - } - }else{ // if set command - switch((int)value){ - case 0: - if(monitor_port) monitor_port->println("voltage"); - controller = ControlType::voltage; - break; - case 1: - if(monitor_port) monitor_port->println("velocity"); - controller = ControlType::velocity; - break; - case 2: - if(monitor_port) monitor_port->println("angle"); - controller = ControlType::angle; - break; - default: // not valid command - errorFlag = 0; - } - } - break; - case 'V': // get current values of the state variables - switch((int)value){ - case 0: // get voltage - if(monitor_port) monitor_port->print("Uq: "); - if(monitor_port) monitor_port->println(voltage_q); - break; - case 1: // get velocity - if(monitor_port) monitor_port->print("Velocity: "); - if(monitor_port) monitor_port->println(shaft_velocity); - break; - case 2: // get angle - if(monitor_port) monitor_port->print("Angle: "); - if(monitor_port) monitor_port->println(shaft_angle); - break; - case 3: // get angle - if(monitor_port) monitor_port->print("Target: "); - if(monitor_port) monitor_port->println(target); - break; - default: // not valid command - errorFlag = 0; - } - break; - default: // target change - if(monitor_port) monitor_port->print("Target : "); - target = user_command.toFloat(); - if(monitor_port) monitor_port->println(target); - } - // return 0 if error and 1 if ok - return errorFlag; } \ No newline at end of file diff --git a/library_source/BLDCMotor.h b/library_source/BLDCMotor.h index 95ca9472..6d597c9a 100644 --- a/library_source/BLDCMotor.h +++ b/library_source/BLDCMotor.h @@ -7,68 +7,16 @@ #define BLDCMotor_h #include "Arduino.h" -#include "FOCutils.h" -#include "Sensor.h" -#include "defaults.h" - - -#define NOT_SET -12345.0 - -/** - * Motiron control type - */ -enum ControlType{ - voltage,//!< Torque control using voltage - velocity,//!< Velocity motion control - angle,//!< Position/angle motion control - velocity_openloop, - angle_openloop -}; - -/** - * FOC modulation type - */ -enum FOCModulationType{ - SinePWM, //!< Sinusoidal PWM modulation - SpaceVectorPWM //!< Space vector modulation method -}; - -/** - * PID controller structure - */ -struct PID_s{ - float P; //!< Proportional gain - float I; //!< Integral gain - float D; //!< Derivative gain - long timestamp; //!< Last execution timestamp - float integral_prev; //!< last integral component value - float output_prev; //!< last pid output value - float output_ramp; //!< Maximum speed of change of the output value - float tracking_error_prev; //!< last tracking error value -}; - -// P controller structure -struct P_s{ - float P; //!< Proportional gain - long timestamp; //!< Last execution timestamp -}; - -/** - * Low pass filter structure - */ -struct LPF_s{ - float Tf; //!< Low pass filter time constant - long timestamp; //!< Last execution timestamp - float prev; //!< filtered value in previous execution step -}; - - - +#include "common/FOCMotor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" +#include "common/defaults.h" /** BLDC motor class */ -class BLDCMotor +class BLDCMotor: public FOCMotor { public: /** @@ -89,22 +37,9 @@ class BLDCMotor /** Motor enable function */ void enable(); - /** - * Function linking a motor and a sensor - * - * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity - */ - void linkSensor(Sensor* sensor); - /** * Function initializing FOC algorithm * and aligning sensor's and motors' zero position - * - * - If zero_electric_offset parameter is set the alignment procedure is skipped - * - * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. - * @param sensor_direction sensor natural direction - default is CW - * */ int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); /** @@ -114,6 +49,7 @@ class BLDCMotor * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us */ void loopFOC(); + /** * Function executing the control loops set by the controller parameter of the BLDCMotor. * @@ -130,53 +66,8 @@ class BLDCMotor int pwmC; //!< phase C pwm pin number int enable_pin; //!< enable pin number - - - - // State calculation methods - /** Shaft angle calculation in radians [rad] */ - float shaftAngle(); - /** - * Shaft angle calculation function in radian per second [rad/s] - * It implements low pass filtering - */ - float shaftVelocity(); - - // state variables - float target; //!< current target value - depends of the controller - float shaft_angle;//!< current motor angle - float shaft_velocity;//!< current motor velocity - float shaft_velocity_sp;//!< current target velocity - float shaft_angle_sp;//!< current target angle - float voltage_q;//!< current voltage u_q set - float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor - - // motor configuration parameters - float voltage_power_supply;//!< Power supply voltage - float voltage_sensor_align;//!< sensor and motor align voltage parameter - float velocity_index_search;//!< target velocity for index search - int pole_pairs;//!< Motor pole pairs number - - // limiting variables - float voltage_limit; //!< Voltage limitting variable - global limit - float velocity_limit; //!< Velocity limitting variable - global limit - - // configuration structures - ControlType controller; //!< parameter determining the control loop to be used - FOCModulationType foc_modulation;//!< parameter derterniming modulation algorithm - PID_s PID_velocity;//!< parameter determining the velocity PI configuration - P_s P_angle; //!< parameter determining the position P configuration - LPF_s LPF_velocity;//!< parameter determining the velocity Lpw pass filter configuration - - /** - * Sensor link: - * - Encoder - * - MagneticSensor - */ - Sensor* sensor; - - float zero_electric_angle;//! -#include "FOCutils.h" -#include "Sensor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" /** * This sensor has been tested with AS5600 running in 'analog mode'. This is where output pin of AS6000 is connected to an analog pin on your microcontroller. @@ -15,7 +15,8 @@ class MagneticSensorAnalog: public Sensor{ /** * MagneticSensorAnalog class constructor * @param _pinAnalog the pin to read the PWM signal - * @param _pinAnalog the pin to read the PWM signal + * @param _min minimal value of angle reading + * @param _max maximal value of angle reading */ MagneticSensorAnalog(uint8_t _pinAnalog, int _min = 0, int _max = 0); diff --git a/library_source/MagneticSensorI2C.h b/library_source/MagneticSensorI2C.h index c5dc3489..91c9e7ca 100644 --- a/library_source/MagneticSensorI2C.h +++ b/library_source/MagneticSensorI2C.h @@ -3,8 +3,9 @@ #include "Arduino.h" #include -#include "FOCutils.h" -#include "Sensor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" class MagneticSensorI2C: public Sensor{ diff --git a/library_source/MagneticSensorSPI.h b/library_source/MagneticSensorSPI.h index da70c0c4..71c0dd02 100644 --- a/library_source/MagneticSensorSPI.h +++ b/library_source/MagneticSensorSPI.h @@ -3,8 +3,9 @@ #include "Arduino.h" #include -#include "FOCutils.h" -#include "Sensor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" #define DEF_ANGLE_REGISTAR 0x3FFF diff --git a/library_source/StepperMotor.cpp b/library_source/StepperMotor.cpp new file mode 100644 index 00000000..fca6b1b1 --- /dev/null +++ b/library_source/StepperMotor.cpp @@ -0,0 +1,305 @@ +#include "StepperMotor.h" + +// StepperMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - ph1A, ph1B - motor phase 1 pwm pins +// - ph2A, ph2B - motor phase 2 pwm pins +// - pp - pole pair number +// - enable pin - (optional input) +StepperMotor::StepperMotor(int ph1A, int ph1B, int ph2A, int ph2B, int pp, int en1, int en2) +: FOCMotor() +{ + // Pin initialization + pwm1A = ph1A; + pwm1B = ph1B; + pwm2A = ph2A; + pwm2B = ph2B; + pole_pairs = pp; + + // enable_pin pin + enable_pin1 = en1; + enable_pin2 = en2; +} + +// init hardware pins +void StepperMotor::init() { + if(monitor_port) monitor_port->println("MOT: Init pins."); + // PWM pins + pinMode(pwm1A, OUTPUT); + pinMode(pwm1B, OUTPUT); + pinMode(pwm2A, OUTPUT); + pinMode(pwm2B, OUTPUT); + if ( enable_pin1 != NOT_SET ) pinMode(enable_pin1, OUTPUT); + if ( enable_pin2 != NOT_SET ) pinMode(enable_pin2, OUTPUT); + + if(monitor_port) monitor_port->println("MOT: PWM config."); + // Increase PWM frequency + // make silent + _setPwmFrequency(pwm1A, pwm1B, pwm2A, pwm2B); + + // sanity check for the voltage limit configuration + if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + + _delay(500); + // enable motor + if(monitor_port) monitor_port->println("MOT: Enable."); + enable(); + _delay(500); + +} + + +// disable motor driver +void StepperMotor::disable() +{ + // disable the driver - if enable_pin pin available + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, LOW); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, LOW); + // set zero to PWM + setPwm(0, 0); +} +// enable motor driver +void StepperMotor::enable() +{ + // set zero to PWM + setPwm(0, 0); + // enable_pin the driver - if enable_pin pin available + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, HIGH); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, HIGH); + +} + + +/** + FOC functions +*/ +// FOC initialization function +int StepperMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } + if(monitor_port) monitor_port->println("MOT: Motor ready."); + + return exit_flag; +} +// Encoder alignment to electrical 0 angle +int StepperMotor::alignSensor() { + if(monitor_port) monitor_port->println("MOT: Align sensor."); + // align the electrical phases of the motor and sensor + // set angle -90 degrees + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } + + // let the motor stabilize for 2 sec + _delay(2000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0,0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int StepperMotor::absoluteZeroAlign() { + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); + + // align absolute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = _normalizeAngle(_electricalAngle(zero_offset, pole_pairs)); + } + // return bool if zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void StepperMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); +} + +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function +// - if target is not set it uses motor.target value +void StepperMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; + // get angular velocity + shaft_velocity = shaftVelocity(); + // choose control loop + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = P_angle( shaft_angle_sp - shaft_angle ); + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // include velocity loop + shaft_velocity_sp = target; + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); + break; + } +} + + +// Method using FOC to set Uq to the motor at the optimal angle +// Function implementingSine PWM algorithms +// - space vector not implemented yet +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) +void StepperMotor::setPhaseVoltage(float Uq, float angle_el) { + // Sinusoidal PWM modulation + // Inverse Park transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + // set the voltages in hardware + setPwm(Ualpha,Ubeta); +} + + + +// Set voltage to the pwm pin +void StepperMotor::setPwm(float Ualpha, float Ubeta) { + float duty_cycle1A(0.0),duty_cycle1B(0.0),duty_cycle2A(0.0),duty_cycle2B(0.0); + // hardware specific writing + if( Ualpha > 0 ) + duty_cycle1B = constrain(abs(Ualpha)/voltage_power_supply,0,1); + else + duty_cycle1A = constrain(abs(Ualpha)/voltage_power_supply,0,1); + + if( Ubeta > 0 ) + duty_cycle2B = constrain(abs(Ubeta)/voltage_power_supply,0,1); + else + duty_cycle2A = constrain(abs(Ubeta)/voltage_power_supply,0,1); + // write to hardware + _writeDutyCycle(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, pwm1A, pwm1B, pwm2A, pwm2B); +} + +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void StepperMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle,pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void StepperMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle,pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} \ No newline at end of file diff --git a/library_source/StepperMotor.h b/library_source/StepperMotor.h new file mode 100644 index 00000000..8f10311f --- /dev/null +++ b/library_source/StepperMotor.h @@ -0,0 +1,122 @@ +/** + * @file StepperMotor.h + * + */ + +#ifndef StepperMotor_h +#define StepperMotor_h + +#include "Arduino.h" +#include "common/FOCMotor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" +#include "common/defaults.h" + +/** + Stepper Motor class +*/ +class StepperMotor: public FOCMotor +{ + public: + /** + StepperMotor class constructor + @param ph1A 1A phase pwm pin + @param ph1B 1B phase pwm pin + @param ph2A 2A phase pwm pin + @param ph2B 2B phase pwm pin + @param pp pole pair number - cpr counts per rotation number (cpm=ppm*4) + @param en1 enable pin phase 1 (optional input) + @param en2 enable pin phase 2 (optional input) + */ + StepperMotor(int ph1A,int ph1B,int ph2A,int ph2B,int pp, int en1 = NOT_SET, int en2 = NOT_SET); + + /** Motor hardware init function */ + void init(); + /** Motor disable function */ + void disable(); + /** Motor enable function */ + void enable(); + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + void loopFOC(); + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET); + + // hardware variables + int pwm1A; //!< phase 1A pwm pin number + int pwm1B; //!< phase 1B pwm pin number + int pwm2A; //!< phase 2A pwm pin number + int pwm2B; //!< phase 2B pwm pin number + int enable_pin1; //!< enable pin number phase 1 + int enable_pin2; //!< enable pin number phase 2 + + private: + + // FOC methods + /** + * Method using FOC to set Uq to the motor at the optimal angle + * Heart of the FOC algorithm + * + * @param Uq Current voltage in q axis to set to the motor + * @param angle_el current electrical angle of the motor + */ + void setPhaseVoltage(float Uq, float angle_el); + + /** Sensor alignment to electrical 0 angle of the motor */ + int alignSensor(); + /** Motor and sensor alignment to the sensors absolute 0 angle */ + int absoluteZeroAlign(); + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + * @param Uc phase C voltage + */ + void setPwm(float Ualpha, float Ubeta); + + // Open loop motion control + /** + * Function (iterative) generating open loop movement for target velocity + * it uses voltage_limit variable + * + * @param target_velocity - rad/s + */ + void velocityOpenloop(float target_velocity); + /** + * Function (iterative) generating open loop movement towards the target angle + * it uses voltage_limit and velocity_limit variables + * + * @param target_angle - rad + */ + void angleOpenloop(float target_angle); + // open loop variables + long open_loop_timestamp; +}; + + +#endif diff --git a/library_source/common/FOCMotor.cpp b/library_source/common/FOCMotor.cpp new file mode 100644 index 00000000..adecbeec --- /dev/null +++ b/library_source/common/FOCMotor.cpp @@ -0,0 +1,245 @@ +#include "FOCMotor.h" + +/** + * Default constructor - setting all variabels to default values + */ +FOCMotor::FOCMotor() +{ + // Power supply voltage + voltage_power_supply = DEF_POWER_SUPPLY; + + // maximum angular velocity to be used for positioning + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = voltage_power_supply; + + // index search velocity + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; + + // electric angle of comthe zero angle + zero_electric_angle = 0; + + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + + // default target value + target = 0; + + //monitor_port + monitor_port = nullptr; + //sensor + sensor = nullptr; +} + + +/** + Sensor communication methods +*/ +void FOCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} +// shaft angle calculation +float FOCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return shaft_angle; + return sensor->getAngle(); +} +// shaft velocity calculation +float FOCMotor::shaftVelocity() { + // if no sensor linked return 0 + if(!sensor) return 0; + return LPF_velocity(sensor->getVelocity()); +} + + + + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void FOCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void FOCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity_openloop: + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle_openloop: + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int FOCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'D': // velocity D gain change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PID velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P angle| "); + break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + } + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("P: "); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("I: "); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); + break; + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("volt_ramp: "); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET) { + voltage_limit = value; + PID_velocity.limit = value; + } + if(monitor_port) monitor_port->println(voltage_limit); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("Tf: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("vel_limit: "); + if(!GET){ + velocity_limit = value; + P_angle.limit = value; + } + if(monitor_port) monitor_port->println(velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Control: "); + + if(GET){ // if get command + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + default: + if(monitor_port) monitor_port->println("open loop"); + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} \ No newline at end of file diff --git a/library_source/common/FOCMotor.h b/library_source/common/FOCMotor.h new file mode 100644 index 00000000..11d566d4 --- /dev/null +++ b/library_source/common/FOCMotor.h @@ -0,0 +1,195 @@ +#ifndef FOCMOTOR_H +#define FOCMOTOR_H + +#include "Arduino.h" +#include "hardware_utils.h" +#include "foc_utils.h" +#include "defaults.h" + +#include "Sensor.h" +#include "pid.h" +#include "lowpass_filter.h" + + +/** + * Motiron control type + */ +enum ControlType{ + voltage,//!< Torque control using voltage + velocity,//!< Velocity motion control + angle,//!< Position/angle motion control + velocity_openloop, + angle_openloop +}; + +/** + * FOC modulation type + */ +enum FOCModulationType{ + SinePWM, //!< Sinusoidal PWM modulation + SpaceVectorPWM //!< Space vector modulation method +}; + +/** + Generic motor class +*/ +class FOCMotor +{ + public: + /** + * Default constructor - setting all variabels to default values + */ + FOCMotor(); + + /** Motor hardware init function */ + virtual void init()=0; + /** Motor disable function */ + virtual void disable()=0; + /** Motor enable function */ + virtual void enable()=0; + + /** + * Function linking a motor and a sensor + * + * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity + */ + void linkSensor(Sensor* sensor); + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + virtual int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW)=0; + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + virtual void loopFOC()=0; + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + virtual void move(float target = NOT_SET)=0; + + // State calculation methods + /** Shaft angle calculation in radians [rad] */ + float shaftAngle(); + /** + * Shaft angle calculation function in radian per second [rad/s] + * It implements low pass filtering + */ + float shaftVelocity(); + + // state variables + float target; //!< current target value - depends of the controller + float shaft_angle;//!< current motor angle + float shaft_velocity;//!< current motor velocity + float shaft_velocity_sp;//!< current target velocity + float shaft_angle_sp;//!< current target angle + float voltage_q;//!< current voltage u_q set + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform + + // motor configuration parameters + float voltage_power_supply;//!< Power supply voltage + float voltage_sensor_align;//!< sensor and motor align voltage parameter + float velocity_index_search;//!< target velocity for index search + int pole_pairs;//!< Motor pole pairs number + + // limiting variables + float voltage_limit; //!< Voltage limitting variable - global limit + float velocity_limit; //!< Velocity limitting variable - global limit + + float zero_electric_angle;//! _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} + + +// normalizing radian angle to [0,2PI] +float _normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} + +// Electrical angle calculation +float _electricalAngle(float shaft_angle, int pole_pairs) { + return (shaft_angle * pole_pairs); +} \ No newline at end of file diff --git a/library_source/common/foc_utils.h b/library_source/common/foc_utils.h new file mode 100644 index 00000000..5ab34f42 --- /dev/null +++ b/library_source/common/foc_utils.h @@ -0,0 +1,55 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + +// sign function +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + +// utility defines +#define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI 3.14159265359 +#define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + + +#define NOT_SET -12345.0 + +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _sin(float a); +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _cos(float a); + +/** + * normalizing radian angle to [0,2PI] + * @param angle - angle to be normalized + */ +float _normalizeAngle(float angle); + + +/** + * Electrical angle calculation + * + * @param shaft_angle - shaft angle of the motor + * @param pole_pairs - number of pole pairs + */ +float _electricalAngle(float shaft_angle, int pole_pairs); +#endif \ No newline at end of file diff --git a/library_source/FOCutils.cpp b/library_source/common/hardware_utils.cpp similarity index 70% rename from library_source/FOCutils.cpp rename to library_source/common/hardware_utils.cpp index 7c92b685..802087a7 100644 --- a/library_source/FOCutils.cpp +++ b/library_source/common/hardware_utils.cpp @@ -1,4 +1,4 @@ -#include "FOCutils.h" +#include "hardware_utils.h" #if defined(ESP_H) // if ESP32 board // empty motor slot @@ -31,27 +31,34 @@ motor_slots_t esp32_motor_slots[4] = { // function setting the high pwm frequency to the supplied pins // - hardware speciffic // supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(const int pinA, const int pinB, const int pinC) { +void _setPwmFrequency(const int pinA, const int pinB, const int pinC, const int pinD) { #if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips - // High PWM frequency + // High PWM frequency // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pinA == 5 || pinA == 6 || pinB == 5 || pinB == 6 || pinC == 5 || pinC == 6 ) { + if (pinA == 5 || pinA == 6 || pinB == 5 || pinB == 6 || pinC == 5 || pinC == 6 || pinD == 5 || pinD == 6 ) { TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 } - if (pinA == 9 || pinA == 10 || pinB == 9 || pinB == 10 || pinC == 9 || pinC == 10 ) + if (pinA == 9 || pinA == 10 || pinB == 9 || pinB == 10 || pinC == 9 || pinC == 10|| pinD == 9 || pinD == 10 ) TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pinA == 3 || pinA == 11 || pinB == 3 || pinB == 11 || pinC == 3 || pinC == 11 ) + if (pinA == 3 || pinA == 11 || pinB == 3 || pinB == 11 || pinC == 3 || pinC == 11 || pinD == 3 || pinD == 11 ) TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 #elif defined(_STM32_DEF_) // if stm chips analogWrite(pinA, 0); analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 analogWrite(pinB, 0); analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 analogWrite(pinC, 0); analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 + if(pinD) { + analogWrite(pinD, 0); + analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 #elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards analogWrite(pinA, 0); @@ -60,6 +67,9 @@ void _setPwmFrequency(const int pinA, const int pinB, const int pinC) { analogWriteFrequency(pinB, 50000); // set 50kHz analogWrite(pinC, 0); analogWriteFrequency(pinC, 50000); // set 50kHz + if(pinD) { + analogWrite(pinD, 0); + analogWriteFrequency(50000); // set 50kHz #elif defined(ESP_H) // if esp32 boards @@ -141,7 +151,12 @@ void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, in break; } } -#else // Arduino & STM32 devices & Teensy +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pinA, 4095.0*dc_a); + analogWrite(pinB, 4095.0*dc_b); + analogWrite(pinC, 4095.0*dc_c); +#else // Arduino & Teensy // transform duty cycle from [0,1] to [0,255] analogWrite(pinA, 255*dc_a); analogWrite(pinB, 255*dc_b); @@ -149,6 +164,29 @@ void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, in #endif } +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ +#if defined(ESP_H) // if ESP32 boards + // not sure how to handle this +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pin1A, 4095.0*dc_1a); + analogWrite(pin1B, 4095.0*dc_1b); + analogWrite(pin2A, 4095.0*dc_2a); + analogWrite(pin2B, 4095.0*dc_2b); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255*dc_1a); + analogWrite(pin1B, 255*dc_1b); + analogWrite(pin2A, 255*dc_2a); + analogWrite(pin2B, 255*dc_2b); +#endif +} + // function buffering delay() // arduino uno function doesn't work well with interrupts @@ -178,46 +216,4 @@ unsigned long _micros(){ // regular micros return micros(); #endif -} - - -// int array instead of float array -// 2x storage save (int 2Byte float 4 Byte ) -// sin*10000 -int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,1103,1181,1260,1338,1416,1494,1572,1650,1728,1806,1883,1961,2038,2115,2192,2269,2346,2423,2499,2575,2652,2728,2804,2879,2955,3030,3105,3180,3255,3329,3404,3478,3552,3625,3699,3772,3845,3918,3990,4063,4135,4206,4278,4349,4420,4491,4561,4631,4701,4770,4840,4909,4977,5046,5113,5181,5249,5316,5382,5449,5515,5580,5646,5711,5775,5839,5903,5967,6030,6093,6155,6217,6279,6340,6401,6461,6521,6581,6640,6699,6758,6815,6873,6930,6987,7043,7099,7154,7209,7264,7318,7371,7424,7477,7529,7581,7632,7683,7733,7783,7832,7881,7930,7977,8025,8072,8118,8164,8209,8254,8298,8342,8385,8428,8470,8512,8553,8594,8634,8673,8712,8751,8789,8826,8863,8899,8935,8970,9005,9039,9072,9105,9138,9169,9201,9231,9261,9291,9320,9348,9376,9403,9429,9455,9481,9506,9530,9554,9577,9599,9621,9642,9663,9683,9702,9721,9739,9757,9774,9790,9806,9821,9836,9850,9863,9876,9888,9899,9910,9920,9930,9939,9947,9955,9962,9969,9975,9980,9985,9989,9992,9995,9997,9999,10000,10000}; - -// function approximating the sine calculation by using fixed size array -// ~40us (float array) -// ~50us (int array) -// precision +-0.005 -// it has to receive an angle in between 0 and 2PI -float _sin(float a){ - if(a < _PI_2){ - //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; - //return sine_array[(int)(126.6873* a)]; // float array optimized - return 0.0001*sine_array[_round(126.6873* a)]; // int array optimized - }else if(a < _PI){ - // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; - //return sine_array[398 - (int)(126.6873*a)]; // float array optimized - return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimized - }else if(a < _3PI_2){ - // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; - //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimized - return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimized - } else { - // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; - //return -sine_array[796 - (int)(126.6873*a)]; // float array optimized - return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimized - } -} - -// function approximating cosine calculation by using fixed size array -// ~55us (float array) -// ~56us (int array) -// precision +-0.005 -// it has to receive an angle in between 0 and 2PI -float _cos(float a){ - float a_sin = a + _PI_2; - a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin; - return _sin(a_sin); -} +} \ No newline at end of file diff --git a/library_source/FOCutils.h b/library_source/common/hardware_utils.h similarity index 54% rename from library_source/FOCutils.h rename to library_source/common/hardware_utils.h index 4c347a12..03c44fdd 100644 --- a/library_source/FOCutils.h +++ b/library_source/common/hardware_utils.h @@ -1,7 +1,8 @@ -#ifndef FOCUTILS_LIB_H -#define FOCUTILS_LIB_H +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H #include "Arduino.h" +#include "foc_utils.h" #if defined(ESP_H) // if esp32 boards @@ -12,23 +13,6 @@ #endif -// sign function -#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) -#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) - -// utility defines -#define _2_SQRT3 1.15470053838 -#define _SQRT3 1.73205080757 -#define _1_SQRT3 0.57735026919 -#define _SQRT3_2 0.86602540378 -#define _SQRT2 1.41421356237 -#define _120_D2R 2.09439510239 -#define _PI 3.14159265359 -#define _PI_2 1.57079632679 -#define _PI_3 1.0471975512 -#define _2PI 6.28318530718 -#define _3PI_2 4.71238898038 - /** * High PWM frequency setting function * - hardware specific @@ -36,23 +20,9 @@ * @param pinA pinA number to configure * @param pinB pinB number to configure * @param pinC pinC number to configure + * @param pinD pinC number to configure */ -void _setPwmFrequency(int pinA, int pinB, int pinC); - -/** - * Function implementing delay() function in milliseconds - * - blocking function - * - hardware specific - - * @param ms number of milliseconds to wait - */ -void _delay(unsigned long ms); - -/** - * Function implementing timestamp getting function in microseconds - * hardware specific - */ -unsigned long _micros(); +void _setPwmFrequency(int pinA, int pinB, int pinC, int pinD = 0); /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) @@ -67,20 +37,35 @@ unsigned long _micros(); */ void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); - -/** - * Function approximating the sine calculation by using fixed size array - * - execution time ~40us (Arduino UNO) +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific * - * @param a angle in between 0 and 2PI + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait */ -float _sin(float a); -/** - * Function approximating cosine calculation by using fixed size array - * - execution time ~50us (Arduino UNO) - * - * @param a angle in between 0 and 2PI +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific */ -float _cos(float a); +unsigned long _micros(); + #endif \ No newline at end of file diff --git a/library_source/common/lowpass_filter.cpp b/library_source/common/lowpass_filter.cpp new file mode 100644 index 00000000..9bf4ab7a --- /dev/null +++ b/library_source/common/lowpass_filter.cpp @@ -0,0 +1,25 @@ +#include "lowpass_filter.h" + +LowPassFilter::LowPassFilter(float time_constant) + : Tf(time_constant) + , y_prev(0.0f) +{ + timestamp_prev = _micros(); +} + + +float LowPassFilter::operator() (float x) +{ + unsigned long timestamp = _micros(); + float dt = (timestamp - timestamp_prev)*1e-6f; + + if (dt < 0.0f || dt > 0.5f) + dt = 1e-3f; + + float alpha = Tf/(Tf + dt); + float y = alpha*y_prev + (1.0f - alpha)*x; + + y_prev = y; + timestamp_prev = timestamp; + return y; +} \ No newline at end of file diff --git a/library_source/common/lowpass_filter.h b/library_source/common/lowpass_filter.h new file mode 100644 index 00000000..5a7619cf --- /dev/null +++ b/library_source/common/lowpass_filter.h @@ -0,0 +1,29 @@ +#ifndef LOWPASS_FILTER_H +#define LOWPASS_FILTER_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + + +/** + * Low pass filter class + */ +class LowPassFilter +{ +public: + /** + * @param Tf - Low pass filter time constant + */ + LowPassFilter(float Tf); + ~LowPassFilter() = default; + + float operator() (float x); + float Tf; //!< Low pass filter time constant + +protected: + unsigned long timestamp_prev; //!< Last execution timestamp + float y_prev; //!< filtered value in previous execution step +}; + +#endif // LOWPASS_FILTER_H \ No newline at end of file diff --git a/library_source/common/pid.cpp b/library_source/common/pid.cpp new file mode 100644 index 00000000..277e17ce --- /dev/null +++ b/library_source/common/pid.cpp @@ -0,0 +1,56 @@ +#include "pid.h" + +PIDController::PIDController(float P, float I, float D, float ramp, float limit) + : P(P) + , I(I) + , D(D) + , output_ramp(ramp) // output derivative limit [volts/second] + , limit(limit) // output supply limit [volts] + , integral_prev(0.0) + , error_prev(0.0) + , output_prev(0.0) +{ + timestamp_prev = _micros()*1e-6; +} + +// PID controller function +float PIDController::operator() (float error){ + // calculate the time from the last call + unsigned long timestamp_now = _micros(); + float Ts = (timestamp_now - timestamp_prev) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = P * error_prev; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = integral_prev + I*Ts*0.5*(error + error_prev); + // antiwindup - limit the output voltage_q + integral = constrain(integral, -limit, limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = D*(error - error_prev)/Ts; + + // sum all the components + float output = proportional + integral + derivative; + // antiwindup - limit the output variable + output = constrain(output, -limit, limit); + + // limit the acceleration by ramping the output + float output_rate = (output - output_prev)/Ts; + if (output_rate > output_ramp) + output = output_prev + output_ramp*Ts; + else if (output_rate < -output_ramp) + output = output_prev - output_ramp*Ts; + + // saving for the next pass + integral_prev = integral; + output_prev = output; + error_prev = error; + timestamp_prev = timestamp_now; + return output; +} \ No newline at end of file diff --git a/library_source/common/pid.h b/library_source/common/pid.h new file mode 100644 index 00000000..7ee337c4 --- /dev/null +++ b/library_source/common/pid.h @@ -0,0 +1,40 @@ +#ifndef PID_H +#define PID_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + +/** + * PID controller class + */ +class PIDController +{ +public: + /** + * + * @param P - Proportional gain + * @param I - Integral gain + * @param D - Derivative gain + * @param ramp - Maximum speed of change of the output value + * @param limit - Maximum output value + */ + PIDController(float P, float I, float D, float ramp, float limit); + ~PIDController() = default; + + float operator() (float error); + + float P; //!< Proportional gain + float I; //!< Integral gain + float D; //!< Derivative gain + float output_ramp; //!< Maximum speed of change of the output value + float limit; //!< Maximum output value + +protected: + float integral_prev; //!< last integral component value + float error_prev; //!< last tracking error value + float timestamp_prev; //!< Last execution timestamp + float output_prev; //!< last pid output value +}; + +#endif // PID_H \ No newline at end of file From 156eb70c238c55608ff48e5be3de1a2feb3c769e Mon Sep 17 00:00:00 2001 From: askuric Date: Sun, 4 Oct 2020 02:53:13 +0200 Subject: [PATCH 58/65] added some examples --- .../arduino_foc_minimal_encoder.ino | 20 +- .../{ => src}/Encoder.cpp | 0 .../arduino_foc_minimal_encoder/src/Encoder.h | 105 +++ .../src/StepperMotor.cpp | 305 ++++++++ .../src/StepperMotor.h | 122 +++ .../src/common/FOCMotor.cpp | 245 ++++++ .../{BLDCMotor.h => src/common/FOCMotor.h} | 194 +---- .../{ => src/common}/Sensor.h | 0 .../{ => src/common}/defaults.h | 0 .../src/common/foc_utils.cpp | 54 ++ .../src/common/foc_utils.h | 55 ++ .../common/hardware_utils.cpp} | 104 +-- .../src/common/hardware_utils.h} | 79 +- .../src/common/lowpass_filter.cpp | 25 + .../src/common/lowpass_filter.h | 29 + .../src/common/pid.cpp | 56 ++ .../src/common/pid.h | 40 + .../arduino_foc_minimal_encoder.ino | 143 ++++ .../src/Encoder.cpp | 228 ++++++ .../src}/Encoder.h | 4 +- .../src/StepperMotor.cpp} | 228 ++---- .../src/StepperMotor.h} | 47 +- .../src/common}/FOCutils.cpp | 46 +- .../src/common}/FOCutils.h | 18 +- .../src/common}/Sensor.h | 0 .../src/common}/defaults.h | 0 .../BLDCMotor.cpp | 716 ------------------ .../arduino_foc_minimal_magnetic_i2c.ino | 8 +- .../src/BLDCMotor.cpp | 376 +++++++++ .../src/BLDCMotor.h | 113 +++ .../{ => src}/MagneticSensorI2C.cpp | 0 .../src/MagneticSensorI2C.h | 79 ++ .../src/common/FOCMotor.cpp | 245 ++++++ .../src/common/FOCMotor.h | 195 +++++ .../src/common/Sensor.h | 59 ++ .../src/common/defaults.h | 18 + .../src/common/foc_utils.cpp | 54 ++ .../src/common/foc_utils.h | 55 ++ .../src/common/hardware_utils.cpp | 219 ++++++ .../src/common/hardware_utils.h | 71 ++ .../src/common/lowpass_filter.cpp | 25 + .../src/common/lowpass_filter.h | 29 + .../src/common/pid.cpp | 57 ++ .../src/common/pid.h | 40 + .../MagneticSensorI2C.cpp | 154 ++++ .../MagneticSensorI2C.h | 0 .../arduino_foc_minimal_magnetic_spi.ino | 13 +- .../BLDCMotor.cpp | 12 +- .../arduino_foc_minimal_openloop/BLDCMotor.h | 5 +- .../arduino_foc_minimal_openloop/FOCutils.cpp | 119 ++- .../arduino_foc_minimal_openloop/FOCutils.h | 4 +- .../arduino_foc_minimal_openloop.ino | 37 +- 52 files changed, 3663 insertions(+), 1187 deletions(-) rename minimal_project_examples/arduino_foc_minimal_encoder/{ => src}/Encoder.cpp (100%) create mode 100644 minimal_project_examples/arduino_foc_minimal_encoder/src/Encoder.h create mode 100644 minimal_project_examples/arduino_foc_minimal_encoder/src/StepperMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_encoder/src/StepperMotor.h create mode 100644 minimal_project_examples/arduino_foc_minimal_encoder/src/common/FOCMotor.cpp rename minimal_project_examples/arduino_foc_minimal_encoder/{BLDCMotor.h => src/common/FOCMotor.h} (56%) rename minimal_project_examples/arduino_foc_minimal_encoder/{ => src/common}/Sensor.h (100%) rename minimal_project_examples/arduino_foc_minimal_encoder/{ => src/common}/defaults.h (100%) create mode 100644 minimal_project_examples/arduino_foc_minimal_encoder/src/common/foc_utils.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_encoder/src/common/foc_utils.h rename minimal_project_examples/arduino_foc_minimal_encoder/{FOCutils.cpp => src/common/hardware_utils.cpp} (69%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c/FOCutils.h => arduino_foc_minimal_encoder/src/common/hardware_utils.h} (54%) create mode 100644 minimal_project_examples/arduino_foc_minimal_encoder/src/common/lowpass_filter.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_encoder/src/common/lowpass_filter.h create mode 100644 minimal_project_examples/arduino_foc_minimal_encoder/src/common/pid.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_encoder/src/common/pid.h create mode 100644 minimal_project_examples/arduino_foc_minimal_encoder1/arduino_foc_minimal_encoder.ino create mode 100644 minimal_project_examples/arduino_foc_minimal_encoder1/src/Encoder.cpp rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_minimal_encoder1/src}/Encoder.h (98%) rename minimal_project_examples/{arduino_foc_minimal_encoder/BLDCMotor.cpp => arduino_foc_minimal_encoder1/src/StepperMotor.cpp} (78%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c/BLDCMotor.h => arduino_foc_minimal_encoder1/src/StepperMotor.h} (90%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_minimal_encoder1/src/common}/FOCutils.cpp (86%) rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_minimal_encoder1/src/common}/FOCutils.h (75%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_minimal_encoder1/src/common}/Sensor.h (100%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_minimal_encoder1/src/common}/defaults.h (100%) delete mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/BLDCMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/BLDCMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/BLDCMotor.h rename minimal_project_examples/arduino_foc_minimal_magnetic_i2c/{ => src}/MagneticSensorI2C.cpp (100%) create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/MagneticSensorI2C.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/FOCMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/FOCMotor.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/Sensor.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/defaults.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/foc_utils.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/foc_utils.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/hardware_utils.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/hardware_utils.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/lowpass_filter.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/lowpass_filter.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/pid.cpp create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/pid.h create mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorI2C.cpp rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_minimal_magnetic_spi}/MagneticSensorI2C.h (100%) diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino b/minimal_project_examples/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino index 8951768f..49c35cbf 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino +++ b/minimal_project_examples/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino @@ -36,20 +36,20 @@ * - 3: current target value * */ -#include "BLDCMotor.h" -#include "Encoder.h" +#include "src/StepperMotor.h" +#include "src/Encoder.h" // motor instance -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 7); - +StepperMotor motor = StepperMotor(10, 6, 5, 9, 50, 8); +// // encoder instance -Encoder encoder = Encoder(2, 3, 8192); +Encoder encoder = Encoder(2,3, 2048); // Interrupt routine intialisation // channel A and B callbacks void doA(){encoder.handleA();} void doB(){encoder.handleB();} - + void setup() { // initialize encoder sensor hardware @@ -58,14 +58,12 @@ void setup() { // link the motor to the sensor motor.linkSensor(&encoder); - // choose FOC modulation - motor.foc_modulation = FOCModulationType::SpaceVectorPWM; - // power supply voltage [V] motor.voltage_power_supply = 12; + motor.voltage_sensor_align = 10; // set control loop type to be used - motor.controller = ControlType::voltage; + motor.controller = ControlType::velocity; // contoller configuration based on the controll type motor.PID_velocity.P = 0.2; @@ -142,4 +140,4 @@ String serialReceiveUserCommand() { } } return command; -} \ No newline at end of file +} diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/Encoder.cpp b/minimal_project_examples/arduino_foc_minimal_encoder/src/Encoder.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_encoder/Encoder.cpp rename to minimal_project_examples/arduino_foc_minimal_encoder/src/Encoder.cpp diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/Encoder.h b/minimal_project_examples/arduino_foc_minimal_encoder/src/Encoder.h new file mode 100644 index 00000000..db9813b8 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_encoder/src/Encoder.h @@ -0,0 +1,105 @@ +#ifndef ENCODER_LIB_H +#define ENCODER_LIB_H + +#include "Arduino.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" + + +/** + * Quadrature mode configuration structure + */ +enum Quadrature{ + ON, //!< Enable quadrature mode CPR = 4xPPR + OFF //!< Disable quadrature mode / CPR = PPR +}; + +class Encoder: public Sensor{ + public: + /** + Encoder class constructor + @param encA encoder B pin + @param encB encoder B pin + @param ppr impulses per rotation (cpr=ppr*4) + @param index index pin number (optional input) + */ + Encoder(int encA, int encB , float ppr, int index = 0); + + /** encoder initialise pins */ + void init(); + /** + * function enabling hardware interrupts for the encoder channels with provided callback functions + * if callback is not provided then the interrupt is not enabled + * + * @param doA pointer to the A channel interrupt handler function + * @param doB pointer to the B channel interrupt handler function + * @param doIndex pointer to the Index channel interrupt handler function + * + */ + void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr); + + // Encoder interrupt callback functions + /** A channel callback function */ + void handleA(); + /** B channel callback function */ + void handleB(); + /** Index channel callback function */ + void handleIndex(); + + + // pins A and B + int pinA; //!< encoder hardware pin A + int pinB; //!< encoder hardware pin B + int index_pin; //!< index pin + + // Encoder configuration + Pullup pullup; //!< Configuration parameter internal or external pullups + Quadrature quadrature;//!< Configuration parameter enable or disable quadrature mode + float cpr;//!< encoder cpr number + + // Abstract functions of the Sensor class implementation + /** get current angle (rad) */ + float getAngle(); + /** get current angular velocity (rad/s) */ + float getVelocity(); + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + float initRelativeZero(); + /** + * set index angle as zero angle + * return the angle [rad] difference + */ + float initAbsoluteZero(); + /** + * returns 0 if it has no index + * 0 - encoder without index + * 1 - encoder with index + */ + int hasAbsoluteZero(); + /** + * returns 0 if it does need search for absolute zero + * 0 - encoder without index + * 1 - ecoder with index + */ + int needsAbsoluteZeroSearch(); + + private: + int hasIndex(); //!< function returning 1 if encoder has index pin and 0 if not. + + volatile long pulse_counter;//!< current pulse counter + volatile long pulse_timestamp;//!< last impulse timestamp in us + volatile int A_active; //!< current active states of A channel + volatile int B_active; //!< current active states of B channel + volatile int I_active; //!< current active states of Index channel + volatile long index_pulse_counter; //!< impulse counter number upon first index interrupt + + // velocity calculation variables + float prev_Th, pulse_per_second; + volatile long prev_pulse_counter, prev_timestamp_us; +}; + + +#endif diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/StepperMotor.cpp b/minimal_project_examples/arduino_foc_minimal_encoder/src/StepperMotor.cpp new file mode 100644 index 00000000..fca6b1b1 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_encoder/src/StepperMotor.cpp @@ -0,0 +1,305 @@ +#include "StepperMotor.h" + +// StepperMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - ph1A, ph1B - motor phase 1 pwm pins +// - ph2A, ph2B - motor phase 2 pwm pins +// - pp - pole pair number +// - enable pin - (optional input) +StepperMotor::StepperMotor(int ph1A, int ph1B, int ph2A, int ph2B, int pp, int en1, int en2) +: FOCMotor() +{ + // Pin initialization + pwm1A = ph1A; + pwm1B = ph1B; + pwm2A = ph2A; + pwm2B = ph2B; + pole_pairs = pp; + + // enable_pin pin + enable_pin1 = en1; + enable_pin2 = en2; +} + +// init hardware pins +void StepperMotor::init() { + if(monitor_port) monitor_port->println("MOT: Init pins."); + // PWM pins + pinMode(pwm1A, OUTPUT); + pinMode(pwm1B, OUTPUT); + pinMode(pwm2A, OUTPUT); + pinMode(pwm2B, OUTPUT); + if ( enable_pin1 != NOT_SET ) pinMode(enable_pin1, OUTPUT); + if ( enable_pin2 != NOT_SET ) pinMode(enable_pin2, OUTPUT); + + if(monitor_port) monitor_port->println("MOT: PWM config."); + // Increase PWM frequency + // make silent + _setPwmFrequency(pwm1A, pwm1B, pwm2A, pwm2B); + + // sanity check for the voltage limit configuration + if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + + _delay(500); + // enable motor + if(monitor_port) monitor_port->println("MOT: Enable."); + enable(); + _delay(500); + +} + + +// disable motor driver +void StepperMotor::disable() +{ + // disable the driver - if enable_pin pin available + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, LOW); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, LOW); + // set zero to PWM + setPwm(0, 0); +} +// enable motor driver +void StepperMotor::enable() +{ + // set zero to PWM + setPwm(0, 0); + // enable_pin the driver - if enable_pin pin available + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, HIGH); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, HIGH); + +} + + +/** + FOC functions +*/ +// FOC initialization function +int StepperMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } + if(monitor_port) monitor_port->println("MOT: Motor ready."); + + return exit_flag; +} +// Encoder alignment to electrical 0 angle +int StepperMotor::alignSensor() { + if(monitor_port) monitor_port->println("MOT: Align sensor."); + // align the electrical phases of the motor and sensor + // set angle -90 degrees + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } + + // let the motor stabilize for 2 sec + _delay(2000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0,0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int StepperMotor::absoluteZeroAlign() { + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); + + // align absolute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = _normalizeAngle(_electricalAngle(zero_offset, pole_pairs)); + } + // return bool if zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void StepperMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); +} + +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function +// - if target is not set it uses motor.target value +void StepperMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; + // get angular velocity + shaft_velocity = shaftVelocity(); + // choose control loop + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = P_angle( shaft_angle_sp - shaft_angle ); + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // include velocity loop + shaft_velocity_sp = target; + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); + break; + } +} + + +// Method using FOC to set Uq to the motor at the optimal angle +// Function implementingSine PWM algorithms +// - space vector not implemented yet +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) +void StepperMotor::setPhaseVoltage(float Uq, float angle_el) { + // Sinusoidal PWM modulation + // Inverse Park transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + // set the voltages in hardware + setPwm(Ualpha,Ubeta); +} + + + +// Set voltage to the pwm pin +void StepperMotor::setPwm(float Ualpha, float Ubeta) { + float duty_cycle1A(0.0),duty_cycle1B(0.0),duty_cycle2A(0.0),duty_cycle2B(0.0); + // hardware specific writing + if( Ualpha > 0 ) + duty_cycle1B = constrain(abs(Ualpha)/voltage_power_supply,0,1); + else + duty_cycle1A = constrain(abs(Ualpha)/voltage_power_supply,0,1); + + if( Ubeta > 0 ) + duty_cycle2B = constrain(abs(Ubeta)/voltage_power_supply,0,1); + else + duty_cycle2A = constrain(abs(Ubeta)/voltage_power_supply,0,1); + // write to hardware + _writeDutyCycle(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, pwm1A, pwm1B, pwm2A, pwm2B); +} + +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void StepperMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle,pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void StepperMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle,pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/StepperMotor.h b/minimal_project_examples/arduino_foc_minimal_encoder/src/StepperMotor.h new file mode 100644 index 00000000..8f10311f --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_encoder/src/StepperMotor.h @@ -0,0 +1,122 @@ +/** + * @file StepperMotor.h + * + */ + +#ifndef StepperMotor_h +#define StepperMotor_h + +#include "Arduino.h" +#include "common/FOCMotor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" +#include "common/defaults.h" + +/** + Stepper Motor class +*/ +class StepperMotor: public FOCMotor +{ + public: + /** + StepperMotor class constructor + @param ph1A 1A phase pwm pin + @param ph1B 1B phase pwm pin + @param ph2A 2A phase pwm pin + @param ph2B 2B phase pwm pin + @param pp pole pair number - cpr counts per rotation number (cpm=ppm*4) + @param en1 enable pin phase 1 (optional input) + @param en2 enable pin phase 2 (optional input) + */ + StepperMotor(int ph1A,int ph1B,int ph2A,int ph2B,int pp, int en1 = NOT_SET, int en2 = NOT_SET); + + /** Motor hardware init function */ + void init(); + /** Motor disable function */ + void disable(); + /** Motor enable function */ + void enable(); + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + void loopFOC(); + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET); + + // hardware variables + int pwm1A; //!< phase 1A pwm pin number + int pwm1B; //!< phase 1B pwm pin number + int pwm2A; //!< phase 2A pwm pin number + int pwm2B; //!< phase 2B pwm pin number + int enable_pin1; //!< enable pin number phase 1 + int enable_pin2; //!< enable pin number phase 2 + + private: + + // FOC methods + /** + * Method using FOC to set Uq to the motor at the optimal angle + * Heart of the FOC algorithm + * + * @param Uq Current voltage in q axis to set to the motor + * @param angle_el current electrical angle of the motor + */ + void setPhaseVoltage(float Uq, float angle_el); + + /** Sensor alignment to electrical 0 angle of the motor */ + int alignSensor(); + /** Motor and sensor alignment to the sensors absolute 0 angle */ + int absoluteZeroAlign(); + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + * @param Uc phase C voltage + */ + void setPwm(float Ualpha, float Ubeta); + + // Open loop motion control + /** + * Function (iterative) generating open loop movement for target velocity + * it uses voltage_limit variable + * + * @param target_velocity - rad/s + */ + void velocityOpenloop(float target_velocity); + /** + * Function (iterative) generating open loop movement towards the target angle + * it uses voltage_limit and velocity_limit variables + * + * @param target_angle - rad + */ + void angleOpenloop(float target_angle); + // open loop variables + long open_loop_timestamp; +}; + + +#endif diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/FOCMotor.cpp b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/FOCMotor.cpp new file mode 100644 index 00000000..adecbeec --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/FOCMotor.cpp @@ -0,0 +1,245 @@ +#include "FOCMotor.h" + +/** + * Default constructor - setting all variabels to default values + */ +FOCMotor::FOCMotor() +{ + // Power supply voltage + voltage_power_supply = DEF_POWER_SUPPLY; + + // maximum angular velocity to be used for positioning + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = voltage_power_supply; + + // index search velocity + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; + + // electric angle of comthe zero angle + zero_electric_angle = 0; + + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + + // default target value + target = 0; + + //monitor_port + monitor_port = nullptr; + //sensor + sensor = nullptr; +} + + +/** + Sensor communication methods +*/ +void FOCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} +// shaft angle calculation +float FOCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return shaft_angle; + return sensor->getAngle(); +} +// shaft velocity calculation +float FOCMotor::shaftVelocity() { + // if no sensor linked return 0 + if(!sensor) return 0; + return LPF_velocity(sensor->getVelocity()); +} + + + + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void FOCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void FOCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity_openloop: + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle_openloop: + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int FOCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'D': // velocity D gain change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PID velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P angle| "); + break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + } + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("P: "); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("I: "); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); + break; + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("volt_ramp: "); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET) { + voltage_limit = value; + PID_velocity.limit = value; + } + if(monitor_port) monitor_port->println(voltage_limit); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("Tf: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("vel_limit: "); + if(!GET){ + velocity_limit = value; + P_angle.limit = value; + } + if(monitor_port) monitor_port->println(velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Control: "); + + if(GET){ // if get command + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + default: + if(monitor_port) monitor_port->println("open loop"); + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/BLDCMotor.h b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/FOCMotor.h similarity index 56% rename from minimal_project_examples/arduino_foc_minimal_encoder/BLDCMotor.h rename to minimal_project_examples/arduino_foc_minimal_encoder/src/common/FOCMotor.h index 95ca9472..11d566d4 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder/BLDCMotor.h +++ b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/FOCMotor.h @@ -1,18 +1,15 @@ -/** - * @file BLDCMotor.h - * - */ - -#ifndef BLDCMotor_h -#define BLDCMotor_h +#ifndef FOCMOTOR_H +#define FOCMOTOR_H #include "Arduino.h" -#include "FOCutils.h" -#include "Sensor.h" +#include "hardware_utils.h" +#include "foc_utils.h" #include "defaults.h" +#include "Sensor.h" +#include "pid.h" +#include "lowpass_filter.h" -#define NOT_SET -12345.0 /** * Motiron control type @@ -34,60 +31,22 @@ enum FOCModulationType{ }; /** - * PID controller structure - */ -struct PID_s{ - float P; //!< Proportional gain - float I; //!< Integral gain - float D; //!< Derivative gain - long timestamp; //!< Last execution timestamp - float integral_prev; //!< last integral component value - float output_prev; //!< last pid output value - float output_ramp; //!< Maximum speed of change of the output value - float tracking_error_prev; //!< last tracking error value -}; - -// P controller structure -struct P_s{ - float P; //!< Proportional gain - long timestamp; //!< Last execution timestamp -}; - -/** - * Low pass filter structure - */ -struct LPF_s{ - float Tf; //!< Low pass filter time constant - long timestamp; //!< Last execution timestamp - float prev; //!< filtered value in previous execution step -}; - - - - -/** - BLDC motor class + Generic motor class */ -class BLDCMotor +class FOCMotor { public: /** - BLDCMotor class constructor - @param phA A phase pwm pin - @param phB B phase pwm pin - @param phC C phase pwm pin - @param pp pole pair number - @param cpr counts per rotation number (cpm=ppm*4) - @param en enable pin (optional input) - */ - BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); - + * Default constructor - setting all variabels to default values + */ + FOCMotor(); + /** Motor hardware init function */ - void init(); + virtual void init()=0; /** Motor disable function */ - void disable(); + virtual void disable()=0; /** Motor enable function */ - void enable(); + virtual void enable()=0; /** * Function linking a motor and a sensor @@ -106,14 +65,14 @@ class BLDCMotor * @param sensor_direction sensor natural direction - default is CW * */ - int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); + virtual int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW)=0; /** * Function running FOC algorithm in real-time * it calculates the gets motor angle and sets the appropriate voltages * to the phase pwm signals * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us */ - void loopFOC(); + virtual void loopFOC()=0; /** * Function executing the control loops set by the controller parameter of the BLDCMotor. * @@ -122,16 +81,7 @@ class BLDCMotor * * This function doesn't need to be run upon each loop execution - depends of the use case */ - void move(float target = NOT_SET); - - // hardware variables - int pwmA; //!< phase A pwm pin number - int pwmB; //!< phase B pwm pin number - int pwmC; //!< phase C pwm pin number - int enable_pin; //!< enable pin number - - - + virtual void move(float target = NOT_SET)=0; // State calculation methods /** Shaft angle calculation in radians [rad] */ @@ -150,6 +100,7 @@ class BLDCMotor float shaft_angle_sp;//!< current target angle float voltage_q;//!< current voltage u_q set float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform // motor configuration parameters float voltage_power_supply;//!< Power supply voltage @@ -161,34 +112,15 @@ class BLDCMotor float voltage_limit; //!< Voltage limitting variable - global limit float velocity_limit; //!< Velocity limitting variable - global limit + float zero_electric_angle;//! _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} + + +// normalizing radian angle to [0,2PI] +float _normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} + +// Electrical angle calculation +float _electricalAngle(float shaft_angle, int pole_pairs) { + return (shaft_angle * pole_pairs); +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/foc_utils.h b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/foc_utils.h new file mode 100644 index 00000000..5ab34f42 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/foc_utils.h @@ -0,0 +1,55 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + +// sign function +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + +// utility defines +#define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI 3.14159265359 +#define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + + +#define NOT_SET -12345.0 + +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _sin(float a); +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _cos(float a); + +/** + * normalizing radian angle to [0,2PI] + * @param angle - angle to be normalized + */ +float _normalizeAngle(float angle); + + +/** + * Electrical angle calculation + * + * @param shaft_angle - shaft angle of the motor + * @param pole_pairs - number of pole pairs + */ +float _electricalAngle(float shaft_angle, int pole_pairs); +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/FOCutils.cpp b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/hardware_utils.cpp similarity index 69% rename from minimal_project_examples/arduino_foc_minimal_encoder/FOCutils.cpp rename to minimal_project_examples/arduino_foc_minimal_encoder/src/common/hardware_utils.cpp index 653c7191..802087a7 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder/FOCutils.cpp +++ b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/hardware_utils.cpp @@ -1,4 +1,4 @@ -#include "FOCutils.h" +#include "hardware_utils.h" #if defined(ESP_H) // if ESP32 board // empty motor slot @@ -31,27 +31,45 @@ motor_slots_t esp32_motor_slots[4] = { // function setting the high pwm frequency to the supplied pins // - hardware speciffic // supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(const int pinA, const int pinB, const int pinC) { +void _setPwmFrequency(const int pinA, const int pinB, const int pinC, const int pinD) { #if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips - // High PWM frequency + // High PWM frequency // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pinA == 5 || pinA == 6 || pinB == 5 || pinB == 6 || pinC == 5 || pinC == 6 ) { + if (pinA == 5 || pinA == 6 || pinB == 5 || pinB == 6 || pinC == 5 || pinC == 6 || pinD == 5 || pinD == 6 ) { TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 } - if (pinA == 9 || pinA == 10 || pinB == 9 || pinB == 10 || pinC == 9 || pinC == 10 ) + if (pinA == 9 || pinA == 10 || pinB == 9 || pinB == 10 || pinC == 9 || pinC == 10|| pinD == 9 || pinD == 10 ) TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pinA == 3 || pinA == 11 || pinB == 3 || pinB == 11 || pinC == 3 || pinC == 11 ) + if (pinA == 3 || pinA == 11 || pinB == 3 || pinB == 11 || pinC == 3 || pinC == 11 || pinD == 3 || pinD == 11 ) TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 #elif defined(_STM32_DEF_) // if stm chips analogWrite(pinA, 0); analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 analogWrite(pinB, 0); analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 analogWrite(pinC, 0); analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 + if(pinD) { + analogWrite(pinD, 0); + analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 + +#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards + analogWrite(pinA, 0); + analogWriteFrequency(pinA, 50000); // set 50kHz + analogWrite(pinB, 0); + analogWriteFrequency(pinB, 50000); // set 50kHz + analogWrite(pinC, 0); + analogWriteFrequency(pinC, 50000); // set 50kHz + if(pinD) { + analogWrite(pinD, 0); + analogWriteFrequency(50000); // set 50kHz #elif defined(ESP_H) // if esp32 boards @@ -133,7 +151,12 @@ void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, in break; } } -#else // Arduino & STM32 devices +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pinA, 4095.0*dc_a); + analogWrite(pinB, 4095.0*dc_b); + analogWrite(pinC, 4095.0*dc_c); +#else // Arduino & Teensy // transform duty cycle from [0,1] to [0,255] analogWrite(pinA, 255*dc_a); analogWrite(pinB, 255*dc_b); @@ -141,6 +164,29 @@ void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, in #endif } +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ +#if defined(ESP_H) // if ESP32 boards + // not sure how to handle this +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pin1A, 4095.0*dc_1a); + analogWrite(pin1B, 4095.0*dc_1b); + analogWrite(pin2A, 4095.0*dc_2a); + analogWrite(pin2B, 4095.0*dc_2b); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255*dc_1a); + analogWrite(pin1B, 255*dc_1b); + analogWrite(pin2A, 255*dc_2a); + analogWrite(pin2B, 255*dc_2b); +#endif +} + // function buffering delay() // arduino uno function doesn't work well with interrupts @@ -170,46 +216,4 @@ unsigned long _micros(){ // regular micros return micros(); #endif -} - - -// int array instead of float array -// 2x storage save (int 2Byte float 4 Byte ) -// sin*10000 -int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,1103,1181,1260,1338,1416,1494,1572,1650,1728,1806,1883,1961,2038,2115,2192,2269,2346,2423,2499,2575,2652,2728,2804,2879,2955,3030,3105,3180,3255,3329,3404,3478,3552,3625,3699,3772,3845,3918,3990,4063,4135,4206,4278,4349,4420,4491,4561,4631,4701,4770,4840,4909,4977,5046,5113,5181,5249,5316,5382,5449,5515,5580,5646,5711,5775,5839,5903,5967,6030,6093,6155,6217,6279,6340,6401,6461,6521,6581,6640,6699,6758,6815,6873,6930,6987,7043,7099,7154,7209,7264,7318,7371,7424,7477,7529,7581,7632,7683,7733,7783,7832,7881,7930,7977,8025,8072,8118,8164,8209,8254,8298,8342,8385,8428,8470,8512,8553,8594,8634,8673,8712,8751,8789,8826,8863,8899,8935,8970,9005,9039,9072,9105,9138,9169,9201,9231,9261,9291,9320,9348,9376,9403,9429,9455,9481,9506,9530,9554,9577,9599,9621,9642,9663,9683,9702,9721,9739,9757,9774,9790,9806,9821,9836,9850,9863,9876,9888,9899,9910,9920,9930,9939,9947,9955,9962,9969,9975,9980,9985,9989,9992,9995,9997,9999,10000,10000}; - -// function approximating the sine calculation by using fixed size array -// ~40us (float array) -// ~50us (int array) -// precision +-0.005 -// it has to receive an angle in between 0 and 2PI -float _sin(float a){ - if(a < _PI_2){ - //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; - //return sine_array[(int)(126.6873* a)]; // float array optimized - return 0.0001*sine_array[_round(126.6873* a)]; // int array optimized - }else if(a < _PI){ - // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; - //return sine_array[398 - (int)(126.6873*a)]; // float array optimized - return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimized - }else if(a < _3PI_2){ - // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; - //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimized - return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimized - } else { - // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; - //return -sine_array[796 - (int)(126.6873*a)]; // float array optimized - return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimized - } -} - -// function approximating cosine calculation by using fixed size array -// ~55us (float array) -// ~56us (int array) -// precision +-0.005 -// it has to receive an angle in between 0 and 2PI -float _cos(float a){ - float a_sin = a + _PI_2; - a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin; - return _sin(a_sin); -} +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/FOCutils.h b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/hardware_utils.h similarity index 54% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/FOCutils.h rename to minimal_project_examples/arduino_foc_minimal_encoder/src/common/hardware_utils.h index 4c347a12..03c44fdd 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/FOCutils.h +++ b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/hardware_utils.h @@ -1,7 +1,8 @@ -#ifndef FOCUTILS_LIB_H -#define FOCUTILS_LIB_H +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H #include "Arduino.h" +#include "foc_utils.h" #if defined(ESP_H) // if esp32 boards @@ -12,23 +13,6 @@ #endif -// sign function -#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) -#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) - -// utility defines -#define _2_SQRT3 1.15470053838 -#define _SQRT3 1.73205080757 -#define _1_SQRT3 0.57735026919 -#define _SQRT3_2 0.86602540378 -#define _SQRT2 1.41421356237 -#define _120_D2R 2.09439510239 -#define _PI 3.14159265359 -#define _PI_2 1.57079632679 -#define _PI_3 1.0471975512 -#define _2PI 6.28318530718 -#define _3PI_2 4.71238898038 - /** * High PWM frequency setting function * - hardware specific @@ -36,23 +20,9 @@ * @param pinA pinA number to configure * @param pinB pinB number to configure * @param pinC pinC number to configure + * @param pinD pinC number to configure */ -void _setPwmFrequency(int pinA, int pinB, int pinC); - -/** - * Function implementing delay() function in milliseconds - * - blocking function - * - hardware specific - - * @param ms number of milliseconds to wait - */ -void _delay(unsigned long ms); - -/** - * Function implementing timestamp getting function in microseconds - * hardware specific - */ -unsigned long _micros(); +void _setPwmFrequency(int pinA, int pinB, int pinC, int pinD = 0); /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) @@ -67,20 +37,35 @@ unsigned long _micros(); */ void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); - -/** - * Function approximating the sine calculation by using fixed size array - * - execution time ~40us (Arduino UNO) +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific * - * @param a angle in between 0 and 2PI + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait */ -float _sin(float a); -/** - * Function approximating cosine calculation by using fixed size array - * - execution time ~50us (Arduino UNO) - * - * @param a angle in between 0 and 2PI +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific */ -float _cos(float a); +unsigned long _micros(); + #endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/lowpass_filter.cpp b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/lowpass_filter.cpp new file mode 100644 index 00000000..9bf4ab7a --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/lowpass_filter.cpp @@ -0,0 +1,25 @@ +#include "lowpass_filter.h" + +LowPassFilter::LowPassFilter(float time_constant) + : Tf(time_constant) + , y_prev(0.0f) +{ + timestamp_prev = _micros(); +} + + +float LowPassFilter::operator() (float x) +{ + unsigned long timestamp = _micros(); + float dt = (timestamp - timestamp_prev)*1e-6f; + + if (dt < 0.0f || dt > 0.5f) + dt = 1e-3f; + + float alpha = Tf/(Tf + dt); + float y = alpha*y_prev + (1.0f - alpha)*x; + + y_prev = y; + timestamp_prev = timestamp; + return y; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/lowpass_filter.h b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/lowpass_filter.h new file mode 100644 index 00000000..5a7619cf --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/lowpass_filter.h @@ -0,0 +1,29 @@ +#ifndef LOWPASS_FILTER_H +#define LOWPASS_FILTER_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + + +/** + * Low pass filter class + */ +class LowPassFilter +{ +public: + /** + * @param Tf - Low pass filter time constant + */ + LowPassFilter(float Tf); + ~LowPassFilter() = default; + + float operator() (float x); + float Tf; //!< Low pass filter time constant + +protected: + unsigned long timestamp_prev; //!< Last execution timestamp + float y_prev; //!< filtered value in previous execution step +}; + +#endif // LOWPASS_FILTER_H \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/pid.cpp b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/pid.cpp new file mode 100644 index 00000000..277e17ce --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/pid.cpp @@ -0,0 +1,56 @@ +#include "pid.h" + +PIDController::PIDController(float P, float I, float D, float ramp, float limit) + : P(P) + , I(I) + , D(D) + , output_ramp(ramp) // output derivative limit [volts/second] + , limit(limit) // output supply limit [volts] + , integral_prev(0.0) + , error_prev(0.0) + , output_prev(0.0) +{ + timestamp_prev = _micros()*1e-6; +} + +// PID controller function +float PIDController::operator() (float error){ + // calculate the time from the last call + unsigned long timestamp_now = _micros(); + float Ts = (timestamp_now - timestamp_prev) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = P * error_prev; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = integral_prev + I*Ts*0.5*(error + error_prev); + // antiwindup - limit the output voltage_q + integral = constrain(integral, -limit, limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = D*(error - error_prev)/Ts; + + // sum all the components + float output = proportional + integral + derivative; + // antiwindup - limit the output variable + output = constrain(output, -limit, limit); + + // limit the acceleration by ramping the output + float output_rate = (output - output_prev)/Ts; + if (output_rate > output_ramp) + output = output_prev + output_ramp*Ts; + else if (output_rate < -output_ramp) + output = output_prev - output_ramp*Ts; + + // saving for the next pass + integral_prev = integral; + output_prev = output; + error_prev = error; + timestamp_prev = timestamp_now; + return output; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/pid.h b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/pid.h new file mode 100644 index 00000000..7ee337c4 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/pid.h @@ -0,0 +1,40 @@ +#ifndef PID_H +#define PID_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + +/** + * PID controller class + */ +class PIDController +{ +public: + /** + * + * @param P - Proportional gain + * @param I - Integral gain + * @param D - Derivative gain + * @param ramp - Maximum speed of change of the output value + * @param limit - Maximum output value + */ + PIDController(float P, float I, float D, float ramp, float limit); + ~PIDController() = default; + + float operator() (float error); + + float P; //!< Proportional gain + float I; //!< Integral gain + float D; //!< Derivative gain + float output_ramp; //!< Maximum speed of change of the output value + float limit; //!< Maximum output value + +protected: + float integral_prev; //!< last integral component value + float error_prev; //!< last tracking error value + float timestamp_prev; //!< Last execution timestamp + float output_prev; //!< last pid output value +}; + +#endif // PID_H \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_encoder1/arduino_foc_minimal_encoder.ino b/minimal_project_examples/arduino_foc_minimal_encoder1/arduino_foc_minimal_encoder.ino new file mode 100644 index 00000000..49c35cbf --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_encoder1/arduino_foc_minimal_encoder.ino @@ -0,0 +1,143 @@ +/** + * Comprehensive BLDC motor control example using encoder + * + * Using serial terminal user can send motor commands and configure the motor and FOC in real-time: + * - configure PID controller constants + * - change motion control loops + * - monitor motor variabels + * - set target values + * - check all the configuration values + * + * To check the config value just enter the command letter. + * For example: - to read velocity PI controller P gain run: P + * - to set velocity PI controller P gain to 1.2 run: P1.2 + * + * To change the target value just enter a number in the terminal: + * For example: - to change the target value to -0.1453 enter: -0.1453 + * - to get the current target value enter: V3 + * + * List of commands: + * - P: velocity PID controller P gain + * - I: velocity PID controller I gain + * - D: velocity PID controller D gain + * - R: velocity PID controller voltage ramp + * - F: velocity Low pass filter time constant + * - K: angle P controller P gain + * - N: angle P controller velocity limit + * - L: system voltage limit + * - C: control loop + * - 0: voltage + * - 1: velocity + * - 2: angle + * - V: get motor variables + * - 0: currently set voltage + * - 1: current velocity + * - 2: current angle + * - 3: current target value + * + */ +#include "src/StepperMotor.h" +#include "src/Encoder.h" + +// motor instance +StepperMotor motor = StepperMotor(10, 6, 5, 9, 50, 8); +// +// encoder instance +Encoder encoder = Encoder(2,3, 2048); + +// Interrupt routine intialisation +// channel A and B callbacks +void doA(){encoder.handleA();} +void doB(){encoder.handleB();} + +void setup() { + + // initialize encoder sensor hardware + encoder.init(); + encoder.enableInterrupts(doA, doB); + // link the motor to the sensor + motor.linkSensor(&encoder); + + // power supply voltage [V] + motor.voltage_power_supply = 12; + motor.voltage_sensor_align = 10; + + // set control loop type to be used + motor.controller = ControlType::velocity; + + // contoller configuration based on the controll type + motor.PID_velocity.P = 0.2; + motor.PID_velocity.I = 20; + motor.PID_velocity.D = 0; + // default voltage_power_supply + motor.voltage_limit = 12; + + // velocity low pass filtering time constant + motor.LPF_velocity.Tf = 0.01; + + // angle loop controller + motor.P_angle.P = 20; + // angle loop velocity limit + motor.velocity_limit = 50; + + // use monitoring with serial for motor init + // monitoring port + Serial.begin(115200); + // comment out if not needed + motor.useMonitoring(Serial); + + // initialise motor + motor.init(); + // align encoder and start FOC + motor.initFOC(); + + // set the inital target value + motor.target = 2; + + + // Run user commands to configure and the motor (find the full command list in docs.simplefoc.com) + Serial.println("Motor commands sketch | Initial motion control > torque/voltage : target 2V."); + + _delay(1000); +} + + +void loop() { + // iterative setting FOC phase voltage + motor.loopFOC(); + + // iterative function setting the outter loop target + // velocity, position or voltage + // if tatget not set in parameter uses motor.target variable + motor.move(); + + // user communication + motor.command(serialReceiveUserCommand()); +} + +// utility function enabling serial communication the user +String serialReceiveUserCommand() { + + // a string to hold incoming data + static String received_chars; + + String command = ""; + + while (Serial.available()) { + // get the new byte: + char inChar = (char)Serial.read(); + // add it to the string buffer: + received_chars += inChar; + + // end of user input + if (inChar == '\n') { + + // execute the user command + command = received_chars; + + // reset the command buffer + received_chars = ""; + } + } + return command; +} diff --git a/minimal_project_examples/arduino_foc_minimal_encoder1/src/Encoder.cpp b/minimal_project_examples/arduino_foc_minimal_encoder1/src/Encoder.cpp new file mode 100644 index 00000000..f5ab90cb --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_encoder1/src/Encoder.cpp @@ -0,0 +1,228 @@ +#include "Encoder.h" + + +/* + Encoder(int encA, int encB , int cpr, int index) + - encA, encB - encoder A and B pins + - cpr - counts per rotation number (cpm=ppm*4) + - index pin - (optional input) +*/ + +Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ + + // Encoder measurement structure init + // hardware pins + pinA = _encA; + pinB = _encB; + // counter setup + pulse_counter = 0; + pulse_timestamp = 0; + + cpr = _ppr; + A_active = 0; + B_active = 0; + I_active = 0; + // index pin + index_pin = _index; // its 0 if not used + index_pulse_counter = 0; + + // velocity calculation variables + prev_Th = 0; + pulse_per_second = 0; + prev_pulse_counter = 0; + prev_timestamp_us = _micros(); + + // extern pullup as default + pullup = Pullup::EXTERN; + // enable quadrature encoder by default + quadrature = Quadrature::ON; +} + +// Encoder interrupt callback functions +// A channel +void Encoder::handleA() { + int A = digitalRead(pinA); + switch (quadrature){ + case Quadrature::ON: + // CPR = 4xPPR + if ( A != A_active ) { + pulse_counter += (A_active == B_active) ? 1 : -1; + pulse_timestamp = _micros(); + A_active = A; + } + break; + case Quadrature::OFF: + // CPR = PPR + if(A && !digitalRead(pinB)){ + pulse_counter++; + pulse_timestamp = _micros(); + } + break; + } +} +// B channel +void Encoder::handleB() { + int B = digitalRead(pinB); + switch (quadrature){ + case Quadrature::ON: + // // CPR = 4xPPR + if ( B != B_active ) { + pulse_counter += (A_active != B_active) ? 1 : -1; + pulse_timestamp = _micros(); + B_active = B; + } + break; + case Quadrature::OFF: + // CPR = PPR + if(B && !digitalRead(pinA)){ + pulse_counter--; + pulse_timestamp = _micros(); + } + break; + } +} + +// Index channel +void Encoder::handleIndex() { + if(hasIndex()){ + int I = digitalRead(index_pin); + if(I && !I_active){ + // align encoder on each index + if(index_pulse_counter){ + long tmp = pulse_counter; + // corrent the counter value + pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; + // preserve relative speed + prev_pulse_counter += pulse_counter - tmp; + } else { + // initial offset + index_pulse_counter = pulse_counter; + } + } + I_active = I; + } +} + +/* + Shaft angle calculation +*/ +float Encoder::getAngle(){ + return natural_direction * _2PI * (pulse_counter) / ((float)cpr); +} +/* + Shaft velocity calculation + function using mixed time and frequency measurement technique +*/ +float Encoder::getVelocity(){ + // timestamp + long timestamp_us = _micros(); + // sampling time calculation + float Ts = (timestamp_us - prev_timestamp_us) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // time from last impulse + float Th = (timestamp_us - pulse_timestamp) * 1e-6; + long dN = pulse_counter - prev_pulse_counter; + + // Pulse per second calculation (Eq.3.) + // dN - impulses received + // Ts - sampling time - time in between function calls + // Th - time from last impulse + // Th_1 - time form last impulse of the previous call + // only increment if some impulses received + float dt = Ts + prev_Th - Th; + pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second; + + // if more than 0.05 passed in between impulses + if ( Th > 0.1) pulse_per_second = 0; + + // velocity calculation + float velocity = pulse_per_second / ((float)cpr) * (_2PI); + + // save variables for next pass + prev_timestamp_us = timestamp_us; + // save velocity calculation variables + prev_Th = Th; + prev_pulse_counter = pulse_counter; + return natural_direction * (velocity); +} + +// getter for index pin +// return -1 if no index +int Encoder::needsAbsoluteZeroSearch(){ + return index_pulse_counter == 0; +} +// getter for index pin +int Encoder::hasAbsoluteZero(){ + return hasIndex(); +} +// initialize counter to zero +float Encoder::initRelativeZero(){ + long angle_offset = -pulse_counter; + pulse_counter = 0; + pulse_timestamp = _micros(); + return _2PI * (angle_offset) / ((float)cpr); +} +// initialize index to zero +float Encoder::initAbsoluteZero(){ + pulse_counter -= index_pulse_counter; + prev_pulse_counter = pulse_counter; + return (index_pulse_counter) / ((float)cpr) * (_2PI); +} +// private function used to determine if encoder has index +int Encoder::hasIndex(){ + return index_pin != 0; +} + + +// encoder initialisation of the hardware pins +// and calculation variables +void Encoder::init(){ + + // Encoder - check if pullup needed for your encoder + if(pullup == Pullup::INTERN){ + pinMode(pinA, INPUT_PULLUP); + pinMode(pinB, INPUT_PULLUP); + if(hasIndex()) pinMode(index_pin,INPUT_PULLUP); + }else{ + pinMode(pinA, INPUT); + pinMode(pinB, INPUT); + if(hasIndex()) pinMode(index_pin,INPUT); + } + + // counter setup + pulse_counter = 0; + pulse_timestamp = _micros(); + // velocity calculation variables + prev_Th = 0; + pulse_per_second = 0; + prev_pulse_counter = 0; + prev_timestamp_us = _micros(); + + // initial cpr = PPR + // change it if the mode is quadrature + if(quadrature == Quadrature::ON) cpr = 4*cpr; + +} + +// function enabling hardware interrupts of the for the callback provided +// if callback is not provided then the interrupt is not enabled +void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){ + // attach interrupt if functions provided + switch(quadrature){ + case Quadrature::ON: + // A callback and B callback + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); + break; + case Quadrature::OFF: + // A callback and B callback + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); + break; + } + + // if index used initialize the index interrupt + if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE); +} diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/Encoder.h b/minimal_project_examples/arduino_foc_minimal_encoder1/src/Encoder.h similarity index 98% rename from minimal_project_examples/arduino_foc_minimal_encoder/Encoder.h rename to minimal_project_examples/arduino_foc_minimal_encoder1/src/Encoder.h index 19aafc94..347cb261 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder/Encoder.h +++ b/minimal_project_examples/arduino_foc_minimal_encoder1/src/Encoder.h @@ -2,8 +2,8 @@ #define ENCODER_LIB_H #include "Arduino.h" -#include "FOCutils.h" -#include "Sensor.h" +#include "common/FOCutils.h" +#include "common/Sensor.h" /** diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_minimal_encoder1/src/StepperMotor.cpp similarity index 78% rename from minimal_project_examples/arduino_foc_minimal_encoder/BLDCMotor.cpp rename to minimal_project_examples/arduino_foc_minimal_encoder1/src/StepperMotor.cpp index f31e818a..5cc6ce17 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder/BLDCMotor.cpp +++ b/minimal_project_examples/arduino_foc_minimal_encoder1/src/StepperMotor.cpp @@ -1,20 +1,22 @@ -#include "BLDCMotor.h" +#include "StepperMotor.h" -// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) -// - phA, phB, phC - motor A,B,C phase pwm pins +// StepperMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - ph1A, ph1B - motor phase 1 pwm pins +// - ph2A, ph2B - motor phase 2 pwm pins // - pp - pole pair number -// - cpr - counts per rotation number (cpm=ppm*4) // - enable pin - (optional input) -BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +StepperMotor::StepperMotor(int ph1A, int ph1B, int ph2A, int ph2B, int pp, int en1, int en2) { // Pin initialization - pwmA = phA; - pwmB = phB; - pwmC = phC; + pwm1A = ph1A; + pwm1B = ph1B; + pwm2A = ph2A; + pwm2B = ph2B; pole_pairs = pp; // enable_pin pin - enable_pin = en; + enable_pin1 = en1; + enable_pin2 = en2; // Power supply voltage voltage_power_supply = DEF_POWER_SUPPLY; @@ -65,19 +67,21 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) } // init hardware pins -void BLDCMotor::init() { +void StepperMotor::init() { if(monitor_port) monitor_port->println("MOT: Init pins."); // PWM pins - pinMode(pwmA, OUTPUT); - pinMode(pwmB, OUTPUT); - pinMode(pwmC, OUTPUT); - if(hasEnable()) pinMode(enable_pin, OUTPUT); + pinMode(pwm1A, OUTPUT); + pinMode(pwm1B, OUTPUT); + pinMode(pwm2A, OUTPUT); + pinMode(pwm2B, OUTPUT); + if ( enable_pin1 != NOT_SET ) pinMode(enable_pin1, OUTPUT); + if ( enable_pin2 != NOT_SET ) pinMode(enable_pin2, OUTPUT); if(monitor_port) monitor_port->println("MOT: PWM config."); - // Increase PWM frequency to 32 kHz + // Increase PWM frequency // make silent - _setPwmFrequency(pwmA, pwmB, pwmC); - + _setPwmFrequency(pwm1A, pwm1B, pwm2A, pwm2B); + // sanity check for the voltage limit configuration if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; // constrain voltage for sensor alignment @@ -93,30 +97,32 @@ void BLDCMotor::init() { // disable motor driver -void BLDCMotor::disable() +void StepperMotor::disable() { // disable the driver - if enable_pin pin available - if (hasEnable()) digitalWrite(enable_pin, LOW); + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, LOW); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, LOW); // set zero to PWM - setPwm(0, 0, 0); + setPwm(0, 0); } // enable motor driver -void BLDCMotor::enable() +void StepperMotor::enable() { // set zero to PWM - setPwm(0, 0, 0); + setPwm(0, 0); // enable_pin the driver - if enable_pin pin available - if (hasEnable()) digitalWrite(enable_pin, HIGH); + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, HIGH); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, HIGH); } -void BLDCMotor::linkSensor(Sensor* _sensor) { +void StepperMotor::linkSensor(Sensor* _sensor) { sensor = _sensor; } // Encoder alignment to electrical 0 angle -int BLDCMotor::alignSensor() { +int StepperMotor::alignSensor() { if(monitor_port) monitor_port->println("MOT: Align sensor."); // align the electrical phases of the motor and sensor // set angle -90 degrees @@ -162,7 +168,7 @@ int BLDCMotor::alignSensor() { // Encoder alignment the absolute zero angle // - to the index -int BLDCMotor::absoluteZeroAlign() { +int StepperMotor::absoluteZeroAlign() { if(monitor_port) monitor_port->println("MOT: Absolute zero align."); // if no absolute zero return @@ -194,19 +200,19 @@ int BLDCMotor::absoluteZeroAlign() { State calculation methods */ // shaft angle calculation -float BLDCMotor::shaftAngle() { +float StepperMotor::shaftAngle() { // if no sensor linked return 0 if(!sensor) return 0; return sensor->getAngle(); } // shaft velocity calculation -float BLDCMotor::shaftVelocity() { +float StepperMotor::shaftVelocity() { // if no sensor linked return 0 if(!sensor) return 0; return lowPassFilter(sensor->getVelocity(), LPF_velocity); } // Electrical angle calculation -float BLDCMotor::electricAngle(float shaftAngle) { +float StepperMotor::electricAngle(float shaftAngle) { //return normalizeAngle(shaftAngle * pole_pairs); return (shaftAngle * pole_pairs); } @@ -215,7 +221,7 @@ float BLDCMotor::electricAngle(float shaftAngle) { FOC functions */ // FOC initialization function -int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { +int StepperMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { int exit_flag = 1; // align motor if necessary // alignment necessary for encoders! @@ -237,7 +243,7 @@ int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction // Iterative function looping FOC algorithm, setting Uq on the Motor // The faster it can be run the better -void BLDCMotor::loopFOC() { +void StepperMotor::loopFOC() { // shaft angle shaft_angle = shaftAngle(); // set the phase voltage - FOC heart function :) @@ -249,7 +255,7 @@ void BLDCMotor::loopFOC() { // It runs either angle, velocity or voltage loop // - needs to be called iteratively it is asynchronous function // - if target is not set it uses motor.target value -void BLDCMotor::move(float new_target) { +void StepperMotor::move(float new_target) { // set internal target variable if( new_target != NOT_SET ) target = new_target; // get angular velocity @@ -289,136 +295,64 @@ void BLDCMotor::move(float new_target) { // Method using FOC to set Uq to the motor at the optimal angle -// Function implementing Space Vector PWM and Sine PWM algorithms +// Function implementingSine PWM algorithms +// - space vector not implemented yet // // Function using sine approximation // regular sin + cos ~300us (no memory usaage) // approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { - switch (foc_modulation) - { - case FOCModulationType::SinePWM : - // Sinusoidal PWM modulation - // Inverse Park + Clarke transformation - - // angle normalization in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - angle_el = normalizeAngle(angle_el + zero_electric_angle); - // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; - - // Clarke transform - Ua = Ualpha + voltage_power_supply/2; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; - break; - - case FOCModulationType::SpaceVectorPWM : - // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm - // https://www.youtube.com/watch?v=QMSWUMEAejg - - // if negative voltages change inverse the phase - // angle + 180degrees - if(Uq < 0) angle_el += _PI; - Uq = abs(Uq); - - // angle normalisation in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - angle_el = normalizeAngle(angle_el + zero_electric_angle + _PI_2); - - // find the sector we are in currently - int sector = floor(angle_el / _PI_3) + 1; - // calculate the duty cycles - float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; - float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; - // two versions possible - // centered around voltage_power_supply/2 - float T0 = 1 - T1 - T2; - // pulled to 0 - better for low power supply voltage - //float T0 = 0; - - // calculate the duty cycles(times) - float Ta,Tb,Tc; - switch(sector){ - case 1: - Ta = T1 + T2 + T0/2; - Tb = T2 + T0/2; - Tc = T0/2; - break; - case 2: - Ta = T1 + T0/2; - Tb = T1 + T2 + T0/2; - Tc = T0/2; - break; - case 3: - Ta = T0/2; - Tb = T1 + T2 + T0/2; - Tc = T2 + T0/2; - break; - case 4: - Ta = T0/2; - Tb = T1+ T0/2; - Tc = T1 + T2 + T0/2; - break; - case 5: - Ta = T2 + T0/2; - Tb = T0/2; - Tc = T1 + T2 + T0/2; - break; - case 6: - Ta = T1 + T2 + T0/2; - Tb = T0/2; - Tc = T1 + T0/2; - break; - default: - // possible error state - Ta = 0; - Tb = 0; - Tc = 0; - } - - // calculate the phase voltages and center - Ua = Ta*voltage_power_supply; - Ub = Tb*voltage_power_supply; - Uc = Tc*voltage_power_supply; - break; - } - +void StepperMotor::setPhaseVoltage(float Uq, float angle_el) { + // Sinusoidal PWM modulation + // Inverse Park transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; // set the voltages in hardware - setPwm(Ua, Ub, Uc); + setPwm(Ualpha,Ubeta); } // Set voltage to the pwm pin -void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { - // calculate duty cycle - // limited in [0,1] - float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); - float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); - float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); +void StepperMotor::setPwm(float Ualpha, float Ubeta) { + float duty_cycle1A = 0,duty_cycle1B,duty_cycle2A,duty_cycle2B; // hardware specific writing - _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); + if( Ualpha > 0 ){ + duty_cycle1A = 0; + duty_cycle1B = constrain(abs(Ualpha)/voltage_power_supply,0,1); + } else { + duty_cycle1B = 0; + duty_cycle1A = constrain(abs(Ualpha)/voltage_power_supply,0,1); + } + + if( Ubeta > 0 ){ + duty_cycle2A = 0; + duty_cycle2B = constrain(abs(Ubeta)/voltage_power_supply,0,1); + } else { + duty_cycle2B = 0; + duty_cycle2A = constrain(abs(Ubeta)/voltage_power_supply,0,1); + } + // write to hardware + _writeDutyCycle(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, pwm1A, pwm1B, pwm2A, pwm2B); } /** Utility functions */ // normalizing radian angle to [0,2PI] -float BLDCMotor::normalizeAngle(float angle){ +float StepperMotor::normalizeAngle(float angle){ float a = fmod(angle, _2PI); return a >= 0 ? a : (a + _2PI); } -// determining if the enable pin has been provided -int BLDCMotor::hasEnable(){ - return enable_pin != NOT_SET; -} // low pass filter function // - input -singal to be filtered // - lpf -LPF_s structure with filter parameters -float BLDCMotor::lowPassFilter(float input, LPF_s& lpf){ +float StepperMotor::lowPassFilter(float input, LPF_s& lpf){ unsigned long now_us = _micros(); float Ts = (now_us - lpf.timestamp) * 1e-6; // quick fix for strange cases (micros overflow) @@ -439,7 +373,7 @@ float BLDCMotor::lowPassFilter(float input, LPF_s& lpf){ Motor control functions */ // PID controller function -float BLDCMotor::controllerPID(float tracking_error, PID_s& cont){ +float StepperMotor::controllerPID(float tracking_error, PID_s& cont){ // calculate the time from the last call unsigned long now_us = _micros(); float Ts = (now_us - cont.timestamp) * 1e-6; @@ -477,12 +411,12 @@ float BLDCMotor::controllerPID(float tracking_error, PID_s& cont){ return voltage; } // velocity control loop PI controller -float BLDCMotor::velocityPID(float tracking_error) { +float StepperMotor::velocityPID(float tracking_error) { return controllerPID(tracking_error, PID_velocity); } // P controller for position control loop -float BLDCMotor::positionP(float ek) { +float StepperMotor::positionP(float ek) { // calculate the target velocity from the position error float velocity_target = P_angle.P * ek; // constrain velocity target value @@ -493,7 +427,7 @@ float BLDCMotor::positionP(float ek) { // Function (iterative) generating open loop movement for target velocity // - target_velocity - rad/s // it uses voltage_limit variable -void BLDCMotor::velocityOpenloop(float target_velocity){ +void StepperMotor::velocityOpenloop(float target_velocity){ // get current timestamp unsigned long now_us = _micros(); // calculate the sample time from last call @@ -512,7 +446,7 @@ void BLDCMotor::velocityOpenloop(float target_velocity){ // Function (iterative) generating open loop movement towards the target angle // - target_angle - rad // it uses voltage_limit and velocity_limit variables -void BLDCMotor::angleOpenloop(float target_angle){ +void StepperMotor::angleOpenloop(float target_angle){ // get current timestamp unsigned long now_us = _micros(); // calculate the sample time from last call @@ -536,13 +470,13 @@ void BLDCMotor::angleOpenloop(float target_angle){ * Monitoring functions */ // function implementing the monitor_port setter -void BLDCMotor::useMonitoring(Print &print){ +void StepperMotor::useMonitoring(Print &print){ monitor_port = &print; //operate on the address of print if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); } // utility function intended to be used with serial plotter to monitor motor variables // significantly slowing the execution down!!!! -void BLDCMotor::monitor() { +void StepperMotor::monitor() { if(!monitor_port) return; switch (controller) { case ControlType::velocity_openloop: @@ -571,7 +505,7 @@ void BLDCMotor::monitor() { } } -int BLDCMotor::command(String user_command) { +int StepperMotor::command(String user_command) { // error flag int errorFlag = 1; // if empty string @@ -713,4 +647,4 @@ int BLDCMotor::command(String user_command) { } // return 0 if error and 1 if ok return errorFlag; -} \ No newline at end of file +} diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/BLDCMotor.h b/minimal_project_examples/arduino_foc_minimal_encoder1/src/StepperMotor.h similarity index 90% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/BLDCMotor.h rename to minimal_project_examples/arduino_foc_minimal_encoder1/src/StepperMotor.h index 95ca9472..17e7b36f 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/BLDCMotor.h +++ b/minimal_project_examples/arduino_foc_minimal_encoder1/src/StepperMotor.h @@ -1,15 +1,15 @@ /** - * @file BLDCMotor.h + * @file StepperMotor.h * */ -#ifndef BLDCMotor_h -#define BLDCMotor_h +#ifndef StepperMotor_h +#define StepperMotor_h #include "Arduino.h" -#include "FOCutils.h" -#include "Sensor.h" -#include "defaults.h" +#include "common/FOCutils.h" +#include "common/Sensor.h" +#include "common/defaults.h" #define NOT_SET -12345.0 @@ -66,21 +66,22 @@ struct LPF_s{ /** - BLDC motor class + Stepper Motor class */ -class BLDCMotor +class StepperMotor { public: /** - BLDCMotor class constructor - @param phA A phase pwm pin - @param phB B phase pwm pin - @param phC C phase pwm pin - @param pp pole pair number - @param cpr counts per rotation number (cpm=ppm*4) - @param en enable pin (optional input) + StepperMotor class constructor + @param ph1A 1A phase pwm pin + @param ph1B 1B phase pwm pin + @param ph2A 2A phase pwm pin + @param ph2B 2B phase pwm pin + @param pp pole pair number - cpr counts per rotation number (cpm=ppm*4) + @param en1 enable pin phase 1 (optional input) + @param en2 enable pin phase 2 (optional input) */ - BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + StepperMotor(int ph1A,int ph1B,int ph2A,int ph2B,int pp, int en1 = NOT_SET, int en2 = NOT_SET); /** Motor hardware init function */ void init(); @@ -125,10 +126,13 @@ class BLDCMotor void move(float target = NOT_SET); // hardware variables - int pwmA; //!< phase A pwm pin number - int pwmB; //!< phase B pwm pin number - int pwmC; //!< phase C pwm pin number - int enable_pin; //!< enable pin number + int pwm1A; //!< phase 1A pwm pin number + int pwm1B; //!< phase 1B pwm pin number + int pwm2A; //!< phase 2A pwm pin number + int pwm2B; //!< phase 2B pwm pin number + int enable_pin1; //!< enable pin number phase 1 + int enable_pin2; //!< enable pin number phase 2 + @@ -149,7 +153,6 @@ class BLDCMotor float shaft_velocity_sp;//!< current target velocity float shaft_angle_sp;//!< current target angle float voltage_q;//!< current voltage u_q set - float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor // motor configuration parameters float voltage_power_supply;//!< Power supply voltage @@ -264,7 +267,7 @@ class BLDCMotor * @param Ub phase B voltage * @param Uc phase C voltage */ - void setPwm(float Ua, float Ub, float Uc); + void setPwm(float Ualpha, float Ubeta); // Utility functions /** normalizing radian angle to [0,2PI] */ diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/FOCutils.cpp b/minimal_project_examples/arduino_foc_minimal_encoder1/src/common/FOCutils.cpp similarity index 86% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/FOCutils.cpp rename to minimal_project_examples/arduino_foc_minimal_encoder1/src/common/FOCutils.cpp index 653c7191..2fac9507 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/FOCutils.cpp +++ b/minimal_project_examples/arduino_foc_minimal_encoder1/src/common/FOCutils.cpp @@ -31,27 +31,35 @@ motor_slots_t esp32_motor_slots[4] = { // function setting the high pwm frequency to the supplied pins // - hardware speciffic // supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(const int pinA, const int pinB, const int pinC) { +void _setPwmFrequency(const int pinA, const int pinB, const int pinC, const int pinD) { #if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips // High PWM frequency // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pinA == 5 || pinA == 6 || pinB == 5 || pinB == 6 || pinC == 5 || pinC == 6 ) { + if (pinA == 5 || pinA == 6 || pinB == 5 || pinB == 6 || pinC == 5 || pinC == 6 || pinD == 5 || pinD == 6 ) { TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 } - if (pinA == 9 || pinA == 10 || pinB == 9 || pinB == 10 || pinC == 9 || pinC == 10 ) + if (pinA == 9 || pinA == 10 || pinB == 9 || pinB == 10 || pinC == 9 || pinC == 10|| pinD == 9 || pinD == 10 ) TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pinA == 3 || pinA == 11 || pinB == 3 || pinB == 11 || pinC == 3 || pinC == 11 ) + if (pinA == 3 || pinA == 11 || pinB == 3 || pinB == 11 || pinC == 3 || pinC == 11 || pinD == 3 || pinD == 11 ) TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 #elif defined(_STM32_DEF_) // if stm chips analogWrite(pinA, 0); analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 analogWrite(pinB, 0); analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 analogWrite(pinC, 0); analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 + if(pinD) { + analogWrite(pinD, 0); + analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 + } #elif defined(ESP_H) // if esp32 boards @@ -133,7 +141,12 @@ void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, in break; } } -#else // Arduino & STM32 devices +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pinA, 4095.0*dc_a); + analogWrite(pinB, 4095.0*dc_b); + analogWrite(pinC, 4095.0*dc_c); +#else // Arduino // transform duty cycle from [0,1] to [0,255] analogWrite(pinA, 255*dc_a); analogWrite(pinB, 255*dc_b); @@ -141,6 +154,29 @@ void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, in #endif } +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ +#if defined(ESP_H) // if ESP32 boards + // not sure how to hande this +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pin1A, 4095.0*dc_1a); + analogWrite(pin1B, 4095.0*dc_1b); + analogWrite(pin2A, 4095.0*dc_2a); + analogWrite(pin2B, 4095.0*dc_2b); +#else // Arduino + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255*dc_1a); + analogWrite(pin1B, 255*dc_1b); + analogWrite(pin2A, 255*dc_2a); + analogWrite(pin2B, 255*dc_2b); +#endif +} + // function buffering delay() // arduino uno function doesn't work well with interrupts diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/FOCutils.h b/minimal_project_examples/arduino_foc_minimal_encoder1/src/common/FOCutils.h similarity index 75% rename from minimal_project_examples/arduino_foc_minimal_encoder/FOCutils.h rename to minimal_project_examples/arduino_foc_minimal_encoder1/src/common/FOCutils.h index 4c347a12..f233407b 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder/FOCutils.h +++ b/minimal_project_examples/arduino_foc_minimal_encoder1/src/common/FOCutils.h @@ -37,7 +37,7 @@ * @param pinB pinB number to configure * @param pinC pinC number to configure */ -void _setPwmFrequency(int pinA, int pinB, int pinC); +void _setPwmFrequency(int pinA, int pinB, int pinC, int pinD = 0); /** * Function implementing delay() function in milliseconds @@ -67,6 +67,20 @@ unsigned long _micros(); */ void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); /** * Function approximating the sine calculation by using fixed size array @@ -83,4 +97,4 @@ float _sin(float a); */ float _cos(float a); -#endif \ No newline at end of file +#endif diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/Sensor.h b/minimal_project_examples/arduino_foc_minimal_encoder1/src/common/Sensor.h similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/Sensor.h rename to minimal_project_examples/arduino_foc_minimal_encoder1/src/common/Sensor.h diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/defaults.h b/minimal_project_examples/arduino_foc_minimal_encoder1/src/common/defaults.h similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/defaults.h rename to minimal_project_examples/arduino_foc_minimal_encoder1/src/common/defaults.h diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/BLDCMotor.cpp deleted file mode 100644 index f31e818a..00000000 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/BLDCMotor.cpp +++ /dev/null @@ -1,716 +0,0 @@ -#include "BLDCMotor.h" - -// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) -// - phA, phB, phC - motor A,B,C phase pwm pins -// - pp - pole pair number -// - cpr - counts per rotation number (cpm=ppm*4) -// - enable pin - (optional input) -BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) -{ - // Pin initialization - pwmA = phA; - pwmB = phB; - pwmC = phC; - pole_pairs = pp; - - // enable_pin pin - enable_pin = en; - - // Power supply voltage - voltage_power_supply = DEF_POWER_SUPPLY; - - // Velocity loop config - // PI controller constant - PID_velocity.P = DEF_PID_VEL_P; - PID_velocity.I = DEF_PID_VEL_I; - PID_velocity.D = DEF_PID_VEL_D; - PID_velocity.output_ramp = DEF_PID_VEL_U_RAMP; - PID_velocity.timestamp = _micros(); - PID_velocity.integral_prev = 0; - PID_velocity.output_prev = 0; - PID_velocity.tracking_error_prev = 0; - - // velocity low pass filter - LPF_velocity.Tf = DEF_VEL_FILTER_Tf; - LPF_velocity.timestamp = _micros(); - LPF_velocity.prev = 0; - - // position loop config - // P controller constant - P_angle.P = DEF_P_ANGLE_P; - - // maximum angular velocity to be used for positioning - velocity_limit = DEF_VEL_LIM; - // maximum voltage to be set to the motor - voltage_limit = voltage_power_supply; - - // index search velocity - velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; - // sensor and motor align voltage - voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; - - // electric angle of the zero angle - zero_electric_angle = 0; - - // default modulation is SinePWM - foc_modulation = FOCModulationType::SinePWM; - - // default target value - target = 0; - - //monitor_port - monitor_port = nullptr; - //sensor - sensor = nullptr; -} - -// init hardware pins -void BLDCMotor::init() { - if(monitor_port) monitor_port->println("MOT: Init pins."); - // PWM pins - pinMode(pwmA, OUTPUT); - pinMode(pwmB, OUTPUT); - pinMode(pwmC, OUTPUT); - if(hasEnable()) pinMode(enable_pin, OUTPUT); - - if(monitor_port) monitor_port->println("MOT: PWM config."); - // Increase PWM frequency to 32 kHz - // make silent - _setPwmFrequency(pwmA, pwmB, pwmC); - - // sanity check for the voltage limit configuration - if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; - // constrain voltage for sensor alignment - if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; - - _delay(500); - // enable motor - if(monitor_port) monitor_port->println("MOT: Enable."); - enable(); - _delay(500); - -} - - -// disable motor driver -void BLDCMotor::disable() -{ - // disable the driver - if enable_pin pin available - if (hasEnable()) digitalWrite(enable_pin, LOW); - // set zero to PWM - setPwm(0, 0, 0); -} -// enable motor driver -void BLDCMotor::enable() -{ - // set zero to PWM - setPwm(0, 0, 0); - // enable_pin the driver - if enable_pin pin available - if (hasEnable()) digitalWrite(enable_pin, HIGH); - -} - -void BLDCMotor::linkSensor(Sensor* _sensor) { - sensor = _sensor; -} - - -// Encoder alignment to electrical 0 angle -int BLDCMotor::alignSensor() { - if(monitor_port) monitor_port->println("MOT: Align sensor."); - // align the electrical phases of the motor and sensor - // set angle -90 degrees - - float start_angle = shaftAngle(); - for (int i = 0; i <=5; i++ ) { - float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); - _delay(200); - } - float mid_angle = shaftAngle(); - for (int i = 5; i >=0; i-- ) { - float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); - _delay(200); - } - if (mid_angle < start_angle) { - if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); - sensor->natural_direction = Direction::CCW; - } else if (mid_angle == start_angle) { - if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); - } - - // let the motor stabilize for 2 sec - _delay(2000); - // set sensor to zero - sensor->initRelativeZero(); - _delay(500); - setPhaseVoltage(0,0); - _delay(200); - - // find the index if available - int exit_flag = absoluteZeroAlign(); - _delay(500); - if(monitor_port){ - if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); - if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); - else monitor_port->println("MOT: Not available!"); - } - return exit_flag; -} - - -// Encoder alignment the absolute zero angle -// - to the index -int BLDCMotor::absoluteZeroAlign() { - - if(monitor_port) monitor_port->println("MOT: Absolute zero align."); - // if no absolute zero return - if(!sensor->hasAbsoluteZero()) return 0; - - - if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); - // search the absolute zero with small velocity - while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ - loopFOC(); - voltage_q = velocityPID(velocity_index_search - shaftVelocity()); - } - voltage_q = 0; - // disable motor - setPhaseVoltage(0,0); - - // align absolute zero if it has been found - if(!sensor->needsAbsoluteZeroSearch()){ - // align the sensor with the absolute zero - float zero_offset = sensor->initAbsoluteZero(); - // remember zero electric angle - zero_electric_angle = normalizeAngle(electricAngle(zero_offset)); - } - // return bool if zero found - return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; -} - -/** - State calculation methods -*/ -// shaft angle calculation -float BLDCMotor::shaftAngle() { - // if no sensor linked return 0 - if(!sensor) return 0; - return sensor->getAngle(); -} -// shaft velocity calculation -float BLDCMotor::shaftVelocity() { - // if no sensor linked return 0 - if(!sensor) return 0; - return lowPassFilter(sensor->getVelocity(), LPF_velocity); -} -// Electrical angle calculation -float BLDCMotor::electricAngle(float shaftAngle) { - //return normalizeAngle(shaftAngle * pole_pairs); - return (shaftAngle * pole_pairs); -} - -/** - FOC functions -*/ -// FOC initialization function -int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { - int exit_flag = 1; - // align motor if necessary - // alignment necessary for encoders! - if(zero_electric_offset != NOT_SET){ - // abosolute zero offset provided - no need to align - zero_electric_angle = zero_electric_offset; - // set the sensor direction - default CW - sensor->natural_direction = sensor_direction; - }else{ - // sensor and motor alignment - _delay(500); - exit_flag = alignSensor(); - _delay(500); - } - if(monitor_port) monitor_port->println("MOT: Motor ready."); - - return exit_flag; -} - -// Iterative function looping FOC algorithm, setting Uq on the Motor -// The faster it can be run the better -void BLDCMotor::loopFOC() { - // shaft angle - shaft_angle = shaftAngle(); - // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); -} - -// Iterative function running outer loop of the FOC algorithm -// Behavior of this function is determined by the motor.controller variable -// It runs either angle, velocity or voltage loop -// - needs to be called iteratively it is asynchronous function -// - if target is not set it uses motor.target value -void BLDCMotor::move(float new_target) { - // set internal target variable - if( new_target != NOT_SET ) target = new_target; - // get angular velocity - shaft_velocity = shaftVelocity(); - // choose control loop - switch (controller) { - case ControlType::voltage: - voltage_q = target; - break; - case ControlType::angle: - // angle set point - // include angle loop - shaft_angle_sp = target; - shaft_velocity_sp = positionP( shaft_angle_sp - shaft_angle ); - voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); - break; - case ControlType::velocity: - // velocity set point - // include velocity loop - shaft_velocity_sp = target; - voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); - break; - case ControlType::velocity_openloop: - // velocity control in open loop - // loopFOC should not be called - shaft_velocity_sp = target; - velocityOpenloop(shaft_velocity_sp); - break; - case ControlType::angle_openloop: - // angle control in open loop - // loopFOC should not be called - shaft_angle_sp = target; - angleOpenloop(shaft_angle_sp); - break; - } -} - - -// Method using FOC to set Uq to the motor at the optimal angle -// Function implementing Space Vector PWM and Sine PWM algorithms -// -// Function using sine approximation -// regular sin + cos ~300us (no memory usaage) -// approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { - switch (foc_modulation) - { - case FOCModulationType::SinePWM : - // Sinusoidal PWM modulation - // Inverse Park + Clarke transformation - - // angle normalization in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - angle_el = normalizeAngle(angle_el + zero_electric_angle); - // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; - - // Clarke transform - Ua = Ualpha + voltage_power_supply/2; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; - break; - - case FOCModulationType::SpaceVectorPWM : - // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm - // https://www.youtube.com/watch?v=QMSWUMEAejg - - // if negative voltages change inverse the phase - // angle + 180degrees - if(Uq < 0) angle_el += _PI; - Uq = abs(Uq); - - // angle normalisation in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - angle_el = normalizeAngle(angle_el + zero_electric_angle + _PI_2); - - // find the sector we are in currently - int sector = floor(angle_el / _PI_3) + 1; - // calculate the duty cycles - float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; - float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; - // two versions possible - // centered around voltage_power_supply/2 - float T0 = 1 - T1 - T2; - // pulled to 0 - better for low power supply voltage - //float T0 = 0; - - // calculate the duty cycles(times) - float Ta,Tb,Tc; - switch(sector){ - case 1: - Ta = T1 + T2 + T0/2; - Tb = T2 + T0/2; - Tc = T0/2; - break; - case 2: - Ta = T1 + T0/2; - Tb = T1 + T2 + T0/2; - Tc = T0/2; - break; - case 3: - Ta = T0/2; - Tb = T1 + T2 + T0/2; - Tc = T2 + T0/2; - break; - case 4: - Ta = T0/2; - Tb = T1+ T0/2; - Tc = T1 + T2 + T0/2; - break; - case 5: - Ta = T2 + T0/2; - Tb = T0/2; - Tc = T1 + T2 + T0/2; - break; - case 6: - Ta = T1 + T2 + T0/2; - Tb = T0/2; - Tc = T1 + T0/2; - break; - default: - // possible error state - Ta = 0; - Tb = 0; - Tc = 0; - } - - // calculate the phase voltages and center - Ua = Ta*voltage_power_supply; - Ub = Tb*voltage_power_supply; - Uc = Tc*voltage_power_supply; - break; - } - - // set the voltages in hardware - setPwm(Ua, Ub, Uc); -} - - - -// Set voltage to the pwm pin -void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { - // calculate duty cycle - // limited in [0,1] - float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); - float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); - float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); - // hardware specific writing - _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); -} - -/** - Utility functions -*/ -// normalizing radian angle to [0,2PI] -float BLDCMotor::normalizeAngle(float angle){ - float a = fmod(angle, _2PI); - return a >= 0 ? a : (a + _2PI); -} -// determining if the enable pin has been provided -int BLDCMotor::hasEnable(){ - return enable_pin != NOT_SET; -} - -// low pass filter function -// - input -singal to be filtered -// - lpf -LPF_s structure with filter parameters -float BLDCMotor::lowPassFilter(float input, LPF_s& lpf){ - unsigned long now_us = _micros(); - float Ts = (now_us - lpf.timestamp) * 1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // calculate the filtering - float alpha = lpf.Tf/(lpf.Tf + Ts); - float out = alpha*lpf.prev + (1-alpha)*input; - - // save the variables - lpf.prev = out; - lpf.timestamp = now_us; - return out; -} - - -/** - Motor control functions -*/ -// PID controller function -float BLDCMotor::controllerPID(float tracking_error, PID_s& cont){ - // calculate the time from the last call - unsigned long now_us = _micros(); - float Ts = (now_us - cont.timestamp) * 1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // u(s) = (P + I/s + Ds)e(s) - // Discrete implementations - // proportional part - // u_p = P *e(k) - float proportional = cont.P * tracking_error; - // Tustin transform of the integral part - // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) - float integral = cont.integral_prev + cont.I*Ts*0.5*(tracking_error + cont.tracking_error_prev); - // antiwindup - limit the output voltage_q - integral = constrain(integral, -voltage_limit, voltage_limit); - // Discrete derivation - // u_dk = D(ek - ek_1)/Ts - float derivative = cont.D*(tracking_error - cont.tracking_error_prev)/Ts; - // sum all the components - float voltage = proportional + integral + derivative; - - // antiwindup - limit the output voltage_q - voltage = constrain(voltage, -voltage_limit, voltage_limit); - - // limit the acceleration by ramping the the voltage - float d_voltage = voltage - cont.output_prev; - if (abs(d_voltage)/Ts > cont.output_ramp) voltage = d_voltage > 0 ? cont.output_prev + cont.output_ramp*Ts : cont.output_prev - cont.output_ramp*Ts; - - // saving for the next pass - cont.integral_prev = integral; - cont.output_prev = voltage; - cont.tracking_error_prev = tracking_error; - cont.timestamp = now_us; - return voltage; -} -// velocity control loop PI controller -float BLDCMotor::velocityPID(float tracking_error) { - return controllerPID(tracking_error, PID_velocity); -} - -// P controller for position control loop -float BLDCMotor::positionP(float ek) { - // calculate the target velocity from the position error - float velocity_target = P_angle.P * ek; - // constrain velocity target value - velocity_target = constrain(velocity_target, -velocity_limit, velocity_limit); - return velocity_target; -} - -// Function (iterative) generating open loop movement for target velocity -// - target_velocity - rad/s -// it uses voltage_limit variable -void BLDCMotor::velocityOpenloop(float target_velocity){ - // get current timestamp - unsigned long now_us = _micros(); - // calculate the sample time from last call - float Ts = (now_us - open_loop_timestamp) * 1e-6; - - // calculate the necessary angle to achieve target velocity - shaft_angle += target_velocity*Ts; - - // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); - - // save timestamp for next call - open_loop_timestamp = now_us; -} - -// Function (iterative) generating open loop movement towards the target angle -// - target_angle - rad -// it uses voltage_limit and velocity_limit variables -void BLDCMotor::angleOpenloop(float target_angle){ - // get current timestamp - unsigned long now_us = _micros(); - // calculate the sample time from last call - float Ts = (now_us - open_loop_timestamp) * 1e-6; - - // calculate the necessary angle to move from current position towards target angle - // with maximal velocity (velocity_limit) - if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) - shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; - else - shaft_angle = target_angle; - - // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); - - // save timestamp for next call - open_loop_timestamp = now_us; -} - -/** - * Monitoring functions - */ -// function implementing the monitor_port setter -void BLDCMotor::useMonitoring(Print &print){ - monitor_port = &print; //operate on the address of print - if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); -} -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void BLDCMotor::monitor() { - if(!monitor_port) return; - switch (controller) { - case ControlType::velocity_openloop: - case ControlType::velocity: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_velocity_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - case ControlType::angle_openloop: - case ControlType::angle: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_angle); - break; - case ControlType::voltage: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - } -} - -int BLDCMotor::command(String user_command) { - // error flag - int errorFlag = 1; - // if empty string - if(user_command.length() < 1) return errorFlag; - - // parse command letter - char cmd = user_command.charAt(0); - // check if get command - char GET = user_command.charAt(1) == '\n'; - // parse command values - float value = user_command.substring(1).toFloat(); - - // a bit of optimisation of variable memory for Arduino UNO (atmega328) - switch(cmd){ - case 'P': // velocity P gain change - case 'I': // velocity I gain change - case 'D': // velocity D gain change - case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print(" PID velocity| "); - break; - case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print(" LPF velocity| "); - break; - case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print(" P angle| "); - break; - case 'L': // velocity voltage limit change - case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print(" Limits| "); - break; - - } - - // apply the the command - switch(cmd){ - case 'P': // velocity P gain change - if(monitor_port) monitor_port->print("P: "); - if(!GET) PID_velocity.P = value; - if(monitor_port) monitor_port->println(PID_velocity.P); - break; - case 'I': // velocity I gain change - if(monitor_port) monitor_port->print("I: "); - if(!GET) PID_velocity.I = value; - if(monitor_port) monitor_port->println(PID_velocity.I); - break; - case 'D': // velocity D gain change - if(monitor_port) monitor_port->print("D: "); - if(!GET) PID_velocity.D = value; - if(monitor_port) monitor_port->println(PID_velocity.D); - break; - case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print("volt_ramp: "); - if(!GET) PID_velocity.output_ramp = value; - if(monitor_port) monitor_port->println(PID_velocity.output_ramp); - break; - case 'L': // velocity voltage limit change - if(monitor_port) monitor_port->print("volt_limit: "); - if(!GET)voltage_limit = value; - if(monitor_port) monitor_port->println(voltage_limit); - break; - case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print("Tf: "); - if(!GET) LPF_velocity.Tf = value; - if(monitor_port) monitor_port->println(LPF_velocity.Tf); - break; - case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print(" P: "); - if(!GET) P_angle.P = value; - if(monitor_port) monitor_port->println(P_angle.P); - break; - case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print("vel_limit: "); - if(!GET) velocity_limit = value; - if(monitor_port) monitor_port->println(velocity_limit); - break; - case 'C': - // change control type - if(monitor_port) monitor_port->print("Control: "); - - if(GET){ // if get command - switch(controller){ - case ControlType::voltage: - if(monitor_port) monitor_port->println("voltage"); - break; - case ControlType::velocity: - if(monitor_port) monitor_port->println("velocity"); - break; - case ControlType::angle: - if(monitor_port) monitor_port->println("angle"); - break; - default: - if(monitor_port) monitor_port->println("open loop"); - } - }else{ // if set command - switch((int)value){ - case 0: - if(monitor_port) monitor_port->println("voltage"); - controller = ControlType::voltage; - break; - case 1: - if(monitor_port) monitor_port->println("velocity"); - controller = ControlType::velocity; - break; - case 2: - if(monitor_port) monitor_port->println("angle"); - controller = ControlType::angle; - break; - default: // not valid command - errorFlag = 0; - } - } - break; - case 'V': // get current values of the state variables - switch((int)value){ - case 0: // get voltage - if(monitor_port) monitor_port->print("Uq: "); - if(monitor_port) monitor_port->println(voltage_q); - break; - case 1: // get velocity - if(monitor_port) monitor_port->print("Velocity: "); - if(monitor_port) monitor_port->println(shaft_velocity); - break; - case 2: // get angle - if(monitor_port) monitor_port->print("Angle: "); - if(monitor_port) monitor_port->println(shaft_angle); - break; - case 3: // get angle - if(monitor_port) monitor_port->print("Target: "); - if(monitor_port) monitor_port->println(target); - break; - default: // not valid command - errorFlag = 0; - } - break; - default: // target change - if(monitor_port) monitor_port->print("Target : "); - target = user_command.toFloat(); - if(monitor_port) monitor_port->println(target); - } - // return 0 if error and 1 if ok - return errorFlag; -} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/arduino_foc_minimal_magnetic_i2c.ino b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/arduino_foc_minimal_magnetic_i2c.ino index d083c6a7..e62ad0cd 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/arduino_foc_minimal_magnetic_i2c.ino +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/arduino_foc_minimal_magnetic_i2c.ino @@ -36,14 +36,14 @@ * - 3: current target value * */ -#include "BLDCMotor.h" -#include "MagneticSensorI2C.h" +#include "src/BLDCMotor.h" +#include "src/MagneticSensorI2C.h" // I2C magnetic sensor instance MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0x0E, 4); // motor instance -BLDCMotor motor = BLDCMotor(9, 5, 6, 11, 8); +BLDCMotor motor = BLDCMotor(9, 5, 6, 11, 7); void setup() { @@ -136,4 +136,4 @@ String serialReceiveUserCommand() { } } return command; -} \ No newline at end of file +} diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/BLDCMotor.cpp new file mode 100644 index 00000000..893ac81a --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/BLDCMotor.cpp @@ -0,0 +1,376 @@ +#include "BLDCMotor.h" + +// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - phA, phB, phC - motor A,B,C phase pwm pins +// - pp - pole pair number +// - cpr - counts per rotation number (cpm=ppm*4) +// - enable pin - (optional input) +BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +: FOCMotor() +{ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + pole_pairs = pp; + + // enable_pin pin + enable_pin = en; + +} + + +// init hardware pins +void BLDCMotor::init() { + if(monitor_port) monitor_port->println("MOT: Init pins."); + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); + + if(monitor_port) monitor_port->println("MOT: PWM config."); + // Increase PWM frequency to 32 kHz + // make silent + _setPwmFrequency(pwmA, pwmB, pwmC); + + // sanity check for the voltage limit configuration + if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + + _delay(500); + // enable motor + if(monitor_port) monitor_port->println("MOT: Enable."); + enable(); + _delay(500); + +} + + +// disable motor driver +void BLDCMotor::disable() +{ + // disable the driver - if enable_pin pin available + if (enable_pin != NOT_SET) digitalWrite(enable_pin, LOW); + // set zero to PWM + setPwm(0, 0, 0); +} +// enable motor driver +void BLDCMotor::enable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // enable_pin the driver - if enable_pin pin available + if (enable_pin != NOT_SET) digitalWrite(enable_pin, HIGH); + +} + +/** + FOC functions +*/ +// FOC initialization function +int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } + if(monitor_port) monitor_port->println("MOT: Motor ready."); + + return exit_flag; +} +// Encoder alignment to electrical 0 angle +int BLDCMotor::alignSensor() { + if(monitor_port) monitor_port->println("MOT: Align sensor."); + // align the electrical phases of the motor and sensor + // set angle -90 degrees + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } + + // let the motor stabilize for 2 sec + _delay(2000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0,0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int BLDCMotor::absoluteZeroAlign() { + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); + + // align absolute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = _normalizeAngle(_electricalAngle(zero_offset, pole_pairs)); + } + // return bool if zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void BLDCMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); +} + +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function +// - if target is not set it uses motor.target value +void BLDCMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; + // get angular velocity + shaft_velocity = shaftVelocity(); + // choose control loop + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = P_angle( shaft_angle_sp - shaft_angle ); + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // include velocity loop + shaft_velocity_sp = target; + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); + break; + } +} + + +// Method using FOC to set Uq to the motor at the optimal angle +// Function implementing Space Vector PWM and Sine PWM algorithms +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) +void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { + switch (foc_modulation) + { + case FOCModulationType::SinePWM : + // Sinusoidal PWM modulation + // Inverse Park + Clarke transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + + // Clarke transform + Ua = Ualpha + voltage_power_supply/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + break; + + case FOCModulationType::SpaceVectorPWM : + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // https://www.youtube.com/watch?v=QMSWUMEAejg + + // if negative voltages change inverse the phase + // angle + 180degrees + if(Uq < 0) angle_el += _PI; + Uq = abs(Uq); + + // angle normalisation in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle + _PI_2); + + // find the sector we are in currently + int sector = floor(angle_el / _PI_3) + 1; + // calculate the duty cycles + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; + // two versions possible + // centered around voltage_power_supply/2 + float T0 = 1 - T1 - T2; + // pulled to 0 - better for low power supply voltage + //float T0 = 0; + + // calculate the duty cycles(times) + float Ta,Tb,Tc; + switch(sector){ + case 1: + Ta = T1 + T2 + T0/2; + Tb = T2 + T0/2; + Tc = T0/2; + break; + case 2: + Ta = T1 + T0/2; + Tb = T1 + T2 + T0/2; + Tc = T0/2; + break; + case 3: + Ta = T0/2; + Tb = T1 + T2 + T0/2; + Tc = T2 + T0/2; + break; + case 4: + Ta = T0/2; + Tb = T1+ T0/2; + Tc = T1 + T2 + T0/2; + break; + case 5: + Ta = T2 + T0/2; + Tb = T0/2; + Tc = T1 + T2 + T0/2; + break; + case 6: + Ta = T1 + T2 + T0/2; + Tb = T0/2; + Tc = T1 + T0/2; + break; + default: + // possible error state + Ta = 0; + Tb = 0; + Tc = 0; + } + + // calculate the phase voltages and center + Ua = Ta*voltage_power_supply; + Ub = Tb*voltage_power_supply; + Uc = Tc*voltage_power_supply; + break; + } + + // set the voltages in hardware + setPwm(Ua, Ub, Uc); +} + + + +// Set voltage to the pwm pin +void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { + // calculate duty cycle + // limited in [0,1] + float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); + // hardware specific writing + _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); +} + + + +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void BLDCMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void BLDCMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/BLDCMotor.h b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/BLDCMotor.h new file mode 100644 index 00000000..6d597c9a --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/BLDCMotor.h @@ -0,0 +1,113 @@ +/** + * @file BLDCMotor.h + * + */ + +#ifndef BLDCMotor_h +#define BLDCMotor_h + +#include "Arduino.h" +#include "common/FOCMotor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" +#include "common/defaults.h" + +/** + BLDC motor class +*/ +class BLDCMotor: public FOCMotor +{ + public: + /** + BLDCMotor class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param pp pole pair number + @param cpr counts per rotation number (cpm=ppm*4) + @param en enable pin (optional input) + */ + BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + + /** Motor hardware init function */ + void init(); + /** Motor disable function */ + void disable(); + /** Motor enable function */ + void enable(); + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + */ + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + void loopFOC(); + + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET); + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + + private: + // FOC methods + /** + * Method using FOC to set Uq to the motor at the optimal angle + * Heart of the FOC algorithm + * + * @param Uq Current voltage in q axis to set to the motor + * @param angle_el current electrical angle of the motor + */ + void setPhaseVoltage(float Uq, float angle_el); + /** Sensor alignment to electrical 0 angle of the motor */ + int alignSensor(); + /** Motor and sensor alignment to the sensors absolute 0 angle */ + int absoluteZeroAlign(); + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + * @param Uc phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc); + + // Open loop motion control + /** + * Function (iterative) generating open loop movement for target velocity + * it uses voltage_limit variable + * + * @param target_velocity - rad/s + */ + void velocityOpenloop(float target_velocity); + /** + * Function (iterative) generating open loop movement towards the target angle + * it uses voltage_limit and velocity_limit variables + * + * @param target_angle - rad + */ + void angleOpenloop(float target_angle); + // open loop variables + long open_loop_timestamp; +}; + + +#endif diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/MagneticSensorI2C.cpp b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/MagneticSensorI2C.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/MagneticSensorI2C.cpp rename to minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/MagneticSensorI2C.cpp diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/MagneticSensorI2C.h b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/MagneticSensorI2C.h new file mode 100644 index 00000000..2d9cad14 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/MagneticSensorI2C.h @@ -0,0 +1,79 @@ +#ifndef MAGNETICSENSORI2C_LIB_H +#define MAGNETICSENSORI2C_LIB_H + +#include "Arduino.h" +#include +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" + + +class MagneticSensorI2C: public Sensor{ + public: + /** + * MagneticSensorI2C class constructor + * @param chip_address I2C chip address + * @param bits number of bits of the sensor resolution + * @param angle_register_msb angle read register msb + * @param _bits_used_msb number of used bits in msb + */ + MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _msb_bits_used); + + + /** sensor initialise pins */ + void init(); + + // implementation of abstract functions of the Sensor class + /** get current angle (rad) */ + float getAngle(); + /** get current angular velocity (rad/s) **/ + float getVelocity(); + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + float initRelativeZero(); + /** + * set absolute zero angle as zero angle + * return the angle [rad] difference + */ + float initAbsoluteZero(); + /** returns 1 because it is the absolute sensor */ + int hasAbsoluteZero(); + /** returns 0 maning it doesn't need search for absolute zero */ + int needsAbsoluteZeroSearch(); + + + private: + float cpr; //!< Maximum range of the magnetic sensor + uint16_t lsb_used; //!< Number of bits used in LSB register + uint8_t lsb_mask; + uint8_t msb_mask; + + // I2C variables + uint8_t angle_register_msb; //!< I2C angle register to read + uint8_t chip_address; //!< I2C chip select pins + + // I2C functions + /** Read one I2C register value */ + int read(uint8_t angle_register_msb); + + word zero_offset; //!< user defined zero offset + /** + * Function getting current angle register value + * it uses angle_register variable + */ + int getRawCount(); + + // total angle tracking variables + float full_rotation_offset; //!getAngle(); +} +// shaft velocity calculation +float FOCMotor::shaftVelocity() { + // if no sensor linked return 0 + if(!sensor) return 0; + return LPF_velocity(sensor->getVelocity()); +} + + + + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void FOCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void FOCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity_openloop: + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle_openloop: + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int FOCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'D': // velocity D gain change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PID velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P angle| "); + break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + } + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("P: "); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("I: "); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); + break; + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("volt_ramp: "); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET) { + voltage_limit = value; + PID_velocity.limit = value; + } + if(monitor_port) monitor_port->println(voltage_limit); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("Tf: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("vel_limit: "); + if(!GET){ + velocity_limit = value; + P_angle.limit = value; + } + if(monitor_port) monitor_port->println(velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Control: "); + + if(GET){ // if get command + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + default: + if(monitor_port) monitor_port->println("open loop"); + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/FOCMotor.h b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/FOCMotor.h new file mode 100644 index 00000000..11d566d4 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/FOCMotor.h @@ -0,0 +1,195 @@ +#ifndef FOCMOTOR_H +#define FOCMOTOR_H + +#include "Arduino.h" +#include "hardware_utils.h" +#include "foc_utils.h" +#include "defaults.h" + +#include "Sensor.h" +#include "pid.h" +#include "lowpass_filter.h" + + +/** + * Motiron control type + */ +enum ControlType{ + voltage,//!< Torque control using voltage + velocity,//!< Velocity motion control + angle,//!< Position/angle motion control + velocity_openloop, + angle_openloop +}; + +/** + * FOC modulation type + */ +enum FOCModulationType{ + SinePWM, //!< Sinusoidal PWM modulation + SpaceVectorPWM //!< Space vector modulation method +}; + +/** + Generic motor class +*/ +class FOCMotor +{ + public: + /** + * Default constructor - setting all variabels to default values + */ + FOCMotor(); + + /** Motor hardware init function */ + virtual void init()=0; + /** Motor disable function */ + virtual void disable()=0; + /** Motor enable function */ + virtual void enable()=0; + + /** + * Function linking a motor and a sensor + * + * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity + */ + void linkSensor(Sensor* sensor); + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + virtual int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW)=0; + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + virtual void loopFOC()=0; + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + virtual void move(float target = NOT_SET)=0; + + // State calculation methods + /** Shaft angle calculation in radians [rad] */ + float shaftAngle(); + /** + * Shaft angle calculation function in radian per second [rad/s] + * It implements low pass filtering + */ + float shaftVelocity(); + + // state variables + float target; //!< current target value - depends of the controller + float shaft_angle;//!< current motor angle + float shaft_velocity;//!< current motor velocity + float shaft_velocity_sp;//!< current target velocity + float shaft_angle_sp;//!< current target angle + float voltage_q;//!< current voltage u_q set + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform + + // motor configuration parameters + float voltage_power_supply;//!< Power supply voltage + float voltage_sensor_align;//!< sensor and motor align voltage parameter + float velocity_index_search;//!< target velocity for index search + int pole_pairs;//!< Motor pole pairs number + + // limiting variables + float voltage_limit; //!< Voltage limitting variable - global limit + float velocity_limit; //!< Velocity limitting variable - global limit + + float zero_electric_angle;//! _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} + + +// normalizing radian angle to [0,2PI] +float _normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} + +// Electrical angle calculation +float _electricalAngle(float shaft_angle, int pole_pairs) { + return (shaft_angle * pole_pairs); +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/foc_utils.h b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/foc_utils.h new file mode 100644 index 00000000..5ab34f42 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/foc_utils.h @@ -0,0 +1,55 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + +// sign function +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + +// utility defines +#define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI 3.14159265359 +#define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + + +#define NOT_SET -12345.0 + +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _sin(float a); +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _cos(float a); + +/** + * normalizing radian angle to [0,2PI] + * @param angle - angle to be normalized + */ +float _normalizeAngle(float angle); + + +/** + * Electrical angle calculation + * + * @param shaft_angle - shaft angle of the motor + * @param pole_pairs - number of pole pairs + */ +float _electricalAngle(float shaft_angle, int pole_pairs); +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/hardware_utils.cpp new file mode 100644 index 00000000..802087a7 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/hardware_utils.cpp @@ -0,0 +1,219 @@ +#include "hardware_utils.h" + +#if defined(ESP_H) // if ESP32 board +// empty motor slot +#define _EMPTY_SLOT -20 + +// structure containing motor slot configuration +// this library supports up to 4 motors +typedef struct { + int pinA; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; + mcpwm_io_signals_t mcpwm_c; + +} motor_slots_t; + +// define motor slots array +motor_slots_t esp32_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B + }; + +#endif + + +// function setting the high pwm frequency to the supplied pins +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _setPwmFrequency(const int pinA, const int pinB, const int pinC, const int pinD) { +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pinA == 5 || pinA == 6 || pinB == 5 || pinB == 6 || pinC == 5 || pinC == 6 || pinD == 5 || pinD == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pinA == 9 || pinA == 10 || pinB == 9 || pinB == 10 || pinC == 9 || pinC == 10|| pinD == 9 || pinD == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pinA == 3 || pinA == 11 || pinB == 3 || pinB == 11 || pinC == 3 || pinC == 11 || pinD == 3 || pinD == 11 ) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +#elif defined(_STM32_DEF_) // if stm chips + + analogWrite(pinA, 0); + analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 + analogWrite(pinB, 0); + analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 + analogWrite(pinC, 0); + analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 + if(pinD) { + analogWrite(pinD, 0); + analogWriteFrequency(50000); // set 50kHz + analogWriteResolution(12); // resolution 12 bit 0 - 4096 + +#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards + analogWrite(pinA, 0); + analogWriteFrequency(pinA, 50000); // set 50kHz + analogWrite(pinB, 0); + analogWriteFrequency(pinB, 50000); // set 50kHz + analogWrite(pinC, 0); + analogWriteFrequency(pinC, 50000); // set 50kHz + if(pinD) { + analogWrite(pinD, 0); + analogWriteFrequency(50000); // set 50kHz + +#elif defined(ESP_H) // if esp32 boards + + motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 4; i++){ + if(esp32_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_motor_slots[i].pinA = pinA; + m_slot = esp32_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); + + mcpwm_config_t pwm_config; + pwm_config.frequency = 4000000; //frequency = 20000Hz + pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% + pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + _delay(100); + + mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_0); + mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_1); + mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_2); + m_slot.mcpwm_num->clk_cfg.prescale = 0; + + m_slot.mcpwm_num->timer[0].period.prescale = 4; + m_slot.mcpwm_num->timer[1].period.prescale = 4; + m_slot.mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + m_slot.mcpwm_num->timer[0].period.period = 2048; + m_slot.mcpwm_num->timer[1].period.period = 2048; + m_slot.mcpwm_num->timer[2].period.period = 2048; + _delay(1); + m_slot.mcpwm_num->timer[0].period.upmethod = 0; + m_slot.mcpwm_num->timer[1].period.upmethod = 0; + m_slot.mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + m_slot.mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + m_slot.mcpwm_num->timer[0].sync.out_sel = 0; +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pinA, 4095.0*dc_a); + analogWrite(pinB, 4095.0*dc_b); + analogWrite(pinC, 4095.0*dc_c); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255*dc_a); + analogWrite(pinB, 255*dc_b); + analogWrite(pinC, 255*dc_c); +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ +#if defined(ESP_H) // if ESP32 boards + // not sure how to handle this +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pin1A, 4095.0*dc_1a); + analogWrite(pin1B, 4095.0*dc_1b); + analogWrite(pin2A, 4095.0*dc_2a); + analogWrite(pin2B, 4095.0*dc_2b); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255*dc_1a); + analogWrite(pin1B, 255*dc_1b); + analogWrite(pin2A, 255*dc_2a); + analogWrite(pin2B, 255*dc_2b); +#endif +} + + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/hardware_utils.h b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/hardware_utils.h new file mode 100644 index 00000000..03c44fdd --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/hardware_utils.h @@ -0,0 +1,71 @@ +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H + +#include "Arduino.h" +#include "foc_utils.h" + + +#if defined(ESP_H) // if esp32 boards + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +#endif + +/** + * High PWM frequency setting function + * - hardware specific + * + * @param pinA pinA number to configure + * @param pinB pinB number to configure + * @param pinC pinC number to configure + * @param pinD pinC number to configure + */ +void _setPwmFrequency(int pinA, int pinB, int pinC, int pinD = 0); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/lowpass_filter.cpp b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/lowpass_filter.cpp new file mode 100644 index 00000000..9bf4ab7a --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/lowpass_filter.cpp @@ -0,0 +1,25 @@ +#include "lowpass_filter.h" + +LowPassFilter::LowPassFilter(float time_constant) + : Tf(time_constant) + , y_prev(0.0f) +{ + timestamp_prev = _micros(); +} + + +float LowPassFilter::operator() (float x) +{ + unsigned long timestamp = _micros(); + float dt = (timestamp - timestamp_prev)*1e-6f; + + if (dt < 0.0f || dt > 0.5f) + dt = 1e-3f; + + float alpha = Tf/(Tf + dt); + float y = alpha*y_prev + (1.0f - alpha)*x; + + y_prev = y; + timestamp_prev = timestamp; + return y; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/lowpass_filter.h b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/lowpass_filter.h new file mode 100644 index 00000000..5a7619cf --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/lowpass_filter.h @@ -0,0 +1,29 @@ +#ifndef LOWPASS_FILTER_H +#define LOWPASS_FILTER_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + + +/** + * Low pass filter class + */ +class LowPassFilter +{ +public: + /** + * @param Tf - Low pass filter time constant + */ + LowPassFilter(float Tf); + ~LowPassFilter() = default; + + float operator() (float x); + float Tf; //!< Low pass filter time constant + +protected: + unsigned long timestamp_prev; //!< Last execution timestamp + float y_prev; //!< filtered value in previous execution step +}; + +#endif // LOWPASS_FILTER_H \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/pid.cpp b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/pid.cpp new file mode 100644 index 00000000..316d88f2 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/pid.cpp @@ -0,0 +1,57 @@ +#include "pid.h" + +PIDController::PIDController(float P, float I, float D, float ramp, float limit) + : P(P) + , I(I) + , D(D) + , output_ramp(ramp) // output derivative limit [volts/second] + , limit(limit) // output supply limit [volts] + , integral_prev(0.0) + , error_prev(0.0) + , output_prev(0.0) +{ + timestamp_prev = _micros()*1e-6; +} + +// PID controller function +float PIDController::operator() (float error){ + // calculate the time from the last call + unsigned long timestamp_now = _micros(); + float Ts = (timestamp_now - timestamp_prev) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = P * error_prev; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = integral_prev + I*Ts*0.5*(error + error_prev); + // antiwindup - limit the integral value + integral = constrain(integral, -limit, limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = D*(error - error_prev)/Ts; + + // sum all the components + float output = proportional + integral + derivative; + + // limit the acceleration by ramping the output + float output_rate = (output - output_prev)/Ts; + if (output_rate > output_ramp) + output = output_prev + output_ramp*Ts; + else if (output_rate < -output_ramp) + output = output_prev - output_ramp*Ts; + + // antiwindup - limit the output variable + output = constrain(output, -limit, limit); + + // saving for the next pass + integral_prev = integral; + output_prev = output; + error_prev = error; + timestamp_prev = timestamp_now; + return output; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/pid.h b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/pid.h new file mode 100644 index 00000000..7ee337c4 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/pid.h @@ -0,0 +1,40 @@ +#ifndef PID_H +#define PID_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + +/** + * PID controller class + */ +class PIDController +{ +public: + /** + * + * @param P - Proportional gain + * @param I - Integral gain + * @param D - Derivative gain + * @param ramp - Maximum speed of change of the output value + * @param limit - Maximum output value + */ + PIDController(float P, float I, float D, float ramp, float limit); + ~PIDController() = default; + + float operator() (float error); + + float P; //!< Proportional gain + float I; //!< Integral gain + float D; //!< Derivative gain + float output_ramp; //!< Maximum speed of change of the output value + float limit; //!< Maximum output value + +protected: + float integral_prev; //!< last integral component value + float error_prev; //!< last tracking error value + float timestamp_prev; //!< Last execution timestamp + float output_prev; //!< last pid output value +}; + +#endif // PID_H \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorI2C.cpp b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorI2C.cpp new file mode 100644 index 00000000..eb94a753 --- /dev/null +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorI2C.cpp @@ -0,0 +1,154 @@ +#include "MagneticSensorI2C.h" + +// MagneticSensorI2C(uint8_t _chip_address, float _cpr, uint8_t _angle_register_msb) +// @param _chip_address I2C chip address +// @param _bit_resolution bit resolution of the sensor +// @param _angle_register_msb angle read register +// @param _bits_used_msb number of used bits in msb +MagneticSensorI2C::MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _bits_used_msb){ + // chip I2C address + chip_address = _chip_address; + // angle read register of the magnetic sensor + angle_register_msb = _angle_register_msb; + // register maximum value (counts per revolution) + cpr = pow(2, _bit_resolution); + + // depending on the sensor architecture there are different combinations of + // LSB and MSB register used bits + // AS5600 uses 0..7 LSB and 8..11 MSB + // AS5048 uses 0..5 LSB and 6..13 MSB + // used bits in LSB + lsb_used = _bit_resolution - _bits_used_msb; + // extraction masks + lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); + msb_mask = (uint8_t)( (2 << _bits_used_msb) - 1 ); +} + + +void MagneticSensorI2C::init(){ + + //I2C communication begin + Wire.begin(); + + // velocity calculation init + angle_prev = 0; + velocity_calc_timestamp = _micros(); + + // full rotations tracking number + full_rotation_offset = 0; + angle_data_prev = getRawCount(); + zero_offset = 0; +} + +// Shaft angle calculation +// angle is in radians [rad] +float MagneticSensorI2C::getAngle(){ + // raw data from the sensor + float angle_data = getRawCount(); + + // tracking the number of rotations + // in order to expand angle range form [0,2PI] + // to basically infinity + float d_angle = angle_data - angle_data_prev; + // if overflow happened track it as full rotation + if(abs(d_angle) > (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; + // save the current angle value for the next steps + // in order to know if overflow happened + angle_data_prev = angle_data; + + // zero offset adding + angle_data -= (int)zero_offset; + // return the full angle + // (number of full rotations)*2PI + current sensor angle + return natural_direction * (full_rotation_offset + ( angle_data / (float)cpr) * _2PI); +} + +// Shaft velocity calculation +float MagneticSensorI2C::getVelocity(){ + // calculate sample time + unsigned long now_us = _micros(); + float Ts = (now_us - velocity_calc_timestamp)*1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // current angle + float angle_c = getAngle(); + // velocity calculation + float vel = (angle_c - angle_prev)/Ts; + + // save variables for future pass + angle_prev = angle_c; + velocity_calc_timestamp = now_us; + return vel; +} + +// set current angle as zero angle +// return the angle [rad] difference +float MagneticSensorI2C::initRelativeZero(){ + float angle_offset = -getAngle(); + zero_offset = natural_direction * getRawCount(); + + // angle tracking variables + full_rotation_offset = 0; + return angle_offset; +} +// set absolute zero angle as zero angle +// return the angle [rad] difference +float MagneticSensorI2C::initAbsoluteZero(){ + float rotation = -(int)zero_offset; + // init absolute zero + zero_offset = 0; + + // angle tracking variables + full_rotation_offset = 0; + // return offset in radians + return rotation / (float)cpr * _2PI; +} +// returns 0 if it has no absolute 0 measurement +// 0 - incremental encoder without index +// 1 - encoder with index & magnetic sensors +int MagneticSensorI2C::hasAbsoluteZero(){ + return 1; +} +// returns 0 if it does need search for absolute zero +// 0 - magnetic sensor +// 1 - ecoder with index +int MagneticSensorI2C::needsAbsoluteZeroSearch(){ + return 0; +} + + +// function reading the raw counter of the magnetic sensor +int MagneticSensorI2C::getRawCount(){ + return (int)MagneticSensorI2C::read(angle_register_msb); +} + +// I2C functions +/* +* Read a register from the sensor +* Takes the address of the register as a uint8_t +* Returns the value of the register +*/ +int MagneticSensorI2C::read(uint8_t angle_reg_msb) { + // read the angle register first MSB then LSB + byte readArray[2]; + uint16_t readValue = 0; + // notify the device that is aboout to be read + Wire.beginTransmission(chip_address); + Wire.write(angle_reg_msb); + Wire.endTransmission(false); + + // read the data msb and lsb + Wire.requestFrom(chip_address, (uint8_t)2); + for (byte i=0; i < 2; i++) { + readArray[i] = Wire.read(); + } + + // depending on the sensor architecture there are different combinations of + // LSB and MSB register used bits + // AS5600 uses 0..7 LSB and 8..11 MSB + // AS5048 uses 0..5 LSB and 6..13 MSB + readValue = ( readArray[1] & lsb_mask ); + readValue += ( ( readArray[0] & msb_mask ) << lsb_used ); + return readValue; +} diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/MagneticSensorI2C.h b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorI2C.h similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/MagneticSensorI2C.h rename to minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorI2C.h diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/arduino_foc_minimal_magnetic_spi.ino b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/arduino_foc_minimal_magnetic_spi.ino index 9c271ad1..7a01bfa3 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/arduino_foc_minimal_magnetic_spi.ino +++ b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/arduino_foc_minimal_magnetic_spi.ino @@ -37,13 +37,14 @@ * */ #include "BLDCMotor.h" -#include "MagneticSensorSPI.h" +#include "MagneticSensorI2C.h" // SPI magnetic sensor instance -MagneticSensorSPI sensor = MagneticSensorSPI(10, 14, 0x3FFF); +//MagneticSensorSPI sensor = MagneticSensorSPI(10, 14, 0x3FFF); +MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0x0E, 4); // motor instance -BLDCMotor motor = BLDCMotor(9, 5, 6, 11, 8); +BLDCMotor motor = BLDCMotor(9, 5, 6, 11, 7); void setup() { @@ -97,6 +98,7 @@ void setup() { _delay(1000); } +long t = 0; void loop() { // iterative setting FOC phase voltage @@ -106,7 +108,8 @@ void loop() { // velocity, position or voltage // if tatget not set in parameter uses motor.target variable motor.move(); - + t>1000 ? t = 0 : t++; + if(!t) Serial.println(_micros()); // user communication motor.command(serialReceiveUserCommand()); } @@ -136,4 +139,4 @@ String serialReceiveUserCommand() { } } return command; -} \ No newline at end of file +} diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.cpp index f31e818a..18ffdfce 100644 --- a/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.cpp +++ b/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.cpp @@ -5,12 +5,15 @@ // - pp - pole pair number // - cpr - counts per rotation number (cpm=ppm*4) // - enable pin - (optional input) -BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +BLDCMotor::BLDCMotor(int phA, int phB, int phC,int phAl,int phBl,int phCl, int pp, int en) { // Pin initialization pwmA = phA; pwmB = phB; pwmC = phC; + pwmA_L = phAl; + pwmB_L = phBl; + pwmC_L = phCl; pole_pairs = pp; // enable_pin pin @@ -71,12 +74,16 @@ void BLDCMotor::init() { pinMode(pwmA, OUTPUT); pinMode(pwmB, OUTPUT); pinMode(pwmC, OUTPUT); + pinMode(pwmA_L, OUTPUT); + pinMode(pwmB_L, OUTPUT); + pinMode(pwmC_L, OUTPUT); if(hasEnable()) pinMode(enable_pin, OUTPUT); if(monitor_port) monitor_port->println("MOT: PWM config."); // Increase PWM frequency to 32 kHz // make silent _setPwmFrequency(pwmA, pwmB, pwmC); + _setPwmFrequencyLow(pwmA_L, pwmB_L, pwmC_L); // sanity check for the voltage limit configuration if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; @@ -399,6 +406,7 @@ void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); // hardware specific writing + _writeDutyCycleLow(dc_a, dc_b, dc_c, pwmA_L, pwmB_L, pwmC_L ); _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); } @@ -713,4 +721,4 @@ int BLDCMotor::command(String user_command) { } // return 0 if error and 1 if ok return errorFlag; -} \ No newline at end of file +} diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.h b/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.h index 95ca9472..4191c29c 100644 --- a/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.h +++ b/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.h @@ -80,7 +80,7 @@ class BLDCMotor @param cpr counts per rotation number (cpm=ppm*4) @param en enable pin (optional input) */ - BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + BLDCMotor(int phA,int phB,int phC,int phAl,int phBl,int phCl,int pp, int en = NOT_SET); /** Motor hardware init function */ void init(); @@ -128,6 +128,9 @@ class BLDCMotor int pwmA; //!< phase A pwm pin number int pwmB; //!< phase B pwm pin number int pwmC; //!< phase C pwm pin number + int pwmA_L; //!< phase A pwm pin number + int pwmB_L; //!< phase B pwm pin number + int pwmC_L; //!< phase C pwm pin number int enable_pin; //!< enable pin number diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.cpp b/minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.cpp index 653c7191..3e7523d0 100644 --- a/minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.cpp +++ b/minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.cpp @@ -46,13 +46,33 @@ void _setPwmFrequency(const int pinA, const int pinB, const int pinC) { #elif defined(_STM32_DEF_) // if stm chips - analogWrite(pinA, 0); - analogWriteFrequency(50000); // set 50kHz - analogWrite(pinB, 0); - analogWriteFrequency(50000); // set 50kHz - analogWrite(pinC, 0); - analogWriteFrequency(50000); // set 50kHz - + // Automatically retrieve TIM instance and channel associated to pin + TIM_TypeDef *InstanceA = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinA), PinMap_PWM); + uint32_t channelA = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinA), PinMap_PWM)); + // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. + HardwareTimer *MyTimA = new HardwareTimer(InstanceA); + MyTimA->setMode(channelA, TIMER_OUTPUT_COMPARE_PWM1, pinA); + MyTimA->setOverflow(20, MICROSEC_FORMAT); // 50khz + MyTimA->resume(); + + // Automatically retrieve TIM instance and channel associated to pin + TIM_TypeDef *InstanceB = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinB), PinMap_PWM); + uint32_t channelB = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinB), PinMap_PWM)); + // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. + HardwareTimer *MyTimB = new HardwareTimer(InstanceB); + MyTimB->setMode(channelB, TIMER_OUTPUT_COMPARE_PWM1, pinB); + MyTimB->setOverflow(20, MICROSEC_FORMAT); // 50khz + MyTimB->resume(); + + // Automatically retrieve TIM instance and channel associated to pin + TIM_TypeDef *InstanceC = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinC), PinMap_PWM); + uint32_t channelC = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinC), PinMap_PWM)); + // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. + HardwareTimer *MyTimC = new HardwareTimer(InstanceC); + MyTimC->setMode(channelC, TIMER_OUTPUT_COMPARE_PWM1, pinC); + MyTimC->setOverflow(20, MICROSEC_FORMAT); // 50khz + MyTimC->resume(); + #elif defined(ESP_H) // if esp32 boards motor_slots_t m_slot = {}; @@ -115,6 +135,37 @@ void _setPwmFrequency(const int pinA, const int pinB, const int pinC) { #endif } +void _setPwmFrequencyLow(const int pinA, const int pinB, const int pinC) { + + // Automatically retrieve TIM instance and channel associated to pin + TIM_TypeDef *InstanceA = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinA), PinMap_PWM); + uint32_t channelA = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinA), PinMap_PWM)); + // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. + HardwareTimer *MyTimA = new HardwareTimer(InstanceA); + MyTimA->setMode(channelA, TIMER_OUTPUT_COMPARE_PWM2, pinA); + MyTimA->setOverflow(20, MICROSEC_FORMAT); // 50khz + MyTimA->resume(); + + // Automatically retrieve TIM instance and channel associated to pin + TIM_TypeDef *InstanceB = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinB), PinMap_PWM); + uint32_t channelB = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinB), PinMap_PWM)); + // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. + HardwareTimer *MyTimB = new HardwareTimer(InstanceB); + MyTimB->setMode(channelB, TIMER_OUTPUT_COMPARE_PWM2, pinB); + MyTimB->setOverflow(20, MICROSEC_FORMAT); // 50khz + MyTimB->resume(); + + // Automatically retrieve TIM instance and channel associated to pin + TIM_TypeDef *InstanceC = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinC), PinMap_PWM); + uint32_t channelC = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinC), PinMap_PWM)); + // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. + HardwareTimer *MyTimC = new HardwareTimer(InstanceC); + MyTimC->setMode(channelC, TIMER_OUTPUT_COMPARE_PWM2, pinC); + MyTimC->setOverflow(20, MICROSEC_FORMAT); // 50khz + MyTimC->resume(); + + +} // function setting the pwm duty cycle to the hardware //- hardware speciffic // @@ -133,13 +184,65 @@ void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, in break; } } -#else // Arduino & STM32 devices + +#elif defined(_STM32_DEF_) // if stm chips + + // Automatically retrieve TIM instance and channel associated to pin + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinA), PinMap_PWM); + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinA), PinMap_PWM)); + // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. + HardwareTimer *MyTim = new HardwareTimer(Instance); + MyTim->setCaptureCompare(channel, dc_a*100.0, PERCENT_COMPARE_FORMAT); // 50% + + // Automatically retrieve TIM instance and channel associated to pin + Instance = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinB), PinMap_PWM); + channel = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinB), PinMap_PWM)); + // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. + MyTim = new HardwareTimer(Instance); + MyTim->setCaptureCompare(channel, dc_b*100.0, PERCENT_COMPARE_FORMAT); // 50% + + // Automatically retrieve TIM instance and channel associated to pin + Instance = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinC), PinMap_PWM); + channel = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinC), PinMap_PWM)); + // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. + MyTim = new HardwareTimer(Instance); + MyTim->setCaptureCompare(channel, dc_c*100.0, PERCENT_COMPARE_FORMAT); // 50% + +// MyTimA->setPWM(channelA, pinA, 50000, dc_a*100.0); +// MyTimB->setPWM(channelB, pinB, 50000, dc_b*100.0); +// MyTimC->setPWM(channelC, pinC, 50000, dc_c*100.0); +#else // Arduino // transform duty cycle from [0,1] to [0,255] analogWrite(pinA, 255*dc_a); analogWrite(pinB, 255*dc_b); analogWrite(pinC, 255*dc_c); #endif } +void _writeDutyCycleLow(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +// +// // Automatically retrieve TIM instance and channel associated to pin +// TIM_TypeDef *InstanceA = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinA), PinMap_PWM); +// uint32_t channelA = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinA), PinMap_PWM)); +// // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. +// HardwareTimer *MyTimA = new HardwareTimer(InstanceA); +// +// // Automatically retrieve TIM instance and channel associated to pin +// TIM_TypeDef *InstanceB = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinB), PinMap_PWM); +// uint32_t channelB = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinB), PinMap_PWM)); +// // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. +// HardwareTimer *MyTimB = new HardwareTimer(InstanceB); +// +// // Automatically retrieve TIM instance and channel associated to pin +// TIM_TypeDef *InstanceC = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinC), PinMap_PWM); +// uint32_t channelC = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinC), PinMap_PWM)); +// // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. +// HardwareTimer *MyTimC = new HardwareTimer(InstanceC); +// +// +// MyTimA->setCaptureCompare(channelA, dc_a*100.0, PERCENT_COMPARE_FORMAT); // 50% +// MyTimB->setCaptureCompare(channelB, dc_b*100.0, PERCENT_COMPARE_FORMAT); // 50% +// MyTimC->setCaptureCompare(channelC, dc_c*100.0, PERCENT_COMPARE_FORMAT); // 50% +} // function buffering delay() diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.h b/minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.h index 4c347a12..72381ead 100644 --- a/minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.h +++ b/minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.h @@ -38,6 +38,7 @@ * @param pinC pinC number to configure */ void _setPwmFrequency(int pinA, int pinB, int pinC); +void _setPwmFrequencyLow(int pinA, int pinB, int pinC); /** * Function implementing delay() function in milliseconds @@ -66,6 +67,7 @@ unsigned long _micros(); * @param pinC phase C hardware pin number */ void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); +void _writeDutyCycleLow(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); /** @@ -83,4 +85,4 @@ float _sin(float a); */ float _cos(float a); -#endif \ No newline at end of file +#endif diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/arduino_foc_minimal_openloop.ino b/minimal_project_examples/arduino_foc_minimal_openloop/arduino_foc_minimal_openloop.ino index 76193fbb..fdc3359a 100644 --- a/minimal_project_examples/arduino_foc_minimal_openloop/arduino_foc_minimal_openloop.ino +++ b/minimal_project_examples/arduino_foc_minimal_openloop/arduino_foc_minimal_openloop.ino @@ -1,9 +1,38 @@ #include "BLDCMotor.h" + +// DRV8302 pins connections +// don't forget to connect the common ground pin +#define INH_A 5 +#define INH_B 4 +#define INH_C 3 +#define INL_A 8 +#define INL_B 9 +#define INL_C 10 +#define EN_GATE 13 +#define M_PWM A0 +#define M_OC A1 +#define OC_ADJ A3 + + // motor instance -BLDCMotor motor = BLDCMotor(3, 10, 6, 11, 7); +BLDCMotor motor = BLDCMotor(INH_A, INH_B, INH_C, INL_A, INL_B, INL_C, 11, EN_GATE); void setup() { + + // DRV8302 specific code + // M_OC - enable overcurrent protection + pinMode(M_OC,OUTPUT); + digitalWrite(M_OC,LOW); + // M_PWM - enable 3pwm mode + pinMode(M_PWM,OUTPUT); + digitalWrite(M_PWM,HIGH); + // OD_ADJ - set the maximum overcurrent limit possible + // Better option would be to use voltage divisor to set exact value + pinMode(OC_ADJ,OUTPUT); + digitalWrite(OC_ADJ,HIGH); + + // power supply voltage // default 12V @@ -13,7 +42,7 @@ void setup() { motor.voltage_limit = 3; // rad/s motor.velocity_limit = 20; // rad/s // open loop control config - motor.controller = ControlType::angle_openloop; + motor.controller = ControlType::velocity_openloop; // init motor hardware motor.init(); @@ -26,13 +55,15 @@ void setup() { float target_position = 0; // rad/s + void loop() { // open loop angle movements // using motor.voltage_limit and motor.velocity_limit - motor.move(target_position); + motor.move(2); // receive the used commands from serial serialReceiveUserCommand(); + Serial.println(micros()); } // utility function enabling serial communication with the user to set the target values From 1aa37bb53b9353ef0e1c8cf515865da197e9393d Mon Sep 17 00:00:00 2001 From: askuric Date: Mon, 19 Oct 2020 23:14:28 +0200 Subject: [PATCH 59/65] FEAT library version 1.6.0 --- README.md | 175 +++-- library_source/BLDCMotor.cpp | 8 +- library_source/BLDCMotor.h | 12 +- library_source/Encoder.cpp | 21 +- library_source/Encoder.h | 12 +- library_source/HallSensor.h | 14 +- library_source/MagneticSensorAnalog.h | 14 +- library_source/MagneticSensorI2C.cpp | 55 +- library_source/MagneticSensorI2C.h | 39 +- library_source/MagneticSensorSPI.cpp | 90 ++- library_source/MagneticSensorSPI.h | 43 +- library_source/SimpleFOC.h | 97 +++ library_source/StepperMotor.cpp | 8 +- library_source/StepperMotor.h | 12 +- library_source/common/FOCMotor.h | 2 +- library_source/common/defaults.h | 12 +- library_source/common/hardware_utils.cpp | 255 +++--- library_source/common/hardware_utils.h | 13 +- .../arduino_foc_bldc_encoder.ino} | 4 +- .../src/BLDCMotor.cpp | 8 +- .../src/BLDCMotor.h | 12 +- .../src/Encoder.cpp | 20 +- .../src/Encoder.h | 12 +- .../src/common/FOCMotor.cpp | 0 .../src/common/FOCMotor.h | 2 +- .../src/common/Sensor.h | 0 .../src/common/defaults.h | 0 .../src/common/foc_utils.cpp | 0 .../src/common/foc_utils.h | 0 .../src/common/hardware_utils.cpp | 284 +++++++ .../src/common/hardware_utils.h | 13 +- .../src/common/lowpass_filter.cpp | 0 .../src/common/lowpass_filter.h | 0 .../src/common/pid.cpp | 0 .../src/common/pid.h | 0 .../arduino_foc_bldc_hall.ino} | 4 +- .../arduino_foc_bldc_hall/src/BLDCMotor.cpp | 378 +++++++++ .../arduino_foc_bldc_hall/src/BLDCMotor.h | 113 +++ .../src}/HallSensor.cpp | 0 .../src}/HallSensor.h | 21 +- .../src/common/FOCMotor.cpp | 0 .../src/common/FOCMotor.h | 2 +- .../src/common/Sensor.h | 0 .../src/common/defaults.h | 12 +- .../src/common/foc_utils.cpp | 0 .../src/common/foc_utils.h | 0 .../src/common/hardware_utils.cpp | 284 +++++++ .../src/common/hardware_utils.h | 13 +- .../src/common/lowpass_filter.cpp | 0 .../src/common/lowpass_filter.h | 0 .../src/common/pid.cpp | 7 +- .../src/common/pid.h | 0 .../arduino_foc_bldc_magnetic_i2c.ino} | 0 .../src/BLDCMotor.cpp | 378 +++++++++ .../src/BLDCMotor.h | 113 +++ .../src/MagneticSensorI2C.cpp | 55 +- .../src/MagneticSensorI2C.h | 41 +- .../src/common/FOCMotor.cpp | 245 ++++++ .../src/common/FOCMotor.h} | 194 +---- .../src/common}/Sensor.h | 0 .../src/common/defaults.h | 12 +- .../src/common/foc_utils.cpp | 54 ++ .../src/common/foc_utils.h | 55 ++ .../src/common/hardware_utils.cpp | 284 +++++++ .../src/common/hardware_utils.h} | 76 +- .../src/common/lowpass_filter.cpp | 25 + .../src/common/lowpass_filter.h | 29 + .../src/common/pid.cpp | 56 ++ .../src/common/pid.h | 40 + .../arduino_foc_bldc_magnetic_spi.ino} | 4 +- .../src/BLDCMotor.cpp | 378 +++++++++ .../src/BLDCMotor.h | 113 +++ .../src}/MagneticSensorSPI.cpp | 90 ++- .../src}/MagneticSensorSPI.h | 48 +- .../src/common/FOCMotor.cpp | 245 ++++++ .../src/common/FOCMotor.h} | 194 +---- .../src/common/Sensor.h | 0 .../src/common}/defaults.h | 12 +- .../src/common/foc_utils.cpp | 54 ++ .../src/common/foc_utils.h | 55 ++ .../src/common/hardware_utils.cpp | 284 +++++++ .../src/common/hardware_utils.h | 72 ++ .../src/common/lowpass_filter.cpp | 25 + .../src/common/lowpass_filter.h | 29 + .../src/common/pid.cpp | 56 ++ .../src/common/pid.h | 40 + .../arduino_foc_bldc_openloop.ino | 64 ++ .../src/BLDCMotor.cpp | 378 +++++++++ .../arduino_foc_bldc_openloop/src/BLDCMotor.h | 113 +++ .../src/common/FOCMotor.cpp | 245 ++++++ .../src/common/FOCMotor.h | 195 +++++ .../src/common}/Sensor.h | 0 .../src/common}/defaults.h | 12 +- .../src/common/foc_utils.cpp | 54 ++ .../src/common/foc_utils.h | 55 ++ .../src/common/hardware_utils.cpp | 284 +++++++ .../src/common/hardware_utils.h | 72 ++ .../src/common/lowpass_filter.cpp | 25 + .../src/common/lowpass_filter.h | 29 + .../src/common/pid.cpp | 56 ++ .../src/common/pid.h | 40 + .../src/common/hardware_utils.cpp | 219 ------ .../src/StepperMotor.cpp | 650 ---------------- .../src/StepperMotor.h | 326 -------- .../src/common/FOCutils.cpp | 251 ------ .../arduino_foc_minimal_hall/BLDCMotor.cpp | 716 ----------------- .../arduino_foc_minimal_hall/FOCutils.cpp | 215 ------ .../arduino_foc_minimal_hall/FOCutils.h | 86 --- .../src/common/hardware_utils.cpp | 219 ------ .../BLDCMotor.cpp | 716 ----------------- .../FOCutils.cpp | 215 ------ .../FOCutils.h | 86 --- .../BLDCMotor.cpp | 724 ------------------ .../arduino_foc_minimal_openloop/BLDCMotor.h | 326 -------- .../arduino_foc_minimal_openloop/FOCutils.cpp | 318 -------- .../arduino_foc_minimal_openloop/FOCutils.h | 88 --- .../arduino_foc_minimal_openloop/defaults.h | 18 - .../arduino_foc_stepper_encoder.ino} | 2 +- .../src/Encoder.cpp | 21 +- .../src/Encoder.h | 15 +- .../src/StepperMotor.cpp | 8 +- .../src/StepperMotor.h | 12 +- .../src/common/FOCMotor.cpp | 245 ++++++ .../src/common/FOCMotor.h | 195 +++++ .../src/common}/Sensor.h | 0 .../src/common/defaults.h | 18 + .../src/common/foc_utils.cpp | 54 ++ .../src/common/foc_utils.h | 55 ++ .../src/common/hardware_utils.cpp | 284 +++++++ .../src/common/hardware_utils.h | 72 ++ .../src/common/lowpass_filter.cpp | 25 + .../src/common/lowpass_filter.h | 29 + .../src/common/pid.cpp | 56 ++ .../src/common/pid.h | 40 + .../arduino_foc_stepper_magnetic_i2c.ino | 139 ++++ .../src}/MagneticSensorI2C.cpp | 55 +- .../src}/MagneticSensorI2C.h | 44 +- .../src/StepperMotor.cpp | 309 ++++++++ .../src/StepperMotor.h | 122 +++ .../src/common/FOCMotor.cpp | 245 ++++++ .../src/common/FOCMotor.h | 195 +++++ .../src/common/Sensor.h | 59 ++ .../src/common/defaults.h | 18 + .../src/common/foc_utils.cpp | 54 ++ .../src/common/foc_utils.h | 55 ++ .../src/common/hardware_utils.cpp | 284 +++++++ .../src/common/hardware_utils.h | 72 ++ .../src/common/lowpass_filter.cpp | 25 + .../src/common/lowpass_filter.h | 29 + .../src/common/pid.cpp | 56 ++ .../src/common/pid.h | 40 + .../arduino_foc_bldc_openloop.ino} | 31 +- .../src/StepperMotor.cpp | 309 ++++++++ .../src/StepperMotor.h | 122 +++ .../src/common/FOCMotor.cpp | 245 ++++++ .../src/common/FOCMotor.h | 195 +++++ .../src/common/Sensor.h | 59 ++ .../src/common/defaults.h | 18 + .../src/common/foc_utils.cpp | 54 ++ .../src/common/foc_utils.h | 55 ++ .../src/common/hardware_utils.cpp | 284 +++++++ .../src/common/hardware_utils.h | 72 ++ .../src/common/lowpass_filter.cpp | 25 + .../src/common/lowpass_filter.h | 29 + .../src/common/pid.cpp | 56 ++ .../src/common/pid.h | 40 + 166 files changed, 10744 insertions(+), 6004 deletions(-) create mode 100644 library_source/SimpleFOC.h rename minimal_project_examples/{arduino_foc_minimal_encoder1/arduino_foc_minimal_encoder.ino => arduino_foc_bldc_encoder/arduino_foc_bldc_encoder.ino} (97%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_bldc_encoder}/src/BLDCMotor.cpp (98%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_bldc_encoder}/src/BLDCMotor.h (93%) rename minimal_project_examples/{arduino_foc_minimal_encoder1 => arduino_foc_bldc_encoder}/src/Encoder.cpp (96%) rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_bldc_encoder}/src/Encoder.h (93%) rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_bldc_encoder}/src/common/FOCMotor.cpp (100%) rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_bldc_encoder}/src/common/FOCMotor.h (99%) rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_bldc_encoder}/src/common/Sensor.h (100%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_bldc_encoder}/src/common/defaults.h (100%) rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_bldc_encoder}/src/common/foc_utils.cpp (100%) rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_bldc_encoder}/src/common/foc_utils.h (100%) create mode 100644 minimal_project_examples/arduino_foc_bldc_encoder/src/common/hardware_utils.cpp rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_bldc_encoder}/src/common/hardware_utils.h (80%) rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_bldc_encoder}/src/common/lowpass_filter.cpp (100%) rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_bldc_encoder}/src/common/lowpass_filter.h (100%) rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_bldc_encoder}/src/common/pid.cpp (100%) rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_bldc_encoder}/src/common/pid.h (100%) rename minimal_project_examples/{arduino_foc_minimal_hall/arduino_foc_minimal_hall.ino => arduino_foc_bldc_hall/arduino_foc_bldc_hall.ino} (98%) create mode 100644 minimal_project_examples/arduino_foc_bldc_hall/src/BLDCMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_hall/src/BLDCMotor.h rename minimal_project_examples/{arduino_foc_minimal_hall => arduino_foc_bldc_hall/src}/HallSensor.cpp (100%) rename minimal_project_examples/{arduino_foc_minimal_hall => arduino_foc_bldc_hall/src}/HallSensor.h (88%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_bldc_hall}/src/common/FOCMotor.cpp (100%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_bldc_hall}/src/common/FOCMotor.h (99%) rename minimal_project_examples/{arduino_foc_minimal_encoder1 => arduino_foc_bldc_hall}/src/common/Sensor.h (100%) rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_bldc_hall}/src/common/defaults.h (54%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_bldc_hall}/src/common/foc_utils.cpp (100%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_bldc_hall}/src/common/foc_utils.h (100%) create mode 100644 minimal_project_examples/arduino_foc_bldc_hall/src/common/hardware_utils.cpp rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_bldc_hall}/src/common/hardware_utils.h (80%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_bldc_hall}/src/common/lowpass_filter.cpp (100%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_bldc_hall}/src/common/lowpass_filter.h (100%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_bldc_hall}/src/common/pid.cpp (97%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_bldc_hall}/src/common/pid.h (100%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c/arduino_foc_minimal_magnetic_i2c.ino => arduino_foc_bldc_magnetic_i2c/arduino_foc_bldc_magnetic_i2c.ino} (100%) create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/BLDCMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/BLDCMotor.h rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_bldc_magnetic_i2c}/src/MagneticSensorI2C.cpp (75%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_bldc_magnetic_i2c}/src/MagneticSensorI2C.h (71%) create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/FOCMotor.cpp rename minimal_project_examples/{arduino_foc_minimal_magnetic_spi/BLDCMotor.h => arduino_foc_bldc_magnetic_i2c/src/common/FOCMotor.h} (56%) rename minimal_project_examples/{arduino_foc_minimal_hall => arduino_foc_bldc_magnetic_i2c/src/common}/Sensor.h (100%) rename minimal_project_examples/{arduino_foc_minimal_encoder1 => arduino_foc_bldc_magnetic_i2c}/src/common/defaults.h (54%) create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/foc_utils.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/foc_utils.h create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.cpp rename minimal_project_examples/{arduino_foc_minimal_encoder1/src/common/FOCutils.h => arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.h} (58%) create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/lowpass_filter.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/lowpass_filter.h create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/pid.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/pid.h rename minimal_project_examples/{arduino_foc_minimal_magnetic_spi/arduino_foc_minimal_magnetic_spi.ino => arduino_foc_bldc_magnetic_spi/arduino_foc_bldc_magnetic_spi.ino} (98%) create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/BLDCMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/BLDCMotor.h rename minimal_project_examples/{arduino_foc_minimal_magnetic_spi => arduino_foc_bldc_magnetic_spi/src}/MagneticSensorSPI.cpp (68%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_spi => arduino_foc_bldc_magnetic_spi/src}/MagneticSensorSPI.h (61%) create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/FOCMotor.cpp rename minimal_project_examples/{arduino_foc_minimal_hall/BLDCMotor.h => arduino_foc_bldc_magnetic_spi/src/common/FOCMotor.h} (56%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_i2c => arduino_foc_bldc_magnetic_spi}/src/common/Sensor.h (100%) rename minimal_project_examples/{arduino_foc_minimal_hall => arduino_foc_bldc_magnetic_spi/src/common}/defaults.h (54%) create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/foc_utils.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/foc_utils.h create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/hardware_utils.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/hardware_utils.h create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/lowpass_filter.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/lowpass_filter.h create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/pid.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/pid.h create mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/arduino_foc_bldc_openloop.ino create mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/BLDCMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/BLDCMotor.h create mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.h rename minimal_project_examples/{arduino_foc_minimal_magnetic_spi => arduino_foc_bldc_openloop/src/common}/Sensor.h (100%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_spi => arduino_foc_bldc_openloop/src/common}/defaults.h (54%) create mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/common/foc_utils.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/common/foc_utils.h create mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/common/hardware_utils.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/common/hardware_utils.h create mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/common/lowpass_filter.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/common/lowpass_filter.h create mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/common/pid.cpp create mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/common/pid.h delete mode 100644 minimal_project_examples/arduino_foc_minimal_encoder/src/common/hardware_utils.cpp delete mode 100644 minimal_project_examples/arduino_foc_minimal_encoder1/src/StepperMotor.cpp delete mode 100644 minimal_project_examples/arduino_foc_minimal_encoder1/src/StepperMotor.h delete mode 100644 minimal_project_examples/arduino_foc_minimal_encoder1/src/common/FOCutils.cpp delete mode 100644 minimal_project_examples/arduino_foc_minimal_hall/BLDCMotor.cpp delete mode 100644 minimal_project_examples/arduino_foc_minimal_hall/FOCutils.cpp delete mode 100644 minimal_project_examples/arduino_foc_minimal_hall/FOCutils.h delete mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/hardware_utils.cpp delete mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_spi/BLDCMotor.cpp delete mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_spi/FOCutils.cpp delete mode 100644 minimal_project_examples/arduino_foc_minimal_magnetic_spi/FOCutils.h delete mode 100644 minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.cpp delete mode 100644 minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.h delete mode 100644 minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.cpp delete mode 100644 minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.h delete mode 100644 minimal_project_examples/arduino_foc_minimal_openloop/defaults.h rename minimal_project_examples/{arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino => arduino_foc_stepper_encoder/arduino_foc_stepper_encoder.ino} (98%) rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_stepper_encoder}/src/Encoder.cpp (96%) rename minimal_project_examples/{arduino_foc_minimal_encoder1 => arduino_foc_stepper_encoder}/src/Encoder.h (91%) rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_stepper_encoder}/src/StepperMotor.cpp (97%) rename minimal_project_examples/{arduino_foc_minimal_encoder => arduino_foc_stepper_encoder}/src/StepperMotor.h (94%) create mode 100644 minimal_project_examples/arduino_foc_stepper_encoder/src/common/FOCMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_encoder/src/common/FOCMotor.h rename minimal_project_examples/{arduino_foc_minimal_openloop => arduino_foc_stepper_encoder/src/common}/Sensor.h (100%) create mode 100644 minimal_project_examples/arduino_foc_stepper_encoder/src/common/defaults.h create mode 100644 minimal_project_examples/arduino_foc_stepper_encoder/src/common/foc_utils.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_encoder/src/common/foc_utils.h create mode 100644 minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.h create mode 100644 minimal_project_examples/arduino_foc_stepper_encoder/src/common/lowpass_filter.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_encoder/src/common/lowpass_filter.h create mode 100644 minimal_project_examples/arduino_foc_stepper_encoder/src/common/pid.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_encoder/src/common/pid.h create mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/arduino_foc_stepper_magnetic_i2c.ino rename minimal_project_examples/{arduino_foc_minimal_magnetic_spi => arduino_foc_stepper_magnetic_i2c/src}/MagneticSensorI2C.cpp (75%) rename minimal_project_examples/{arduino_foc_minimal_magnetic_spi => arduino_foc_stepper_magnetic_i2c/src}/MagneticSensorI2C.h (69%) create mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/StepperMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/StepperMotor.h create mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/FOCMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/FOCMotor.h create mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/Sensor.h create mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/defaults.h create mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/foc_utils.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/foc_utils.h create mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.h create mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/lowpass_filter.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/lowpass_filter.h create mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/pid.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/pid.h rename minimal_project_examples/{arduino_foc_minimal_openloop/arduino_foc_minimal_openloop.ino => arduino_foc_stepper_openloop/arduino_foc_bldc_openloop.ino} (66%) create mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/StepperMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/StepperMotor.h create mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/common/FOCMotor.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/common/FOCMotor.h create mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/common/Sensor.h create mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/common/defaults.h create mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/common/foc_utils.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/common/foc_utils.h create mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.h create mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/common/lowpass_filter.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/common/lowpass_filter.h create mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/common/pid.cpp create mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/common/pid.h diff --git a/README.md b/README.md index c17367b8..1df71eaa 100644 --- a/README.md +++ b/README.md @@ -1,37 +1,63 @@ -# Arduino Simple FOC library minimal example +# Arduino *SimpleFOClibrary* v1.6.0 - minimal project builder ![MinimalBuild](https://github.com/askuric/Arduino-FOC/workflows/MinimalBuild/badge.svg?branch=minimal) [![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT) [![arduino-library-badge](https://www.ardu-badge.com/badge/Simple%20FOC.svg?)](https://www.ardu-badge.com/badge/Simple%20FOC.svg) -This is the repository of the [*SimpleFOClibrary*](https://github.com/askuric/Arduino-FOC) intended to be used to crete the projects with minimal code possible which is specific for certain **motor+sensor+driver** combination. +This is the branch of the [*SimpleFOClibrary*](https://github.com/askuric/Arduino-FOC) repository intended to be used to simplify the creation of the projects with minimal code possible which is specific for certain **motor+sensor+driver** combination. ### Repository structure +Library source code structure ```shell ├─── library_source | | -| ├─ BLDCMotor.cpp/h # BLDCMotor class implementing all the FOC operation -| ├─ FOCutils.cpp/h # Utility functions -| ├─ defaults.h # Default configuration values -│ ├─ Sensor.h # Abstract Sensor class that all the sensors implement +| ├─── common # Contains all the common utility classes and functions +| | | +| | ├─ defaults.h # default motion control parameters +| | | +| | ├─ foc_utils.cpp./h # utility functions of the FOC algorithm +| | ├─ hardware_utils.cpp./h # all the hardware specific implementations are in these files +| | ├─ pid.cpp./h # class implementing PID controller +| | ├─ lowpass_filter.cpp./h # class implementing Low pass filter +| | | +| | ├─ FOCMotor.cpp./h # common class for all implemented motors +| | └─ Sensor./h # common class for all implemented sensors +| | +| ├─ BLDCMotor.cpp/h # BLDC motor handling class +| ├─ StepperMotor.cpp/h # Stepper motor handling class │ │ │ ├─ Encoder.cpp/h # Encoder class implementing the Quadrature encoder operations │ ├─ MagneticSensorSPI.cpp/h # class implementing SPI communication for Magnetic sensors │ ├─ MagneticSensorI2C.cpp/h # class implementing I2C communication for Magnetic sensors │ ├─ MagneticSensorAnalog.cpp/h # class implementing Analog output for Magnetic sensors -│ └─ HallSensor.cpp/h # class implementing Hall sensor -| -└─── minimal_project_examples - ├─ arduino_foc_minimal_openloop # Arduino minimal code for running a motor in the open loop - ├─ arduino_foc_minimal_encoder # Arduino minimal code for running a motor with Encoder - ├─ arduino_foc_minimal_hall # Arduino minimal code for running a motor with Hall sensors - ├─ arduino_foc_minimal_magnetic_i2c # Arduino minimal code for running a motor with I2C magnetic sensor - └─ arduino_foc_minimal_magnetic_spi # Arduino minimal code for running a motor with SPI magnetic sensor + └─ HallSensor.cpp/h # class implementing Hall sensor +``` + +Minimal project examples provided for quick start: +```shell +├─── minimal_project_examples # Project examples +│ ├─ arduino_foc_bldc_openloop # BLDC motor + Open loop control +│ ├─ arduino_foc_bldc_encoder # BLDC motor + Encoder +│ ├─ arduino_foc_bldc_hall # BLDC motor + Hall sensors +│ ├─ arduino_foc_bldc_magnetic_i2c # BLDC motor + I2C magnetic sensor +│ ├─ arduino_foc_bldc_magnetic_spi # BLDC motor + SPI magnetic sensor +│ | +│ ├─ arduino_foc_stepper_openloop # Stepper motor + Open loop control +│ ├─ arduino_foc_stepper_encoder # Stepper motor + Encoder + └─ arduino_foc_stepper_magnetic_i2c # Stepper motor + I2C magnetic sensor ``` + + # Creating your own minimal project -First you need to download this repository to your computer. +Creating your own minimal project version is very simple and is done in four steps: +- Step 0: Download minimal branch contents to your PC +- Step 1: Create your the arduino project +- Step 2: Add motor specific code +- Step 3: Add sensor specific code + +## Step 0. Download the code #### Github website download - Make sure you are in [minimal branch](https://github.com/askuric/Arduino-FOC/tree/minimal) - Download the code by clicking on the `Clone or Download > Download ZIP`. @@ -48,100 +74,119 @@ After this step you will be able to open the example projects directly with Ardu > **BEWARE** In some cases this minimal version of the code will produce conflicts with the *Simple FOC* library if it is installed through Arduino library manager. So you might need to uninstall the library to run minimal projects. -## BLDC motor support code +## Step 1. Creating the Arduino project -In the `library_source` folder you will find all *SimpleFOClibrary* source files. From those files you will choose just the ones you need for your own project. - -In each Arduino project using the *SimpleFOClibrary* you will need to copy these six files into your project directory. +Open a directory you want to use as your arduino project directory `my_arduino_project` and create `my_arduino_project.ino` file. After this you create `src` folder in this directory and copy the folder named `common` from the `library_source` folder. Your project directory should now have structure: ```shell ├─── my_arduino_project | ├─ my_arduino_project.ino -| | -| ├─ BLDCMotor.cpp/h # BLDCMotor class implementing all the FOC operation -| ├─ FOCutils.cpp/h # Utility functions -| ├─ defaults.h # Default configuration values - └─ Sensor.h # Abstract Sensor class that all the sensors implement +| └─── src +| | ├─── common # Contains all the common utility classes and functions +| | ├─ defaults.h # default motion control parameters +| | ├─ foc_utils.cpp./h # utility functions of the FOC algorithm +| | ├─ hardware_utils.cpp./h # all the hardware specific implementations are in these files +| | ├─ pid.cpp./h # class implementing PID controller +| | ├─ lowpass_filter.cpp./h # class implementing Low pass filter +| | ├─ FOCMotor.cpp./h # common class for all implemented motors +| | └─ Sensor./h # common class for all implemented sensors ``` -And in your arduino code you need to add the include: +## Step 2. Add motor specific code +If you wish to use the BLDC motor with your setup you will have to copy the `BLDCMotor.cpp/h` from the `library_source` folder, and if you wish to use the stepper motor make sure to copy the `StepperMotor.cpp/h` files and place them to the `src` folder +```shell +├─── my_arduino_project +| ├─ my_arduino_project.ino +| └─── src +| | ├─── common # Common utility classes and functions +| | | +| | └─ BLDCMotor.cpp/h # BLDC motor handling class +``` +And in your Arduino code in the `my_arduino_project.ino` file make sure to add the the include: ```cpp -#include "BLDCMotor.h" +#include "src/BLDCMotor.h" ``` +For stepper motors the procedure is equivalent: -If you wish to run your motor in the open loop mode these are all the files that you will need. See the `arduino_foc_minimal_openloop.ino` project example. +```shell +├─── my_arduino_project +| ├─ my_arduino_project.ino +| └─── src +| | ├─── common # Common utility classes and functions +| | | +| | └─ StepperMotor.cpp/h # Stepper motor handling class +``` +And the include: +```cpp +#include "src/StepperMotor.h" +``` +If you wish to run your motor in the open loop mode these are all the files that you will need. See the `arduino_foc_bldc_openloop` and `arduino_foc_stepper_openloop` project example. -## Sensor support -In order to support the different position sensors you will have to add their `*.cpp` and `*.h` files into the directory. All you need to do is copy the header files from the `library_source` directory. +## Step 3. Add sensor specific code +In order to support the different position sensors you will have to copy their `*.cpp` and `*.h` into your `src` directory. All you need to do is copy the header files from the `library_source` directory. ### Example: Encoder sensor -For example if you wish to use encoder, your arduino project will have structure: - +For example if you wish to use BLDC motor and encoder as a sensor, your arduino project will have structure: ```shell ├─── my_arduino_project | ├─ my_arduino_project.ino -| | -| ├─ BLDCMotor.cpp/h # BLDCMotor class implementing all the FOC operation -| ├─ FOCutils.cpp/h # Utility functions -│ ├─ defaults.h # Default configuration values -│ ├─ Sensor.h # Abstract Sensor class that all the sensors implement -│ | - └─ Encoder.cpp/h # Encoder class implementing the Quadrature encoder operations +| └─── src +| | ├─── common # Common utility classes and functions +| | | +| | ├─ BLDCMotor.cpp/h # BLDC motor handling class +| | └─ Encoder.cpp/h # Encoder class implementing the Quadrature encoder operations ``` And your includes will be: ```cpp -#include "BLDCMotor.h" -#include "Encoder.h" +#include "src/BLDCMotor.h" +#include "src/Encoder.h" ``` -See `arduino_foc_minimal_encoder.ino`. +See `arduino_foc_bldc_encoder` project example or `arduino_foc_stepper_encoder` for stepper equivalent. ### Example: SPI Magnetic sensor -If you wish to use SPI magnetic sensor with your project, your folder structure will be: +If you wish to use Stepper motor and SPI magnetic sensor in your project, your folder structure will be: ```shell ├─── my_arduino_project | ├─ my_arduino_project.ino -| | -| ├─ BLDCMotor.cpp/h # BLDCMotor class implementing all the FOC operation -| ├─ FOCutils.cpp/h # Utility functions -│ ├─ defaults.h # Default configuration values -│ ├─ Sensor.h # Abstract Sensor class that all the sensors implement -│ | - └─ MagneticSensorSPI.cpp/h # class implementing SPI communication for Magnetic sensors +| └─── src +| | ├─── common # Common utility classes and functions +| | | +| | ├─ StepperMotor.cpp/h # Stepper motor handling class +| | └─ MagneticSensorSPI.cpp/h # class implementing SPI communication for Magnetic sensors ``` And your includes will be: ```cpp -#include "BLDCMotor.h" -#include "MagneticSensorSPI.h" +#include "src/StepperMotor.h" +#include "src/MagneticSensorSPI.h" ``` -See `arduino_foc_minimal_magnetic_spi.ino`. +See `arduino_foc_stepper_magnetic_spi` project example or `arduino_foc_bldc_magnetic_spi` for BLDC motor equivalent. -### Example: Analog magnetic sensor and encoder +### Example: Multiple sensors: analog magnetic sensor and encoder For example if you wish to use magnetic sensor with SPI communication, your arduino project will have structure: ```shell ├─── my_arduino_project | ├─ my_arduino_project.ino -| | -| ├─ BLDCMotor.cpp/h # BLDCMotor class implementing all the FOC operation -| ├─ FOCutils.cpp/h # Utility functions -│ ├─ defaults.h # Default configuration values -│ ├─ Sensor.h # Abstract Sensor class that all the sensors implement -│ | -│ ├─ Encoder.cpp/h # Encoder class implementing the Quadrature encoder operations - └─ MagneticSensorAnalog.cpp/h # class implementing Analog output for Magnetic sensors +| └─── src +| | ├─── common # Common utility classes and functions +| | | +| | ├─ BLDCMotor.cpp/h # BLDC motor handling class +| | ├─ Encoder.cpp/h # Encoder class implementing the Quadrature encoder operations +| | └─ MagneticSensorAnalog.cpp/h # class implementing Analog output for Magnetic sensors ``` And your includes will be: ```cpp -#include "BLDCMotor.h" -#include "MagneticSensorAnalog.h" -#include "Encoder.h" +#include "src/BLDCMotor.h" +#include "src/MagneticSensorAnalog.h" +#include "src/Encoder.h" ``` + ## Documentation -Find out more information about the Arduino *SimpleFOCproject* in [docs website](https://docs.simplefoc.com/) +Find out more information about the Arduino *Simple**FOC**library* and *Simple**FOC**project* in [docs website](https://docs.simplefoc.com/) ## Arduino FOC repo structure diff --git a/library_source/BLDCMotor.cpp b/library_source/BLDCMotor.cpp index 893ac81a..989b74a9 100644 --- a/library_source/BLDCMotor.cpp +++ b/library_source/BLDCMotor.cpp @@ -21,7 +21,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // init hardware pins -void BLDCMotor::init() { +void BLDCMotor::init(long pwm_frequency) { if(monitor_port) monitor_port->println("MOT: Init pins."); // PWM pins pinMode(pwmA, OUTPUT); @@ -32,19 +32,21 @@ void BLDCMotor::init() { if(monitor_port) monitor_port->println("MOT: PWM config."); // Increase PWM frequency to 32 kHz // make silent - _setPwmFrequency(pwmA, pwmB, pwmC); + _setPwmFrequency(pwm_frequency, pwmA, pwmB, pwmC); // sanity check for the voltage limit configuration if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; // constrain voltage for sensor alignment if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + // update the controller limits + PID_velocity.limit = voltage_limit; + P_angle.limit = velocity_limit; _delay(500); // enable motor if(monitor_port) monitor_port->println("MOT: Enable."); enable(); _delay(500); - } diff --git a/library_source/BLDCMotor.h b/library_source/BLDCMotor.h index 6d597c9a..a4fbb678 100644 --- a/library_source/BLDCMotor.h +++ b/library_source/BLDCMotor.h @@ -31,24 +31,24 @@ class BLDCMotor: public FOCMotor BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); /** Motor hardware init function */ - void init(); + void init(long pwm_frequency = NOT_SET) override; /** Motor disable function */ - void disable(); + void disable() override; /** Motor enable function */ - void enable(); + void enable() override; /** * Function initializing FOC algorithm * and aligning sensor's and motors' zero position */ - int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW) override; /** * Function running FOC algorithm in real-time * it calculates the gets motor angle and sets the appropriate voltages * to the phase pwm signals * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us */ - void loopFOC(); + void loopFOC() override; /** * Function executing the control loops set by the controller parameter of the BLDCMotor. @@ -58,7 +58,7 @@ class BLDCMotor: public FOCMotor * * This function doesn't need to be run upon each loop execution - depends of the use case */ - void move(float target = NOT_SET); + void move(float target = NOT_SET) override; // hardware variables int pwmA; //!< phase A pwm pin number diff --git a/library_source/Encoder.cpp b/library_source/Encoder.cpp index 77631345..1965c015 100644 --- a/library_source/Encoder.cpp +++ b/library_source/Encoder.cpp @@ -9,7 +9,7 @@ */ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ - + // Encoder measurement structure init // hardware pins pinA = _encA; @@ -87,11 +87,11 @@ void Encoder::handleIndex() { if(hasIndex()){ int I = digitalRead(index_pin); if(I && !I_active){ - // align encoder on each index + // align encoder on each index if(index_pulse_counter){ long tmp = pulse_counter; // corrent the counter value - pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; + pulse_counter = round((double)pulse_counter/(double)cpr)*cpr; // preserve relative speed prev_pulse_counter += pulse_counter - tmp; } else { @@ -119,8 +119,8 @@ float Encoder::getVelocity(){ // sampling time calculation float Ts = (timestamp_us - prev_timestamp_us) * 1e-6; // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + // time from last impulse float Th = (timestamp_us - pulse_timestamp) * 1e-6; long dN = pulse_counter - prev_pulse_counter; @@ -133,7 +133,7 @@ float Encoder::getVelocity(){ // only increment if some impulses received float dt = Ts + prev_Th - Th; pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second; - + // if more than 0.05 passed in between impulses if ( Th > 0.1) pulse_per_second = 0; @@ -176,10 +176,10 @@ int Encoder::hasIndex(){ } -// encoder initialisation of the hardware pins +// encoder initialisation of the hardware pins // and calculation variables void Encoder::init(){ - + // Encoder - check if pullup needed for your encoder if(pullup == Pullup::INTERN){ pinMode(pinA, INPUT_PULLUP); @@ -190,7 +190,7 @@ void Encoder::init(){ pinMode(pinB, INPUT); if(hasIndex()) pinMode(index_pin,INPUT); } - + // counter setup pulse_counter = 0; pulse_timestamp = _micros(); @@ -222,8 +222,7 @@ void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){ if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); break; } - + // if index used initialize the index interrupt if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE); } - diff --git a/library_source/Encoder.h b/library_source/Encoder.h index db9813b8..d1a55f0e 100644 --- a/library_source/Encoder.h +++ b/library_source/Encoder.h @@ -60,31 +60,31 @@ class Encoder: public Sensor{ // Abstract functions of the Sensor class implementation /** get current angle (rad) */ - float getAngle(); + float getAngle() override; /** get current angular velocity (rad/s) */ - float getVelocity(); + float getVelocity() override; /** * set current angle as zero angle * return the angle [rad] difference */ - float initRelativeZero(); + float initRelativeZero() override; /** * set index angle as zero angle * return the angle [rad] difference */ - float initAbsoluteZero(); + float initAbsoluteZero() override; /** * returns 0 if it has no index * 0 - encoder without index * 1 - encoder with index */ - int hasAbsoluteZero(); + int hasAbsoluteZero() override; /** * returns 0 if it does need search for absolute zero * 0 - encoder without index * 1 - ecoder with index */ - int needsAbsoluteZeroSearch(); + int needsAbsoluteZeroSearch() override; private: int hasIndex(); //!< function returning 1 if encoder has index pin and 0 if not. diff --git a/library_source/HallSensor.h b/library_source/HallSensor.h index b09a7fdb..9b467b0a 100644 --- a/library_source/HallSensor.h +++ b/library_source/HallSensor.h @@ -11,7 +11,7 @@ class HallSensor: public Sensor{ public: /** HallSensor class constructor - @param encA HallSensor B pin + @param encA HallSensor A pin @param encB HallSensor B pin @param encC HallSensor C pin @param pp pole pairs (e.g hoverboard motor has 15pp and small gimbals often have 7pp) @@ -52,31 +52,31 @@ class HallSensor: public Sensor{ // Abstract functions of the Sensor class implementation /** get current angle (rad) */ - float getAngle(); + float getAngle() override; /** get current angular velocity (rad/s) */ - float getVelocity(); + float getVelocity() override; /** * set current angle as zero angle * return the angle [rad] difference */ - float initRelativeZero(); + float initRelativeZero() override; /** * set index angle as zero angle * return the angle [rad] difference */ - float initAbsoluteZero(); + float initAbsoluteZero() override; /** * returns 0 if it has no index * 0 - HallSensor without index * 1 - HallSensor with index */ - int hasAbsoluteZero(); + int hasAbsoluteZero() override; /** * returns 0 if it does need search for absolute zero * 0 - HallSensor without index * 1 - ecoder with index */ - int needsAbsoluteZeroSearch(); + int needsAbsoluteZeroSearch() override; // whether last step was CW (+1) or CCW (-1) direction Direction direction; diff --git a/library_source/MagneticSensorAnalog.h b/library_source/MagneticSensorAnalog.h index 60c6fd50..cfe1b905 100644 --- a/library_source/MagneticSensorAnalog.h +++ b/library_source/MagneticSensorAnalog.h @@ -15,8 +15,6 @@ class MagneticSensorAnalog: public Sensor{ /** * MagneticSensorAnalog class constructor * @param _pinAnalog the pin to read the PWM signal - * @param _min minimal value of angle reading - * @param _max maximal value of angle reading */ MagneticSensorAnalog(uint8_t _pinAnalog, int _min = 0, int _max = 0); @@ -31,23 +29,23 @@ class MagneticSensorAnalog: public Sensor{ // implementation of abstract functions of the Sensor class /** get current angle (rad) */ - float getAngle(); + float getAngle() override; /** get current angular velocity (rad/s) **/ - float getVelocity(); + float getVelocity() override; /** * set current angle as zero angle * return the angle [rad] difference */ - float initRelativeZero(); + float initRelativeZero() override; /** * set absolute zero angle as zero angle * return the angle [rad] difference */ - float initAbsoluteZero(); + float initAbsoluteZero() override; /** returns 1 because it is the absolute sensor */ - int hasAbsoluteZero(); + int hasAbsoluteZero() override; /** returns 0 maning it doesn't need search for absolute zero */ - int needsAbsoluteZeroSearch(); + int needsAbsoluteZeroSearch() override; /** raw count (typically in range of 0-1023), useful for debugging resolution issues */ int raw_count; int min_raw_count; diff --git a/library_source/MagneticSensorI2C.cpp b/library_source/MagneticSensorI2C.cpp index eb94a753..a02b762b 100644 --- a/library_source/MagneticSensorI2C.cpp +++ b/library_source/MagneticSensorI2C.cpp @@ -1,5 +1,24 @@ #include "MagneticSensorI2C.h" +/** Typical configuration for the 12bit AMS AS5600 magnetic sensor over I2C interface */ +MagneticSensorI2CConfig_s AS5600_I2C = { + .chip_address = 0x36, + .clock_speed = 1000000, + .bit_resolution = 12, + .angle_register = 0x0E, + .data_start_bit = 11 +}; + +/** Typical configuration for the 12bit AMS AS5048 magnetic sensor over I2C interface */ +MagneticSensorI2CConfig_s AS5048_I2C = { + .chip_address = 0x40, // highly configurable. if A1 and A2 are held low, this is probable value + .clock_speed = 1000000, + .bit_resolution = 14, + .angle_register = 0xFE, + .data_start_bit = 15 +}; + + // MagneticSensorI2C(uint8_t _chip_address, float _cpr, uint8_t _angle_register_msb) // @param _chip_address I2C chip address // @param _bit_resolution bit resolution of the sensor @@ -22,13 +41,47 @@ MagneticSensorI2C::MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, // extraction masks lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); msb_mask = (uint8_t)( (2 << _bits_used_msb) - 1 ); + clock_speed = 400000; + sda_pin = SDA; + scl_pin = SCL; + } +MagneticSensorI2C::MagneticSensorI2C(MagneticSensorI2CConfig_s config){ + chip_address = config.chip_address; + + // angle read register of the magnetic sensor + angle_register_msb = config.angle_register; + // register maximum value (counts per revolution) + cpr = pow(2, config.bit_resolution); + + int bits_used_msb = config.data_start_bit - 7; + lsb_used = config.bit_resolution - bits_used_msb; + // extraction masks + lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); + msb_mask = (uint8_t)( (2 << bits_used_msb) - 1 ); + clock_speed = 400000; + sda_pin = SDA; + scl_pin = SCL; + +} void MagneticSensorI2C::init(){ +#if defined(_STM32_DEF_) // if stm chips + // I2C communication begin + Wire.begin(); + Wire.setClock(clock_speed); + Wire.setSCL(scl_pin); + Wire.setSDA(sda_pin); +#elif defined(ESP_H) // if esp32 //I2C communication begin - Wire.begin(); + Wire.begin(sda_pin, scl_pin, clock_speed); +#else + // I2C communication begin + Wire.begin(); + Wire.setClock(clock_speed); +#endif // velocity calculation init angle_prev = 0; diff --git a/library_source/MagneticSensorI2C.h b/library_source/MagneticSensorI2C.h index 91c9e7ca..88d74d35 100644 --- a/library_source/MagneticSensorI2C.h +++ b/library_source/MagneticSensorI2C.h @@ -7,6 +7,15 @@ #include "common/hardware_utils.h" #include "common/Sensor.h" +struct MagneticSensorI2CConfig_s { + int chip_address; + long clock_speed; + int bit_resolution; + int angle_register; + int data_start_bit; +}; +// some predefined structures +extern MagneticSensorI2CConfig_s AS5600_I2C,AS5048_I2C; class MagneticSensorI2C: public Sensor{ public: @@ -18,31 +27,47 @@ class MagneticSensorI2C: public Sensor{ * @param _bits_used_msb number of used bits in msb */ MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _msb_bits_used); - + /** + * MagneticSensorI2C class constructor + * @param config I2C config + */ + MagneticSensorI2C(MagneticSensorI2CConfig_s config); + + static MagneticSensorI2C AS5600(); + /** sensor initialise pins */ void init(); // implementation of abstract functions of the Sensor class /** get current angle (rad) */ - float getAngle(); + float getAngle() override; /** get current angular velocity (rad/s) **/ - float getVelocity(); + float getVelocity() override; /** * set current angle as zero angle * return the angle [rad] difference */ - float initRelativeZero(); + float initRelativeZero() override; /** * set absolute zero angle as zero angle * return the angle [rad] difference */ - float initAbsoluteZero(); + float initAbsoluteZero() override; /** returns 1 because it is the absolute sensor */ - int hasAbsoluteZero(); + int hasAbsoluteZero() override; /** returns 0 maning it doesn't need search for absolute zero */ - int needsAbsoluteZeroSearch(); + + int needsAbsoluteZeroSearch() override; + + /* the speed of the i2c clock signal */ + long clock_speed; + + /* the pin used for i2c data */ + int sda_pin; + /* the pin used for i2c clock */ + int scl_pin; private: float cpr; //!< Maximum range of the magnetic sensor diff --git a/library_source/MagneticSensorSPI.cpp b/library_source/MagneticSensorSPI.cpp index 79430b13..1f63bc11 100644 --- a/library_source/MagneticSensorSPI.cpp +++ b/library_source/MagneticSensorSPI.cpp @@ -1,33 +1,76 @@ #include "MagneticSensorSPI.h" +/** Typical configuration for the 14bit AMS AS5147 magnetic sensor over SPI interface */ +MagneticSensorSPIConfig_s AS5147_SPI = { + .spi_mode = SPI_MODE1, + .clock_speed = 1000000, + .bit_resolution = 14, + .angle_register = 0xCFFF, + .data_start_bit = 13, + .command_rw_bit = 14, + .command_parity_bit = 15 +}; + +/** Typical configuration for the 14bit MonolithicPower MA730 magnetic sensor over SPI interface */ +MagneticSensorSPIConfig_s MA730_SPI = { + .spi_mode = SPI_MODE0, + .clock_speed = 1000000, + .bit_resolution = 14, + .angle_register = 0x0000, + .data_start_bit = 15, + .command_rw_bit = 0, // not required + .command_parity_bit = 0 // parity not implemented +}; + + // MagneticSensorSPI(int cs, float _bit_resolution, int _angle_register) // cs - SPI chip select pin // _bit_resolution sensor resolution bit number // _angle_register - (optional) angle read register - default 0x3FFF MagneticSensorSPI::MagneticSensorSPI(int cs, float _bit_resolution, int _angle_register){ - // chip select pin + chip_select_pin = cs; // angle read register of the magnetic sensor angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTAR; // register maximum value (counts per revolution) cpr = pow(2,_bit_resolution); - + spi_mode = SPI_MODE1; + clock_speed = 1000000; + bit_resolution = _bit_resolution; + + command_parity_bit = 15; // for backwards compatibilty + command_rw_bit = 14; // for backwards compatibilty + data_start_bit = 13; // for backwards compatibilty + } +MagneticSensorSPI::MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs){ + chip_select_pin = cs; + // angle read register of the magnetic sensor + angle_register = config.angle_register ? config.angle_register : DEF_ANGLE_REGISTAR; + // register maximum value (counts per revolution) + cpr = pow(2, config.bit_resolution); + spi_mode = config.spi_mode; + clock_speed = config.clock_speed; + bit_resolution = config.bit_resolution; + + command_parity_bit = config.command_parity_bit; // for backwards compatibilty + command_rw_bit = config.command_rw_bit; // for backwards compatibilty + data_start_bit = config.data_start_bit; // for backwards compatibilty +} void MagneticSensorSPI::init(){ // 1MHz clock (AMS should be able to accept up to 10MHz) - settings = SPISettings(1000000, MSBFIRST, SPI_MODE1); + settings = SPISettings(clock_speed, MSBFIRST, spi_mode); //setup pins pinMode(chip_select_pin, OUTPUT); - //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices SPI.begin(); #ifndef ESP_H // if not ESP32 board SPI.setBitOrder(MSBFIRST); // Set the SPI_1 bit order - SPI.setDataMode(SPI_MODE1) ; + SPI.setDataMode(spi_mode) ; SPI.setClockDivider(SPI_CLOCK_DIV8); #endif @@ -77,7 +120,7 @@ float MagneticSensorSPI::getVelocity(){ float angle_c = getAngle(); // velocity calculation float vel = (angle_c - angle_prev)/Ts; - + // save variables for future pass angle_prev = angle_c; velocity_calc_timestamp = now_us; @@ -147,35 +190,28 @@ byte MagneticSensorSPI::spiCalcEvenParity(word value){ * Returns the value of the register */ word MagneticSensorSPI::read(word angle_register){ - word command = 0b0100000000000000; // PAR=0 R/W=R - command = command | angle_register; - //Add a parity bit on the the MSB - command |= ((word)spiCalcEvenParity(command)<<15); - - //Split the command into two bytes - byte right_byte = command & 0xFF; - byte left_byte = ( command >> 8 ) & 0xFF; + word command = angle_register; + if (command_rw_bit > 0) { + command = angle_register | (1 << command_rw_bit); + } + if (command_parity_bit > 0) { + //Add a parity bit on the the MSB + command |= ((word)spiCalcEvenParity(command) << command_parity_bit); + } #if !defined(_STM32_DEF_) // if not stm chips //SPI - begin transaction SPI.beginTransaction(settings); #endif - //SPI - begin transaction - //SPI.beginTransaction(settings); //Send the command digitalWrite(chip_select_pin, LOW); -#ifndef ESP_H // if not ESP32 board digitalWrite(chip_select_pin, LOW); -#endif - SPI.transfer(left_byte); - SPI.transfer(right_byte); + SPI.transfer16(command); digitalWrite(chip_select_pin,HIGH); -#ifndef ESP_H // if not ESP32 board digitalWrite(chip_select_pin,HIGH); -#endif #if defined( ESP_H ) // if ESP32 board delayMicroseconds(50); @@ -186,8 +222,7 @@ word MagneticSensorSPI::read(word angle_register){ //Now read the response digitalWrite(chip_select_pin, LOW); digitalWrite(chip_select_pin, LOW); - left_byte = SPI.transfer(0x00); - right_byte = SPI.transfer(0x00); + word register_value = SPI.transfer16(0x00); digitalWrite(chip_select_pin, HIGH); digitalWrite(chip_select_pin,HIGH); @@ -195,9 +230,12 @@ word MagneticSensorSPI::read(word angle_register){ //SPI - end transaction SPI.endTransaction(); #endif + + register_value = register_value >> (1 + data_start_bit - bit_resolution); //this should shift data to the rightmost bits of the word + + const static word data_mask = ~(0 >> (16 - bit_resolution)); - // Return the data, stripping the parity and error bits - return (( ( left_byte & 0xFF ) << 8 ) | ( right_byte & 0xFF )) & ~0xC000; + return register_value & data_mask; // Return the data, stripping the non data (e.g parity) bits } /** diff --git a/library_source/MagneticSensorSPI.h b/library_source/MagneticSensorSPI.h index 71c0dd02..8e884cf4 100644 --- a/library_source/MagneticSensorSPI.h +++ b/library_source/MagneticSensorSPI.h @@ -9,6 +9,18 @@ #define DEF_ANGLE_REGISTAR 0x3FFF +struct MagneticSensorSPIConfig_s { + int spi_mode; + long clock_speed; + int bit_resolution; + int angle_register; + int data_start_bit; + int command_rw_bit; + int command_parity_bit; +}; +// typical configuration structures +extern MagneticSensorSPIConfig_s AS5147_SPI, MA730_SPI; + class MagneticSensorSPI: public Sensor{ public: /** @@ -18,30 +30,42 @@ class MagneticSensorSPI: public Sensor{ * @param angle_register (optional) angle read register - default 0x3FFF */ MagneticSensorSPI(int cs, float bit_resolution, int angle_register = 0); - + /** + * MagneticSensorSPI class constructor + * @param config SPI config + * @param cs SPI chip select pin + */ + MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs); /** sensor initialise pins */ void init(); // implementation of abstract functions of the Sensor class /** get current angle (rad) */ - float getAngle(); + float getAngle() override; /** get current angular velocity (rad/s) **/ - float getVelocity(); + float getVelocity() override; /** * set current angle as zero angle * return the angle [rad] difference */ - float initRelativeZero(); + float initRelativeZero() override; /** * set absolute zero angle as zero angle * return the angle [rad] difference */ - float initAbsoluteZero(); + float initAbsoluteZero() override; /** returns 1 because it is the absolute sensor */ - int hasAbsoluteZero(); + int hasAbsoluteZero() override; /** returns 0 maning it doesn't need search for absolute zero */ - int needsAbsoluteZeroSearch(); + + int needsAbsoluteZeroSearch() override; + + // returns the spi mode (phase/polarity of read/writes) i.e one of SPI_MODE0 | SPI_MODE1 | SPI_MODE2 | SPI_MODE3 + int spi_mode; + + /* returns the speed of the SPI clock signal */ + long clock_speed; private: @@ -73,6 +97,11 @@ class MagneticSensorSPI: public Sensor{ // velocity calculation variables float angle_prev; //!< angle in previous velocity calculation step long velocity_calc_timestamp; //!< last velocity calculation timestamp + + int bit_resolution; //!< the number of bites of angle data + int command_parity_bit; //!< the bit where parity flag is stored in command + int command_rw_bit; //!< the bit where read/write flag is stored in command + int data_start_bit; //!< the the position of first bit }; diff --git a/library_source/SimpleFOC.h b/library_source/SimpleFOC.h new file mode 100644 index 00000000..5925e78d --- /dev/null +++ b/library_source/SimpleFOC.h @@ -0,0 +1,97 @@ +/*! + * @file SimpleFOC.h + * + * @mainpage Simple Field Oriented Control BLDC motor control library + * + * @section intro_sec Introduction + * + * Proper low-cost and low-power FOC supporting boards are very hard to find these days and even may not exist.
Even harder to find is a stable and simple FOC algorithm code capable of running on Arduino devices. Therefore this is an attempt to: + * - Demystify FOC algorithm and make a robust but simple Arduino library: Arduino SimpleFOC library + * - Develop a modular BLDC driver board: Arduino SimpleFOC shield. + * + * @section features Features + * - Arduino compatible: Arduino library code + * - Easy to setup and configure: + * - Easy hardware configuration + * - Easy tuning the control loops + * - Modular: + * - Supports as many sensors , BLDC motors and driver boards as possible + * - Supports as many application requirements as possible + * - Plug & play: Arduino SimpleFOC shield + * + * @section dependencies Supported Hardware + * + * This library supports any arduino device and it is especially optimized for Arduino UNO boards and + * other Atmega328 boards. But it supports Arrduinio MEGA boards and similar. + * + * From the version 1.3.0 it will support the STM32 boards such as Bluepill and Nucelo devices.
+ * The programming is done the same way as for the Arduino UNO but stm32 devices require STM32Duino package.
+ * You can download it directly from library manager. + * + * @section example_code Example code + * @code +#include + +// initialize the motor +BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); +// initialize the encoder +Encoder encoder = Encoder(2, 3, 2048); +// channel A and B callbacks +void doA(){encoder.handleA();} +void doB(){encoder.handleB();} + + +void setup() { + // initialize encoder hardware + encoder.init(); + // hardware interrupt enable + encoder.enableInterrupts(doA, doB); + + // set control loop type to be used + motor.controller = ControlType::velocity; + + // use monitoring with the BLDCMotor + Serial.begin(115200); + // monitoring port + motor.useMonitoring(Serial); + + // link the motor to the sensor + motor.linkSensor(&encoder); + + // initialize motor + motor.init(); + // align encoder and start FOC + motor.initFOC(); +} + +void loop() { + // FOC algorithm function + motor.loopFOC(); + + // velocity control loop function + // setting the target velocity or 2rad/s + motor.move(2); + + // monitoring function outputting motor variables to the serial terminal + motor.monitor(); +} + * @endcode + * + * @section license License + * + * MIT license, all text here must be included in any redistribution. + * + */ + +#ifndef SIMPLEFOC_H +#define SIMPLEFOC_H + +#include "BLDCMotor.h" +#include "StepperMotor.h" +#include "Encoder.h" +#include "MagneticSensorSPI.h" +#include "MagneticSensorI2C.h" +#include "MagneticSensorAnalog.h" +#include "HallSensor.h" + +#endif diff --git a/library_source/StepperMotor.cpp b/library_source/StepperMotor.cpp index fca6b1b1..22ceb256 100644 --- a/library_source/StepperMotor.cpp +++ b/library_source/StepperMotor.cpp @@ -21,7 +21,7 @@ StepperMotor::StepperMotor(int ph1A, int ph1B, int ph2A, int ph2B, int pp, int e } // init hardware pins -void StepperMotor::init() { +void StepperMotor::init(long pwm_frequency) { if(monitor_port) monitor_port->println("MOT: Init pins."); // PWM pins pinMode(pwm1A, OUTPUT); @@ -34,12 +34,16 @@ void StepperMotor::init() { if(monitor_port) monitor_port->println("MOT: PWM config."); // Increase PWM frequency // make silent - _setPwmFrequency(pwm1A, pwm1B, pwm2A, pwm2B); + _setPwmFrequency(pwm_frequency, pwm1A, pwm1B, pwm2A, pwm2B); // sanity check for the voltage limit configuration if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; // constrain voltage for sensor alignment if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + + // update the controller limits + PID_velocity.limit = voltage_limit; + P_angle.limit = velocity_limit; _delay(500); // enable motor diff --git a/library_source/StepperMotor.h b/library_source/StepperMotor.h index 8f10311f..bf14e096 100644 --- a/library_source/StepperMotor.h +++ b/library_source/StepperMotor.h @@ -32,11 +32,11 @@ class StepperMotor: public FOCMotor StepperMotor(int ph1A,int ph1B,int ph2A,int ph2B,int pp, int en1 = NOT_SET, int en2 = NOT_SET); /** Motor hardware init function */ - void init(); + void init(long pwm_frequency = NOT_SET) override; /** Motor disable function */ - void disable(); + void disable() override; /** Motor enable function */ - void enable(); + void enable() override; /** * Function initializing FOC algorithm @@ -48,14 +48,14 @@ class StepperMotor: public FOCMotor * @param sensor_direction sensor natural direction - default is CW * */ - int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW) override; /** * Function running FOC algorithm in real-time * it calculates the gets motor angle and sets the appropriate voltages * to the phase pwm signals * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us */ - void loopFOC(); + void loopFOC() override; /** * Function executing the control loops set by the controller parameter of the BLDCMotor. * @@ -64,7 +64,7 @@ class StepperMotor: public FOCMotor * * This function doesn't need to be run upon each loop execution - depends of the use case */ - void move(float target = NOT_SET); + void move(float target = NOT_SET) override; // hardware variables int pwm1A; //!< phase 1A pwm pin number diff --git a/library_source/common/FOCMotor.h b/library_source/common/FOCMotor.h index 11d566d4..40f7f6d4 100644 --- a/library_source/common/FOCMotor.h +++ b/library_source/common/FOCMotor.h @@ -42,7 +42,7 @@ class FOCMotor FOCMotor(); /** Motor hardware init function */ - virtual void init()=0; + virtual void init(long pwm_frequency)=0; /** Motor disable function */ virtual void disable()=0; /** Motor enable function */ diff --git a/library_source/common/defaults.h b/library_source/common/defaults.h index bbb48c6e..7448af04 100644 --- a/library_source/common/defaults.h +++ b/library_source/common/defaults.h @@ -4,14 +4,14 @@ #define DEF_POWER_SUPPLY 12.0 //!< default power supply voltage // velocity PI controller params #define DEF_PID_VEL_P 0.5 //!< default PID controller P value -#define DEF_PID_VEL_I 10 //!< default PID controller I value -#define DEF_PID_VEL_D 0 //!< default PID controller D value -#define DEF_PID_VEL_U_RAMP 1000 //!< default PID controller voltage ramp value +#define DEF_PID_VEL_I 10.0 //!< default PID controller I value +#define DEF_PID_VEL_D 0.0 //!< default PID controller D value +#define DEF_PID_VEL_U_RAMP 1000.0 //!< default PID controller voltage ramp value // angle P params -#define DEF_P_ANGLE_P 20 //!< default P controller P value -#define DEF_VEL_LIM 20 //!< angle velocity limit default +#define DEF_P_ANGLE_P 20.0 //!< default P controller P value +#define DEF_VEL_LIM 20.0 //!< angle velocity limit default // index search -#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 //!< default index search velocity +#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1.0 //!< default index search velocity // align voltage #define DEF_VOLTAGE_SENSOR_ALIGN 6.0 //!< default voltage for sensor and motor zero alignemt // low pass filter velocity diff --git a/library_source/common/hardware_utils.cpp b/library_source/common/hardware_utils.cpp index 802087a7..0d080bab 100644 --- a/library_source/common/hardware_utils.cpp +++ b/library_source/common/hardware_utils.cpp @@ -14,122 +14,176 @@ typedef struct { mcpwm_io_signals_t mcpwm_a; mcpwm_io_signals_t mcpwm_b; mcpwm_io_signals_t mcpwm_c; +} bldc_motor_slots_t; +typedef struct { + int pin1A; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_1a; + mcpwm_io_signals_t mcpwm_1b; + mcpwm_io_signals_t mcpwm_2a; + mcpwm_io_signals_t mcpwm_2b; +} stepper_motor_slots_t; -} motor_slots_t; - -// define motor slots array -motor_slots_t esp32_motor_slots[4] = { +// define bldc motor slots array +bldc_motor_slots_t esp32_bldc_motor_slots[4] = { {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B }; -#endif +// define stepper motor slots array +stepper_motor_slots_t esp32_stepper_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + }; +// configuring high frequency pwm timer +// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller +void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ -// function setting the high pwm frequency to the supplied pins -// - hardware speciffic -// supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(const int pinA, const int pinB, const int pinC, const int pinD) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips - // High PWM frequency + mcpwm_config_t pwm_config; + pwm_config.frequency = pwm_frequency; //frequency + pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% + pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + _delay(100); + + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); + mcpwm_num->clk_cfg.prescale = 0; + + mcpwm_num->timer[0].period.prescale = 4; + mcpwm_num->timer[1].period.prescale = 4; + mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + mcpwm_num->timer[0].period.period = 2048; + mcpwm_num->timer[1].period.period = 2048; + mcpwm_num->timer[2].period.period = 2048; + _delay(1); + mcpwm_num->timer[0].period.upmethod = 0; + mcpwm_num->timer[1].period.upmethod = 0; + mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 0; +} + +#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips +// set pwm frequency to 32KHz +void _pinHighFrequency(const int pin){ + // High PWM frequency // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pinA == 5 || pinA == 6 || pinB == 5 || pinB == 6 || pinC == 5 || pinC == 6 || pinD == 5 || pinD == 6 ) { + if (pin == 5 || pin == 6 ) { TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 } - if (pinA == 9 || pinA == 10 || pinB == 9 || pinB == 10 || pinC == 9 || pinC == 10|| pinD == 9 || pinD == 10 ) + if (pin == 9 || pin == 10 ) TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pinA == 3 || pinA == 11 || pinB == 3 || pinB == 11 || pinC == 3 || pinC == 11 || pinD == 3 || pinD == 11 ) + if (pin == 3 || pin == 11) TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 +} #elif defined(_STM32_DEF_) // if stm chips - - analogWrite(pinA, 0); - analogWriteFrequency(50000); // set 50kHz - analogWriteResolution(12); // resolution 12 bit 0 - 4096 - analogWrite(pinB, 0); - analogWriteFrequency(50000); // set 50kHz +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); analogWriteResolution(12); // resolution 12 bit 0 - 4096 - analogWrite(pinC, 0); - analogWriteFrequency(50000); // set 50kHz - analogWriteResolution(12); // resolution 12 bit 0 - 4096 - if(pinD) { - analogWrite(pinD, 0); - analogWriteFrequency(50000); // set 50kHz - analogWriteResolution(12); // resolution 12 bit 0 - 4096 - +} #elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards - analogWrite(pinA, 0); - analogWriteFrequency(pinA, 50000); // set 50kHz - analogWrite(pinB, 0); - analogWriteFrequency(pinB, 50000); // set 50kHz - analogWrite(pinC, 0); - analogWriteFrequency(pinC, 50000); // set 50kHz - if(pinD) { - analogWrite(pinD, 0); - analogWriteFrequency(50000); // set 50kHz +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); +} +#endif -#elif defined(ESP_H) // if esp32 boards - motor_slots_t m_slot = {}; +// function setting the high pwm frequency to the supplied pins +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); + _pinHighFrequency(pinC); + if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 4; i++){ - if(esp32_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_motor_slots[i].pinA = pinA; - m_slot = esp32_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); +#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards + if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor - mcpwm_config_t pwm_config; - pwm_config.frequency = 4000000; //frequency = 20000Hz - pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% - pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% - pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) - pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings +#elif defined(ESP_H) // if esp32 boards + if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency - _delay(100); + if(pinD == NOT_SET){ + bldc_motor_slots_t m_slot = {}; - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_0); - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_1); - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_2); - m_slot.mcpwm_num->clk_cfg.prescale = 0; + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_motor_slots[i].pinA = pinA; + m_slot = esp32_bldc_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); - m_slot.mcpwm_num->timer[0].period.prescale = 4; - m_slot.mcpwm_num->timer[1].period.prescale = 4; - m_slot.mcpwm_num->timer[2].period.prescale = 4; - _delay(1); - m_slot.mcpwm_num->timer[0].period.period = 2048; - m_slot.mcpwm_num->timer[1].period.period = 2048; - m_slot.mcpwm_num->timer[2].period.period = 2048; - _delay(1); - m_slot.mcpwm_num->timer[0].period.upmethod = 0; - m_slot.mcpwm_num->timer[1].period.upmethod = 0; - m_slot.mcpwm_num->timer[2].period.upmethod = 0; - _delay(1); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_0); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_1); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_2); + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); - _delay(1); - m_slot.mcpwm_num->timer[0].sync.out_sel = 1; - _delay(1); - m_slot.mcpwm_num->timer[0].sync.out_sel = 0; + }else{ + stepper_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_motor_slots[i].pin1A = pinA; + m_slot = esp32_stepper_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + } #endif } @@ -142,12 +196,12 @@ void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, in #if defined(ESP_H) // if ESP32 boards // determine which motor slot is the motor connected to for(int i = 0; i < 4; i++){ - if(esp32_motor_slots[i].pinA == pinA){ // if motor slot found + if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found // se the PWM on the slot timers // transform duty cycle from [0,1] to [0,2047] - esp32_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; - esp32_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; - esp32_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; break; } } @@ -171,7 +225,18 @@ void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, in // ESP32 uses MCPWM void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ #if defined(ESP_H) // if ESP32 boards - // not sure how to handle this + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; + break; + } + } #elif defined(_STM32_DEF_) // STM32 devices // transform duty cycle from [0,1] to [0,4095] analogWrite(pin1A, 4095.0*dc_1a); @@ -216,4 +281,4 @@ unsigned long _micros(){ // regular micros return micros(); #endif -} \ No newline at end of file +} diff --git a/library_source/common/hardware_utils.h b/library_source/common/hardware_utils.h index 03c44fdd..f99c260a 100644 --- a/library_source/common/hardware_utils.h +++ b/library_source/common/hardware_utils.h @@ -17,12 +17,13 @@ * High PWM frequency setting function * - hardware specific * - * @param pinA pinA number to configure - * @param pinB pinB number to configure - * @param pinC pinC number to configure - * @param pinD pinC number to configure + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc motor or pin1A stepper motor + * @param pinB pinB bldc motor or pin1B stepper motor + * @param pinC pinC bldc motor or pin2A stepper motor + * @param pinD pin2B stepper motor */ -void _setPwmFrequency(int pinA, int pinB, int pinC, int pinD = 0); +void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) @@ -35,7 +36,7 @@ void _setPwmFrequency(int pinA, int pinB, int pinC, int pinD = 0); * @param pinB phase B hardware pin number * @param pinC phase C hardware pin number */ -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) diff --git a/minimal_project_examples/arduino_foc_minimal_encoder1/arduino_foc_minimal_encoder.ino b/minimal_project_examples/arduino_foc_bldc_encoder/arduino_foc_bldc_encoder.ino similarity index 97% rename from minimal_project_examples/arduino_foc_minimal_encoder1/arduino_foc_minimal_encoder.ino rename to minimal_project_examples/arduino_foc_bldc_encoder/arduino_foc_bldc_encoder.ino index 49c35cbf..e7a8a26b 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder1/arduino_foc_minimal_encoder.ino +++ b/minimal_project_examples/arduino_foc_bldc_encoder/arduino_foc_bldc_encoder.ino @@ -36,11 +36,11 @@ * - 3: current target value * */ -#include "src/StepperMotor.h" +#include "src/BLDCMotor.h" #include "src/Encoder.h" // motor instance -StepperMotor motor = StepperMotor(10, 6, 5, 9, 50, 8); +BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 7); // // encoder instance Encoder encoder = Encoder(2,3, 2048); diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_bldc_encoder/src/BLDCMotor.cpp similarity index 98% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/BLDCMotor.cpp rename to minimal_project_examples/arduino_foc_bldc_encoder/src/BLDCMotor.cpp index 893ac81a..989b74a9 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/BLDCMotor.cpp +++ b/minimal_project_examples/arduino_foc_bldc_encoder/src/BLDCMotor.cpp @@ -21,7 +21,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) // init hardware pins -void BLDCMotor::init() { +void BLDCMotor::init(long pwm_frequency) { if(monitor_port) monitor_port->println("MOT: Init pins."); // PWM pins pinMode(pwmA, OUTPUT); @@ -32,19 +32,21 @@ void BLDCMotor::init() { if(monitor_port) monitor_port->println("MOT: PWM config."); // Increase PWM frequency to 32 kHz // make silent - _setPwmFrequency(pwmA, pwmB, pwmC); + _setPwmFrequency(pwm_frequency, pwmA, pwmB, pwmC); // sanity check for the voltage limit configuration if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; // constrain voltage for sensor alignment if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + // update the controller limits + PID_velocity.limit = voltage_limit; + P_angle.limit = velocity_limit; _delay(500); // enable motor if(monitor_port) monitor_port->println("MOT: Enable."); enable(); _delay(500); - } diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/BLDCMotor.h b/minimal_project_examples/arduino_foc_bldc_encoder/src/BLDCMotor.h similarity index 93% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/BLDCMotor.h rename to minimal_project_examples/arduino_foc_bldc_encoder/src/BLDCMotor.h index 6d597c9a..a4fbb678 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/BLDCMotor.h +++ b/minimal_project_examples/arduino_foc_bldc_encoder/src/BLDCMotor.h @@ -31,24 +31,24 @@ class BLDCMotor: public FOCMotor BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); /** Motor hardware init function */ - void init(); + void init(long pwm_frequency = NOT_SET) override; /** Motor disable function */ - void disable(); + void disable() override; /** Motor enable function */ - void enable(); + void enable() override; /** * Function initializing FOC algorithm * and aligning sensor's and motors' zero position */ - int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW) override; /** * Function running FOC algorithm in real-time * it calculates the gets motor angle and sets the appropriate voltages * to the phase pwm signals * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us */ - void loopFOC(); + void loopFOC() override; /** * Function executing the control loops set by the controller parameter of the BLDCMotor. @@ -58,7 +58,7 @@ class BLDCMotor: public FOCMotor * * This function doesn't need to be run upon each loop execution - depends of the use case */ - void move(float target = NOT_SET); + void move(float target = NOT_SET) override; // hardware variables int pwmA; //!< phase A pwm pin number diff --git a/minimal_project_examples/arduino_foc_minimal_encoder1/src/Encoder.cpp b/minimal_project_examples/arduino_foc_bldc_encoder/src/Encoder.cpp similarity index 96% rename from minimal_project_examples/arduino_foc_minimal_encoder1/src/Encoder.cpp rename to minimal_project_examples/arduino_foc_bldc_encoder/src/Encoder.cpp index f5ab90cb..1965c015 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder1/src/Encoder.cpp +++ b/minimal_project_examples/arduino_foc_bldc_encoder/src/Encoder.cpp @@ -9,7 +9,7 @@ */ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ - + // Encoder measurement structure init // hardware pins pinA = _encA; @@ -87,11 +87,11 @@ void Encoder::handleIndex() { if(hasIndex()){ int I = digitalRead(index_pin); if(I && !I_active){ - // align encoder on each index + // align encoder on each index if(index_pulse_counter){ long tmp = pulse_counter; // corrent the counter value - pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; + pulse_counter = round((double)pulse_counter/(double)cpr)*cpr; // preserve relative speed prev_pulse_counter += pulse_counter - tmp; } else { @@ -119,8 +119,8 @@ float Encoder::getVelocity(){ // sampling time calculation float Ts = (timestamp_us - prev_timestamp_us) * 1e-6; // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + // time from last impulse float Th = (timestamp_us - pulse_timestamp) * 1e-6; long dN = pulse_counter - prev_pulse_counter; @@ -133,7 +133,7 @@ float Encoder::getVelocity(){ // only increment if some impulses received float dt = Ts + prev_Th - Th; pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second; - + // if more than 0.05 passed in between impulses if ( Th > 0.1) pulse_per_second = 0; @@ -176,10 +176,10 @@ int Encoder::hasIndex(){ } -// encoder initialisation of the hardware pins +// encoder initialisation of the hardware pins // and calculation variables void Encoder::init(){ - + // Encoder - check if pullup needed for your encoder if(pullup == Pullup::INTERN){ pinMode(pinA, INPUT_PULLUP); @@ -190,7 +190,7 @@ void Encoder::init(){ pinMode(pinB, INPUT); if(hasIndex()) pinMode(index_pin,INPUT); } - + // counter setup pulse_counter = 0; pulse_timestamp = _micros(); @@ -222,7 +222,7 @@ void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){ if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); break; } - + // if index used initialize the index interrupt if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE); } diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/Encoder.h b/minimal_project_examples/arduino_foc_bldc_encoder/src/Encoder.h similarity index 93% rename from minimal_project_examples/arduino_foc_minimal_encoder/src/Encoder.h rename to minimal_project_examples/arduino_foc_bldc_encoder/src/Encoder.h index db9813b8..d1a55f0e 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder/src/Encoder.h +++ b/minimal_project_examples/arduino_foc_bldc_encoder/src/Encoder.h @@ -60,31 +60,31 @@ class Encoder: public Sensor{ // Abstract functions of the Sensor class implementation /** get current angle (rad) */ - float getAngle(); + float getAngle() override; /** get current angular velocity (rad/s) */ - float getVelocity(); + float getVelocity() override; /** * set current angle as zero angle * return the angle [rad] difference */ - float initRelativeZero(); + float initRelativeZero() override; /** * set index angle as zero angle * return the angle [rad] difference */ - float initAbsoluteZero(); + float initAbsoluteZero() override; /** * returns 0 if it has no index * 0 - encoder without index * 1 - encoder with index */ - int hasAbsoluteZero(); + int hasAbsoluteZero() override; /** * returns 0 if it does need search for absolute zero * 0 - encoder without index * 1 - ecoder with index */ - int needsAbsoluteZeroSearch(); + int needsAbsoluteZeroSearch() override; private: int hasIndex(); //!< function returning 1 if encoder has index pin and 0 if not. diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/FOCMotor.cpp b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/FOCMotor.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_encoder/src/common/FOCMotor.cpp rename to minimal_project_examples/arduino_foc_bldc_encoder/src/common/FOCMotor.cpp diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/FOCMotor.h b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/FOCMotor.h similarity index 99% rename from minimal_project_examples/arduino_foc_minimal_encoder/src/common/FOCMotor.h rename to minimal_project_examples/arduino_foc_bldc_encoder/src/common/FOCMotor.h index 11d566d4..40f7f6d4 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/FOCMotor.h +++ b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/FOCMotor.h @@ -42,7 +42,7 @@ class FOCMotor FOCMotor(); /** Motor hardware init function */ - virtual void init()=0; + virtual void init(long pwm_frequency)=0; /** Motor disable function */ virtual void disable()=0; /** Motor enable function */ diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/Sensor.h b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/Sensor.h similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_encoder/src/common/Sensor.h rename to minimal_project_examples/arduino_foc_bldc_encoder/src/common/Sensor.h diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/defaults.h b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/defaults.h similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/defaults.h rename to minimal_project_examples/arduino_foc_bldc_encoder/src/common/defaults.h diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/foc_utils.cpp b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/foc_utils.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_encoder/src/common/foc_utils.cpp rename to minimal_project_examples/arduino_foc_bldc_encoder/src/common/foc_utils.cpp diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/foc_utils.h b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/foc_utils.h similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_encoder/src/common/foc_utils.h rename to minimal_project_examples/arduino_foc_bldc_encoder/src/common/foc_utils.h diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/hardware_utils.cpp new file mode 100644 index 00000000..0d080bab --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/hardware_utils.cpp @@ -0,0 +1,284 @@ +#include "hardware_utils.h" + +#if defined(ESP_H) // if ESP32 board +// empty motor slot +#define _EMPTY_SLOT -20 + +// structure containing motor slot configuration +// this library supports up to 4 motors +typedef struct { + int pinA; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; + mcpwm_io_signals_t mcpwm_c; +} bldc_motor_slots_t; +typedef struct { + int pin1A; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_1a; + mcpwm_io_signals_t mcpwm_1b; + mcpwm_io_signals_t mcpwm_2a; + mcpwm_io_signals_t mcpwm_2b; +} stepper_motor_slots_t; + +// define bldc motor slots array +bldc_motor_slots_t esp32_bldc_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B + }; + +// define stepper motor slots array +stepper_motor_slots_t esp32_stepper_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + }; + +// configuring high frequency pwm timer +// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller +void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ + + mcpwm_config_t pwm_config; + pwm_config.frequency = pwm_frequency; //frequency + pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% + pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + _delay(100); + + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); + mcpwm_num->clk_cfg.prescale = 0; + + mcpwm_num->timer[0].period.prescale = 4; + mcpwm_num->timer[1].period.prescale = 4; + mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + mcpwm_num->timer[0].period.period = 2048; + mcpwm_num->timer[1].period.period = 2048; + mcpwm_num->timer[2].period.period = 2048; + _delay(1); + mcpwm_num->timer[0].period.upmethod = 0; + mcpwm_num->timer[1].period.upmethod = 0; + mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 0; +} + +#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips +// set pwm frequency to 32KHz +void _pinHighFrequency(const int pin){ + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pin == 5 || pin == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pin == 9 || pin == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pin == 3 || pin == 11) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +} +#elif defined(_STM32_DEF_) // if stm chips +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); + analogWriteResolution(12); // resolution 12 bit 0 - 4096 +} +#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); +} +#endif + + +// function setting the high pwm frequency to the supplied pins +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); + _pinHighFrequency(pinC); + if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor + +#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards + if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor + +#elif defined(ESP_H) // if esp32 boards + if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency + + if(pinD == NOT_SET){ + bldc_motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_motor_slots[i].pinA = pinA; + m_slot = esp32_bldc_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + + }else{ + stepper_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_motor_slots[i].pin1A = pinA; + m_slot = esp32_stepper_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + } +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pinA, 4095.0*dc_a); + analogWrite(pinB, 4095.0*dc_b); + analogWrite(pinC, 4095.0*dc_c); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255*dc_a); + analogWrite(pinB, 255*dc_b); + analogWrite(pinC, 255*dc_c); +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pin1A, 4095.0*dc_1a); + analogWrite(pin1B, 4095.0*dc_1b); + analogWrite(pin2A, 4095.0*dc_2a); + analogWrite(pin2B, 4095.0*dc_2b); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255*dc_1a); + analogWrite(pin1B, 255*dc_1b); + analogWrite(pin2A, 255*dc_2a); + analogWrite(pin2B, 255*dc_2b); +#endif +} + + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/hardware_utils.h b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/hardware_utils.h similarity index 80% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/hardware_utils.h rename to minimal_project_examples/arduino_foc_bldc_encoder/src/common/hardware_utils.h index 03c44fdd..f99c260a 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/hardware_utils.h +++ b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/hardware_utils.h @@ -17,12 +17,13 @@ * High PWM frequency setting function * - hardware specific * - * @param pinA pinA number to configure - * @param pinB pinB number to configure - * @param pinC pinC number to configure - * @param pinD pinC number to configure + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc motor or pin1A stepper motor + * @param pinB pinB bldc motor or pin1B stepper motor + * @param pinC pinC bldc motor or pin2A stepper motor + * @param pinD pin2B stepper motor */ -void _setPwmFrequency(int pinA, int pinB, int pinC, int pinD = 0); +void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) @@ -35,7 +36,7 @@ void _setPwmFrequency(int pinA, int pinB, int pinC, int pinD = 0); * @param pinB phase B hardware pin number * @param pinC phase C hardware pin number */ -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/lowpass_filter.cpp b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/lowpass_filter.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_encoder/src/common/lowpass_filter.cpp rename to minimal_project_examples/arduino_foc_bldc_encoder/src/common/lowpass_filter.cpp diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/lowpass_filter.h b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/lowpass_filter.h similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_encoder/src/common/lowpass_filter.h rename to minimal_project_examples/arduino_foc_bldc_encoder/src/common/lowpass_filter.h diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/pid.cpp b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/pid.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_encoder/src/common/pid.cpp rename to minimal_project_examples/arduino_foc_bldc_encoder/src/common/pid.cpp diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/pid.h b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/pid.h similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_encoder/src/common/pid.h rename to minimal_project_examples/arduino_foc_bldc_encoder/src/common/pid.h diff --git a/minimal_project_examples/arduino_foc_minimal_hall/arduino_foc_minimal_hall.ino b/minimal_project_examples/arduino_foc_bldc_hall/arduino_foc_bldc_hall.ino similarity index 98% rename from minimal_project_examples/arduino_foc_minimal_hall/arduino_foc_minimal_hall.ino rename to minimal_project_examples/arduino_foc_bldc_hall/arduino_foc_bldc_hall.ino index d06cb7a3..796ea01e 100644 --- a/minimal_project_examples/arduino_foc_minimal_hall/arduino_foc_minimal_hall.ino +++ b/minimal_project_examples/arduino_foc_bldc_hall/arduino_foc_bldc_hall.ino @@ -36,8 +36,8 @@ * - 3: current target value * */ -#include "BLDCMotor.h" -#include "HallSensor.h" +#include "src/BLDCMotor.h" +#include "src/HallSensor.h" // software interrupt library #include diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_bldc_hall/src/BLDCMotor.cpp new file mode 100644 index 00000000..989b74a9 --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_hall/src/BLDCMotor.cpp @@ -0,0 +1,378 @@ +#include "BLDCMotor.h" + +// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - phA, phB, phC - motor A,B,C phase pwm pins +// - pp - pole pair number +// - cpr - counts per rotation number (cpm=ppm*4) +// - enable pin - (optional input) +BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +: FOCMotor() +{ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + pole_pairs = pp; + + // enable_pin pin + enable_pin = en; + +} + + +// init hardware pins +void BLDCMotor::init(long pwm_frequency) { + if(monitor_port) monitor_port->println("MOT: Init pins."); + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); + + if(monitor_port) monitor_port->println("MOT: PWM config."); + // Increase PWM frequency to 32 kHz + // make silent + _setPwmFrequency(pwm_frequency, pwmA, pwmB, pwmC); + + // sanity check for the voltage limit configuration + if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + // update the controller limits + PID_velocity.limit = voltage_limit; + P_angle.limit = velocity_limit; + + _delay(500); + // enable motor + if(monitor_port) monitor_port->println("MOT: Enable."); + enable(); + _delay(500); +} + + +// disable motor driver +void BLDCMotor::disable() +{ + // disable the driver - if enable_pin pin available + if (enable_pin != NOT_SET) digitalWrite(enable_pin, LOW); + // set zero to PWM + setPwm(0, 0, 0); +} +// enable motor driver +void BLDCMotor::enable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // enable_pin the driver - if enable_pin pin available + if (enable_pin != NOT_SET) digitalWrite(enable_pin, HIGH); + +} + +/** + FOC functions +*/ +// FOC initialization function +int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } + if(monitor_port) monitor_port->println("MOT: Motor ready."); + + return exit_flag; +} +// Encoder alignment to electrical 0 angle +int BLDCMotor::alignSensor() { + if(monitor_port) monitor_port->println("MOT: Align sensor."); + // align the electrical phases of the motor and sensor + // set angle -90 degrees + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } + + // let the motor stabilize for 2 sec + _delay(2000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0,0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int BLDCMotor::absoluteZeroAlign() { + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); + + // align absolute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = _normalizeAngle(_electricalAngle(zero_offset, pole_pairs)); + } + // return bool if zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void BLDCMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); +} + +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function +// - if target is not set it uses motor.target value +void BLDCMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; + // get angular velocity + shaft_velocity = shaftVelocity(); + // choose control loop + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = P_angle( shaft_angle_sp - shaft_angle ); + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // include velocity loop + shaft_velocity_sp = target; + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); + break; + } +} + + +// Method using FOC to set Uq to the motor at the optimal angle +// Function implementing Space Vector PWM and Sine PWM algorithms +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) +void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { + switch (foc_modulation) + { + case FOCModulationType::SinePWM : + // Sinusoidal PWM modulation + // Inverse Park + Clarke transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + + // Clarke transform + Ua = Ualpha + voltage_power_supply/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + break; + + case FOCModulationType::SpaceVectorPWM : + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // https://www.youtube.com/watch?v=QMSWUMEAejg + + // if negative voltages change inverse the phase + // angle + 180degrees + if(Uq < 0) angle_el += _PI; + Uq = abs(Uq); + + // angle normalisation in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle + _PI_2); + + // find the sector we are in currently + int sector = floor(angle_el / _PI_3) + 1; + // calculate the duty cycles + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; + // two versions possible + // centered around voltage_power_supply/2 + float T0 = 1 - T1 - T2; + // pulled to 0 - better for low power supply voltage + //float T0 = 0; + + // calculate the duty cycles(times) + float Ta,Tb,Tc; + switch(sector){ + case 1: + Ta = T1 + T2 + T0/2; + Tb = T2 + T0/2; + Tc = T0/2; + break; + case 2: + Ta = T1 + T0/2; + Tb = T1 + T2 + T0/2; + Tc = T0/2; + break; + case 3: + Ta = T0/2; + Tb = T1 + T2 + T0/2; + Tc = T2 + T0/2; + break; + case 4: + Ta = T0/2; + Tb = T1+ T0/2; + Tc = T1 + T2 + T0/2; + break; + case 5: + Ta = T2 + T0/2; + Tb = T0/2; + Tc = T1 + T2 + T0/2; + break; + case 6: + Ta = T1 + T2 + T0/2; + Tb = T0/2; + Tc = T1 + T0/2; + break; + default: + // possible error state + Ta = 0; + Tb = 0; + Tc = 0; + } + + // calculate the phase voltages and center + Ua = Ta*voltage_power_supply; + Ub = Tb*voltage_power_supply; + Uc = Tc*voltage_power_supply; + break; + } + + // set the voltages in hardware + setPwm(Ua, Ub, Uc); +} + + + +// Set voltage to the pwm pin +void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { + // calculate duty cycle + // limited in [0,1] + float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); + // hardware specific writing + _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); +} + + + +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void BLDCMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void BLDCMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/BLDCMotor.h b/minimal_project_examples/arduino_foc_bldc_hall/src/BLDCMotor.h new file mode 100644 index 00000000..a4fbb678 --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_hall/src/BLDCMotor.h @@ -0,0 +1,113 @@ +/** + * @file BLDCMotor.h + * + */ + +#ifndef BLDCMotor_h +#define BLDCMotor_h + +#include "Arduino.h" +#include "common/FOCMotor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" +#include "common/defaults.h" + +/** + BLDC motor class +*/ +class BLDCMotor: public FOCMotor +{ + public: + /** + BLDCMotor class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param pp pole pair number + @param cpr counts per rotation number (cpm=ppm*4) + @param en enable pin (optional input) + */ + BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + + /** Motor hardware init function */ + void init(long pwm_frequency = NOT_SET) override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + */ + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW) override; + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + void loopFOC() override; + + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET) override; + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + + private: + // FOC methods + /** + * Method using FOC to set Uq to the motor at the optimal angle + * Heart of the FOC algorithm + * + * @param Uq Current voltage in q axis to set to the motor + * @param angle_el current electrical angle of the motor + */ + void setPhaseVoltage(float Uq, float angle_el); + /** Sensor alignment to electrical 0 angle of the motor */ + int alignSensor(); + /** Motor and sensor alignment to the sensors absolute 0 angle */ + int absoluteZeroAlign(); + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + * @param Uc phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc); + + // Open loop motion control + /** + * Function (iterative) generating open loop movement for target velocity + * it uses voltage_limit variable + * + * @param target_velocity - rad/s + */ + void velocityOpenloop(float target_velocity); + /** + * Function (iterative) generating open loop movement towards the target angle + * it uses voltage_limit and velocity_limit variables + * + * @param target_angle - rad + */ + void angleOpenloop(float target_angle); + // open loop variables + long open_loop_timestamp; +}; + + +#endif diff --git a/minimal_project_examples/arduino_foc_minimal_hall/HallSensor.cpp b/minimal_project_examples/arduino_foc_bldc_hall/src/HallSensor.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_hall/HallSensor.cpp rename to minimal_project_examples/arduino_foc_bldc_hall/src/HallSensor.cpp diff --git a/minimal_project_examples/arduino_foc_minimal_hall/HallSensor.h b/minimal_project_examples/arduino_foc_bldc_hall/src/HallSensor.h similarity index 88% rename from minimal_project_examples/arduino_foc_minimal_hall/HallSensor.h rename to minimal_project_examples/arduino_foc_bldc_hall/src/HallSensor.h index 018426f9..9b467b0a 100644 --- a/minimal_project_examples/arduino_foc_minimal_hall/HallSensor.h +++ b/minimal_project_examples/arduino_foc_bldc_hall/src/HallSensor.h @@ -2,17 +2,18 @@ #define HALL_SENSOR_LIB_H #include "Arduino.h" -#include "FOCutils.h" -#include "Sensor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" class HallSensor: public Sensor{ public: /** HallSensor class constructor - @param encA HallSensor B pin + @param encA HallSensor A pin @param encB HallSensor B pin - @param encC HallSensor B pin + @param encC HallSensor C pin @param pp pole pairs (e.g hoverboard motor has 15pp and small gimbals often have 7pp) @param index index pin number (optional input) */ @@ -51,31 +52,31 @@ class HallSensor: public Sensor{ // Abstract functions of the Sensor class implementation /** get current angle (rad) */ - float getAngle(); + float getAngle() override; /** get current angular velocity (rad/s) */ - float getVelocity(); + float getVelocity() override; /** * set current angle as zero angle * return the angle [rad] difference */ - float initRelativeZero(); + float initRelativeZero() override; /** * set index angle as zero angle * return the angle [rad] difference */ - float initAbsoluteZero(); + float initAbsoluteZero() override; /** * returns 0 if it has no index * 0 - HallSensor without index * 1 - HallSensor with index */ - int hasAbsoluteZero(); + int hasAbsoluteZero() override; /** * returns 0 if it does need search for absolute zero * 0 - HallSensor without index * 1 - ecoder with index */ - int needsAbsoluteZeroSearch(); + int needsAbsoluteZeroSearch() override; // whether last step was CW (+1) or CCW (-1) direction Direction direction; diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/FOCMotor.cpp b/minimal_project_examples/arduino_foc_bldc_hall/src/common/FOCMotor.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/FOCMotor.cpp rename to minimal_project_examples/arduino_foc_bldc_hall/src/common/FOCMotor.cpp diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/FOCMotor.h b/minimal_project_examples/arduino_foc_bldc_hall/src/common/FOCMotor.h similarity index 99% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/FOCMotor.h rename to minimal_project_examples/arduino_foc_bldc_hall/src/common/FOCMotor.h index 11d566d4..40f7f6d4 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/FOCMotor.h +++ b/minimal_project_examples/arduino_foc_bldc_hall/src/common/FOCMotor.h @@ -42,7 +42,7 @@ class FOCMotor FOCMotor(); /** Motor hardware init function */ - virtual void init()=0; + virtual void init(long pwm_frequency)=0; /** Motor disable function */ virtual void disable()=0; /** Motor enable function */ diff --git a/minimal_project_examples/arduino_foc_minimal_encoder1/src/common/Sensor.h b/minimal_project_examples/arduino_foc_bldc_hall/src/common/Sensor.h similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_encoder1/src/common/Sensor.h rename to minimal_project_examples/arduino_foc_bldc_hall/src/common/Sensor.h diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/defaults.h b/minimal_project_examples/arduino_foc_bldc_hall/src/common/defaults.h similarity index 54% rename from minimal_project_examples/arduino_foc_minimal_encoder/src/common/defaults.h rename to minimal_project_examples/arduino_foc_bldc_hall/src/common/defaults.h index bbb48c6e..7448af04 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/defaults.h +++ b/minimal_project_examples/arduino_foc_bldc_hall/src/common/defaults.h @@ -4,14 +4,14 @@ #define DEF_POWER_SUPPLY 12.0 //!< default power supply voltage // velocity PI controller params #define DEF_PID_VEL_P 0.5 //!< default PID controller P value -#define DEF_PID_VEL_I 10 //!< default PID controller I value -#define DEF_PID_VEL_D 0 //!< default PID controller D value -#define DEF_PID_VEL_U_RAMP 1000 //!< default PID controller voltage ramp value +#define DEF_PID_VEL_I 10.0 //!< default PID controller I value +#define DEF_PID_VEL_D 0.0 //!< default PID controller D value +#define DEF_PID_VEL_U_RAMP 1000.0 //!< default PID controller voltage ramp value // angle P params -#define DEF_P_ANGLE_P 20 //!< default P controller P value -#define DEF_VEL_LIM 20 //!< angle velocity limit default +#define DEF_P_ANGLE_P 20.0 //!< default P controller P value +#define DEF_VEL_LIM 20.0 //!< angle velocity limit default // index search -#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 //!< default index search velocity +#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1.0 //!< default index search velocity // align voltage #define DEF_VOLTAGE_SENSOR_ALIGN 6.0 //!< default voltage for sensor and motor zero alignemt // low pass filter velocity diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/foc_utils.cpp b/minimal_project_examples/arduino_foc_bldc_hall/src/common/foc_utils.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/foc_utils.cpp rename to minimal_project_examples/arduino_foc_bldc_hall/src/common/foc_utils.cpp diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/foc_utils.h b/minimal_project_examples/arduino_foc_bldc_hall/src/common/foc_utils.h similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/foc_utils.h rename to minimal_project_examples/arduino_foc_bldc_hall/src/common/foc_utils.h diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_bldc_hall/src/common/hardware_utils.cpp new file mode 100644 index 00000000..0d080bab --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_hall/src/common/hardware_utils.cpp @@ -0,0 +1,284 @@ +#include "hardware_utils.h" + +#if defined(ESP_H) // if ESP32 board +// empty motor slot +#define _EMPTY_SLOT -20 + +// structure containing motor slot configuration +// this library supports up to 4 motors +typedef struct { + int pinA; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; + mcpwm_io_signals_t mcpwm_c; +} bldc_motor_slots_t; +typedef struct { + int pin1A; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_1a; + mcpwm_io_signals_t mcpwm_1b; + mcpwm_io_signals_t mcpwm_2a; + mcpwm_io_signals_t mcpwm_2b; +} stepper_motor_slots_t; + +// define bldc motor slots array +bldc_motor_slots_t esp32_bldc_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B + }; + +// define stepper motor slots array +stepper_motor_slots_t esp32_stepper_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + }; + +// configuring high frequency pwm timer +// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller +void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ + + mcpwm_config_t pwm_config; + pwm_config.frequency = pwm_frequency; //frequency + pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% + pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + _delay(100); + + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); + mcpwm_num->clk_cfg.prescale = 0; + + mcpwm_num->timer[0].period.prescale = 4; + mcpwm_num->timer[1].period.prescale = 4; + mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + mcpwm_num->timer[0].period.period = 2048; + mcpwm_num->timer[1].period.period = 2048; + mcpwm_num->timer[2].period.period = 2048; + _delay(1); + mcpwm_num->timer[0].period.upmethod = 0; + mcpwm_num->timer[1].period.upmethod = 0; + mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 0; +} + +#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips +// set pwm frequency to 32KHz +void _pinHighFrequency(const int pin){ + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pin == 5 || pin == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pin == 9 || pin == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pin == 3 || pin == 11) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +} +#elif defined(_STM32_DEF_) // if stm chips +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); + analogWriteResolution(12); // resolution 12 bit 0 - 4096 +} +#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); +} +#endif + + +// function setting the high pwm frequency to the supplied pins +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); + _pinHighFrequency(pinC); + if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor + +#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards + if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor + +#elif defined(ESP_H) // if esp32 boards + if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency + + if(pinD == NOT_SET){ + bldc_motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_motor_slots[i].pinA = pinA; + m_slot = esp32_bldc_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + + }else{ + stepper_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_motor_slots[i].pin1A = pinA; + m_slot = esp32_stepper_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + } +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pinA, 4095.0*dc_a); + analogWrite(pinB, 4095.0*dc_b); + analogWrite(pinC, 4095.0*dc_c); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255*dc_a); + analogWrite(pinB, 255*dc_b); + analogWrite(pinC, 255*dc_c); +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pin1A, 4095.0*dc_1a); + analogWrite(pin1B, 4095.0*dc_1b); + analogWrite(pin2A, 4095.0*dc_2a); + analogWrite(pin2B, 4095.0*dc_2b); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255*dc_1a); + analogWrite(pin1B, 255*dc_1b); + analogWrite(pin2A, 255*dc_2a); + analogWrite(pin2B, 255*dc_2b); +#endif +} + + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/hardware_utils.h b/minimal_project_examples/arduino_foc_bldc_hall/src/common/hardware_utils.h similarity index 80% rename from minimal_project_examples/arduino_foc_minimal_encoder/src/common/hardware_utils.h rename to minimal_project_examples/arduino_foc_bldc_hall/src/common/hardware_utils.h index 03c44fdd..f99c260a 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/hardware_utils.h +++ b/minimal_project_examples/arduino_foc_bldc_hall/src/common/hardware_utils.h @@ -17,12 +17,13 @@ * High PWM frequency setting function * - hardware specific * - * @param pinA pinA number to configure - * @param pinB pinB number to configure - * @param pinC pinC number to configure - * @param pinD pinC number to configure + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc motor or pin1A stepper motor + * @param pinB pinB bldc motor or pin1B stepper motor + * @param pinC pinC bldc motor or pin2A stepper motor + * @param pinD pin2B stepper motor */ -void _setPwmFrequency(int pinA, int pinB, int pinC, int pinD = 0); +void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) @@ -35,7 +36,7 @@ void _setPwmFrequency(int pinA, int pinB, int pinC, int pinD = 0); * @param pinB phase B hardware pin number * @param pinC phase C hardware pin number */ -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/lowpass_filter.cpp b/minimal_project_examples/arduino_foc_bldc_hall/src/common/lowpass_filter.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/lowpass_filter.cpp rename to minimal_project_examples/arduino_foc_bldc_hall/src/common/lowpass_filter.cpp diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/lowpass_filter.h b/minimal_project_examples/arduino_foc_bldc_hall/src/common/lowpass_filter.h similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/lowpass_filter.h rename to minimal_project_examples/arduino_foc_bldc_hall/src/common/lowpass_filter.h diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/pid.cpp b/minimal_project_examples/arduino_foc_bldc_hall/src/common/pid.cpp similarity index 97% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/pid.cpp rename to minimal_project_examples/arduino_foc_bldc_hall/src/common/pid.cpp index 316d88f2..277e17ce 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/pid.cpp +++ b/minimal_project_examples/arduino_foc_bldc_hall/src/common/pid.cpp @@ -29,7 +29,7 @@ float PIDController::operator() (float error){ // Tustin transform of the integral part // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) float integral = integral_prev + I*Ts*0.5*(error + error_prev); - // antiwindup - limit the integral value + // antiwindup - limit the output voltage_q integral = constrain(integral, -limit, limit); // Discrete derivation // u_dk = D(ek - ek_1)/Ts @@ -37,6 +37,8 @@ float PIDController::operator() (float error){ // sum all the components float output = proportional + integral + derivative; + // antiwindup - limit the output variable + output = constrain(output, -limit, limit); // limit the acceleration by ramping the output float output_rate = (output - output_prev)/Ts; @@ -45,9 +47,6 @@ float PIDController::operator() (float error){ else if (output_rate < -output_ramp) output = output_prev - output_ramp*Ts; - // antiwindup - limit the output variable - output = constrain(output, -limit, limit); - // saving for the next pass integral_prev = integral; output_prev = output; diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/pid.h b/minimal_project_examples/arduino_foc_bldc_hall/src/common/pid.h similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/pid.h rename to minimal_project_examples/arduino_foc_bldc_hall/src/common/pid.h diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/arduino_foc_minimal_magnetic_i2c.ino b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/arduino_foc_bldc_magnetic_i2c.ino similarity index 100% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/arduino_foc_minimal_magnetic_i2c.ino rename to minimal_project_examples/arduino_foc_bldc_magnetic_i2c/arduino_foc_bldc_magnetic_i2c.ino diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/BLDCMotor.cpp new file mode 100644 index 00000000..989b74a9 --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/BLDCMotor.cpp @@ -0,0 +1,378 @@ +#include "BLDCMotor.h" + +// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - phA, phB, phC - motor A,B,C phase pwm pins +// - pp - pole pair number +// - cpr - counts per rotation number (cpm=ppm*4) +// - enable pin - (optional input) +BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +: FOCMotor() +{ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + pole_pairs = pp; + + // enable_pin pin + enable_pin = en; + +} + + +// init hardware pins +void BLDCMotor::init(long pwm_frequency) { + if(monitor_port) monitor_port->println("MOT: Init pins."); + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); + + if(monitor_port) monitor_port->println("MOT: PWM config."); + // Increase PWM frequency to 32 kHz + // make silent + _setPwmFrequency(pwm_frequency, pwmA, pwmB, pwmC); + + // sanity check for the voltage limit configuration + if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + // update the controller limits + PID_velocity.limit = voltage_limit; + P_angle.limit = velocity_limit; + + _delay(500); + // enable motor + if(monitor_port) monitor_port->println("MOT: Enable."); + enable(); + _delay(500); +} + + +// disable motor driver +void BLDCMotor::disable() +{ + // disable the driver - if enable_pin pin available + if (enable_pin != NOT_SET) digitalWrite(enable_pin, LOW); + // set zero to PWM + setPwm(0, 0, 0); +} +// enable motor driver +void BLDCMotor::enable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // enable_pin the driver - if enable_pin pin available + if (enable_pin != NOT_SET) digitalWrite(enable_pin, HIGH); + +} + +/** + FOC functions +*/ +// FOC initialization function +int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } + if(monitor_port) monitor_port->println("MOT: Motor ready."); + + return exit_flag; +} +// Encoder alignment to electrical 0 angle +int BLDCMotor::alignSensor() { + if(monitor_port) monitor_port->println("MOT: Align sensor."); + // align the electrical phases of the motor and sensor + // set angle -90 degrees + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } + + // let the motor stabilize for 2 sec + _delay(2000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0,0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int BLDCMotor::absoluteZeroAlign() { + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); + + // align absolute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = _normalizeAngle(_electricalAngle(zero_offset, pole_pairs)); + } + // return bool if zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void BLDCMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); +} + +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function +// - if target is not set it uses motor.target value +void BLDCMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; + // get angular velocity + shaft_velocity = shaftVelocity(); + // choose control loop + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = P_angle( shaft_angle_sp - shaft_angle ); + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // include velocity loop + shaft_velocity_sp = target; + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); + break; + } +} + + +// Method using FOC to set Uq to the motor at the optimal angle +// Function implementing Space Vector PWM and Sine PWM algorithms +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) +void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { + switch (foc_modulation) + { + case FOCModulationType::SinePWM : + // Sinusoidal PWM modulation + // Inverse Park + Clarke transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + + // Clarke transform + Ua = Ualpha + voltage_power_supply/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + break; + + case FOCModulationType::SpaceVectorPWM : + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // https://www.youtube.com/watch?v=QMSWUMEAejg + + // if negative voltages change inverse the phase + // angle + 180degrees + if(Uq < 0) angle_el += _PI; + Uq = abs(Uq); + + // angle normalisation in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle + _PI_2); + + // find the sector we are in currently + int sector = floor(angle_el / _PI_3) + 1; + // calculate the duty cycles + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; + // two versions possible + // centered around voltage_power_supply/2 + float T0 = 1 - T1 - T2; + // pulled to 0 - better for low power supply voltage + //float T0 = 0; + + // calculate the duty cycles(times) + float Ta,Tb,Tc; + switch(sector){ + case 1: + Ta = T1 + T2 + T0/2; + Tb = T2 + T0/2; + Tc = T0/2; + break; + case 2: + Ta = T1 + T0/2; + Tb = T1 + T2 + T0/2; + Tc = T0/2; + break; + case 3: + Ta = T0/2; + Tb = T1 + T2 + T0/2; + Tc = T2 + T0/2; + break; + case 4: + Ta = T0/2; + Tb = T1+ T0/2; + Tc = T1 + T2 + T0/2; + break; + case 5: + Ta = T2 + T0/2; + Tb = T0/2; + Tc = T1 + T2 + T0/2; + break; + case 6: + Ta = T1 + T2 + T0/2; + Tb = T0/2; + Tc = T1 + T0/2; + break; + default: + // possible error state + Ta = 0; + Tb = 0; + Tc = 0; + } + + // calculate the phase voltages and center + Ua = Ta*voltage_power_supply; + Ub = Tb*voltage_power_supply; + Uc = Tc*voltage_power_supply; + break; + } + + // set the voltages in hardware + setPwm(Ua, Ub, Uc); +} + + + +// Set voltage to the pwm pin +void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { + // calculate duty cycle + // limited in [0,1] + float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); + // hardware specific writing + _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); +} + + + +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void BLDCMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void BLDCMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/BLDCMotor.h b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/BLDCMotor.h new file mode 100644 index 00000000..a4fbb678 --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/BLDCMotor.h @@ -0,0 +1,113 @@ +/** + * @file BLDCMotor.h + * + */ + +#ifndef BLDCMotor_h +#define BLDCMotor_h + +#include "Arduino.h" +#include "common/FOCMotor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" +#include "common/defaults.h" + +/** + BLDC motor class +*/ +class BLDCMotor: public FOCMotor +{ + public: + /** + BLDCMotor class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param pp pole pair number + @param cpr counts per rotation number (cpm=ppm*4) + @param en enable pin (optional input) + */ + BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + + /** Motor hardware init function */ + void init(long pwm_frequency = NOT_SET) override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + */ + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW) override; + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + void loopFOC() override; + + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET) override; + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + + private: + // FOC methods + /** + * Method using FOC to set Uq to the motor at the optimal angle + * Heart of the FOC algorithm + * + * @param Uq Current voltage in q axis to set to the motor + * @param angle_el current electrical angle of the motor + */ + void setPhaseVoltage(float Uq, float angle_el); + /** Sensor alignment to electrical 0 angle of the motor */ + int alignSensor(); + /** Motor and sensor alignment to the sensors absolute 0 angle */ + int absoluteZeroAlign(); + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + * @param Uc phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc); + + // Open loop motion control + /** + * Function (iterative) generating open loop movement for target velocity + * it uses voltage_limit variable + * + * @param target_velocity - rad/s + */ + void velocityOpenloop(float target_velocity); + /** + * Function (iterative) generating open loop movement towards the target angle + * it uses voltage_limit and velocity_limit variables + * + * @param target_angle - rad + */ + void angleOpenloop(float target_angle); + // open loop variables + long open_loop_timestamp; +}; + + +#endif diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/MagneticSensorI2C.cpp b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/MagneticSensorI2C.cpp similarity index 75% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/MagneticSensorI2C.cpp rename to minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/MagneticSensorI2C.cpp index eb94a753..a02b762b 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/MagneticSensorI2C.cpp +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/MagneticSensorI2C.cpp @@ -1,5 +1,24 @@ #include "MagneticSensorI2C.h" +/** Typical configuration for the 12bit AMS AS5600 magnetic sensor over I2C interface */ +MagneticSensorI2CConfig_s AS5600_I2C = { + .chip_address = 0x36, + .clock_speed = 1000000, + .bit_resolution = 12, + .angle_register = 0x0E, + .data_start_bit = 11 +}; + +/** Typical configuration for the 12bit AMS AS5048 magnetic sensor over I2C interface */ +MagneticSensorI2CConfig_s AS5048_I2C = { + .chip_address = 0x40, // highly configurable. if A1 and A2 are held low, this is probable value + .clock_speed = 1000000, + .bit_resolution = 14, + .angle_register = 0xFE, + .data_start_bit = 15 +}; + + // MagneticSensorI2C(uint8_t _chip_address, float _cpr, uint8_t _angle_register_msb) // @param _chip_address I2C chip address // @param _bit_resolution bit resolution of the sensor @@ -22,13 +41,47 @@ MagneticSensorI2C::MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, // extraction masks lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); msb_mask = (uint8_t)( (2 << _bits_used_msb) - 1 ); + clock_speed = 400000; + sda_pin = SDA; + scl_pin = SCL; + } +MagneticSensorI2C::MagneticSensorI2C(MagneticSensorI2CConfig_s config){ + chip_address = config.chip_address; + + // angle read register of the magnetic sensor + angle_register_msb = config.angle_register; + // register maximum value (counts per revolution) + cpr = pow(2, config.bit_resolution); + + int bits_used_msb = config.data_start_bit - 7; + lsb_used = config.bit_resolution - bits_used_msb; + // extraction masks + lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); + msb_mask = (uint8_t)( (2 << bits_used_msb) - 1 ); + clock_speed = 400000; + sda_pin = SDA; + scl_pin = SCL; + +} void MagneticSensorI2C::init(){ +#if defined(_STM32_DEF_) // if stm chips + // I2C communication begin + Wire.begin(); + Wire.setClock(clock_speed); + Wire.setSCL(scl_pin); + Wire.setSDA(sda_pin); +#elif defined(ESP_H) // if esp32 //I2C communication begin - Wire.begin(); + Wire.begin(sda_pin, scl_pin, clock_speed); +#else + // I2C communication begin + Wire.begin(); + Wire.setClock(clock_speed); +#endif // velocity calculation init angle_prev = 0; diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/MagneticSensorI2C.h b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/MagneticSensorI2C.h similarity index 71% rename from minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/MagneticSensorI2C.h rename to minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/MagneticSensorI2C.h index 2d9cad14..88d74d35 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/MagneticSensorI2C.h +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/MagneticSensorI2C.h @@ -7,42 +7,67 @@ #include "common/hardware_utils.h" #include "common/Sensor.h" +struct MagneticSensorI2CConfig_s { + int chip_address; + long clock_speed; + int bit_resolution; + int angle_register; + int data_start_bit; +}; +// some predefined structures +extern MagneticSensorI2CConfig_s AS5600_I2C,AS5048_I2C; class MagneticSensorI2C: public Sensor{ public: /** - * MagneticSensorI2C class constructor + * MagneticSensorI2C class constructor * @param chip_address I2C chip address * @param bits number of bits of the sensor resolution * @param angle_register_msb angle read register msb * @param _bits_used_msb number of used bits in msb */ MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _msb_bits_used); - + /** + * MagneticSensorI2C class constructor + * @param config I2C config + */ + MagneticSensorI2C(MagneticSensorI2CConfig_s config); + + static MagneticSensorI2C AS5600(); + /** sensor initialise pins */ void init(); // implementation of abstract functions of the Sensor class /** get current angle (rad) */ - float getAngle(); + float getAngle() override; /** get current angular velocity (rad/s) **/ - float getVelocity(); + float getVelocity() override; /** * set current angle as zero angle * return the angle [rad] difference */ - float initRelativeZero(); + float initRelativeZero() override; /** * set absolute zero angle as zero angle * return the angle [rad] difference */ - float initAbsoluteZero(); + float initAbsoluteZero() override; /** returns 1 because it is the absolute sensor */ - int hasAbsoluteZero(); + int hasAbsoluteZero() override; /** returns 0 maning it doesn't need search for absolute zero */ - int needsAbsoluteZeroSearch(); + + int needsAbsoluteZeroSearch() override; + + /* the speed of the i2c clock signal */ + long clock_speed; + + /* the pin used for i2c data */ + int sda_pin; + /* the pin used for i2c clock */ + int scl_pin; private: float cpr; //!< Maximum range of the magnetic sensor diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/FOCMotor.cpp b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/FOCMotor.cpp new file mode 100644 index 00000000..adecbeec --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/FOCMotor.cpp @@ -0,0 +1,245 @@ +#include "FOCMotor.h" + +/** + * Default constructor - setting all variabels to default values + */ +FOCMotor::FOCMotor() +{ + // Power supply voltage + voltage_power_supply = DEF_POWER_SUPPLY; + + // maximum angular velocity to be used for positioning + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = voltage_power_supply; + + // index search velocity + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; + + // electric angle of comthe zero angle + zero_electric_angle = 0; + + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + + // default target value + target = 0; + + //monitor_port + monitor_port = nullptr; + //sensor + sensor = nullptr; +} + + +/** + Sensor communication methods +*/ +void FOCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} +// shaft angle calculation +float FOCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return shaft_angle; + return sensor->getAngle(); +} +// shaft velocity calculation +float FOCMotor::shaftVelocity() { + // if no sensor linked return 0 + if(!sensor) return 0; + return LPF_velocity(sensor->getVelocity()); +} + + + + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void FOCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void FOCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity_openloop: + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle_openloop: + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int FOCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'D': // velocity D gain change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PID velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P angle| "); + break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + } + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("P: "); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("I: "); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); + break; + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("volt_ramp: "); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET) { + voltage_limit = value; + PID_velocity.limit = value; + } + if(monitor_port) monitor_port->println(voltage_limit); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("Tf: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("vel_limit: "); + if(!GET){ + velocity_limit = value; + P_angle.limit = value; + } + if(monitor_port) monitor_port->println(velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Control: "); + + if(GET){ // if get command + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + default: + if(monitor_port) monitor_port->println("open loop"); + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/BLDCMotor.h b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/FOCMotor.h similarity index 56% rename from minimal_project_examples/arduino_foc_minimal_magnetic_spi/BLDCMotor.h rename to minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/FOCMotor.h index 95ca9472..40f7f6d4 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/BLDCMotor.h +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/FOCMotor.h @@ -1,18 +1,15 @@ -/** - * @file BLDCMotor.h - * - */ - -#ifndef BLDCMotor_h -#define BLDCMotor_h +#ifndef FOCMOTOR_H +#define FOCMOTOR_H #include "Arduino.h" -#include "FOCutils.h" -#include "Sensor.h" +#include "hardware_utils.h" +#include "foc_utils.h" #include "defaults.h" +#include "Sensor.h" +#include "pid.h" +#include "lowpass_filter.h" -#define NOT_SET -12345.0 /** * Motiron control type @@ -34,60 +31,22 @@ enum FOCModulationType{ }; /** - * PID controller structure - */ -struct PID_s{ - float P; //!< Proportional gain - float I; //!< Integral gain - float D; //!< Derivative gain - long timestamp; //!< Last execution timestamp - float integral_prev; //!< last integral component value - float output_prev; //!< last pid output value - float output_ramp; //!< Maximum speed of change of the output value - float tracking_error_prev; //!< last tracking error value -}; - -// P controller structure -struct P_s{ - float P; //!< Proportional gain - long timestamp; //!< Last execution timestamp -}; - -/** - * Low pass filter structure - */ -struct LPF_s{ - float Tf; //!< Low pass filter time constant - long timestamp; //!< Last execution timestamp - float prev; //!< filtered value in previous execution step -}; - - - - -/** - BLDC motor class + Generic motor class */ -class BLDCMotor +class FOCMotor { public: /** - BLDCMotor class constructor - @param phA A phase pwm pin - @param phB B phase pwm pin - @param phC C phase pwm pin - @param pp pole pair number - @param cpr counts per rotation number (cpm=ppm*4) - @param en enable pin (optional input) - */ - BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); - + * Default constructor - setting all variabels to default values + */ + FOCMotor(); + /** Motor hardware init function */ - void init(); + virtual void init(long pwm_frequency)=0; /** Motor disable function */ - void disable(); + virtual void disable()=0; /** Motor enable function */ - void enable(); + virtual void enable()=0; /** * Function linking a motor and a sensor @@ -106,14 +65,14 @@ class BLDCMotor * @param sensor_direction sensor natural direction - default is CW * */ - int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); + virtual int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW)=0; /** * Function running FOC algorithm in real-time * it calculates the gets motor angle and sets the appropriate voltages * to the phase pwm signals * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us */ - void loopFOC(); + virtual void loopFOC()=0; /** * Function executing the control loops set by the controller parameter of the BLDCMotor. * @@ -122,16 +81,7 @@ class BLDCMotor * * This function doesn't need to be run upon each loop execution - depends of the use case */ - void move(float target = NOT_SET); - - // hardware variables - int pwmA; //!< phase A pwm pin number - int pwmB; //!< phase B pwm pin number - int pwmC; //!< phase C pwm pin number - int enable_pin; //!< enable pin number - - - + virtual void move(float target = NOT_SET)=0; // State calculation methods /** Shaft angle calculation in radians [rad] */ @@ -150,6 +100,7 @@ class BLDCMotor float shaft_angle_sp;//!< current target angle float voltage_q;//!< current voltage u_q set float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform // motor configuration parameters float voltage_power_supply;//!< Power supply voltage @@ -161,34 +112,15 @@ class BLDCMotor float voltage_limit; //!< Voltage limitting variable - global limit float velocity_limit; //!< Velocity limitting variable - global limit + float zero_electric_angle;//! _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} + + +// normalizing radian angle to [0,2PI] +float _normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} + +// Electrical angle calculation +float _electricalAngle(float shaft_angle, int pole_pairs) { + return (shaft_angle * pole_pairs); +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/foc_utils.h b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/foc_utils.h new file mode 100644 index 00000000..5ab34f42 --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/foc_utils.h @@ -0,0 +1,55 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + +// sign function +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + +// utility defines +#define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI 3.14159265359 +#define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + + +#define NOT_SET -12345.0 + +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _sin(float a); +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _cos(float a); + +/** + * normalizing radian angle to [0,2PI] + * @param angle - angle to be normalized + */ +float _normalizeAngle(float angle); + + +/** + * Electrical angle calculation + * + * @param shaft_angle - shaft angle of the motor + * @param pole_pairs - number of pole pairs + */ +float _electricalAngle(float shaft_angle, int pole_pairs); +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.cpp new file mode 100644 index 00000000..0d080bab --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.cpp @@ -0,0 +1,284 @@ +#include "hardware_utils.h" + +#if defined(ESP_H) // if ESP32 board +// empty motor slot +#define _EMPTY_SLOT -20 + +// structure containing motor slot configuration +// this library supports up to 4 motors +typedef struct { + int pinA; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; + mcpwm_io_signals_t mcpwm_c; +} bldc_motor_slots_t; +typedef struct { + int pin1A; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_1a; + mcpwm_io_signals_t mcpwm_1b; + mcpwm_io_signals_t mcpwm_2a; + mcpwm_io_signals_t mcpwm_2b; +} stepper_motor_slots_t; + +// define bldc motor slots array +bldc_motor_slots_t esp32_bldc_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B + }; + +// define stepper motor slots array +stepper_motor_slots_t esp32_stepper_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + }; + +// configuring high frequency pwm timer +// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller +void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ + + mcpwm_config_t pwm_config; + pwm_config.frequency = pwm_frequency; //frequency + pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% + pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + _delay(100); + + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); + mcpwm_num->clk_cfg.prescale = 0; + + mcpwm_num->timer[0].period.prescale = 4; + mcpwm_num->timer[1].period.prescale = 4; + mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + mcpwm_num->timer[0].period.period = 2048; + mcpwm_num->timer[1].period.period = 2048; + mcpwm_num->timer[2].period.period = 2048; + _delay(1); + mcpwm_num->timer[0].period.upmethod = 0; + mcpwm_num->timer[1].period.upmethod = 0; + mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 0; +} + +#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips +// set pwm frequency to 32KHz +void _pinHighFrequency(const int pin){ + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pin == 5 || pin == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pin == 9 || pin == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pin == 3 || pin == 11) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +} +#elif defined(_STM32_DEF_) // if stm chips +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); + analogWriteResolution(12); // resolution 12 bit 0 - 4096 +} +#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); +} +#endif + + +// function setting the high pwm frequency to the supplied pins +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); + _pinHighFrequency(pinC); + if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor + +#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards + if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor + +#elif defined(ESP_H) // if esp32 boards + if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency + + if(pinD == NOT_SET){ + bldc_motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_motor_slots[i].pinA = pinA; + m_slot = esp32_bldc_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + + }else{ + stepper_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_motor_slots[i].pin1A = pinA; + m_slot = esp32_stepper_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + } +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pinA, 4095.0*dc_a); + analogWrite(pinB, 4095.0*dc_b); + analogWrite(pinC, 4095.0*dc_c); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255*dc_a); + analogWrite(pinB, 255*dc_b); + analogWrite(pinC, 255*dc_c); +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pin1A, 4095.0*dc_1a); + analogWrite(pin1B, 4095.0*dc_1b); + analogWrite(pin2A, 4095.0*dc_2a); + analogWrite(pin2B, 4095.0*dc_2b); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255*dc_1a); + analogWrite(pin1B, 255*dc_1b); + analogWrite(pin2A, 255*dc_2a); + analogWrite(pin2B, 255*dc_2b); +#endif +} + + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/arduino_foc_minimal_encoder1/src/common/FOCutils.h b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.h similarity index 58% rename from minimal_project_examples/arduino_foc_minimal_encoder1/src/common/FOCutils.h rename to minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.h index f233407b..f99c260a 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder1/src/common/FOCutils.h +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.h @@ -1,7 +1,8 @@ -#ifndef FOCUTILS_LIB_H -#define FOCUTILS_LIB_H +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H #include "Arduino.h" +#include "foc_utils.h" #if defined(ESP_H) // if esp32 boards @@ -12,47 +13,17 @@ #endif -// sign function -#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) -#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) - -// utility defines -#define _2_SQRT3 1.15470053838 -#define _SQRT3 1.73205080757 -#define _1_SQRT3 0.57735026919 -#define _SQRT3_2 0.86602540378 -#define _SQRT2 1.41421356237 -#define _120_D2R 2.09439510239 -#define _PI 3.14159265359 -#define _PI_2 1.57079632679 -#define _PI_3 1.0471975512 -#define _2PI 6.28318530718 -#define _3PI_2 4.71238898038 - /** * High PWM frequency setting function * - hardware specific * - * @param pinA pinA number to configure - * @param pinB pinB number to configure - * @param pinC pinC number to configure + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc motor or pin1A stepper motor + * @param pinB pinB bldc motor or pin1B stepper motor + * @param pinC pinC bldc motor or pin2A stepper motor + * @param pinD pin2B stepper motor */ -void _setPwmFrequency(int pinA, int pinB, int pinC, int pinD = 0); - -/** - * Function implementing delay() function in milliseconds - * - blocking function - * - hardware specific - - * @param ms number of milliseconds to wait - */ -void _delay(unsigned long ms); - -/** - * Function implementing timestamp getting function in microseconds - * hardware specific - */ -unsigned long _micros(); +void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) @@ -65,7 +36,7 @@ unsigned long _micros(); * @param pinB phase B hardware pin number * @param pinC phase C hardware pin number */ -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) @@ -82,19 +53,20 @@ void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, in */ void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); -/** - * Function approximating the sine calculation by using fixed size array - * - execution time ~40us (Arduino UNO) - * - * @param a angle in between 0 and 2PI +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait */ -float _sin(float a); -/** - * Function approximating cosine calculation by using fixed size array - * - execution time ~50us (Arduino UNO) - * - * @param a angle in between 0 and 2PI +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific */ -float _cos(float a); +unsigned long _micros(); -#endif + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/lowpass_filter.cpp b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/lowpass_filter.cpp new file mode 100644 index 00000000..9bf4ab7a --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/lowpass_filter.cpp @@ -0,0 +1,25 @@ +#include "lowpass_filter.h" + +LowPassFilter::LowPassFilter(float time_constant) + : Tf(time_constant) + , y_prev(0.0f) +{ + timestamp_prev = _micros(); +} + + +float LowPassFilter::operator() (float x) +{ + unsigned long timestamp = _micros(); + float dt = (timestamp - timestamp_prev)*1e-6f; + + if (dt < 0.0f || dt > 0.5f) + dt = 1e-3f; + + float alpha = Tf/(Tf + dt); + float y = alpha*y_prev + (1.0f - alpha)*x; + + y_prev = y; + timestamp_prev = timestamp; + return y; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/lowpass_filter.h b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/lowpass_filter.h new file mode 100644 index 00000000..5a7619cf --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/lowpass_filter.h @@ -0,0 +1,29 @@ +#ifndef LOWPASS_FILTER_H +#define LOWPASS_FILTER_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + + +/** + * Low pass filter class + */ +class LowPassFilter +{ +public: + /** + * @param Tf - Low pass filter time constant + */ + LowPassFilter(float Tf); + ~LowPassFilter() = default; + + float operator() (float x); + float Tf; //!< Low pass filter time constant + +protected: + unsigned long timestamp_prev; //!< Last execution timestamp + float y_prev; //!< filtered value in previous execution step +}; + +#endif // LOWPASS_FILTER_H \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/pid.cpp b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/pid.cpp new file mode 100644 index 00000000..277e17ce --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/pid.cpp @@ -0,0 +1,56 @@ +#include "pid.h" + +PIDController::PIDController(float P, float I, float D, float ramp, float limit) + : P(P) + , I(I) + , D(D) + , output_ramp(ramp) // output derivative limit [volts/second] + , limit(limit) // output supply limit [volts] + , integral_prev(0.0) + , error_prev(0.0) + , output_prev(0.0) +{ + timestamp_prev = _micros()*1e-6; +} + +// PID controller function +float PIDController::operator() (float error){ + // calculate the time from the last call + unsigned long timestamp_now = _micros(); + float Ts = (timestamp_now - timestamp_prev) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = P * error_prev; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = integral_prev + I*Ts*0.5*(error + error_prev); + // antiwindup - limit the output voltage_q + integral = constrain(integral, -limit, limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = D*(error - error_prev)/Ts; + + // sum all the components + float output = proportional + integral + derivative; + // antiwindup - limit the output variable + output = constrain(output, -limit, limit); + + // limit the acceleration by ramping the output + float output_rate = (output - output_prev)/Ts; + if (output_rate > output_ramp) + output = output_prev + output_ramp*Ts; + else if (output_rate < -output_ramp) + output = output_prev - output_ramp*Ts; + + // saving for the next pass + integral_prev = integral; + output_prev = output; + error_prev = error; + timestamp_prev = timestamp_now; + return output; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/pid.h b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/pid.h new file mode 100644 index 00000000..7ee337c4 --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/pid.h @@ -0,0 +1,40 @@ +#ifndef PID_H +#define PID_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + +/** + * PID controller class + */ +class PIDController +{ +public: + /** + * + * @param P - Proportional gain + * @param I - Integral gain + * @param D - Derivative gain + * @param ramp - Maximum speed of change of the output value + * @param limit - Maximum output value + */ + PIDController(float P, float I, float D, float ramp, float limit); + ~PIDController() = default; + + float operator() (float error); + + float P; //!< Proportional gain + float I; //!< Integral gain + float D; //!< Derivative gain + float output_ramp; //!< Maximum speed of change of the output value + float limit; //!< Maximum output value + +protected: + float integral_prev; //!< last integral component value + float error_prev; //!< last tracking error value + float timestamp_prev; //!< Last execution timestamp + float output_prev; //!< last pid output value +}; + +#endif // PID_H \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/arduino_foc_minimal_magnetic_spi.ino b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/arduino_foc_bldc_magnetic_spi.ino similarity index 98% rename from minimal_project_examples/arduino_foc_minimal_magnetic_spi/arduino_foc_minimal_magnetic_spi.ino rename to minimal_project_examples/arduino_foc_bldc_magnetic_spi/arduino_foc_bldc_magnetic_spi.ino index 7a01bfa3..31366bed 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/arduino_foc_minimal_magnetic_spi.ino +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/arduino_foc_bldc_magnetic_spi.ino @@ -36,8 +36,8 @@ * - 3: current target value * */ -#include "BLDCMotor.h" -#include "MagneticSensorI2C.h" +#include "src/BLDCMotor.h" +#include "src/MagneticSensorI2C.h" // SPI magnetic sensor instance //MagneticSensorSPI sensor = MagneticSensorSPI(10, 14, 0x3FFF); diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/BLDCMotor.cpp new file mode 100644 index 00000000..989b74a9 --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/BLDCMotor.cpp @@ -0,0 +1,378 @@ +#include "BLDCMotor.h" + +// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - phA, phB, phC - motor A,B,C phase pwm pins +// - pp - pole pair number +// - cpr - counts per rotation number (cpm=ppm*4) +// - enable pin - (optional input) +BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +: FOCMotor() +{ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + pole_pairs = pp; + + // enable_pin pin + enable_pin = en; + +} + + +// init hardware pins +void BLDCMotor::init(long pwm_frequency) { + if(monitor_port) monitor_port->println("MOT: Init pins."); + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); + + if(monitor_port) monitor_port->println("MOT: PWM config."); + // Increase PWM frequency to 32 kHz + // make silent + _setPwmFrequency(pwm_frequency, pwmA, pwmB, pwmC); + + // sanity check for the voltage limit configuration + if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + // update the controller limits + PID_velocity.limit = voltage_limit; + P_angle.limit = velocity_limit; + + _delay(500); + // enable motor + if(monitor_port) monitor_port->println("MOT: Enable."); + enable(); + _delay(500); +} + + +// disable motor driver +void BLDCMotor::disable() +{ + // disable the driver - if enable_pin pin available + if (enable_pin != NOT_SET) digitalWrite(enable_pin, LOW); + // set zero to PWM + setPwm(0, 0, 0); +} +// enable motor driver +void BLDCMotor::enable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // enable_pin the driver - if enable_pin pin available + if (enable_pin != NOT_SET) digitalWrite(enable_pin, HIGH); + +} + +/** + FOC functions +*/ +// FOC initialization function +int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } + if(monitor_port) monitor_port->println("MOT: Motor ready."); + + return exit_flag; +} +// Encoder alignment to electrical 0 angle +int BLDCMotor::alignSensor() { + if(monitor_port) monitor_port->println("MOT: Align sensor."); + // align the electrical phases of the motor and sensor + // set angle -90 degrees + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } + + // let the motor stabilize for 2 sec + _delay(2000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0,0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int BLDCMotor::absoluteZeroAlign() { + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); + + // align absolute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = _normalizeAngle(_electricalAngle(zero_offset, pole_pairs)); + } + // return bool if zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void BLDCMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); +} + +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function +// - if target is not set it uses motor.target value +void BLDCMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; + // get angular velocity + shaft_velocity = shaftVelocity(); + // choose control loop + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = P_angle( shaft_angle_sp - shaft_angle ); + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // include velocity loop + shaft_velocity_sp = target; + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); + break; + } +} + + +// Method using FOC to set Uq to the motor at the optimal angle +// Function implementing Space Vector PWM and Sine PWM algorithms +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) +void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { + switch (foc_modulation) + { + case FOCModulationType::SinePWM : + // Sinusoidal PWM modulation + // Inverse Park + Clarke transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + + // Clarke transform + Ua = Ualpha + voltage_power_supply/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + break; + + case FOCModulationType::SpaceVectorPWM : + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // https://www.youtube.com/watch?v=QMSWUMEAejg + + // if negative voltages change inverse the phase + // angle + 180degrees + if(Uq < 0) angle_el += _PI; + Uq = abs(Uq); + + // angle normalisation in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle + _PI_2); + + // find the sector we are in currently + int sector = floor(angle_el / _PI_3) + 1; + // calculate the duty cycles + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; + // two versions possible + // centered around voltage_power_supply/2 + float T0 = 1 - T1 - T2; + // pulled to 0 - better for low power supply voltage + //float T0 = 0; + + // calculate the duty cycles(times) + float Ta,Tb,Tc; + switch(sector){ + case 1: + Ta = T1 + T2 + T0/2; + Tb = T2 + T0/2; + Tc = T0/2; + break; + case 2: + Ta = T1 + T0/2; + Tb = T1 + T2 + T0/2; + Tc = T0/2; + break; + case 3: + Ta = T0/2; + Tb = T1 + T2 + T0/2; + Tc = T2 + T0/2; + break; + case 4: + Ta = T0/2; + Tb = T1+ T0/2; + Tc = T1 + T2 + T0/2; + break; + case 5: + Ta = T2 + T0/2; + Tb = T0/2; + Tc = T1 + T2 + T0/2; + break; + case 6: + Ta = T1 + T2 + T0/2; + Tb = T0/2; + Tc = T1 + T0/2; + break; + default: + // possible error state + Ta = 0; + Tb = 0; + Tc = 0; + } + + // calculate the phase voltages and center + Ua = Ta*voltage_power_supply; + Ub = Tb*voltage_power_supply; + Uc = Tc*voltage_power_supply; + break; + } + + // set the voltages in hardware + setPwm(Ua, Ub, Uc); +} + + + +// Set voltage to the pwm pin +void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { + // calculate duty cycle + // limited in [0,1] + float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); + // hardware specific writing + _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); +} + + + +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void BLDCMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void BLDCMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/BLDCMotor.h b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/BLDCMotor.h new file mode 100644 index 00000000..a4fbb678 --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/BLDCMotor.h @@ -0,0 +1,113 @@ +/** + * @file BLDCMotor.h + * + */ + +#ifndef BLDCMotor_h +#define BLDCMotor_h + +#include "Arduino.h" +#include "common/FOCMotor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" +#include "common/defaults.h" + +/** + BLDC motor class +*/ +class BLDCMotor: public FOCMotor +{ + public: + /** + BLDCMotor class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param pp pole pair number + @param cpr counts per rotation number (cpm=ppm*4) + @param en enable pin (optional input) + */ + BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + + /** Motor hardware init function */ + void init(long pwm_frequency = NOT_SET) override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + */ + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW) override; + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + void loopFOC() override; + + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET) override; + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + + private: + // FOC methods + /** + * Method using FOC to set Uq to the motor at the optimal angle + * Heart of the FOC algorithm + * + * @param Uq Current voltage in q axis to set to the motor + * @param angle_el current electrical angle of the motor + */ + void setPhaseVoltage(float Uq, float angle_el); + /** Sensor alignment to electrical 0 angle of the motor */ + int alignSensor(); + /** Motor and sensor alignment to the sensors absolute 0 angle */ + int absoluteZeroAlign(); + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + * @param Uc phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc); + + // Open loop motion control + /** + * Function (iterative) generating open loop movement for target velocity + * it uses voltage_limit variable + * + * @param target_velocity - rad/s + */ + void velocityOpenloop(float target_velocity); + /** + * Function (iterative) generating open loop movement towards the target angle + * it uses voltage_limit and velocity_limit variables + * + * @param target_angle - rad + */ + void angleOpenloop(float target_angle); + // open loop variables + long open_loop_timestamp; +}; + + +#endif diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorSPI.cpp b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/MagneticSensorSPI.cpp similarity index 68% rename from minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorSPI.cpp rename to minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/MagneticSensorSPI.cpp index 79430b13..1f63bc11 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorSPI.cpp +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/MagneticSensorSPI.cpp @@ -1,33 +1,76 @@ #include "MagneticSensorSPI.h" +/** Typical configuration for the 14bit AMS AS5147 magnetic sensor over SPI interface */ +MagneticSensorSPIConfig_s AS5147_SPI = { + .spi_mode = SPI_MODE1, + .clock_speed = 1000000, + .bit_resolution = 14, + .angle_register = 0xCFFF, + .data_start_bit = 13, + .command_rw_bit = 14, + .command_parity_bit = 15 +}; + +/** Typical configuration for the 14bit MonolithicPower MA730 magnetic sensor over SPI interface */ +MagneticSensorSPIConfig_s MA730_SPI = { + .spi_mode = SPI_MODE0, + .clock_speed = 1000000, + .bit_resolution = 14, + .angle_register = 0x0000, + .data_start_bit = 15, + .command_rw_bit = 0, // not required + .command_parity_bit = 0 // parity not implemented +}; + + // MagneticSensorSPI(int cs, float _bit_resolution, int _angle_register) // cs - SPI chip select pin // _bit_resolution sensor resolution bit number // _angle_register - (optional) angle read register - default 0x3FFF MagneticSensorSPI::MagneticSensorSPI(int cs, float _bit_resolution, int _angle_register){ - // chip select pin + chip_select_pin = cs; // angle read register of the magnetic sensor angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTAR; // register maximum value (counts per revolution) cpr = pow(2,_bit_resolution); - + spi_mode = SPI_MODE1; + clock_speed = 1000000; + bit_resolution = _bit_resolution; + + command_parity_bit = 15; // for backwards compatibilty + command_rw_bit = 14; // for backwards compatibilty + data_start_bit = 13; // for backwards compatibilty + } +MagneticSensorSPI::MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs){ + chip_select_pin = cs; + // angle read register of the magnetic sensor + angle_register = config.angle_register ? config.angle_register : DEF_ANGLE_REGISTAR; + // register maximum value (counts per revolution) + cpr = pow(2, config.bit_resolution); + spi_mode = config.spi_mode; + clock_speed = config.clock_speed; + bit_resolution = config.bit_resolution; + + command_parity_bit = config.command_parity_bit; // for backwards compatibilty + command_rw_bit = config.command_rw_bit; // for backwards compatibilty + data_start_bit = config.data_start_bit; // for backwards compatibilty +} void MagneticSensorSPI::init(){ // 1MHz clock (AMS should be able to accept up to 10MHz) - settings = SPISettings(1000000, MSBFIRST, SPI_MODE1); + settings = SPISettings(clock_speed, MSBFIRST, spi_mode); //setup pins pinMode(chip_select_pin, OUTPUT); - //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices SPI.begin(); #ifndef ESP_H // if not ESP32 board SPI.setBitOrder(MSBFIRST); // Set the SPI_1 bit order - SPI.setDataMode(SPI_MODE1) ; + SPI.setDataMode(spi_mode) ; SPI.setClockDivider(SPI_CLOCK_DIV8); #endif @@ -77,7 +120,7 @@ float MagneticSensorSPI::getVelocity(){ float angle_c = getAngle(); // velocity calculation float vel = (angle_c - angle_prev)/Ts; - + // save variables for future pass angle_prev = angle_c; velocity_calc_timestamp = now_us; @@ -147,35 +190,28 @@ byte MagneticSensorSPI::spiCalcEvenParity(word value){ * Returns the value of the register */ word MagneticSensorSPI::read(word angle_register){ - word command = 0b0100000000000000; // PAR=0 R/W=R - command = command | angle_register; - //Add a parity bit on the the MSB - command |= ((word)spiCalcEvenParity(command)<<15); - - //Split the command into two bytes - byte right_byte = command & 0xFF; - byte left_byte = ( command >> 8 ) & 0xFF; + word command = angle_register; + if (command_rw_bit > 0) { + command = angle_register | (1 << command_rw_bit); + } + if (command_parity_bit > 0) { + //Add a parity bit on the the MSB + command |= ((word)spiCalcEvenParity(command) << command_parity_bit); + } #if !defined(_STM32_DEF_) // if not stm chips //SPI - begin transaction SPI.beginTransaction(settings); #endif - //SPI - begin transaction - //SPI.beginTransaction(settings); //Send the command digitalWrite(chip_select_pin, LOW); -#ifndef ESP_H // if not ESP32 board digitalWrite(chip_select_pin, LOW); -#endif - SPI.transfer(left_byte); - SPI.transfer(right_byte); + SPI.transfer16(command); digitalWrite(chip_select_pin,HIGH); -#ifndef ESP_H // if not ESP32 board digitalWrite(chip_select_pin,HIGH); -#endif #if defined( ESP_H ) // if ESP32 board delayMicroseconds(50); @@ -186,8 +222,7 @@ word MagneticSensorSPI::read(word angle_register){ //Now read the response digitalWrite(chip_select_pin, LOW); digitalWrite(chip_select_pin, LOW); - left_byte = SPI.transfer(0x00); - right_byte = SPI.transfer(0x00); + word register_value = SPI.transfer16(0x00); digitalWrite(chip_select_pin, HIGH); digitalWrite(chip_select_pin,HIGH); @@ -195,9 +230,12 @@ word MagneticSensorSPI::read(word angle_register){ //SPI - end transaction SPI.endTransaction(); #endif + + register_value = register_value >> (1 + data_start_bit - bit_resolution); //this should shift data to the rightmost bits of the word + + const static word data_mask = ~(0 >> (16 - bit_resolution)); - // Return the data, stripping the parity and error bits - return (( ( left_byte & 0xFF ) << 8 ) | ( right_byte & 0xFF )) & ~0xC000; + return register_value & data_mask; // Return the data, stripping the non data (e.g parity) bits } /** diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorSPI.h b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/MagneticSensorSPI.h similarity index 61% rename from minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorSPI.h rename to minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/MagneticSensorSPI.h index da70c0c4..8e884cf4 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorSPI.h +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/MagneticSensorSPI.h @@ -3,11 +3,24 @@ #include "Arduino.h" #include -#include "FOCutils.h" -#include "Sensor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" #define DEF_ANGLE_REGISTAR 0x3FFF +struct MagneticSensorSPIConfig_s { + int spi_mode; + long clock_speed; + int bit_resolution; + int angle_register; + int data_start_bit; + int command_rw_bit; + int command_parity_bit; +}; +// typical configuration structures +extern MagneticSensorSPIConfig_s AS5147_SPI, MA730_SPI; + class MagneticSensorSPI: public Sensor{ public: /** @@ -17,30 +30,42 @@ class MagneticSensorSPI: public Sensor{ * @param angle_register (optional) angle read register - default 0x3FFF */ MagneticSensorSPI(int cs, float bit_resolution, int angle_register = 0); - + /** + * MagneticSensorSPI class constructor + * @param config SPI config + * @param cs SPI chip select pin + */ + MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs); /** sensor initialise pins */ void init(); // implementation of abstract functions of the Sensor class /** get current angle (rad) */ - float getAngle(); + float getAngle() override; /** get current angular velocity (rad/s) **/ - float getVelocity(); + float getVelocity() override; /** * set current angle as zero angle * return the angle [rad] difference */ - float initRelativeZero(); + float initRelativeZero() override; /** * set absolute zero angle as zero angle * return the angle [rad] difference */ - float initAbsoluteZero(); + float initAbsoluteZero() override; /** returns 1 because it is the absolute sensor */ - int hasAbsoluteZero(); + int hasAbsoluteZero() override; /** returns 0 maning it doesn't need search for absolute zero */ - int needsAbsoluteZeroSearch(); + + int needsAbsoluteZeroSearch() override; + + // returns the spi mode (phase/polarity of read/writes) i.e one of SPI_MODE0 | SPI_MODE1 | SPI_MODE2 | SPI_MODE3 + int spi_mode; + + /* returns the speed of the SPI clock signal */ + long clock_speed; private: @@ -72,6 +97,11 @@ class MagneticSensorSPI: public Sensor{ // velocity calculation variables float angle_prev; //!< angle in previous velocity calculation step long velocity_calc_timestamp; //!< last velocity calculation timestamp + + int bit_resolution; //!< the number of bites of angle data + int command_parity_bit; //!< the bit where parity flag is stored in command + int command_rw_bit; //!< the bit where read/write flag is stored in command + int data_start_bit; //!< the the position of first bit }; diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/FOCMotor.cpp b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/FOCMotor.cpp new file mode 100644 index 00000000..adecbeec --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/FOCMotor.cpp @@ -0,0 +1,245 @@ +#include "FOCMotor.h" + +/** + * Default constructor - setting all variabels to default values + */ +FOCMotor::FOCMotor() +{ + // Power supply voltage + voltage_power_supply = DEF_POWER_SUPPLY; + + // maximum angular velocity to be used for positioning + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = voltage_power_supply; + + // index search velocity + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; + + // electric angle of comthe zero angle + zero_electric_angle = 0; + + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + + // default target value + target = 0; + + //monitor_port + monitor_port = nullptr; + //sensor + sensor = nullptr; +} + + +/** + Sensor communication methods +*/ +void FOCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} +// shaft angle calculation +float FOCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return shaft_angle; + return sensor->getAngle(); +} +// shaft velocity calculation +float FOCMotor::shaftVelocity() { + // if no sensor linked return 0 + if(!sensor) return 0; + return LPF_velocity(sensor->getVelocity()); +} + + + + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void FOCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void FOCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity_openloop: + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle_openloop: + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int FOCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'D': // velocity D gain change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PID velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P angle| "); + break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + } + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("P: "); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("I: "); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); + break; + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("volt_ramp: "); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET) { + voltage_limit = value; + PID_velocity.limit = value; + } + if(monitor_port) monitor_port->println(voltage_limit); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("Tf: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("vel_limit: "); + if(!GET){ + velocity_limit = value; + P_angle.limit = value; + } + if(monitor_port) monitor_port->println(velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Control: "); + + if(GET){ // if get command + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + default: + if(monitor_port) monitor_port->println("open loop"); + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_hall/BLDCMotor.h b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/FOCMotor.h similarity index 56% rename from minimal_project_examples/arduino_foc_minimal_hall/BLDCMotor.h rename to minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/FOCMotor.h index 95ca9472..40f7f6d4 100644 --- a/minimal_project_examples/arduino_foc_minimal_hall/BLDCMotor.h +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/FOCMotor.h @@ -1,18 +1,15 @@ -/** - * @file BLDCMotor.h - * - */ - -#ifndef BLDCMotor_h -#define BLDCMotor_h +#ifndef FOCMOTOR_H +#define FOCMOTOR_H #include "Arduino.h" -#include "FOCutils.h" -#include "Sensor.h" +#include "hardware_utils.h" +#include "foc_utils.h" #include "defaults.h" +#include "Sensor.h" +#include "pid.h" +#include "lowpass_filter.h" -#define NOT_SET -12345.0 /** * Motiron control type @@ -34,60 +31,22 @@ enum FOCModulationType{ }; /** - * PID controller structure - */ -struct PID_s{ - float P; //!< Proportional gain - float I; //!< Integral gain - float D; //!< Derivative gain - long timestamp; //!< Last execution timestamp - float integral_prev; //!< last integral component value - float output_prev; //!< last pid output value - float output_ramp; //!< Maximum speed of change of the output value - float tracking_error_prev; //!< last tracking error value -}; - -// P controller structure -struct P_s{ - float P; //!< Proportional gain - long timestamp; //!< Last execution timestamp -}; - -/** - * Low pass filter structure - */ -struct LPF_s{ - float Tf; //!< Low pass filter time constant - long timestamp; //!< Last execution timestamp - float prev; //!< filtered value in previous execution step -}; - - - - -/** - BLDC motor class + Generic motor class */ -class BLDCMotor +class FOCMotor { public: /** - BLDCMotor class constructor - @param phA A phase pwm pin - @param phB B phase pwm pin - @param phC C phase pwm pin - @param pp pole pair number - @param cpr counts per rotation number (cpm=ppm*4) - @param en enable pin (optional input) - */ - BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); - + * Default constructor - setting all variabels to default values + */ + FOCMotor(); + /** Motor hardware init function */ - void init(); + virtual void init(long pwm_frequency)=0; /** Motor disable function */ - void disable(); + virtual void disable()=0; /** Motor enable function */ - void enable(); + virtual void enable()=0; /** * Function linking a motor and a sensor @@ -106,14 +65,14 @@ class BLDCMotor * @param sensor_direction sensor natural direction - default is CW * */ - int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); + virtual int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW)=0; /** * Function running FOC algorithm in real-time * it calculates the gets motor angle and sets the appropriate voltages * to the phase pwm signals * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us */ - void loopFOC(); + virtual void loopFOC()=0; /** * Function executing the control loops set by the controller parameter of the BLDCMotor. * @@ -122,16 +81,7 @@ class BLDCMotor * * This function doesn't need to be run upon each loop execution - depends of the use case */ - void move(float target = NOT_SET); - - // hardware variables - int pwmA; //!< phase A pwm pin number - int pwmB; //!< phase B pwm pin number - int pwmC; //!< phase C pwm pin number - int enable_pin; //!< enable pin number - - - + virtual void move(float target = NOT_SET)=0; // State calculation methods /** Shaft angle calculation in radians [rad] */ @@ -150,6 +100,7 @@ class BLDCMotor float shaft_angle_sp;//!< current target angle float voltage_q;//!< current voltage u_q set float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform // motor configuration parameters float voltage_power_supply;//!< Power supply voltage @@ -161,34 +112,15 @@ class BLDCMotor float voltage_limit; //!< Voltage limitting variable - global limit float velocity_limit; //!< Velocity limitting variable - global limit + float zero_electric_angle;//! _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} + + +// normalizing radian angle to [0,2PI] +float _normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} + +// Electrical angle calculation +float _electricalAngle(float shaft_angle, int pole_pairs) { + return (shaft_angle * pole_pairs); +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/foc_utils.h b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/foc_utils.h new file mode 100644 index 00000000..5ab34f42 --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/foc_utils.h @@ -0,0 +1,55 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + +// sign function +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + +// utility defines +#define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI 3.14159265359 +#define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + + +#define NOT_SET -12345.0 + +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _sin(float a); +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _cos(float a); + +/** + * normalizing radian angle to [0,2PI] + * @param angle - angle to be normalized + */ +float _normalizeAngle(float angle); + + +/** + * Electrical angle calculation + * + * @param shaft_angle - shaft angle of the motor + * @param pole_pairs - number of pole pairs + */ +float _electricalAngle(float shaft_angle, int pole_pairs); +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/hardware_utils.cpp new file mode 100644 index 00000000..0d080bab --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/hardware_utils.cpp @@ -0,0 +1,284 @@ +#include "hardware_utils.h" + +#if defined(ESP_H) // if ESP32 board +// empty motor slot +#define _EMPTY_SLOT -20 + +// structure containing motor slot configuration +// this library supports up to 4 motors +typedef struct { + int pinA; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; + mcpwm_io_signals_t mcpwm_c; +} bldc_motor_slots_t; +typedef struct { + int pin1A; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_1a; + mcpwm_io_signals_t mcpwm_1b; + mcpwm_io_signals_t mcpwm_2a; + mcpwm_io_signals_t mcpwm_2b; +} stepper_motor_slots_t; + +// define bldc motor slots array +bldc_motor_slots_t esp32_bldc_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B + }; + +// define stepper motor slots array +stepper_motor_slots_t esp32_stepper_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + }; + +// configuring high frequency pwm timer +// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller +void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ + + mcpwm_config_t pwm_config; + pwm_config.frequency = pwm_frequency; //frequency + pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% + pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + _delay(100); + + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); + mcpwm_num->clk_cfg.prescale = 0; + + mcpwm_num->timer[0].period.prescale = 4; + mcpwm_num->timer[1].period.prescale = 4; + mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + mcpwm_num->timer[0].period.period = 2048; + mcpwm_num->timer[1].period.period = 2048; + mcpwm_num->timer[2].period.period = 2048; + _delay(1); + mcpwm_num->timer[0].period.upmethod = 0; + mcpwm_num->timer[1].period.upmethod = 0; + mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 0; +} + +#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips +// set pwm frequency to 32KHz +void _pinHighFrequency(const int pin){ + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pin == 5 || pin == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pin == 9 || pin == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pin == 3 || pin == 11) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +} +#elif defined(_STM32_DEF_) // if stm chips +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); + analogWriteResolution(12); // resolution 12 bit 0 - 4096 +} +#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); +} +#endif + + +// function setting the high pwm frequency to the supplied pins +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); + _pinHighFrequency(pinC); + if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor + +#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards + if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor + +#elif defined(ESP_H) // if esp32 boards + if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency + + if(pinD == NOT_SET){ + bldc_motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_motor_slots[i].pinA = pinA; + m_slot = esp32_bldc_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + + }else{ + stepper_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_motor_slots[i].pin1A = pinA; + m_slot = esp32_stepper_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + } +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pinA, 4095.0*dc_a); + analogWrite(pinB, 4095.0*dc_b); + analogWrite(pinC, 4095.0*dc_c); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255*dc_a); + analogWrite(pinB, 255*dc_b); + analogWrite(pinC, 255*dc_c); +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pin1A, 4095.0*dc_1a); + analogWrite(pin1B, 4095.0*dc_1b); + analogWrite(pin2A, 4095.0*dc_2a); + analogWrite(pin2B, 4095.0*dc_2b); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255*dc_1a); + analogWrite(pin1B, 255*dc_1b); + analogWrite(pin2A, 255*dc_2a); + analogWrite(pin2B, 255*dc_2b); +#endif +} + + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/hardware_utils.h b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/hardware_utils.h new file mode 100644 index 00000000..f99c260a --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/hardware_utils.h @@ -0,0 +1,72 @@ +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H + +#include "Arduino.h" +#include "foc_utils.h" + + +#if defined(ESP_H) // if esp32 boards + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +#endif + +/** + * High PWM frequency setting function + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc motor or pin1A stepper motor + * @param pinB pinB bldc motor or pin1B stepper motor + * @param pinC pinC bldc motor or pin2A stepper motor + * @param pinD pin2B stepper motor + */ +void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/lowpass_filter.cpp b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/lowpass_filter.cpp new file mode 100644 index 00000000..9bf4ab7a --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/lowpass_filter.cpp @@ -0,0 +1,25 @@ +#include "lowpass_filter.h" + +LowPassFilter::LowPassFilter(float time_constant) + : Tf(time_constant) + , y_prev(0.0f) +{ + timestamp_prev = _micros(); +} + + +float LowPassFilter::operator() (float x) +{ + unsigned long timestamp = _micros(); + float dt = (timestamp - timestamp_prev)*1e-6f; + + if (dt < 0.0f || dt > 0.5f) + dt = 1e-3f; + + float alpha = Tf/(Tf + dt); + float y = alpha*y_prev + (1.0f - alpha)*x; + + y_prev = y; + timestamp_prev = timestamp; + return y; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/lowpass_filter.h b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/lowpass_filter.h new file mode 100644 index 00000000..5a7619cf --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/lowpass_filter.h @@ -0,0 +1,29 @@ +#ifndef LOWPASS_FILTER_H +#define LOWPASS_FILTER_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + + +/** + * Low pass filter class + */ +class LowPassFilter +{ +public: + /** + * @param Tf - Low pass filter time constant + */ + LowPassFilter(float Tf); + ~LowPassFilter() = default; + + float operator() (float x); + float Tf; //!< Low pass filter time constant + +protected: + unsigned long timestamp_prev; //!< Last execution timestamp + float y_prev; //!< filtered value in previous execution step +}; + +#endif // LOWPASS_FILTER_H \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/pid.cpp b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/pid.cpp new file mode 100644 index 00000000..277e17ce --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/pid.cpp @@ -0,0 +1,56 @@ +#include "pid.h" + +PIDController::PIDController(float P, float I, float D, float ramp, float limit) + : P(P) + , I(I) + , D(D) + , output_ramp(ramp) // output derivative limit [volts/second] + , limit(limit) // output supply limit [volts] + , integral_prev(0.0) + , error_prev(0.0) + , output_prev(0.0) +{ + timestamp_prev = _micros()*1e-6; +} + +// PID controller function +float PIDController::operator() (float error){ + // calculate the time from the last call + unsigned long timestamp_now = _micros(); + float Ts = (timestamp_now - timestamp_prev) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = P * error_prev; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = integral_prev + I*Ts*0.5*(error + error_prev); + // antiwindup - limit the output voltage_q + integral = constrain(integral, -limit, limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = D*(error - error_prev)/Ts; + + // sum all the components + float output = proportional + integral + derivative; + // antiwindup - limit the output variable + output = constrain(output, -limit, limit); + + // limit the acceleration by ramping the output + float output_rate = (output - output_prev)/Ts; + if (output_rate > output_ramp) + output = output_prev + output_ramp*Ts; + else if (output_rate < -output_ramp) + output = output_prev - output_ramp*Ts; + + // saving for the next pass + integral_prev = integral; + output_prev = output; + error_prev = error; + timestamp_prev = timestamp_now; + return output; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/pid.h b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/pid.h new file mode 100644 index 00000000..7ee337c4 --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/pid.h @@ -0,0 +1,40 @@ +#ifndef PID_H +#define PID_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + +/** + * PID controller class + */ +class PIDController +{ +public: + /** + * + * @param P - Proportional gain + * @param I - Integral gain + * @param D - Derivative gain + * @param ramp - Maximum speed of change of the output value + * @param limit - Maximum output value + */ + PIDController(float P, float I, float D, float ramp, float limit); + ~PIDController() = default; + + float operator() (float error); + + float P; //!< Proportional gain + float I; //!< Integral gain + float D; //!< Derivative gain + float output_ramp; //!< Maximum speed of change of the output value + float limit; //!< Maximum output value + +protected: + float integral_prev; //!< last integral component value + float error_prev; //!< last tracking error value + float timestamp_prev; //!< Last execution timestamp + float output_prev; //!< last pid output value +}; + +#endif // PID_H \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/arduino_foc_bldc_openloop.ino b/minimal_project_examples/arduino_foc_bldc_openloop/arduino_foc_bldc_openloop.ino new file mode 100644 index 00000000..fa632c9b --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_openloop/arduino_foc_bldc_openloop.ino @@ -0,0 +1,64 @@ +#include "src/BLDCMotor.h" + +// motor instance +BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 7); + +void setup() { + + // power supply voltage + // default 12V + motor.voltage_power_supply = 12; + + // limiting motor movements + motor.voltage_limit = 3; // rad/s + motor.velocity_limit = 20; // rad/s + // open loop control config + motor.controller = ControlType::velocity_openloop; + + // init motor hardware + motor.init(); + + + Serial.begin(115200); + Serial.println("Motor ready!"); + _delay(1000); +} + +float target_position = 0; // rad/s + + +void loop() { + // open loop angle movements + // using motor.voltage_limit and motor.velocity_limit + motor.move(2); + + // receive the used commands from serial + serialReceiveUserCommand(); + Serial.println(micros()); +} + +// utility function enabling serial communication with the user to set the target values +// this function can be implemented in serialEvent function as well +void serialReceiveUserCommand() { + + // a string to hold incoming data + static String received_chars; + + while (Serial.available()) { + // get the new byte: + char inChar = (char)Serial.read(); + // add it to the string buffer: + received_chars += inChar; + // end of user input + if (inChar == '\n') { + + // change the motor target + target_position = received_chars.toFloat(); + Serial.print("Target position: "); + Serial.println(target_position); + + // reset the command buffer + received_chars = ""; + } + } +} diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_bldc_openloop/src/BLDCMotor.cpp new file mode 100644 index 00000000..989b74a9 --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_openloop/src/BLDCMotor.cpp @@ -0,0 +1,378 @@ +#include "BLDCMotor.h" + +// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - phA, phB, phC - motor A,B,C phase pwm pins +// - pp - pole pair number +// - cpr - counts per rotation number (cpm=ppm*4) +// - enable pin - (optional input) +BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +: FOCMotor() +{ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + pole_pairs = pp; + + // enable_pin pin + enable_pin = en; + +} + + +// init hardware pins +void BLDCMotor::init(long pwm_frequency) { + if(monitor_port) monitor_port->println("MOT: Init pins."); + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); + + if(monitor_port) monitor_port->println("MOT: PWM config."); + // Increase PWM frequency to 32 kHz + // make silent + _setPwmFrequency(pwm_frequency, pwmA, pwmB, pwmC); + + // sanity check for the voltage limit configuration + if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + // update the controller limits + PID_velocity.limit = voltage_limit; + P_angle.limit = velocity_limit; + + _delay(500); + // enable motor + if(monitor_port) monitor_port->println("MOT: Enable."); + enable(); + _delay(500); +} + + +// disable motor driver +void BLDCMotor::disable() +{ + // disable the driver - if enable_pin pin available + if (enable_pin != NOT_SET) digitalWrite(enable_pin, LOW); + // set zero to PWM + setPwm(0, 0, 0); +} +// enable motor driver +void BLDCMotor::enable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // enable_pin the driver - if enable_pin pin available + if (enable_pin != NOT_SET) digitalWrite(enable_pin, HIGH); + +} + +/** + FOC functions +*/ +// FOC initialization function +int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } + if(monitor_port) monitor_port->println("MOT: Motor ready."); + + return exit_flag; +} +// Encoder alignment to electrical 0 angle +int BLDCMotor::alignSensor() { + if(monitor_port) monitor_port->println("MOT: Align sensor."); + // align the electrical phases of the motor and sensor + // set angle -90 degrees + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } + + // let the motor stabilize for 2 sec + _delay(2000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0,0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int BLDCMotor::absoluteZeroAlign() { + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); + + // align absolute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = _normalizeAngle(_electricalAngle(zero_offset, pole_pairs)); + } + // return bool if zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void BLDCMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); +} + +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function +// - if target is not set it uses motor.target value +void BLDCMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; + // get angular velocity + shaft_velocity = shaftVelocity(); + // choose control loop + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = P_angle( shaft_angle_sp - shaft_angle ); + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // include velocity loop + shaft_velocity_sp = target; + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); + break; + } +} + + +// Method using FOC to set Uq to the motor at the optimal angle +// Function implementing Space Vector PWM and Sine PWM algorithms +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) +void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { + switch (foc_modulation) + { + case FOCModulationType::SinePWM : + // Sinusoidal PWM modulation + // Inverse Park + Clarke transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + + // Clarke transform + Ua = Ualpha + voltage_power_supply/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + break; + + case FOCModulationType::SpaceVectorPWM : + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // https://www.youtube.com/watch?v=QMSWUMEAejg + + // if negative voltages change inverse the phase + // angle + 180degrees + if(Uq < 0) angle_el += _PI; + Uq = abs(Uq); + + // angle normalisation in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle + _PI_2); + + // find the sector we are in currently + int sector = floor(angle_el / _PI_3) + 1; + // calculate the duty cycles + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; + // two versions possible + // centered around voltage_power_supply/2 + float T0 = 1 - T1 - T2; + // pulled to 0 - better for low power supply voltage + //float T0 = 0; + + // calculate the duty cycles(times) + float Ta,Tb,Tc; + switch(sector){ + case 1: + Ta = T1 + T2 + T0/2; + Tb = T2 + T0/2; + Tc = T0/2; + break; + case 2: + Ta = T1 + T0/2; + Tb = T1 + T2 + T0/2; + Tc = T0/2; + break; + case 3: + Ta = T0/2; + Tb = T1 + T2 + T0/2; + Tc = T2 + T0/2; + break; + case 4: + Ta = T0/2; + Tb = T1+ T0/2; + Tc = T1 + T2 + T0/2; + break; + case 5: + Ta = T2 + T0/2; + Tb = T0/2; + Tc = T1 + T2 + T0/2; + break; + case 6: + Ta = T1 + T2 + T0/2; + Tb = T0/2; + Tc = T1 + T0/2; + break; + default: + // possible error state + Ta = 0; + Tb = 0; + Tc = 0; + } + + // calculate the phase voltages and center + Ua = Ta*voltage_power_supply; + Ub = Tb*voltage_power_supply; + Uc = Tc*voltage_power_supply; + break; + } + + // set the voltages in hardware + setPwm(Ua, Ub, Uc); +} + + + +// Set voltage to the pwm pin +void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { + // calculate duty cycle + // limited in [0,1] + float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); + // hardware specific writing + _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); +} + + + +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void BLDCMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void BLDCMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/BLDCMotor.h b/minimal_project_examples/arduino_foc_bldc_openloop/src/BLDCMotor.h new file mode 100644 index 00000000..a4fbb678 --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_openloop/src/BLDCMotor.h @@ -0,0 +1,113 @@ +/** + * @file BLDCMotor.h + * + */ + +#ifndef BLDCMotor_h +#define BLDCMotor_h + +#include "Arduino.h" +#include "common/FOCMotor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" +#include "common/defaults.h" + +/** + BLDC motor class +*/ +class BLDCMotor: public FOCMotor +{ + public: + /** + BLDCMotor class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param pp pole pair number + @param cpr counts per rotation number (cpm=ppm*4) + @param en enable pin (optional input) + */ + BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + + /** Motor hardware init function */ + void init(long pwm_frequency = NOT_SET) override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + */ + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW) override; + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + void loopFOC() override; + + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET) override; + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + + private: + // FOC methods + /** + * Method using FOC to set Uq to the motor at the optimal angle + * Heart of the FOC algorithm + * + * @param Uq Current voltage in q axis to set to the motor + * @param angle_el current electrical angle of the motor + */ + void setPhaseVoltage(float Uq, float angle_el); + /** Sensor alignment to electrical 0 angle of the motor */ + int alignSensor(); + /** Motor and sensor alignment to the sensors absolute 0 angle */ + int absoluteZeroAlign(); + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + * @param Uc phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc); + + // Open loop motion control + /** + * Function (iterative) generating open loop movement for target velocity + * it uses voltage_limit variable + * + * @param target_velocity - rad/s + */ + void velocityOpenloop(float target_velocity); + /** + * Function (iterative) generating open loop movement towards the target angle + * it uses voltage_limit and velocity_limit variables + * + * @param target_angle - rad + */ + void angleOpenloop(float target_angle); + // open loop variables + long open_loop_timestamp; +}; + + +#endif diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.cpp b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.cpp new file mode 100644 index 00000000..adecbeec --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.cpp @@ -0,0 +1,245 @@ +#include "FOCMotor.h" + +/** + * Default constructor - setting all variabels to default values + */ +FOCMotor::FOCMotor() +{ + // Power supply voltage + voltage_power_supply = DEF_POWER_SUPPLY; + + // maximum angular velocity to be used for positioning + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = voltage_power_supply; + + // index search velocity + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; + + // electric angle of comthe zero angle + zero_electric_angle = 0; + + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + + // default target value + target = 0; + + //monitor_port + monitor_port = nullptr; + //sensor + sensor = nullptr; +} + + +/** + Sensor communication methods +*/ +void FOCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} +// shaft angle calculation +float FOCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return shaft_angle; + return sensor->getAngle(); +} +// shaft velocity calculation +float FOCMotor::shaftVelocity() { + // if no sensor linked return 0 + if(!sensor) return 0; + return LPF_velocity(sensor->getVelocity()); +} + + + + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void FOCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void FOCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity_openloop: + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle_openloop: + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int FOCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'D': // velocity D gain change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PID velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P angle| "); + break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + } + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("P: "); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("I: "); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); + break; + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("volt_ramp: "); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET) { + voltage_limit = value; + PID_velocity.limit = value; + } + if(monitor_port) monitor_port->println(voltage_limit); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("Tf: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("vel_limit: "); + if(!GET){ + velocity_limit = value; + P_angle.limit = value; + } + if(monitor_port) monitor_port->println(velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Control: "); + + if(GET){ // if get command + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + default: + if(monitor_port) monitor_port->println("open loop"); + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.h b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.h new file mode 100644 index 00000000..40f7f6d4 --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.h @@ -0,0 +1,195 @@ +#ifndef FOCMOTOR_H +#define FOCMOTOR_H + +#include "Arduino.h" +#include "hardware_utils.h" +#include "foc_utils.h" +#include "defaults.h" + +#include "Sensor.h" +#include "pid.h" +#include "lowpass_filter.h" + + +/** + * Motiron control type + */ +enum ControlType{ + voltage,//!< Torque control using voltage + velocity,//!< Velocity motion control + angle,//!< Position/angle motion control + velocity_openloop, + angle_openloop +}; + +/** + * FOC modulation type + */ +enum FOCModulationType{ + SinePWM, //!< Sinusoidal PWM modulation + SpaceVectorPWM //!< Space vector modulation method +}; + +/** + Generic motor class +*/ +class FOCMotor +{ + public: + /** + * Default constructor - setting all variabels to default values + */ + FOCMotor(); + + /** Motor hardware init function */ + virtual void init(long pwm_frequency)=0; + /** Motor disable function */ + virtual void disable()=0; + /** Motor enable function */ + virtual void enable()=0; + + /** + * Function linking a motor and a sensor + * + * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity + */ + void linkSensor(Sensor* sensor); + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + virtual int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW)=0; + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + virtual void loopFOC()=0; + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + virtual void move(float target = NOT_SET)=0; + + // State calculation methods + /** Shaft angle calculation in radians [rad] */ + float shaftAngle(); + /** + * Shaft angle calculation function in radian per second [rad/s] + * It implements low pass filtering + */ + float shaftVelocity(); + + // state variables + float target; //!< current target value - depends of the controller + float shaft_angle;//!< current motor angle + float shaft_velocity;//!< current motor velocity + float shaft_velocity_sp;//!< current target velocity + float shaft_angle_sp;//!< current target angle + float voltage_q;//!< current voltage u_q set + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform + + // motor configuration parameters + float voltage_power_supply;//!< Power supply voltage + float voltage_sensor_align;//!< sensor and motor align voltage parameter + float velocity_index_search;//!< target velocity for index search + int pole_pairs;//!< Motor pole pairs number + + // limiting variables + float voltage_limit; //!< Voltage limitting variable - global limit + float velocity_limit; //!< Velocity limitting variable - global limit + + float zero_electric_angle;//! _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} + + +// normalizing radian angle to [0,2PI] +float _normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} + +// Electrical angle calculation +float _electricalAngle(float shaft_angle, int pole_pairs) { + return (shaft_angle * pole_pairs); +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/foc_utils.h b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/foc_utils.h new file mode 100644 index 00000000..5ab34f42 --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/foc_utils.h @@ -0,0 +1,55 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + +// sign function +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + +// utility defines +#define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI 3.14159265359 +#define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + + +#define NOT_SET -12345.0 + +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _sin(float a); +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _cos(float a); + +/** + * normalizing radian angle to [0,2PI] + * @param angle - angle to be normalized + */ +float _normalizeAngle(float angle); + + +/** + * Electrical angle calculation + * + * @param shaft_angle - shaft angle of the motor + * @param pole_pairs - number of pole pairs + */ +float _electricalAngle(float shaft_angle, int pole_pairs); +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/hardware_utils.cpp new file mode 100644 index 00000000..0d080bab --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/hardware_utils.cpp @@ -0,0 +1,284 @@ +#include "hardware_utils.h" + +#if defined(ESP_H) // if ESP32 board +// empty motor slot +#define _EMPTY_SLOT -20 + +// structure containing motor slot configuration +// this library supports up to 4 motors +typedef struct { + int pinA; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; + mcpwm_io_signals_t mcpwm_c; +} bldc_motor_slots_t; +typedef struct { + int pin1A; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_1a; + mcpwm_io_signals_t mcpwm_1b; + mcpwm_io_signals_t mcpwm_2a; + mcpwm_io_signals_t mcpwm_2b; +} stepper_motor_slots_t; + +// define bldc motor slots array +bldc_motor_slots_t esp32_bldc_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B + }; + +// define stepper motor slots array +stepper_motor_slots_t esp32_stepper_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + }; + +// configuring high frequency pwm timer +// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller +void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ + + mcpwm_config_t pwm_config; + pwm_config.frequency = pwm_frequency; //frequency + pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% + pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + _delay(100); + + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); + mcpwm_num->clk_cfg.prescale = 0; + + mcpwm_num->timer[0].period.prescale = 4; + mcpwm_num->timer[1].period.prescale = 4; + mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + mcpwm_num->timer[0].period.period = 2048; + mcpwm_num->timer[1].period.period = 2048; + mcpwm_num->timer[2].period.period = 2048; + _delay(1); + mcpwm_num->timer[0].period.upmethod = 0; + mcpwm_num->timer[1].period.upmethod = 0; + mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 0; +} + +#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips +// set pwm frequency to 32KHz +void _pinHighFrequency(const int pin){ + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pin == 5 || pin == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pin == 9 || pin == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pin == 3 || pin == 11) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +} +#elif defined(_STM32_DEF_) // if stm chips +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); + analogWriteResolution(12); // resolution 12 bit 0 - 4096 +} +#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); +} +#endif + + +// function setting the high pwm frequency to the supplied pins +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); + _pinHighFrequency(pinC); + if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor + +#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards + if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor + +#elif defined(ESP_H) // if esp32 boards + if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency + + if(pinD == NOT_SET){ + bldc_motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_motor_slots[i].pinA = pinA; + m_slot = esp32_bldc_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + + }else{ + stepper_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_motor_slots[i].pin1A = pinA; + m_slot = esp32_stepper_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + } +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pinA, 4095.0*dc_a); + analogWrite(pinB, 4095.0*dc_b); + analogWrite(pinC, 4095.0*dc_c); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255*dc_a); + analogWrite(pinB, 255*dc_b); + analogWrite(pinC, 255*dc_c); +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pin1A, 4095.0*dc_1a); + analogWrite(pin1B, 4095.0*dc_1b); + analogWrite(pin2A, 4095.0*dc_2a); + analogWrite(pin2B, 4095.0*dc_2b); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255*dc_1a); + analogWrite(pin1B, 255*dc_1b); + analogWrite(pin2A, 255*dc_2a); + analogWrite(pin2B, 255*dc_2b); +#endif +} + + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/hardware_utils.h b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/hardware_utils.h new file mode 100644 index 00000000..f99c260a --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/hardware_utils.h @@ -0,0 +1,72 @@ +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H + +#include "Arduino.h" +#include "foc_utils.h" + + +#if defined(ESP_H) // if esp32 boards + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +#endif + +/** + * High PWM frequency setting function + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc motor or pin1A stepper motor + * @param pinB pinB bldc motor or pin1B stepper motor + * @param pinC pinC bldc motor or pin2A stepper motor + * @param pinD pin2B stepper motor + */ +void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/lowpass_filter.cpp b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/lowpass_filter.cpp new file mode 100644 index 00000000..9bf4ab7a --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/lowpass_filter.cpp @@ -0,0 +1,25 @@ +#include "lowpass_filter.h" + +LowPassFilter::LowPassFilter(float time_constant) + : Tf(time_constant) + , y_prev(0.0f) +{ + timestamp_prev = _micros(); +} + + +float LowPassFilter::operator() (float x) +{ + unsigned long timestamp = _micros(); + float dt = (timestamp - timestamp_prev)*1e-6f; + + if (dt < 0.0f || dt > 0.5f) + dt = 1e-3f; + + float alpha = Tf/(Tf + dt); + float y = alpha*y_prev + (1.0f - alpha)*x; + + y_prev = y; + timestamp_prev = timestamp; + return y; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/lowpass_filter.h b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/lowpass_filter.h new file mode 100644 index 00000000..5a7619cf --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/lowpass_filter.h @@ -0,0 +1,29 @@ +#ifndef LOWPASS_FILTER_H +#define LOWPASS_FILTER_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + + +/** + * Low pass filter class + */ +class LowPassFilter +{ +public: + /** + * @param Tf - Low pass filter time constant + */ + LowPassFilter(float Tf); + ~LowPassFilter() = default; + + float operator() (float x); + float Tf; //!< Low pass filter time constant + +protected: + unsigned long timestamp_prev; //!< Last execution timestamp + float y_prev; //!< filtered value in previous execution step +}; + +#endif // LOWPASS_FILTER_H \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/pid.cpp b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/pid.cpp new file mode 100644 index 00000000..277e17ce --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/pid.cpp @@ -0,0 +1,56 @@ +#include "pid.h" + +PIDController::PIDController(float P, float I, float D, float ramp, float limit) + : P(P) + , I(I) + , D(D) + , output_ramp(ramp) // output derivative limit [volts/second] + , limit(limit) // output supply limit [volts] + , integral_prev(0.0) + , error_prev(0.0) + , output_prev(0.0) +{ + timestamp_prev = _micros()*1e-6; +} + +// PID controller function +float PIDController::operator() (float error){ + // calculate the time from the last call + unsigned long timestamp_now = _micros(); + float Ts = (timestamp_now - timestamp_prev) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = P * error_prev; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = integral_prev + I*Ts*0.5*(error + error_prev); + // antiwindup - limit the output voltage_q + integral = constrain(integral, -limit, limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = D*(error - error_prev)/Ts; + + // sum all the components + float output = proportional + integral + derivative; + // antiwindup - limit the output variable + output = constrain(output, -limit, limit); + + // limit the acceleration by ramping the output + float output_rate = (output - output_prev)/Ts; + if (output_rate > output_ramp) + output = output_prev + output_ramp*Ts; + else if (output_rate < -output_ramp) + output = output_prev - output_ramp*Ts; + + // saving for the next pass + integral_prev = integral; + output_prev = output; + error_prev = error; + timestamp_prev = timestamp_now; + return output; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/pid.h b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/pid.h new file mode 100644 index 00000000..7ee337c4 --- /dev/null +++ b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/pid.h @@ -0,0 +1,40 @@ +#ifndef PID_H +#define PID_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + +/** + * PID controller class + */ +class PIDController +{ +public: + /** + * + * @param P - Proportional gain + * @param I - Integral gain + * @param D - Derivative gain + * @param ramp - Maximum speed of change of the output value + * @param limit - Maximum output value + */ + PIDController(float P, float I, float D, float ramp, float limit); + ~PIDController() = default; + + float operator() (float error); + + float P; //!< Proportional gain + float I; //!< Integral gain + float D; //!< Derivative gain + float output_ramp; //!< Maximum speed of change of the output value + float limit; //!< Maximum output value + +protected: + float integral_prev; //!< last integral component value + float error_prev; //!< last tracking error value + float timestamp_prev; //!< Last execution timestamp + float output_prev; //!< last pid output value +}; + +#endif // PID_H \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_minimal_encoder/src/common/hardware_utils.cpp deleted file mode 100644 index 802087a7..00000000 --- a/minimal_project_examples/arduino_foc_minimal_encoder/src/common/hardware_utils.cpp +++ /dev/null @@ -1,219 +0,0 @@ -#include "hardware_utils.h" - -#if defined(ESP_H) // if ESP32 board -// empty motor slot -#define _EMPTY_SLOT -20 - -// structure containing motor slot configuration -// this library supports up to 4 motors -typedef struct { - int pinA; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator; - mcpwm_io_signals_t mcpwm_a; - mcpwm_io_signals_t mcpwm_b; - mcpwm_io_signals_t mcpwm_c; - -} motor_slots_t; - -// define motor slots array -motor_slots_t esp32_motor_slots[4] = { - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B - }; - -#endif - - -// function setting the high pwm frequency to the supplied pins -// - hardware speciffic -// supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(const int pinA, const int pinB, const int pinC, const int pinD) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips - // High PWM frequency - // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pinA == 5 || pinA == 6 || pinB == 5 || pinB == 6 || pinC == 5 || pinC == 6 || pinD == 5 || pinD == 6 ) { - TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode - TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - } - if (pinA == 9 || pinA == 10 || pinB == 9 || pinB == 10 || pinC == 9 || pinC == 10|| pinD == 9 || pinD == 10 ) - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pinA == 3 || pinA == 11 || pinB == 3 || pinB == 11 || pinC == 3 || pinC == 11 || pinD == 3 || pinD == 11 ) - TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 - -#elif defined(_STM32_DEF_) // if stm chips - - analogWrite(pinA, 0); - analogWriteFrequency(50000); // set 50kHz - analogWriteResolution(12); // resolution 12 bit 0 - 4096 - analogWrite(pinB, 0); - analogWriteFrequency(50000); // set 50kHz - analogWriteResolution(12); // resolution 12 bit 0 - 4096 - analogWrite(pinC, 0); - analogWriteFrequency(50000); // set 50kHz - analogWriteResolution(12); // resolution 12 bit 0 - 4096 - if(pinD) { - analogWrite(pinD, 0); - analogWriteFrequency(50000); // set 50kHz - analogWriteResolution(12); // resolution 12 bit 0 - 4096 - -#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards - analogWrite(pinA, 0); - analogWriteFrequency(pinA, 50000); // set 50kHz - analogWrite(pinB, 0); - analogWriteFrequency(pinB, 50000); // set 50kHz - analogWrite(pinC, 0); - analogWriteFrequency(pinC, 50000); // set 50kHz - if(pinD) { - analogWrite(pinD, 0); - analogWriteFrequency(50000); // set 50kHz - -#elif defined(ESP_H) // if esp32 boards - - motor_slots_t m_slot = {}; - - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 4; i++){ - if(esp32_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_motor_slots[i].pinA = pinA; - m_slot = esp32_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); - - mcpwm_config_t pwm_config; - pwm_config.frequency = 4000000; //frequency = 20000Hz - pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% - pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% - pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) - pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings - - _delay(100); - - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_0); - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_1); - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_2); - m_slot.mcpwm_num->clk_cfg.prescale = 0; - - m_slot.mcpwm_num->timer[0].period.prescale = 4; - m_slot.mcpwm_num->timer[1].period.prescale = 4; - m_slot.mcpwm_num->timer[2].period.prescale = 4; - _delay(1); - m_slot.mcpwm_num->timer[0].period.period = 2048; - m_slot.mcpwm_num->timer[1].period.period = 2048; - m_slot.mcpwm_num->timer[2].period.period = 2048; - _delay(1); - m_slot.mcpwm_num->timer[0].period.upmethod = 0; - m_slot.mcpwm_num->timer[1].period.upmethod = 0; - m_slot.mcpwm_num->timer[2].period.upmethod = 0; - _delay(1); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_0); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_1); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_2); - - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); - _delay(1); - m_slot.mcpwm_num->timer[0].sync.out_sel = 1; - _delay(1); - m_slot.mcpwm_num->timer[0].sync.out_sel = 0; -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 4; i++){ - if(esp32_motor_slots[i].pinA == pinA){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; - esp32_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; - esp32_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pinA, 4095.0*dc_a); - analogWrite(pinB, 4095.0*dc_b); - analogWrite(pinC, 4095.0*dc_c); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255*dc_a); - analogWrite(pinB, 255*dc_b); - analogWrite(pinC, 255*dc_c); -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ -#if defined(ESP_H) // if ESP32 boards - // not sure how to handle this -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pin1A, 4095.0*dc_1a); - analogWrite(pin1B, 4095.0*dc_1b); - analogWrite(pin2A, 4095.0*dc_2a); - analogWrite(pin2B, 4095.0*dc_2b); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255*dc_1a); - analogWrite(pin1B, 255*dc_1b); - analogWrite(pin2A, 255*dc_2a); - analogWrite(pin2B, 255*dc_2b); -#endif -} - - -// function buffering delay() -// arduino uno function doesn't work well with interrupts -void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) - // if arduino uno and other atmega328p chips - // use while instad of delay, - // due to wrong measurement based on changed timer0 - unsigned long t = _micros() + ms*1000; - while( _micros() < t ){}; -#else - // regular micros - delay(ms); -#endif -} - - -// function buffering _micros() -// arduino function doesn't work well with interrupts -unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) -// if arduino uno and other atmega328p chips - //return the value based on the prescaler - if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); - else return (micros()); -#else - // regular micros - return micros(); -#endif -} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_encoder1/src/StepperMotor.cpp b/minimal_project_examples/arduino_foc_minimal_encoder1/src/StepperMotor.cpp deleted file mode 100644 index 5cc6ce17..00000000 --- a/minimal_project_examples/arduino_foc_minimal_encoder1/src/StepperMotor.cpp +++ /dev/null @@ -1,650 +0,0 @@ -#include "StepperMotor.h" - -// StepperMotor( int phA, int phB, int phC, int pp, int cpr, int en) -// - ph1A, ph1B - motor phase 1 pwm pins -// - ph2A, ph2B - motor phase 2 pwm pins -// - pp - pole pair number -// - enable pin - (optional input) -StepperMotor::StepperMotor(int ph1A, int ph1B, int ph2A, int ph2B, int pp, int en1, int en2) -{ - // Pin initialization - pwm1A = ph1A; - pwm1B = ph1B; - pwm2A = ph2A; - pwm2B = ph2B; - pole_pairs = pp; - - // enable_pin pin - enable_pin1 = en1; - enable_pin2 = en2; - - // Power supply voltage - voltage_power_supply = DEF_POWER_SUPPLY; - - // Velocity loop config - // PI controller constant - PID_velocity.P = DEF_PID_VEL_P; - PID_velocity.I = DEF_PID_VEL_I; - PID_velocity.D = DEF_PID_VEL_D; - PID_velocity.output_ramp = DEF_PID_VEL_U_RAMP; - PID_velocity.timestamp = _micros(); - PID_velocity.integral_prev = 0; - PID_velocity.output_prev = 0; - PID_velocity.tracking_error_prev = 0; - - // velocity low pass filter - LPF_velocity.Tf = DEF_VEL_FILTER_Tf; - LPF_velocity.timestamp = _micros(); - LPF_velocity.prev = 0; - - // position loop config - // P controller constant - P_angle.P = DEF_P_ANGLE_P; - - // maximum angular velocity to be used for positioning - velocity_limit = DEF_VEL_LIM; - // maximum voltage to be set to the motor - voltage_limit = voltage_power_supply; - - // index search velocity - velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; - // sensor and motor align voltage - voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; - - // electric angle of the zero angle - zero_electric_angle = 0; - - // default modulation is SinePWM - foc_modulation = FOCModulationType::SinePWM; - - // default target value - target = 0; - - //monitor_port - monitor_port = nullptr; - //sensor - sensor = nullptr; -} - -// init hardware pins -void StepperMotor::init() { - if(monitor_port) monitor_port->println("MOT: Init pins."); - // PWM pins - pinMode(pwm1A, OUTPUT); - pinMode(pwm1B, OUTPUT); - pinMode(pwm2A, OUTPUT); - pinMode(pwm2B, OUTPUT); - if ( enable_pin1 != NOT_SET ) pinMode(enable_pin1, OUTPUT); - if ( enable_pin2 != NOT_SET ) pinMode(enable_pin2, OUTPUT); - - if(monitor_port) monitor_port->println("MOT: PWM config."); - // Increase PWM frequency - // make silent - _setPwmFrequency(pwm1A, pwm1B, pwm2A, pwm2B); - - // sanity check for the voltage limit configuration - if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; - // constrain voltage for sensor alignment - if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; - - _delay(500); - // enable motor - if(monitor_port) monitor_port->println("MOT: Enable."); - enable(); - _delay(500); - -} - - -// disable motor driver -void StepperMotor::disable() -{ - // disable the driver - if enable_pin pin available - if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, LOW); - if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, LOW); - // set zero to PWM - setPwm(0, 0); -} -// enable motor driver -void StepperMotor::enable() -{ - // set zero to PWM - setPwm(0, 0); - // enable_pin the driver - if enable_pin pin available - if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, HIGH); - if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, HIGH); - -} - -void StepperMotor::linkSensor(Sensor* _sensor) { - sensor = _sensor; -} - - -// Encoder alignment to electrical 0 angle -int StepperMotor::alignSensor() { - if(monitor_port) monitor_port->println("MOT: Align sensor."); - // align the electrical phases of the motor and sensor - // set angle -90 degrees - - float start_angle = shaftAngle(); - for (int i = 0; i <=5; i++ ) { - float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); - _delay(200); - } - float mid_angle = shaftAngle(); - for (int i = 5; i >=0; i-- ) { - float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); - _delay(200); - } - if (mid_angle < start_angle) { - if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); - sensor->natural_direction = Direction::CCW; - } else if (mid_angle == start_angle) { - if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); - } - - // let the motor stabilize for 2 sec - _delay(2000); - // set sensor to zero - sensor->initRelativeZero(); - _delay(500); - setPhaseVoltage(0,0); - _delay(200); - - // find the index if available - int exit_flag = absoluteZeroAlign(); - _delay(500); - if(monitor_port){ - if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); - if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); - else monitor_port->println("MOT: Not available!"); - } - return exit_flag; -} - - -// Encoder alignment the absolute zero angle -// - to the index -int StepperMotor::absoluteZeroAlign() { - - if(monitor_port) monitor_port->println("MOT: Absolute zero align."); - // if no absolute zero return - if(!sensor->hasAbsoluteZero()) return 0; - - - if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); - // search the absolute zero with small velocity - while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ - loopFOC(); - voltage_q = velocityPID(velocity_index_search - shaftVelocity()); - } - voltage_q = 0; - // disable motor - setPhaseVoltage(0,0); - - // align absolute zero if it has been found - if(!sensor->needsAbsoluteZeroSearch()){ - // align the sensor with the absolute zero - float zero_offset = sensor->initAbsoluteZero(); - // remember zero electric angle - zero_electric_angle = normalizeAngle(electricAngle(zero_offset)); - } - // return bool if zero found - return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; -} - -/** - State calculation methods -*/ -// shaft angle calculation -float StepperMotor::shaftAngle() { - // if no sensor linked return 0 - if(!sensor) return 0; - return sensor->getAngle(); -} -// shaft velocity calculation -float StepperMotor::shaftVelocity() { - // if no sensor linked return 0 - if(!sensor) return 0; - return lowPassFilter(sensor->getVelocity(), LPF_velocity); -} -// Electrical angle calculation -float StepperMotor::electricAngle(float shaftAngle) { - //return normalizeAngle(shaftAngle * pole_pairs); - return (shaftAngle * pole_pairs); -} - -/** - FOC functions -*/ -// FOC initialization function -int StepperMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { - int exit_flag = 1; - // align motor if necessary - // alignment necessary for encoders! - if(zero_electric_offset != NOT_SET){ - // abosolute zero offset provided - no need to align - zero_electric_angle = zero_electric_offset; - // set the sensor direction - default CW - sensor->natural_direction = sensor_direction; - }else{ - // sensor and motor alignment - _delay(500); - exit_flag = alignSensor(); - _delay(500); - } - if(monitor_port) monitor_port->println("MOT: Motor ready."); - - return exit_flag; -} - -// Iterative function looping FOC algorithm, setting Uq on the Motor -// The faster it can be run the better -void StepperMotor::loopFOC() { - // shaft angle - shaft_angle = shaftAngle(); - // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); -} - -// Iterative function running outer loop of the FOC algorithm -// Behavior of this function is determined by the motor.controller variable -// It runs either angle, velocity or voltage loop -// - needs to be called iteratively it is asynchronous function -// - if target is not set it uses motor.target value -void StepperMotor::move(float new_target) { - // set internal target variable - if( new_target != NOT_SET ) target = new_target; - // get angular velocity - shaft_velocity = shaftVelocity(); - // choose control loop - switch (controller) { - case ControlType::voltage: - voltage_q = target; - break; - case ControlType::angle: - // angle set point - // include angle loop - shaft_angle_sp = target; - shaft_velocity_sp = positionP( shaft_angle_sp - shaft_angle ); - voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); - break; - case ControlType::velocity: - // velocity set point - // include velocity loop - shaft_velocity_sp = target; - voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); - break; - case ControlType::velocity_openloop: - // velocity control in open loop - // loopFOC should not be called - shaft_velocity_sp = target; - velocityOpenloop(shaft_velocity_sp); - break; - case ControlType::angle_openloop: - // angle control in open loop - // loopFOC should not be called - shaft_angle_sp = target; - angleOpenloop(shaft_angle_sp); - break; - } -} - - -// Method using FOC to set Uq to the motor at the optimal angle -// Function implementingSine PWM algorithms -// - space vector not implemented yet -// -// Function using sine approximation -// regular sin + cos ~300us (no memory usaage) -// approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void StepperMotor::setPhaseVoltage(float Uq, float angle_el) { - // Sinusoidal PWM modulation - // Inverse Park transformation - - // angle normalization in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - angle_el = normalizeAngle(angle_el + zero_electric_angle); - // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; - // set the voltages in hardware - setPwm(Ualpha,Ubeta); -} - - - -// Set voltage to the pwm pin -void StepperMotor::setPwm(float Ualpha, float Ubeta) { - float duty_cycle1A = 0,duty_cycle1B,duty_cycle2A,duty_cycle2B; - // hardware specific writing - if( Ualpha > 0 ){ - duty_cycle1A = 0; - duty_cycle1B = constrain(abs(Ualpha)/voltage_power_supply,0,1); - } else { - duty_cycle1B = 0; - duty_cycle1A = constrain(abs(Ualpha)/voltage_power_supply,0,1); - } - - if( Ubeta > 0 ){ - duty_cycle2A = 0; - duty_cycle2B = constrain(abs(Ubeta)/voltage_power_supply,0,1); - } else { - duty_cycle2B = 0; - duty_cycle2A = constrain(abs(Ubeta)/voltage_power_supply,0,1); - } - // write to hardware - _writeDutyCycle(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, pwm1A, pwm1B, pwm2A, pwm2B); -} - -/** - Utility functions -*/ -// normalizing radian angle to [0,2PI] -float StepperMotor::normalizeAngle(float angle){ - float a = fmod(angle, _2PI); - return a >= 0 ? a : (a + _2PI); -} - -// low pass filter function -// - input -singal to be filtered -// - lpf -LPF_s structure with filter parameters -float StepperMotor::lowPassFilter(float input, LPF_s& lpf){ - unsigned long now_us = _micros(); - float Ts = (now_us - lpf.timestamp) * 1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // calculate the filtering - float alpha = lpf.Tf/(lpf.Tf + Ts); - float out = alpha*lpf.prev + (1-alpha)*input; - - // save the variables - lpf.prev = out; - lpf.timestamp = now_us; - return out; -} - - -/** - Motor control functions -*/ -// PID controller function -float StepperMotor::controllerPID(float tracking_error, PID_s& cont){ - // calculate the time from the last call - unsigned long now_us = _micros(); - float Ts = (now_us - cont.timestamp) * 1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // u(s) = (P + I/s + Ds)e(s) - // Discrete implementations - // proportional part - // u_p = P *e(k) - float proportional = cont.P * tracking_error; - // Tustin transform of the integral part - // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) - float integral = cont.integral_prev + cont.I*Ts*0.5*(tracking_error + cont.tracking_error_prev); - // antiwindup - limit the output voltage_q - integral = constrain(integral, -voltage_limit, voltage_limit); - // Discrete derivation - // u_dk = D(ek - ek_1)/Ts - float derivative = cont.D*(tracking_error - cont.tracking_error_prev)/Ts; - // sum all the components - float voltage = proportional + integral + derivative; - - // antiwindup - limit the output voltage_q - voltage = constrain(voltage, -voltage_limit, voltage_limit); - - // limit the acceleration by ramping the the voltage - float d_voltage = voltage - cont.output_prev; - if (abs(d_voltage)/Ts > cont.output_ramp) voltage = d_voltage > 0 ? cont.output_prev + cont.output_ramp*Ts : cont.output_prev - cont.output_ramp*Ts; - - // saving for the next pass - cont.integral_prev = integral; - cont.output_prev = voltage; - cont.tracking_error_prev = tracking_error; - cont.timestamp = now_us; - return voltage; -} -// velocity control loop PI controller -float StepperMotor::velocityPID(float tracking_error) { - return controllerPID(tracking_error, PID_velocity); -} - -// P controller for position control loop -float StepperMotor::positionP(float ek) { - // calculate the target velocity from the position error - float velocity_target = P_angle.P * ek; - // constrain velocity target value - velocity_target = constrain(velocity_target, -velocity_limit, velocity_limit); - return velocity_target; -} - -// Function (iterative) generating open loop movement for target velocity -// - target_velocity - rad/s -// it uses voltage_limit variable -void StepperMotor::velocityOpenloop(float target_velocity){ - // get current timestamp - unsigned long now_us = _micros(); - // calculate the sample time from last call - float Ts = (now_us - open_loop_timestamp) * 1e-6; - - // calculate the necessary angle to achieve target velocity - shaft_angle += target_velocity*Ts; - - // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); - - // save timestamp for next call - open_loop_timestamp = now_us; -} - -// Function (iterative) generating open loop movement towards the target angle -// - target_angle - rad -// it uses voltage_limit and velocity_limit variables -void StepperMotor::angleOpenloop(float target_angle){ - // get current timestamp - unsigned long now_us = _micros(); - // calculate the sample time from last call - float Ts = (now_us - open_loop_timestamp) * 1e-6; - - // calculate the necessary angle to move from current position towards target angle - // with maximal velocity (velocity_limit) - if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) - shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; - else - shaft_angle = target_angle; - - // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); - - // save timestamp for next call - open_loop_timestamp = now_us; -} - -/** - * Monitoring functions - */ -// function implementing the monitor_port setter -void StepperMotor::useMonitoring(Print &print){ - monitor_port = &print; //operate on the address of print - if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); -} -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void StepperMotor::monitor() { - if(!monitor_port) return; - switch (controller) { - case ControlType::velocity_openloop: - case ControlType::velocity: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_velocity_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - case ControlType::angle_openloop: - case ControlType::angle: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_angle); - break; - case ControlType::voltage: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - } -} - -int StepperMotor::command(String user_command) { - // error flag - int errorFlag = 1; - // if empty string - if(user_command.length() < 1) return errorFlag; - - // parse command letter - char cmd = user_command.charAt(0); - // check if get command - char GET = user_command.charAt(1) == '\n'; - // parse command values - float value = user_command.substring(1).toFloat(); - - // a bit of optimisation of variable memory for Arduino UNO (atmega328) - switch(cmd){ - case 'P': // velocity P gain change - case 'I': // velocity I gain change - case 'D': // velocity D gain change - case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print(" PID velocity| "); - break; - case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print(" LPF velocity| "); - break; - case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print(" P angle| "); - break; - case 'L': // velocity voltage limit change - case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print(" Limits| "); - break; - - } - - // apply the the command - switch(cmd){ - case 'P': // velocity P gain change - if(monitor_port) monitor_port->print("P: "); - if(!GET) PID_velocity.P = value; - if(monitor_port) monitor_port->println(PID_velocity.P); - break; - case 'I': // velocity I gain change - if(monitor_port) monitor_port->print("I: "); - if(!GET) PID_velocity.I = value; - if(monitor_port) monitor_port->println(PID_velocity.I); - break; - case 'D': // velocity D gain change - if(monitor_port) monitor_port->print("D: "); - if(!GET) PID_velocity.D = value; - if(monitor_port) monitor_port->println(PID_velocity.D); - break; - case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print("volt_ramp: "); - if(!GET) PID_velocity.output_ramp = value; - if(monitor_port) monitor_port->println(PID_velocity.output_ramp); - break; - case 'L': // velocity voltage limit change - if(monitor_port) monitor_port->print("volt_limit: "); - if(!GET)voltage_limit = value; - if(monitor_port) monitor_port->println(voltage_limit); - break; - case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print("Tf: "); - if(!GET) LPF_velocity.Tf = value; - if(monitor_port) monitor_port->println(LPF_velocity.Tf); - break; - case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print(" P: "); - if(!GET) P_angle.P = value; - if(monitor_port) monitor_port->println(P_angle.P); - break; - case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print("vel_limit: "); - if(!GET) velocity_limit = value; - if(monitor_port) monitor_port->println(velocity_limit); - break; - case 'C': - // change control type - if(monitor_port) monitor_port->print("Control: "); - - if(GET){ // if get command - switch(controller){ - case ControlType::voltage: - if(monitor_port) monitor_port->println("voltage"); - break; - case ControlType::velocity: - if(monitor_port) monitor_port->println("velocity"); - break; - case ControlType::angle: - if(monitor_port) monitor_port->println("angle"); - break; - default: - if(monitor_port) monitor_port->println("open loop"); - } - }else{ // if set command - switch((int)value){ - case 0: - if(monitor_port) monitor_port->println("voltage"); - controller = ControlType::voltage; - break; - case 1: - if(monitor_port) monitor_port->println("velocity"); - controller = ControlType::velocity; - break; - case 2: - if(monitor_port) monitor_port->println("angle"); - controller = ControlType::angle; - break; - default: // not valid command - errorFlag = 0; - } - } - break; - case 'V': // get current values of the state variables - switch((int)value){ - case 0: // get voltage - if(monitor_port) monitor_port->print("Uq: "); - if(monitor_port) monitor_port->println(voltage_q); - break; - case 1: // get velocity - if(monitor_port) monitor_port->print("Velocity: "); - if(monitor_port) monitor_port->println(shaft_velocity); - break; - case 2: // get angle - if(monitor_port) monitor_port->print("Angle: "); - if(monitor_port) monitor_port->println(shaft_angle); - break; - case 3: // get angle - if(monitor_port) monitor_port->print("Target: "); - if(monitor_port) monitor_port->println(target); - break; - default: // not valid command - errorFlag = 0; - } - break; - default: // target change - if(monitor_port) monitor_port->print("Target : "); - target = user_command.toFloat(); - if(monitor_port) monitor_port->println(target); - } - // return 0 if error and 1 if ok - return errorFlag; -} diff --git a/minimal_project_examples/arduino_foc_minimal_encoder1/src/StepperMotor.h b/minimal_project_examples/arduino_foc_minimal_encoder1/src/StepperMotor.h deleted file mode 100644 index 17e7b36f..00000000 --- a/minimal_project_examples/arduino_foc_minimal_encoder1/src/StepperMotor.h +++ /dev/null @@ -1,326 +0,0 @@ -/** - * @file StepperMotor.h - * - */ - -#ifndef StepperMotor_h -#define StepperMotor_h - -#include "Arduino.h" -#include "common/FOCutils.h" -#include "common/Sensor.h" -#include "common/defaults.h" - - -#define NOT_SET -12345.0 - -/** - * Motiron control type - */ -enum ControlType{ - voltage,//!< Torque control using voltage - velocity,//!< Velocity motion control - angle,//!< Position/angle motion control - velocity_openloop, - angle_openloop -}; - -/** - * FOC modulation type - */ -enum FOCModulationType{ - SinePWM, //!< Sinusoidal PWM modulation - SpaceVectorPWM //!< Space vector modulation method -}; - -/** - * PID controller structure - */ -struct PID_s{ - float P; //!< Proportional gain - float I; //!< Integral gain - float D; //!< Derivative gain - long timestamp; //!< Last execution timestamp - float integral_prev; //!< last integral component value - float output_prev; //!< last pid output value - float output_ramp; //!< Maximum speed of change of the output value - float tracking_error_prev; //!< last tracking error value -}; - -// P controller structure -struct P_s{ - float P; //!< Proportional gain - long timestamp; //!< Last execution timestamp -}; - -/** - * Low pass filter structure - */ -struct LPF_s{ - float Tf; //!< Low pass filter time constant - long timestamp; //!< Last execution timestamp - float prev; //!< filtered value in previous execution step -}; - - - - -/** - Stepper Motor class -*/ -class StepperMotor -{ - public: - /** - StepperMotor class constructor - @param ph1A 1A phase pwm pin - @param ph1B 1B phase pwm pin - @param ph2A 2A phase pwm pin - @param ph2B 2B phase pwm pin - @param pp pole pair number - cpr counts per rotation number (cpm=ppm*4) - @param en1 enable pin phase 1 (optional input) - @param en2 enable pin phase 2 (optional input) - */ - StepperMotor(int ph1A,int ph1B,int ph2A,int ph2B,int pp, int en1 = NOT_SET, int en2 = NOT_SET); - - /** Motor hardware init function */ - void init(); - /** Motor disable function */ - void disable(); - /** Motor enable function */ - void enable(); - - /** - * Function linking a motor and a sensor - * - * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity - */ - void linkSensor(Sensor* sensor); - - /** - * Function initializing FOC algorithm - * and aligning sensor's and motors' zero position - * - * - If zero_electric_offset parameter is set the alignment procedure is skipped - * - * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. - * @param sensor_direction sensor natural direction - default is CW - * - */ - int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); - /** - * Function running FOC algorithm in real-time - * it calculates the gets motor angle and sets the appropriate voltages - * to the phase pwm signals - * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us - */ - void loopFOC(); - /** - * Function executing the control loops set by the controller parameter of the BLDCMotor. - * - * @param target Either voltage, angle or velocity based on the motor.controller - * If it is not set the motor will use the target set in its variable motor.target - * - * This function doesn't need to be run upon each loop execution - depends of the use case - */ - void move(float target = NOT_SET); - - // hardware variables - int pwm1A; //!< phase 1A pwm pin number - int pwm1B; //!< phase 1B pwm pin number - int pwm2A; //!< phase 2A pwm pin number - int pwm2B; //!< phase 2B pwm pin number - int enable_pin1; //!< enable pin number phase 1 - int enable_pin2; //!< enable pin number phase 2 - - - - - - // State calculation methods - /** Shaft angle calculation in radians [rad] */ - float shaftAngle(); - /** - * Shaft angle calculation function in radian per second [rad/s] - * It implements low pass filtering - */ - float shaftVelocity(); - - // state variables - float target; //!< current target value - depends of the controller - float shaft_angle;//!< current motor angle - float shaft_velocity;//!< current motor velocity - float shaft_velocity_sp;//!< current target velocity - float shaft_angle_sp;//!< current target angle - float voltage_q;//!< current voltage u_q set - - // motor configuration parameters - float voltage_power_supply;//!< Power supply voltage - float voltage_sensor_align;//!< sensor and motor align voltage parameter - float velocity_index_search;//!< target velocity for index search - int pole_pairs;//!< Motor pole pairs number - - // limiting variables - float voltage_limit; //!< Voltage limitting variable - global limit - float velocity_limit; //!< Velocity limitting variable - global limit - - // configuration structures - ControlType controller; //!< parameter determining the control loop to be used - FOCModulationType foc_modulation;//!< parameter derterniming modulation algorithm - PID_s PID_velocity;//!< parameter determining the velocity PI configuration - P_s P_angle; //!< parameter determining the position P configuration - LPF_s LPF_velocity;//!< parameter determining the velocity Lpw pass filter configuration - - /** - * Sensor link: - * - Encoder - * - MagneticSensor - */ - Sensor* sensor; - - float zero_electric_angle;//!clk_cfg.prescale = 0; - - m_slot.mcpwm_num->timer[0].period.prescale = 4; - m_slot.mcpwm_num->timer[1].period.prescale = 4; - m_slot.mcpwm_num->timer[2].period.prescale = 4; - _delay(1); - m_slot.mcpwm_num->timer[0].period.period = 2048; - m_slot.mcpwm_num->timer[1].period.period = 2048; - m_slot.mcpwm_num->timer[2].period.period = 2048; - _delay(1); - m_slot.mcpwm_num->timer[0].period.upmethod = 0; - m_slot.mcpwm_num->timer[1].period.upmethod = 0; - m_slot.mcpwm_num->timer[2].period.upmethod = 0; - _delay(1); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_0); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_1); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_2); - - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); - _delay(1); - m_slot.mcpwm_num->timer[0].sync.out_sel = 1; - _delay(1); - m_slot.mcpwm_num->timer[0].sync.out_sel = 0; -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 4; i++){ - if(esp32_motor_slots[i].pinA == pinA){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; - esp32_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; - esp32_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pinA, 4095.0*dc_a); - analogWrite(pinB, 4095.0*dc_b); - analogWrite(pinC, 4095.0*dc_c); -#else // Arduino - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255*dc_a); - analogWrite(pinB, 255*dc_b); - analogWrite(pinC, 255*dc_c); -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ -#if defined(ESP_H) // if ESP32 boards - // not sure how to hande this -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pin1A, 4095.0*dc_1a); - analogWrite(pin1B, 4095.0*dc_1b); - analogWrite(pin2A, 4095.0*dc_2a); - analogWrite(pin2B, 4095.0*dc_2b); -#else // Arduino - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255*dc_1a); - analogWrite(pin1B, 255*dc_1b); - analogWrite(pin2A, 255*dc_2a); - analogWrite(pin2B, 255*dc_2b); -#endif -} - - -// function buffering delay() -// arduino uno function doesn't work well with interrupts -void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) - // if arduino uno and other atmega328p chips - // use while instad of delay, - // due to wrong measurement based on changed timer0 - unsigned long t = _micros() + ms*1000; - while( _micros() < t ){}; -#else - // regular micros - delay(ms); -#endif -} - - -// function buffering _micros() -// arduino function doesn't work well with interrupts -unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) -// if arduino uno and other atmega328p chips - //return the value based on the prescaler - if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); - else return (micros()); -#else - // regular micros - return micros(); -#endif -} - - -// int array instead of float array -// 2x storage save (int 2Byte float 4 Byte ) -// sin*10000 -int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,1103,1181,1260,1338,1416,1494,1572,1650,1728,1806,1883,1961,2038,2115,2192,2269,2346,2423,2499,2575,2652,2728,2804,2879,2955,3030,3105,3180,3255,3329,3404,3478,3552,3625,3699,3772,3845,3918,3990,4063,4135,4206,4278,4349,4420,4491,4561,4631,4701,4770,4840,4909,4977,5046,5113,5181,5249,5316,5382,5449,5515,5580,5646,5711,5775,5839,5903,5967,6030,6093,6155,6217,6279,6340,6401,6461,6521,6581,6640,6699,6758,6815,6873,6930,6987,7043,7099,7154,7209,7264,7318,7371,7424,7477,7529,7581,7632,7683,7733,7783,7832,7881,7930,7977,8025,8072,8118,8164,8209,8254,8298,8342,8385,8428,8470,8512,8553,8594,8634,8673,8712,8751,8789,8826,8863,8899,8935,8970,9005,9039,9072,9105,9138,9169,9201,9231,9261,9291,9320,9348,9376,9403,9429,9455,9481,9506,9530,9554,9577,9599,9621,9642,9663,9683,9702,9721,9739,9757,9774,9790,9806,9821,9836,9850,9863,9876,9888,9899,9910,9920,9930,9939,9947,9955,9962,9969,9975,9980,9985,9989,9992,9995,9997,9999,10000,10000}; - -// function approximating the sine calculation by using fixed size array -// ~40us (float array) -// ~50us (int array) -// precision +-0.005 -// it has to receive an angle in between 0 and 2PI -float _sin(float a){ - if(a < _PI_2){ - //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; - //return sine_array[(int)(126.6873* a)]; // float array optimized - return 0.0001*sine_array[_round(126.6873* a)]; // int array optimized - }else if(a < _PI){ - // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; - //return sine_array[398 - (int)(126.6873*a)]; // float array optimized - return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimized - }else if(a < _3PI_2){ - // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; - //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimized - return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimized - } else { - // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; - //return -sine_array[796 - (int)(126.6873*a)]; // float array optimized - return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimized - } -} - -// function approximating cosine calculation by using fixed size array -// ~55us (float array) -// ~56us (int array) -// precision +-0.005 -// it has to receive an angle in between 0 and 2PI -float _cos(float a){ - float a_sin = a + _PI_2; - a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin; - return _sin(a_sin); -} diff --git a/minimal_project_examples/arduino_foc_minimal_hall/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_minimal_hall/BLDCMotor.cpp deleted file mode 100644 index f31e818a..00000000 --- a/minimal_project_examples/arduino_foc_minimal_hall/BLDCMotor.cpp +++ /dev/null @@ -1,716 +0,0 @@ -#include "BLDCMotor.h" - -// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) -// - phA, phB, phC - motor A,B,C phase pwm pins -// - pp - pole pair number -// - cpr - counts per rotation number (cpm=ppm*4) -// - enable pin - (optional input) -BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) -{ - // Pin initialization - pwmA = phA; - pwmB = phB; - pwmC = phC; - pole_pairs = pp; - - // enable_pin pin - enable_pin = en; - - // Power supply voltage - voltage_power_supply = DEF_POWER_SUPPLY; - - // Velocity loop config - // PI controller constant - PID_velocity.P = DEF_PID_VEL_P; - PID_velocity.I = DEF_PID_VEL_I; - PID_velocity.D = DEF_PID_VEL_D; - PID_velocity.output_ramp = DEF_PID_VEL_U_RAMP; - PID_velocity.timestamp = _micros(); - PID_velocity.integral_prev = 0; - PID_velocity.output_prev = 0; - PID_velocity.tracking_error_prev = 0; - - // velocity low pass filter - LPF_velocity.Tf = DEF_VEL_FILTER_Tf; - LPF_velocity.timestamp = _micros(); - LPF_velocity.prev = 0; - - // position loop config - // P controller constant - P_angle.P = DEF_P_ANGLE_P; - - // maximum angular velocity to be used for positioning - velocity_limit = DEF_VEL_LIM; - // maximum voltage to be set to the motor - voltage_limit = voltage_power_supply; - - // index search velocity - velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; - // sensor and motor align voltage - voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; - - // electric angle of the zero angle - zero_electric_angle = 0; - - // default modulation is SinePWM - foc_modulation = FOCModulationType::SinePWM; - - // default target value - target = 0; - - //monitor_port - monitor_port = nullptr; - //sensor - sensor = nullptr; -} - -// init hardware pins -void BLDCMotor::init() { - if(monitor_port) monitor_port->println("MOT: Init pins."); - // PWM pins - pinMode(pwmA, OUTPUT); - pinMode(pwmB, OUTPUT); - pinMode(pwmC, OUTPUT); - if(hasEnable()) pinMode(enable_pin, OUTPUT); - - if(monitor_port) monitor_port->println("MOT: PWM config."); - // Increase PWM frequency to 32 kHz - // make silent - _setPwmFrequency(pwmA, pwmB, pwmC); - - // sanity check for the voltage limit configuration - if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; - // constrain voltage for sensor alignment - if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; - - _delay(500); - // enable motor - if(monitor_port) monitor_port->println("MOT: Enable."); - enable(); - _delay(500); - -} - - -// disable motor driver -void BLDCMotor::disable() -{ - // disable the driver - if enable_pin pin available - if (hasEnable()) digitalWrite(enable_pin, LOW); - // set zero to PWM - setPwm(0, 0, 0); -} -// enable motor driver -void BLDCMotor::enable() -{ - // set zero to PWM - setPwm(0, 0, 0); - // enable_pin the driver - if enable_pin pin available - if (hasEnable()) digitalWrite(enable_pin, HIGH); - -} - -void BLDCMotor::linkSensor(Sensor* _sensor) { - sensor = _sensor; -} - - -// Encoder alignment to electrical 0 angle -int BLDCMotor::alignSensor() { - if(monitor_port) monitor_port->println("MOT: Align sensor."); - // align the electrical phases of the motor and sensor - // set angle -90 degrees - - float start_angle = shaftAngle(); - for (int i = 0; i <=5; i++ ) { - float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); - _delay(200); - } - float mid_angle = shaftAngle(); - for (int i = 5; i >=0; i-- ) { - float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); - _delay(200); - } - if (mid_angle < start_angle) { - if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); - sensor->natural_direction = Direction::CCW; - } else if (mid_angle == start_angle) { - if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); - } - - // let the motor stabilize for 2 sec - _delay(2000); - // set sensor to zero - sensor->initRelativeZero(); - _delay(500); - setPhaseVoltage(0,0); - _delay(200); - - // find the index if available - int exit_flag = absoluteZeroAlign(); - _delay(500); - if(monitor_port){ - if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); - if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); - else monitor_port->println("MOT: Not available!"); - } - return exit_flag; -} - - -// Encoder alignment the absolute zero angle -// - to the index -int BLDCMotor::absoluteZeroAlign() { - - if(monitor_port) monitor_port->println("MOT: Absolute zero align."); - // if no absolute zero return - if(!sensor->hasAbsoluteZero()) return 0; - - - if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); - // search the absolute zero with small velocity - while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ - loopFOC(); - voltage_q = velocityPID(velocity_index_search - shaftVelocity()); - } - voltage_q = 0; - // disable motor - setPhaseVoltage(0,0); - - // align absolute zero if it has been found - if(!sensor->needsAbsoluteZeroSearch()){ - // align the sensor with the absolute zero - float zero_offset = sensor->initAbsoluteZero(); - // remember zero electric angle - zero_electric_angle = normalizeAngle(electricAngle(zero_offset)); - } - // return bool if zero found - return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; -} - -/** - State calculation methods -*/ -// shaft angle calculation -float BLDCMotor::shaftAngle() { - // if no sensor linked return 0 - if(!sensor) return 0; - return sensor->getAngle(); -} -// shaft velocity calculation -float BLDCMotor::shaftVelocity() { - // if no sensor linked return 0 - if(!sensor) return 0; - return lowPassFilter(sensor->getVelocity(), LPF_velocity); -} -// Electrical angle calculation -float BLDCMotor::electricAngle(float shaftAngle) { - //return normalizeAngle(shaftAngle * pole_pairs); - return (shaftAngle * pole_pairs); -} - -/** - FOC functions -*/ -// FOC initialization function -int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { - int exit_flag = 1; - // align motor if necessary - // alignment necessary for encoders! - if(zero_electric_offset != NOT_SET){ - // abosolute zero offset provided - no need to align - zero_electric_angle = zero_electric_offset; - // set the sensor direction - default CW - sensor->natural_direction = sensor_direction; - }else{ - // sensor and motor alignment - _delay(500); - exit_flag = alignSensor(); - _delay(500); - } - if(monitor_port) monitor_port->println("MOT: Motor ready."); - - return exit_flag; -} - -// Iterative function looping FOC algorithm, setting Uq on the Motor -// The faster it can be run the better -void BLDCMotor::loopFOC() { - // shaft angle - shaft_angle = shaftAngle(); - // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); -} - -// Iterative function running outer loop of the FOC algorithm -// Behavior of this function is determined by the motor.controller variable -// It runs either angle, velocity or voltage loop -// - needs to be called iteratively it is asynchronous function -// - if target is not set it uses motor.target value -void BLDCMotor::move(float new_target) { - // set internal target variable - if( new_target != NOT_SET ) target = new_target; - // get angular velocity - shaft_velocity = shaftVelocity(); - // choose control loop - switch (controller) { - case ControlType::voltage: - voltage_q = target; - break; - case ControlType::angle: - // angle set point - // include angle loop - shaft_angle_sp = target; - shaft_velocity_sp = positionP( shaft_angle_sp - shaft_angle ); - voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); - break; - case ControlType::velocity: - // velocity set point - // include velocity loop - shaft_velocity_sp = target; - voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); - break; - case ControlType::velocity_openloop: - // velocity control in open loop - // loopFOC should not be called - shaft_velocity_sp = target; - velocityOpenloop(shaft_velocity_sp); - break; - case ControlType::angle_openloop: - // angle control in open loop - // loopFOC should not be called - shaft_angle_sp = target; - angleOpenloop(shaft_angle_sp); - break; - } -} - - -// Method using FOC to set Uq to the motor at the optimal angle -// Function implementing Space Vector PWM and Sine PWM algorithms -// -// Function using sine approximation -// regular sin + cos ~300us (no memory usaage) -// approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { - switch (foc_modulation) - { - case FOCModulationType::SinePWM : - // Sinusoidal PWM modulation - // Inverse Park + Clarke transformation - - // angle normalization in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - angle_el = normalizeAngle(angle_el + zero_electric_angle); - // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; - - // Clarke transform - Ua = Ualpha + voltage_power_supply/2; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; - break; - - case FOCModulationType::SpaceVectorPWM : - // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm - // https://www.youtube.com/watch?v=QMSWUMEAejg - - // if negative voltages change inverse the phase - // angle + 180degrees - if(Uq < 0) angle_el += _PI; - Uq = abs(Uq); - - // angle normalisation in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - angle_el = normalizeAngle(angle_el + zero_electric_angle + _PI_2); - - // find the sector we are in currently - int sector = floor(angle_el / _PI_3) + 1; - // calculate the duty cycles - float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; - float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; - // two versions possible - // centered around voltage_power_supply/2 - float T0 = 1 - T1 - T2; - // pulled to 0 - better for low power supply voltage - //float T0 = 0; - - // calculate the duty cycles(times) - float Ta,Tb,Tc; - switch(sector){ - case 1: - Ta = T1 + T2 + T0/2; - Tb = T2 + T0/2; - Tc = T0/2; - break; - case 2: - Ta = T1 + T0/2; - Tb = T1 + T2 + T0/2; - Tc = T0/2; - break; - case 3: - Ta = T0/2; - Tb = T1 + T2 + T0/2; - Tc = T2 + T0/2; - break; - case 4: - Ta = T0/2; - Tb = T1+ T0/2; - Tc = T1 + T2 + T0/2; - break; - case 5: - Ta = T2 + T0/2; - Tb = T0/2; - Tc = T1 + T2 + T0/2; - break; - case 6: - Ta = T1 + T2 + T0/2; - Tb = T0/2; - Tc = T1 + T0/2; - break; - default: - // possible error state - Ta = 0; - Tb = 0; - Tc = 0; - } - - // calculate the phase voltages and center - Ua = Ta*voltage_power_supply; - Ub = Tb*voltage_power_supply; - Uc = Tc*voltage_power_supply; - break; - } - - // set the voltages in hardware - setPwm(Ua, Ub, Uc); -} - - - -// Set voltage to the pwm pin -void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { - // calculate duty cycle - // limited in [0,1] - float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); - float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); - float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); - // hardware specific writing - _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); -} - -/** - Utility functions -*/ -// normalizing radian angle to [0,2PI] -float BLDCMotor::normalizeAngle(float angle){ - float a = fmod(angle, _2PI); - return a >= 0 ? a : (a + _2PI); -} -// determining if the enable pin has been provided -int BLDCMotor::hasEnable(){ - return enable_pin != NOT_SET; -} - -// low pass filter function -// - input -singal to be filtered -// - lpf -LPF_s structure with filter parameters -float BLDCMotor::lowPassFilter(float input, LPF_s& lpf){ - unsigned long now_us = _micros(); - float Ts = (now_us - lpf.timestamp) * 1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // calculate the filtering - float alpha = lpf.Tf/(lpf.Tf + Ts); - float out = alpha*lpf.prev + (1-alpha)*input; - - // save the variables - lpf.prev = out; - lpf.timestamp = now_us; - return out; -} - - -/** - Motor control functions -*/ -// PID controller function -float BLDCMotor::controllerPID(float tracking_error, PID_s& cont){ - // calculate the time from the last call - unsigned long now_us = _micros(); - float Ts = (now_us - cont.timestamp) * 1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // u(s) = (P + I/s + Ds)e(s) - // Discrete implementations - // proportional part - // u_p = P *e(k) - float proportional = cont.P * tracking_error; - // Tustin transform of the integral part - // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) - float integral = cont.integral_prev + cont.I*Ts*0.5*(tracking_error + cont.tracking_error_prev); - // antiwindup - limit the output voltage_q - integral = constrain(integral, -voltage_limit, voltage_limit); - // Discrete derivation - // u_dk = D(ek - ek_1)/Ts - float derivative = cont.D*(tracking_error - cont.tracking_error_prev)/Ts; - // sum all the components - float voltage = proportional + integral + derivative; - - // antiwindup - limit the output voltage_q - voltage = constrain(voltage, -voltage_limit, voltage_limit); - - // limit the acceleration by ramping the the voltage - float d_voltage = voltage - cont.output_prev; - if (abs(d_voltage)/Ts > cont.output_ramp) voltage = d_voltage > 0 ? cont.output_prev + cont.output_ramp*Ts : cont.output_prev - cont.output_ramp*Ts; - - // saving for the next pass - cont.integral_prev = integral; - cont.output_prev = voltage; - cont.tracking_error_prev = tracking_error; - cont.timestamp = now_us; - return voltage; -} -// velocity control loop PI controller -float BLDCMotor::velocityPID(float tracking_error) { - return controllerPID(tracking_error, PID_velocity); -} - -// P controller for position control loop -float BLDCMotor::positionP(float ek) { - // calculate the target velocity from the position error - float velocity_target = P_angle.P * ek; - // constrain velocity target value - velocity_target = constrain(velocity_target, -velocity_limit, velocity_limit); - return velocity_target; -} - -// Function (iterative) generating open loop movement for target velocity -// - target_velocity - rad/s -// it uses voltage_limit variable -void BLDCMotor::velocityOpenloop(float target_velocity){ - // get current timestamp - unsigned long now_us = _micros(); - // calculate the sample time from last call - float Ts = (now_us - open_loop_timestamp) * 1e-6; - - // calculate the necessary angle to achieve target velocity - shaft_angle += target_velocity*Ts; - - // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); - - // save timestamp for next call - open_loop_timestamp = now_us; -} - -// Function (iterative) generating open loop movement towards the target angle -// - target_angle - rad -// it uses voltage_limit and velocity_limit variables -void BLDCMotor::angleOpenloop(float target_angle){ - // get current timestamp - unsigned long now_us = _micros(); - // calculate the sample time from last call - float Ts = (now_us - open_loop_timestamp) * 1e-6; - - // calculate the necessary angle to move from current position towards target angle - // with maximal velocity (velocity_limit) - if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) - shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; - else - shaft_angle = target_angle; - - // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); - - // save timestamp for next call - open_loop_timestamp = now_us; -} - -/** - * Monitoring functions - */ -// function implementing the monitor_port setter -void BLDCMotor::useMonitoring(Print &print){ - monitor_port = &print; //operate on the address of print - if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); -} -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void BLDCMotor::monitor() { - if(!monitor_port) return; - switch (controller) { - case ControlType::velocity_openloop: - case ControlType::velocity: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_velocity_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - case ControlType::angle_openloop: - case ControlType::angle: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_angle); - break; - case ControlType::voltage: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - } -} - -int BLDCMotor::command(String user_command) { - // error flag - int errorFlag = 1; - // if empty string - if(user_command.length() < 1) return errorFlag; - - // parse command letter - char cmd = user_command.charAt(0); - // check if get command - char GET = user_command.charAt(1) == '\n'; - // parse command values - float value = user_command.substring(1).toFloat(); - - // a bit of optimisation of variable memory for Arduino UNO (atmega328) - switch(cmd){ - case 'P': // velocity P gain change - case 'I': // velocity I gain change - case 'D': // velocity D gain change - case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print(" PID velocity| "); - break; - case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print(" LPF velocity| "); - break; - case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print(" P angle| "); - break; - case 'L': // velocity voltage limit change - case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print(" Limits| "); - break; - - } - - // apply the the command - switch(cmd){ - case 'P': // velocity P gain change - if(monitor_port) monitor_port->print("P: "); - if(!GET) PID_velocity.P = value; - if(monitor_port) monitor_port->println(PID_velocity.P); - break; - case 'I': // velocity I gain change - if(monitor_port) monitor_port->print("I: "); - if(!GET) PID_velocity.I = value; - if(monitor_port) monitor_port->println(PID_velocity.I); - break; - case 'D': // velocity D gain change - if(monitor_port) monitor_port->print("D: "); - if(!GET) PID_velocity.D = value; - if(monitor_port) monitor_port->println(PID_velocity.D); - break; - case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print("volt_ramp: "); - if(!GET) PID_velocity.output_ramp = value; - if(monitor_port) monitor_port->println(PID_velocity.output_ramp); - break; - case 'L': // velocity voltage limit change - if(monitor_port) monitor_port->print("volt_limit: "); - if(!GET)voltage_limit = value; - if(monitor_port) monitor_port->println(voltage_limit); - break; - case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print("Tf: "); - if(!GET) LPF_velocity.Tf = value; - if(monitor_port) monitor_port->println(LPF_velocity.Tf); - break; - case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print(" P: "); - if(!GET) P_angle.P = value; - if(monitor_port) monitor_port->println(P_angle.P); - break; - case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print("vel_limit: "); - if(!GET) velocity_limit = value; - if(monitor_port) monitor_port->println(velocity_limit); - break; - case 'C': - // change control type - if(monitor_port) monitor_port->print("Control: "); - - if(GET){ // if get command - switch(controller){ - case ControlType::voltage: - if(monitor_port) monitor_port->println("voltage"); - break; - case ControlType::velocity: - if(monitor_port) monitor_port->println("velocity"); - break; - case ControlType::angle: - if(monitor_port) monitor_port->println("angle"); - break; - default: - if(monitor_port) monitor_port->println("open loop"); - } - }else{ // if set command - switch((int)value){ - case 0: - if(monitor_port) monitor_port->println("voltage"); - controller = ControlType::voltage; - break; - case 1: - if(monitor_port) monitor_port->println("velocity"); - controller = ControlType::velocity; - break; - case 2: - if(monitor_port) monitor_port->println("angle"); - controller = ControlType::angle; - break; - default: // not valid command - errorFlag = 0; - } - } - break; - case 'V': // get current values of the state variables - switch((int)value){ - case 0: // get voltage - if(monitor_port) monitor_port->print("Uq: "); - if(monitor_port) monitor_port->println(voltage_q); - break; - case 1: // get velocity - if(monitor_port) monitor_port->print("Velocity: "); - if(monitor_port) monitor_port->println(shaft_velocity); - break; - case 2: // get angle - if(monitor_port) monitor_port->print("Angle: "); - if(monitor_port) monitor_port->println(shaft_angle); - break; - case 3: // get angle - if(monitor_port) monitor_port->print("Target: "); - if(monitor_port) monitor_port->println(target); - break; - default: // not valid command - errorFlag = 0; - } - break; - default: // target change - if(monitor_port) monitor_port->print("Target : "); - target = user_command.toFloat(); - if(monitor_port) monitor_port->println(target); - } - // return 0 if error and 1 if ok - return errorFlag; -} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_hall/FOCutils.cpp b/minimal_project_examples/arduino_foc_minimal_hall/FOCutils.cpp deleted file mode 100644 index 653c7191..00000000 --- a/minimal_project_examples/arduino_foc_minimal_hall/FOCutils.cpp +++ /dev/null @@ -1,215 +0,0 @@ -#include "FOCutils.h" - -#if defined(ESP_H) // if ESP32 board -// empty motor slot -#define _EMPTY_SLOT -20 - -// structure containing motor slot configuration -// this library supports up to 4 motors -typedef struct { - int pinA; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator; - mcpwm_io_signals_t mcpwm_a; - mcpwm_io_signals_t mcpwm_b; - mcpwm_io_signals_t mcpwm_c; - -} motor_slots_t; - -// define motor slots array -motor_slots_t esp32_motor_slots[4] = { - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B - }; - -#endif - - -// function setting the high pwm frequency to the supplied pins -// - hardware speciffic -// supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(const int pinA, const int pinB, const int pinC) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips - // High PWM frequency - // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pinA == 5 || pinA == 6 || pinB == 5 || pinB == 6 || pinC == 5 || pinC == 6 ) { - TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode - TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - } - if (pinA == 9 || pinA == 10 || pinB == 9 || pinB == 10 || pinC == 9 || pinC == 10 ) - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pinA == 3 || pinA == 11 || pinB == 3 || pinB == 11 || pinC == 3 || pinC == 11 ) - TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 - -#elif defined(_STM32_DEF_) // if stm chips - - analogWrite(pinA, 0); - analogWriteFrequency(50000); // set 50kHz - analogWrite(pinB, 0); - analogWriteFrequency(50000); // set 50kHz - analogWrite(pinC, 0); - analogWriteFrequency(50000); // set 50kHz - -#elif defined(ESP_H) // if esp32 boards - - motor_slots_t m_slot = {}; - - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 4; i++){ - if(esp32_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_motor_slots[i].pinA = pinA; - m_slot = esp32_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); - - mcpwm_config_t pwm_config; - pwm_config.frequency = 4000000; //frequency = 20000Hz - pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% - pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% - pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) - pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings - - _delay(100); - - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_0); - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_1); - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_2); - m_slot.mcpwm_num->clk_cfg.prescale = 0; - - m_slot.mcpwm_num->timer[0].period.prescale = 4; - m_slot.mcpwm_num->timer[1].period.prescale = 4; - m_slot.mcpwm_num->timer[2].period.prescale = 4; - _delay(1); - m_slot.mcpwm_num->timer[0].period.period = 2048; - m_slot.mcpwm_num->timer[1].period.period = 2048; - m_slot.mcpwm_num->timer[2].period.period = 2048; - _delay(1); - m_slot.mcpwm_num->timer[0].period.upmethod = 0; - m_slot.mcpwm_num->timer[1].period.upmethod = 0; - m_slot.mcpwm_num->timer[2].period.upmethod = 0; - _delay(1); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_0); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_1); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_2); - - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); - _delay(1); - m_slot.mcpwm_num->timer[0].sync.out_sel = 1; - _delay(1); - m_slot.mcpwm_num->timer[0].sync.out_sel = 0; -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 4; i++){ - if(esp32_motor_slots[i].pinA == pinA){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; - esp32_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; - esp32_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; - break; - } - } -#else // Arduino & STM32 devices - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255*dc_a); - analogWrite(pinB, 255*dc_b); - analogWrite(pinC, 255*dc_c); -#endif -} - - -// function buffering delay() -// arduino uno function doesn't work well with interrupts -void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) - // if arduino uno and other atmega328p chips - // use while instad of delay, - // due to wrong measurement based on changed timer0 - unsigned long t = _micros() + ms*1000; - while( _micros() < t ){}; -#else - // regular micros - delay(ms); -#endif -} - - -// function buffering _micros() -// arduino function doesn't work well with interrupts -unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) -// if arduino uno and other atmega328p chips - //return the value based on the prescaler - if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); - else return (micros()); -#else - // regular micros - return micros(); -#endif -} - - -// int array instead of float array -// 2x storage save (int 2Byte float 4 Byte ) -// sin*10000 -int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,1103,1181,1260,1338,1416,1494,1572,1650,1728,1806,1883,1961,2038,2115,2192,2269,2346,2423,2499,2575,2652,2728,2804,2879,2955,3030,3105,3180,3255,3329,3404,3478,3552,3625,3699,3772,3845,3918,3990,4063,4135,4206,4278,4349,4420,4491,4561,4631,4701,4770,4840,4909,4977,5046,5113,5181,5249,5316,5382,5449,5515,5580,5646,5711,5775,5839,5903,5967,6030,6093,6155,6217,6279,6340,6401,6461,6521,6581,6640,6699,6758,6815,6873,6930,6987,7043,7099,7154,7209,7264,7318,7371,7424,7477,7529,7581,7632,7683,7733,7783,7832,7881,7930,7977,8025,8072,8118,8164,8209,8254,8298,8342,8385,8428,8470,8512,8553,8594,8634,8673,8712,8751,8789,8826,8863,8899,8935,8970,9005,9039,9072,9105,9138,9169,9201,9231,9261,9291,9320,9348,9376,9403,9429,9455,9481,9506,9530,9554,9577,9599,9621,9642,9663,9683,9702,9721,9739,9757,9774,9790,9806,9821,9836,9850,9863,9876,9888,9899,9910,9920,9930,9939,9947,9955,9962,9969,9975,9980,9985,9989,9992,9995,9997,9999,10000,10000}; - -// function approximating the sine calculation by using fixed size array -// ~40us (float array) -// ~50us (int array) -// precision +-0.005 -// it has to receive an angle in between 0 and 2PI -float _sin(float a){ - if(a < _PI_2){ - //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; - //return sine_array[(int)(126.6873* a)]; // float array optimized - return 0.0001*sine_array[_round(126.6873* a)]; // int array optimized - }else if(a < _PI){ - // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; - //return sine_array[398 - (int)(126.6873*a)]; // float array optimized - return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimized - }else if(a < _3PI_2){ - // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; - //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimized - return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimized - } else { - // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; - //return -sine_array[796 - (int)(126.6873*a)]; // float array optimized - return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimized - } -} - -// function approximating cosine calculation by using fixed size array -// ~55us (float array) -// ~56us (int array) -// precision +-0.005 -// it has to receive an angle in between 0 and 2PI -float _cos(float a){ - float a_sin = a + _PI_2; - a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin; - return _sin(a_sin); -} diff --git a/minimal_project_examples/arduino_foc_minimal_hall/FOCutils.h b/minimal_project_examples/arduino_foc_minimal_hall/FOCutils.h deleted file mode 100644 index 4c347a12..00000000 --- a/minimal_project_examples/arduino_foc_minimal_hall/FOCutils.h +++ /dev/null @@ -1,86 +0,0 @@ -#ifndef FOCUTILS_LIB_H -#define FOCUTILS_LIB_H - -#include "Arduino.h" - - -#if defined(ESP_H) // if esp32 boards - -#include "driver/mcpwm.h" -#include "soc/mcpwm_reg.h" -#include "soc/mcpwm_struct.h" - -#endif - -// sign function -#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) -#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) - -// utility defines -#define _2_SQRT3 1.15470053838 -#define _SQRT3 1.73205080757 -#define _1_SQRT3 0.57735026919 -#define _SQRT3_2 0.86602540378 -#define _SQRT2 1.41421356237 -#define _120_D2R 2.09439510239 -#define _PI 3.14159265359 -#define _PI_2 1.57079632679 -#define _PI_3 1.0471975512 -#define _2PI 6.28318530718 -#define _3PI_2 4.71238898038 - -/** - * High PWM frequency setting function - * - hardware specific - * - * @param pinA pinA number to configure - * @param pinB pinB number to configure - * @param pinC pinC number to configure - */ -void _setPwmFrequency(int pinA, int pinB, int pinC); - -/** - * Function implementing delay() function in milliseconds - * - blocking function - * - hardware specific - - * @param ms number of milliseconds to wait - */ -void _delay(unsigned long ms); - -/** - * Function implementing timestamp getting function in microseconds - * hardware specific - */ -unsigned long _micros(); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_a duty cycle phase A [0, 1] - * @param dc_b duty cycle phase B [0, 1] - * @param dc_c duty cycle phase C [0, 1] - * @param pinA phase A hardware pin number - * @param pinB phase B hardware pin number - * @param pinC phase C hardware pin number - */ -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); - - -/** - * Function approximating the sine calculation by using fixed size array - * - execution time ~40us (Arduino UNO) - * - * @param a angle in between 0 and 2PI - */ -float _sin(float a); -/** - * Function approximating cosine calculation by using fixed size array - * - execution time ~50us (Arduino UNO) - * - * @param a angle in between 0 and 2PI - */ -float _cos(float a); - -#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/hardware_utils.cpp deleted file mode 100644 index 802087a7..00000000 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_i2c/src/common/hardware_utils.cpp +++ /dev/null @@ -1,219 +0,0 @@ -#include "hardware_utils.h" - -#if defined(ESP_H) // if ESP32 board -// empty motor slot -#define _EMPTY_SLOT -20 - -// structure containing motor slot configuration -// this library supports up to 4 motors -typedef struct { - int pinA; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator; - mcpwm_io_signals_t mcpwm_a; - mcpwm_io_signals_t mcpwm_b; - mcpwm_io_signals_t mcpwm_c; - -} motor_slots_t; - -// define motor slots array -motor_slots_t esp32_motor_slots[4] = { - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B - }; - -#endif - - -// function setting the high pwm frequency to the supplied pins -// - hardware speciffic -// supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(const int pinA, const int pinB, const int pinC, const int pinD) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips - // High PWM frequency - // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pinA == 5 || pinA == 6 || pinB == 5 || pinB == 6 || pinC == 5 || pinC == 6 || pinD == 5 || pinD == 6 ) { - TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode - TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - } - if (pinA == 9 || pinA == 10 || pinB == 9 || pinB == 10 || pinC == 9 || pinC == 10|| pinD == 9 || pinD == 10 ) - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pinA == 3 || pinA == 11 || pinB == 3 || pinB == 11 || pinC == 3 || pinC == 11 || pinD == 3 || pinD == 11 ) - TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 - -#elif defined(_STM32_DEF_) // if stm chips - - analogWrite(pinA, 0); - analogWriteFrequency(50000); // set 50kHz - analogWriteResolution(12); // resolution 12 bit 0 - 4096 - analogWrite(pinB, 0); - analogWriteFrequency(50000); // set 50kHz - analogWriteResolution(12); // resolution 12 bit 0 - 4096 - analogWrite(pinC, 0); - analogWriteFrequency(50000); // set 50kHz - analogWriteResolution(12); // resolution 12 bit 0 - 4096 - if(pinD) { - analogWrite(pinD, 0); - analogWriteFrequency(50000); // set 50kHz - analogWriteResolution(12); // resolution 12 bit 0 - 4096 - -#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards - analogWrite(pinA, 0); - analogWriteFrequency(pinA, 50000); // set 50kHz - analogWrite(pinB, 0); - analogWriteFrequency(pinB, 50000); // set 50kHz - analogWrite(pinC, 0); - analogWriteFrequency(pinC, 50000); // set 50kHz - if(pinD) { - analogWrite(pinD, 0); - analogWriteFrequency(50000); // set 50kHz - -#elif defined(ESP_H) // if esp32 boards - - motor_slots_t m_slot = {}; - - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 4; i++){ - if(esp32_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_motor_slots[i].pinA = pinA; - m_slot = esp32_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); - - mcpwm_config_t pwm_config; - pwm_config.frequency = 4000000; //frequency = 20000Hz - pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% - pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% - pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) - pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings - - _delay(100); - - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_0); - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_1); - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_2); - m_slot.mcpwm_num->clk_cfg.prescale = 0; - - m_slot.mcpwm_num->timer[0].period.prescale = 4; - m_slot.mcpwm_num->timer[1].period.prescale = 4; - m_slot.mcpwm_num->timer[2].period.prescale = 4; - _delay(1); - m_slot.mcpwm_num->timer[0].period.period = 2048; - m_slot.mcpwm_num->timer[1].period.period = 2048; - m_slot.mcpwm_num->timer[2].period.period = 2048; - _delay(1); - m_slot.mcpwm_num->timer[0].period.upmethod = 0; - m_slot.mcpwm_num->timer[1].period.upmethod = 0; - m_slot.mcpwm_num->timer[2].period.upmethod = 0; - _delay(1); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_0); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_1); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_2); - - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); - _delay(1); - m_slot.mcpwm_num->timer[0].sync.out_sel = 1; - _delay(1); - m_slot.mcpwm_num->timer[0].sync.out_sel = 0; -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 4; i++){ - if(esp32_motor_slots[i].pinA == pinA){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; - esp32_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; - esp32_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pinA, 4095.0*dc_a); - analogWrite(pinB, 4095.0*dc_b); - analogWrite(pinC, 4095.0*dc_c); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255*dc_a); - analogWrite(pinB, 255*dc_b); - analogWrite(pinC, 255*dc_c); -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ -#if defined(ESP_H) // if ESP32 boards - // not sure how to handle this -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pin1A, 4095.0*dc_1a); - analogWrite(pin1B, 4095.0*dc_1b); - analogWrite(pin2A, 4095.0*dc_2a); - analogWrite(pin2B, 4095.0*dc_2b); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255*dc_1a); - analogWrite(pin1B, 255*dc_1b); - analogWrite(pin2A, 255*dc_2a); - analogWrite(pin2B, 255*dc_2b); -#endif -} - - -// function buffering delay() -// arduino uno function doesn't work well with interrupts -void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) - // if arduino uno and other atmega328p chips - // use while instad of delay, - // due to wrong measurement based on changed timer0 - unsigned long t = _micros() + ms*1000; - while( _micros() < t ){}; -#else - // regular micros - delay(ms); -#endif -} - - -// function buffering _micros() -// arduino function doesn't work well with interrupts -unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) -// if arduino uno and other atmega328p chips - //return the value based on the prescaler - if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); - else return (micros()); -#else - // regular micros - return micros(); -#endif -} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/BLDCMotor.cpp deleted file mode 100644 index f31e818a..00000000 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/BLDCMotor.cpp +++ /dev/null @@ -1,716 +0,0 @@ -#include "BLDCMotor.h" - -// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) -// - phA, phB, phC - motor A,B,C phase pwm pins -// - pp - pole pair number -// - cpr - counts per rotation number (cpm=ppm*4) -// - enable pin - (optional input) -BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) -{ - // Pin initialization - pwmA = phA; - pwmB = phB; - pwmC = phC; - pole_pairs = pp; - - // enable_pin pin - enable_pin = en; - - // Power supply voltage - voltage_power_supply = DEF_POWER_SUPPLY; - - // Velocity loop config - // PI controller constant - PID_velocity.P = DEF_PID_VEL_P; - PID_velocity.I = DEF_PID_VEL_I; - PID_velocity.D = DEF_PID_VEL_D; - PID_velocity.output_ramp = DEF_PID_VEL_U_RAMP; - PID_velocity.timestamp = _micros(); - PID_velocity.integral_prev = 0; - PID_velocity.output_prev = 0; - PID_velocity.tracking_error_prev = 0; - - // velocity low pass filter - LPF_velocity.Tf = DEF_VEL_FILTER_Tf; - LPF_velocity.timestamp = _micros(); - LPF_velocity.prev = 0; - - // position loop config - // P controller constant - P_angle.P = DEF_P_ANGLE_P; - - // maximum angular velocity to be used for positioning - velocity_limit = DEF_VEL_LIM; - // maximum voltage to be set to the motor - voltage_limit = voltage_power_supply; - - // index search velocity - velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; - // sensor and motor align voltage - voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; - - // electric angle of the zero angle - zero_electric_angle = 0; - - // default modulation is SinePWM - foc_modulation = FOCModulationType::SinePWM; - - // default target value - target = 0; - - //monitor_port - monitor_port = nullptr; - //sensor - sensor = nullptr; -} - -// init hardware pins -void BLDCMotor::init() { - if(monitor_port) monitor_port->println("MOT: Init pins."); - // PWM pins - pinMode(pwmA, OUTPUT); - pinMode(pwmB, OUTPUT); - pinMode(pwmC, OUTPUT); - if(hasEnable()) pinMode(enable_pin, OUTPUT); - - if(monitor_port) monitor_port->println("MOT: PWM config."); - // Increase PWM frequency to 32 kHz - // make silent - _setPwmFrequency(pwmA, pwmB, pwmC); - - // sanity check for the voltage limit configuration - if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; - // constrain voltage for sensor alignment - if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; - - _delay(500); - // enable motor - if(monitor_port) monitor_port->println("MOT: Enable."); - enable(); - _delay(500); - -} - - -// disable motor driver -void BLDCMotor::disable() -{ - // disable the driver - if enable_pin pin available - if (hasEnable()) digitalWrite(enable_pin, LOW); - // set zero to PWM - setPwm(0, 0, 0); -} -// enable motor driver -void BLDCMotor::enable() -{ - // set zero to PWM - setPwm(0, 0, 0); - // enable_pin the driver - if enable_pin pin available - if (hasEnable()) digitalWrite(enable_pin, HIGH); - -} - -void BLDCMotor::linkSensor(Sensor* _sensor) { - sensor = _sensor; -} - - -// Encoder alignment to electrical 0 angle -int BLDCMotor::alignSensor() { - if(monitor_port) monitor_port->println("MOT: Align sensor."); - // align the electrical phases of the motor and sensor - // set angle -90 degrees - - float start_angle = shaftAngle(); - for (int i = 0; i <=5; i++ ) { - float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); - _delay(200); - } - float mid_angle = shaftAngle(); - for (int i = 5; i >=0; i-- ) { - float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); - _delay(200); - } - if (mid_angle < start_angle) { - if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); - sensor->natural_direction = Direction::CCW; - } else if (mid_angle == start_angle) { - if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); - } - - // let the motor stabilize for 2 sec - _delay(2000); - // set sensor to zero - sensor->initRelativeZero(); - _delay(500); - setPhaseVoltage(0,0); - _delay(200); - - // find the index if available - int exit_flag = absoluteZeroAlign(); - _delay(500); - if(monitor_port){ - if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); - if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); - else monitor_port->println("MOT: Not available!"); - } - return exit_flag; -} - - -// Encoder alignment the absolute zero angle -// - to the index -int BLDCMotor::absoluteZeroAlign() { - - if(monitor_port) monitor_port->println("MOT: Absolute zero align."); - // if no absolute zero return - if(!sensor->hasAbsoluteZero()) return 0; - - - if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); - // search the absolute zero with small velocity - while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ - loopFOC(); - voltage_q = velocityPID(velocity_index_search - shaftVelocity()); - } - voltage_q = 0; - // disable motor - setPhaseVoltage(0,0); - - // align absolute zero if it has been found - if(!sensor->needsAbsoluteZeroSearch()){ - // align the sensor with the absolute zero - float zero_offset = sensor->initAbsoluteZero(); - // remember zero electric angle - zero_electric_angle = normalizeAngle(electricAngle(zero_offset)); - } - // return bool if zero found - return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; -} - -/** - State calculation methods -*/ -// shaft angle calculation -float BLDCMotor::shaftAngle() { - // if no sensor linked return 0 - if(!sensor) return 0; - return sensor->getAngle(); -} -// shaft velocity calculation -float BLDCMotor::shaftVelocity() { - // if no sensor linked return 0 - if(!sensor) return 0; - return lowPassFilter(sensor->getVelocity(), LPF_velocity); -} -// Electrical angle calculation -float BLDCMotor::electricAngle(float shaftAngle) { - //return normalizeAngle(shaftAngle * pole_pairs); - return (shaftAngle * pole_pairs); -} - -/** - FOC functions -*/ -// FOC initialization function -int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { - int exit_flag = 1; - // align motor if necessary - // alignment necessary for encoders! - if(zero_electric_offset != NOT_SET){ - // abosolute zero offset provided - no need to align - zero_electric_angle = zero_electric_offset; - // set the sensor direction - default CW - sensor->natural_direction = sensor_direction; - }else{ - // sensor and motor alignment - _delay(500); - exit_flag = alignSensor(); - _delay(500); - } - if(monitor_port) monitor_port->println("MOT: Motor ready."); - - return exit_flag; -} - -// Iterative function looping FOC algorithm, setting Uq on the Motor -// The faster it can be run the better -void BLDCMotor::loopFOC() { - // shaft angle - shaft_angle = shaftAngle(); - // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); -} - -// Iterative function running outer loop of the FOC algorithm -// Behavior of this function is determined by the motor.controller variable -// It runs either angle, velocity or voltage loop -// - needs to be called iteratively it is asynchronous function -// - if target is not set it uses motor.target value -void BLDCMotor::move(float new_target) { - // set internal target variable - if( new_target != NOT_SET ) target = new_target; - // get angular velocity - shaft_velocity = shaftVelocity(); - // choose control loop - switch (controller) { - case ControlType::voltage: - voltage_q = target; - break; - case ControlType::angle: - // angle set point - // include angle loop - shaft_angle_sp = target; - shaft_velocity_sp = positionP( shaft_angle_sp - shaft_angle ); - voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); - break; - case ControlType::velocity: - // velocity set point - // include velocity loop - shaft_velocity_sp = target; - voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); - break; - case ControlType::velocity_openloop: - // velocity control in open loop - // loopFOC should not be called - shaft_velocity_sp = target; - velocityOpenloop(shaft_velocity_sp); - break; - case ControlType::angle_openloop: - // angle control in open loop - // loopFOC should not be called - shaft_angle_sp = target; - angleOpenloop(shaft_angle_sp); - break; - } -} - - -// Method using FOC to set Uq to the motor at the optimal angle -// Function implementing Space Vector PWM and Sine PWM algorithms -// -// Function using sine approximation -// regular sin + cos ~300us (no memory usaage) -// approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { - switch (foc_modulation) - { - case FOCModulationType::SinePWM : - // Sinusoidal PWM modulation - // Inverse Park + Clarke transformation - - // angle normalization in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - angle_el = normalizeAngle(angle_el + zero_electric_angle); - // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; - - // Clarke transform - Ua = Ualpha + voltage_power_supply/2; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; - break; - - case FOCModulationType::SpaceVectorPWM : - // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm - // https://www.youtube.com/watch?v=QMSWUMEAejg - - // if negative voltages change inverse the phase - // angle + 180degrees - if(Uq < 0) angle_el += _PI; - Uq = abs(Uq); - - // angle normalisation in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - angle_el = normalizeAngle(angle_el + zero_electric_angle + _PI_2); - - // find the sector we are in currently - int sector = floor(angle_el / _PI_3) + 1; - // calculate the duty cycles - float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; - float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; - // two versions possible - // centered around voltage_power_supply/2 - float T0 = 1 - T1 - T2; - // pulled to 0 - better for low power supply voltage - //float T0 = 0; - - // calculate the duty cycles(times) - float Ta,Tb,Tc; - switch(sector){ - case 1: - Ta = T1 + T2 + T0/2; - Tb = T2 + T0/2; - Tc = T0/2; - break; - case 2: - Ta = T1 + T0/2; - Tb = T1 + T2 + T0/2; - Tc = T0/2; - break; - case 3: - Ta = T0/2; - Tb = T1 + T2 + T0/2; - Tc = T2 + T0/2; - break; - case 4: - Ta = T0/2; - Tb = T1+ T0/2; - Tc = T1 + T2 + T0/2; - break; - case 5: - Ta = T2 + T0/2; - Tb = T0/2; - Tc = T1 + T2 + T0/2; - break; - case 6: - Ta = T1 + T2 + T0/2; - Tb = T0/2; - Tc = T1 + T0/2; - break; - default: - // possible error state - Ta = 0; - Tb = 0; - Tc = 0; - } - - // calculate the phase voltages and center - Ua = Ta*voltage_power_supply; - Ub = Tb*voltage_power_supply; - Uc = Tc*voltage_power_supply; - break; - } - - // set the voltages in hardware - setPwm(Ua, Ub, Uc); -} - - - -// Set voltage to the pwm pin -void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { - // calculate duty cycle - // limited in [0,1] - float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); - float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); - float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); - // hardware specific writing - _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); -} - -/** - Utility functions -*/ -// normalizing radian angle to [0,2PI] -float BLDCMotor::normalizeAngle(float angle){ - float a = fmod(angle, _2PI); - return a >= 0 ? a : (a + _2PI); -} -// determining if the enable pin has been provided -int BLDCMotor::hasEnable(){ - return enable_pin != NOT_SET; -} - -// low pass filter function -// - input -singal to be filtered -// - lpf -LPF_s structure with filter parameters -float BLDCMotor::lowPassFilter(float input, LPF_s& lpf){ - unsigned long now_us = _micros(); - float Ts = (now_us - lpf.timestamp) * 1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // calculate the filtering - float alpha = lpf.Tf/(lpf.Tf + Ts); - float out = alpha*lpf.prev + (1-alpha)*input; - - // save the variables - lpf.prev = out; - lpf.timestamp = now_us; - return out; -} - - -/** - Motor control functions -*/ -// PID controller function -float BLDCMotor::controllerPID(float tracking_error, PID_s& cont){ - // calculate the time from the last call - unsigned long now_us = _micros(); - float Ts = (now_us - cont.timestamp) * 1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // u(s) = (P + I/s + Ds)e(s) - // Discrete implementations - // proportional part - // u_p = P *e(k) - float proportional = cont.P * tracking_error; - // Tustin transform of the integral part - // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) - float integral = cont.integral_prev + cont.I*Ts*0.5*(tracking_error + cont.tracking_error_prev); - // antiwindup - limit the output voltage_q - integral = constrain(integral, -voltage_limit, voltage_limit); - // Discrete derivation - // u_dk = D(ek - ek_1)/Ts - float derivative = cont.D*(tracking_error - cont.tracking_error_prev)/Ts; - // sum all the components - float voltage = proportional + integral + derivative; - - // antiwindup - limit the output voltage_q - voltage = constrain(voltage, -voltage_limit, voltage_limit); - - // limit the acceleration by ramping the the voltage - float d_voltage = voltage - cont.output_prev; - if (abs(d_voltage)/Ts > cont.output_ramp) voltage = d_voltage > 0 ? cont.output_prev + cont.output_ramp*Ts : cont.output_prev - cont.output_ramp*Ts; - - // saving for the next pass - cont.integral_prev = integral; - cont.output_prev = voltage; - cont.tracking_error_prev = tracking_error; - cont.timestamp = now_us; - return voltage; -} -// velocity control loop PI controller -float BLDCMotor::velocityPID(float tracking_error) { - return controllerPID(tracking_error, PID_velocity); -} - -// P controller for position control loop -float BLDCMotor::positionP(float ek) { - // calculate the target velocity from the position error - float velocity_target = P_angle.P * ek; - // constrain velocity target value - velocity_target = constrain(velocity_target, -velocity_limit, velocity_limit); - return velocity_target; -} - -// Function (iterative) generating open loop movement for target velocity -// - target_velocity - rad/s -// it uses voltage_limit variable -void BLDCMotor::velocityOpenloop(float target_velocity){ - // get current timestamp - unsigned long now_us = _micros(); - // calculate the sample time from last call - float Ts = (now_us - open_loop_timestamp) * 1e-6; - - // calculate the necessary angle to achieve target velocity - shaft_angle += target_velocity*Ts; - - // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); - - // save timestamp for next call - open_loop_timestamp = now_us; -} - -// Function (iterative) generating open loop movement towards the target angle -// - target_angle - rad -// it uses voltage_limit and velocity_limit variables -void BLDCMotor::angleOpenloop(float target_angle){ - // get current timestamp - unsigned long now_us = _micros(); - // calculate the sample time from last call - float Ts = (now_us - open_loop_timestamp) * 1e-6; - - // calculate the necessary angle to move from current position towards target angle - // with maximal velocity (velocity_limit) - if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) - shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; - else - shaft_angle = target_angle; - - // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); - - // save timestamp for next call - open_loop_timestamp = now_us; -} - -/** - * Monitoring functions - */ -// function implementing the monitor_port setter -void BLDCMotor::useMonitoring(Print &print){ - monitor_port = &print; //operate on the address of print - if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); -} -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void BLDCMotor::monitor() { - if(!monitor_port) return; - switch (controller) { - case ControlType::velocity_openloop: - case ControlType::velocity: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_velocity_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - case ControlType::angle_openloop: - case ControlType::angle: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_angle); - break; - case ControlType::voltage: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - } -} - -int BLDCMotor::command(String user_command) { - // error flag - int errorFlag = 1; - // if empty string - if(user_command.length() < 1) return errorFlag; - - // parse command letter - char cmd = user_command.charAt(0); - // check if get command - char GET = user_command.charAt(1) == '\n'; - // parse command values - float value = user_command.substring(1).toFloat(); - - // a bit of optimisation of variable memory for Arduino UNO (atmega328) - switch(cmd){ - case 'P': // velocity P gain change - case 'I': // velocity I gain change - case 'D': // velocity D gain change - case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print(" PID velocity| "); - break; - case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print(" LPF velocity| "); - break; - case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print(" P angle| "); - break; - case 'L': // velocity voltage limit change - case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print(" Limits| "); - break; - - } - - // apply the the command - switch(cmd){ - case 'P': // velocity P gain change - if(monitor_port) monitor_port->print("P: "); - if(!GET) PID_velocity.P = value; - if(monitor_port) monitor_port->println(PID_velocity.P); - break; - case 'I': // velocity I gain change - if(monitor_port) monitor_port->print("I: "); - if(!GET) PID_velocity.I = value; - if(monitor_port) monitor_port->println(PID_velocity.I); - break; - case 'D': // velocity D gain change - if(monitor_port) monitor_port->print("D: "); - if(!GET) PID_velocity.D = value; - if(monitor_port) monitor_port->println(PID_velocity.D); - break; - case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print("volt_ramp: "); - if(!GET) PID_velocity.output_ramp = value; - if(monitor_port) monitor_port->println(PID_velocity.output_ramp); - break; - case 'L': // velocity voltage limit change - if(monitor_port) monitor_port->print("volt_limit: "); - if(!GET)voltage_limit = value; - if(monitor_port) monitor_port->println(voltage_limit); - break; - case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print("Tf: "); - if(!GET) LPF_velocity.Tf = value; - if(monitor_port) monitor_port->println(LPF_velocity.Tf); - break; - case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print(" P: "); - if(!GET) P_angle.P = value; - if(monitor_port) monitor_port->println(P_angle.P); - break; - case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print("vel_limit: "); - if(!GET) velocity_limit = value; - if(monitor_port) monitor_port->println(velocity_limit); - break; - case 'C': - // change control type - if(monitor_port) monitor_port->print("Control: "); - - if(GET){ // if get command - switch(controller){ - case ControlType::voltage: - if(monitor_port) monitor_port->println("voltage"); - break; - case ControlType::velocity: - if(monitor_port) monitor_port->println("velocity"); - break; - case ControlType::angle: - if(monitor_port) monitor_port->println("angle"); - break; - default: - if(monitor_port) monitor_port->println("open loop"); - } - }else{ // if set command - switch((int)value){ - case 0: - if(monitor_port) monitor_port->println("voltage"); - controller = ControlType::voltage; - break; - case 1: - if(monitor_port) monitor_port->println("velocity"); - controller = ControlType::velocity; - break; - case 2: - if(monitor_port) monitor_port->println("angle"); - controller = ControlType::angle; - break; - default: // not valid command - errorFlag = 0; - } - } - break; - case 'V': // get current values of the state variables - switch((int)value){ - case 0: // get voltage - if(monitor_port) monitor_port->print("Uq: "); - if(monitor_port) monitor_port->println(voltage_q); - break; - case 1: // get velocity - if(monitor_port) monitor_port->print("Velocity: "); - if(monitor_port) monitor_port->println(shaft_velocity); - break; - case 2: // get angle - if(monitor_port) monitor_port->print("Angle: "); - if(monitor_port) monitor_port->println(shaft_angle); - break; - case 3: // get angle - if(monitor_port) monitor_port->print("Target: "); - if(monitor_port) monitor_port->println(target); - break; - default: // not valid command - errorFlag = 0; - } - break; - default: // target change - if(monitor_port) monitor_port->print("Target : "); - target = user_command.toFloat(); - if(monitor_port) monitor_port->println(target); - } - // return 0 if error and 1 if ok - return errorFlag; -} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/FOCutils.cpp b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/FOCutils.cpp deleted file mode 100644 index 653c7191..00000000 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/FOCutils.cpp +++ /dev/null @@ -1,215 +0,0 @@ -#include "FOCutils.h" - -#if defined(ESP_H) // if ESP32 board -// empty motor slot -#define _EMPTY_SLOT -20 - -// structure containing motor slot configuration -// this library supports up to 4 motors -typedef struct { - int pinA; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator; - mcpwm_io_signals_t mcpwm_a; - mcpwm_io_signals_t mcpwm_b; - mcpwm_io_signals_t mcpwm_c; - -} motor_slots_t; - -// define motor slots array -motor_slots_t esp32_motor_slots[4] = { - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B - }; - -#endif - - -// function setting the high pwm frequency to the supplied pins -// - hardware speciffic -// supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(const int pinA, const int pinB, const int pinC) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips - // High PWM frequency - // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pinA == 5 || pinA == 6 || pinB == 5 || pinB == 6 || pinC == 5 || pinC == 6 ) { - TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode - TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - } - if (pinA == 9 || pinA == 10 || pinB == 9 || pinB == 10 || pinC == 9 || pinC == 10 ) - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pinA == 3 || pinA == 11 || pinB == 3 || pinB == 11 || pinC == 3 || pinC == 11 ) - TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 - -#elif defined(_STM32_DEF_) // if stm chips - - analogWrite(pinA, 0); - analogWriteFrequency(50000); // set 50kHz - analogWrite(pinB, 0); - analogWriteFrequency(50000); // set 50kHz - analogWrite(pinC, 0); - analogWriteFrequency(50000); // set 50kHz - -#elif defined(ESP_H) // if esp32 boards - - motor_slots_t m_slot = {}; - - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 4; i++){ - if(esp32_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_motor_slots[i].pinA = pinA; - m_slot = esp32_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); - - mcpwm_config_t pwm_config; - pwm_config.frequency = 4000000; //frequency = 20000Hz - pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% - pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% - pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) - pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings - - _delay(100); - - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_0); - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_1); - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_2); - m_slot.mcpwm_num->clk_cfg.prescale = 0; - - m_slot.mcpwm_num->timer[0].period.prescale = 4; - m_slot.mcpwm_num->timer[1].period.prescale = 4; - m_slot.mcpwm_num->timer[2].period.prescale = 4; - _delay(1); - m_slot.mcpwm_num->timer[0].period.period = 2048; - m_slot.mcpwm_num->timer[1].period.period = 2048; - m_slot.mcpwm_num->timer[2].period.period = 2048; - _delay(1); - m_slot.mcpwm_num->timer[0].period.upmethod = 0; - m_slot.mcpwm_num->timer[1].period.upmethod = 0; - m_slot.mcpwm_num->timer[2].period.upmethod = 0; - _delay(1); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_0); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_1); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_2); - - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); - _delay(1); - m_slot.mcpwm_num->timer[0].sync.out_sel = 1; - _delay(1); - m_slot.mcpwm_num->timer[0].sync.out_sel = 0; -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 4; i++){ - if(esp32_motor_slots[i].pinA == pinA){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; - esp32_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; - esp32_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; - break; - } - } -#else // Arduino & STM32 devices - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255*dc_a); - analogWrite(pinB, 255*dc_b); - analogWrite(pinC, 255*dc_c); -#endif -} - - -// function buffering delay() -// arduino uno function doesn't work well with interrupts -void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) - // if arduino uno and other atmega328p chips - // use while instad of delay, - // due to wrong measurement based on changed timer0 - unsigned long t = _micros() + ms*1000; - while( _micros() < t ){}; -#else - // regular micros - delay(ms); -#endif -} - - -// function buffering _micros() -// arduino function doesn't work well with interrupts -unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) -// if arduino uno and other atmega328p chips - //return the value based on the prescaler - if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); - else return (micros()); -#else - // regular micros - return micros(); -#endif -} - - -// int array instead of float array -// 2x storage save (int 2Byte float 4 Byte ) -// sin*10000 -int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,1103,1181,1260,1338,1416,1494,1572,1650,1728,1806,1883,1961,2038,2115,2192,2269,2346,2423,2499,2575,2652,2728,2804,2879,2955,3030,3105,3180,3255,3329,3404,3478,3552,3625,3699,3772,3845,3918,3990,4063,4135,4206,4278,4349,4420,4491,4561,4631,4701,4770,4840,4909,4977,5046,5113,5181,5249,5316,5382,5449,5515,5580,5646,5711,5775,5839,5903,5967,6030,6093,6155,6217,6279,6340,6401,6461,6521,6581,6640,6699,6758,6815,6873,6930,6987,7043,7099,7154,7209,7264,7318,7371,7424,7477,7529,7581,7632,7683,7733,7783,7832,7881,7930,7977,8025,8072,8118,8164,8209,8254,8298,8342,8385,8428,8470,8512,8553,8594,8634,8673,8712,8751,8789,8826,8863,8899,8935,8970,9005,9039,9072,9105,9138,9169,9201,9231,9261,9291,9320,9348,9376,9403,9429,9455,9481,9506,9530,9554,9577,9599,9621,9642,9663,9683,9702,9721,9739,9757,9774,9790,9806,9821,9836,9850,9863,9876,9888,9899,9910,9920,9930,9939,9947,9955,9962,9969,9975,9980,9985,9989,9992,9995,9997,9999,10000,10000}; - -// function approximating the sine calculation by using fixed size array -// ~40us (float array) -// ~50us (int array) -// precision +-0.005 -// it has to receive an angle in between 0 and 2PI -float _sin(float a){ - if(a < _PI_2){ - //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; - //return sine_array[(int)(126.6873* a)]; // float array optimized - return 0.0001*sine_array[_round(126.6873* a)]; // int array optimized - }else if(a < _PI){ - // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; - //return sine_array[398 - (int)(126.6873*a)]; // float array optimized - return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimized - }else if(a < _3PI_2){ - // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; - //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimized - return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimized - } else { - // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; - //return -sine_array[796 - (int)(126.6873*a)]; // float array optimized - return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimized - } -} - -// function approximating cosine calculation by using fixed size array -// ~55us (float array) -// ~56us (int array) -// precision +-0.005 -// it has to receive an angle in between 0 and 2PI -float _cos(float a){ - float a_sin = a + _PI_2; - a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin; - return _sin(a_sin); -} diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/FOCutils.h b/minimal_project_examples/arduino_foc_minimal_magnetic_spi/FOCutils.h deleted file mode 100644 index 4c347a12..00000000 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/FOCutils.h +++ /dev/null @@ -1,86 +0,0 @@ -#ifndef FOCUTILS_LIB_H -#define FOCUTILS_LIB_H - -#include "Arduino.h" - - -#if defined(ESP_H) // if esp32 boards - -#include "driver/mcpwm.h" -#include "soc/mcpwm_reg.h" -#include "soc/mcpwm_struct.h" - -#endif - -// sign function -#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) -#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) - -// utility defines -#define _2_SQRT3 1.15470053838 -#define _SQRT3 1.73205080757 -#define _1_SQRT3 0.57735026919 -#define _SQRT3_2 0.86602540378 -#define _SQRT2 1.41421356237 -#define _120_D2R 2.09439510239 -#define _PI 3.14159265359 -#define _PI_2 1.57079632679 -#define _PI_3 1.0471975512 -#define _2PI 6.28318530718 -#define _3PI_2 4.71238898038 - -/** - * High PWM frequency setting function - * - hardware specific - * - * @param pinA pinA number to configure - * @param pinB pinB number to configure - * @param pinC pinC number to configure - */ -void _setPwmFrequency(int pinA, int pinB, int pinC); - -/** - * Function implementing delay() function in milliseconds - * - blocking function - * - hardware specific - - * @param ms number of milliseconds to wait - */ -void _delay(unsigned long ms); - -/** - * Function implementing timestamp getting function in microseconds - * hardware specific - */ -unsigned long _micros(); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_a duty cycle phase A [0, 1] - * @param dc_b duty cycle phase B [0, 1] - * @param dc_c duty cycle phase C [0, 1] - * @param pinA phase A hardware pin number - * @param pinB phase B hardware pin number - * @param pinC phase C hardware pin number - */ -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); - - -/** - * Function approximating the sine calculation by using fixed size array - * - execution time ~40us (Arduino UNO) - * - * @param a angle in between 0 and 2PI - */ -float _sin(float a); -/** - * Function approximating cosine calculation by using fixed size array - * - execution time ~50us (Arduino UNO) - * - * @param a angle in between 0 and 2PI - */ -float _cos(float a); - -#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.cpp b/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.cpp deleted file mode 100644 index 18ffdfce..00000000 --- a/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.cpp +++ /dev/null @@ -1,724 +0,0 @@ -#include "BLDCMotor.h" - -// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) -// - phA, phB, phC - motor A,B,C phase pwm pins -// - pp - pole pair number -// - cpr - counts per rotation number (cpm=ppm*4) -// - enable pin - (optional input) -BLDCMotor::BLDCMotor(int phA, int phB, int phC,int phAl,int phBl,int phCl, int pp, int en) -{ - // Pin initialization - pwmA = phA; - pwmB = phB; - pwmC = phC; - pwmA_L = phAl; - pwmB_L = phBl; - pwmC_L = phCl; - pole_pairs = pp; - - // enable_pin pin - enable_pin = en; - - // Power supply voltage - voltage_power_supply = DEF_POWER_SUPPLY; - - // Velocity loop config - // PI controller constant - PID_velocity.P = DEF_PID_VEL_P; - PID_velocity.I = DEF_PID_VEL_I; - PID_velocity.D = DEF_PID_VEL_D; - PID_velocity.output_ramp = DEF_PID_VEL_U_RAMP; - PID_velocity.timestamp = _micros(); - PID_velocity.integral_prev = 0; - PID_velocity.output_prev = 0; - PID_velocity.tracking_error_prev = 0; - - // velocity low pass filter - LPF_velocity.Tf = DEF_VEL_FILTER_Tf; - LPF_velocity.timestamp = _micros(); - LPF_velocity.prev = 0; - - // position loop config - // P controller constant - P_angle.P = DEF_P_ANGLE_P; - - // maximum angular velocity to be used for positioning - velocity_limit = DEF_VEL_LIM; - // maximum voltage to be set to the motor - voltage_limit = voltage_power_supply; - - // index search velocity - velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; - // sensor and motor align voltage - voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; - - // electric angle of the zero angle - zero_electric_angle = 0; - - // default modulation is SinePWM - foc_modulation = FOCModulationType::SinePWM; - - // default target value - target = 0; - - //monitor_port - monitor_port = nullptr; - //sensor - sensor = nullptr; -} - -// init hardware pins -void BLDCMotor::init() { - if(monitor_port) monitor_port->println("MOT: Init pins."); - // PWM pins - pinMode(pwmA, OUTPUT); - pinMode(pwmB, OUTPUT); - pinMode(pwmC, OUTPUT); - pinMode(pwmA_L, OUTPUT); - pinMode(pwmB_L, OUTPUT); - pinMode(pwmC_L, OUTPUT); - if(hasEnable()) pinMode(enable_pin, OUTPUT); - - if(monitor_port) monitor_port->println("MOT: PWM config."); - // Increase PWM frequency to 32 kHz - // make silent - _setPwmFrequency(pwmA, pwmB, pwmC); - _setPwmFrequencyLow(pwmA_L, pwmB_L, pwmC_L); - - // sanity check for the voltage limit configuration - if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; - // constrain voltage for sensor alignment - if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; - - _delay(500); - // enable motor - if(monitor_port) monitor_port->println("MOT: Enable."); - enable(); - _delay(500); - -} - - -// disable motor driver -void BLDCMotor::disable() -{ - // disable the driver - if enable_pin pin available - if (hasEnable()) digitalWrite(enable_pin, LOW); - // set zero to PWM - setPwm(0, 0, 0); -} -// enable motor driver -void BLDCMotor::enable() -{ - // set zero to PWM - setPwm(0, 0, 0); - // enable_pin the driver - if enable_pin pin available - if (hasEnable()) digitalWrite(enable_pin, HIGH); - -} - -void BLDCMotor::linkSensor(Sensor* _sensor) { - sensor = _sensor; -} - - -// Encoder alignment to electrical 0 angle -int BLDCMotor::alignSensor() { - if(monitor_port) monitor_port->println("MOT: Align sensor."); - // align the electrical phases of the motor and sensor - // set angle -90 degrees - - float start_angle = shaftAngle(); - for (int i = 0; i <=5; i++ ) { - float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); - _delay(200); - } - float mid_angle = shaftAngle(); - for (int i = 5; i >=0; i-- ) { - float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); - _delay(200); - } - if (mid_angle < start_angle) { - if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); - sensor->natural_direction = Direction::CCW; - } else if (mid_angle == start_angle) { - if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); - } - - // let the motor stabilize for 2 sec - _delay(2000); - // set sensor to zero - sensor->initRelativeZero(); - _delay(500); - setPhaseVoltage(0,0); - _delay(200); - - // find the index if available - int exit_flag = absoluteZeroAlign(); - _delay(500); - if(monitor_port){ - if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); - if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); - else monitor_port->println("MOT: Not available!"); - } - return exit_flag; -} - - -// Encoder alignment the absolute zero angle -// - to the index -int BLDCMotor::absoluteZeroAlign() { - - if(monitor_port) monitor_port->println("MOT: Absolute zero align."); - // if no absolute zero return - if(!sensor->hasAbsoluteZero()) return 0; - - - if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); - // search the absolute zero with small velocity - while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ - loopFOC(); - voltage_q = velocityPID(velocity_index_search - shaftVelocity()); - } - voltage_q = 0; - // disable motor - setPhaseVoltage(0,0); - - // align absolute zero if it has been found - if(!sensor->needsAbsoluteZeroSearch()){ - // align the sensor with the absolute zero - float zero_offset = sensor->initAbsoluteZero(); - // remember zero electric angle - zero_electric_angle = normalizeAngle(electricAngle(zero_offset)); - } - // return bool if zero found - return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; -} - -/** - State calculation methods -*/ -// shaft angle calculation -float BLDCMotor::shaftAngle() { - // if no sensor linked return 0 - if(!sensor) return 0; - return sensor->getAngle(); -} -// shaft velocity calculation -float BLDCMotor::shaftVelocity() { - // if no sensor linked return 0 - if(!sensor) return 0; - return lowPassFilter(sensor->getVelocity(), LPF_velocity); -} -// Electrical angle calculation -float BLDCMotor::electricAngle(float shaftAngle) { - //return normalizeAngle(shaftAngle * pole_pairs); - return (shaftAngle * pole_pairs); -} - -/** - FOC functions -*/ -// FOC initialization function -int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { - int exit_flag = 1; - // align motor if necessary - // alignment necessary for encoders! - if(zero_electric_offset != NOT_SET){ - // abosolute zero offset provided - no need to align - zero_electric_angle = zero_electric_offset; - // set the sensor direction - default CW - sensor->natural_direction = sensor_direction; - }else{ - // sensor and motor alignment - _delay(500); - exit_flag = alignSensor(); - _delay(500); - } - if(monitor_port) monitor_port->println("MOT: Motor ready."); - - return exit_flag; -} - -// Iterative function looping FOC algorithm, setting Uq on the Motor -// The faster it can be run the better -void BLDCMotor::loopFOC() { - // shaft angle - shaft_angle = shaftAngle(); - // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, electricAngle(shaft_angle)); -} - -// Iterative function running outer loop of the FOC algorithm -// Behavior of this function is determined by the motor.controller variable -// It runs either angle, velocity or voltage loop -// - needs to be called iteratively it is asynchronous function -// - if target is not set it uses motor.target value -void BLDCMotor::move(float new_target) { - // set internal target variable - if( new_target != NOT_SET ) target = new_target; - // get angular velocity - shaft_velocity = shaftVelocity(); - // choose control loop - switch (controller) { - case ControlType::voltage: - voltage_q = target; - break; - case ControlType::angle: - // angle set point - // include angle loop - shaft_angle_sp = target; - shaft_velocity_sp = positionP( shaft_angle_sp - shaft_angle ); - voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); - break; - case ControlType::velocity: - // velocity set point - // include velocity loop - shaft_velocity_sp = target; - voltage_q = velocityPID(shaft_velocity_sp - shaft_velocity); - break; - case ControlType::velocity_openloop: - // velocity control in open loop - // loopFOC should not be called - shaft_velocity_sp = target; - velocityOpenloop(shaft_velocity_sp); - break; - case ControlType::angle_openloop: - // angle control in open loop - // loopFOC should not be called - shaft_angle_sp = target; - angleOpenloop(shaft_angle_sp); - break; - } -} - - -// Method using FOC to set Uq to the motor at the optimal angle -// Function implementing Space Vector PWM and Sine PWM algorithms -// -// Function using sine approximation -// regular sin + cos ~300us (no memory usaage) -// approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { - switch (foc_modulation) - { - case FOCModulationType::SinePWM : - // Sinusoidal PWM modulation - // Inverse Park + Clarke transformation - - // angle normalization in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - angle_el = normalizeAngle(angle_el + zero_electric_angle); - // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; - - // Clarke transform - Ua = Ualpha + voltage_power_supply/2; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; - break; - - case FOCModulationType::SpaceVectorPWM : - // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm - // https://www.youtube.com/watch?v=QMSWUMEAejg - - // if negative voltages change inverse the phase - // angle + 180degrees - if(Uq < 0) angle_el += _PI; - Uq = abs(Uq); - - // angle normalisation in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - angle_el = normalizeAngle(angle_el + zero_electric_angle + _PI_2); - - // find the sector we are in currently - int sector = floor(angle_el / _PI_3) + 1; - // calculate the duty cycles - float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; - float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; - // two versions possible - // centered around voltage_power_supply/2 - float T0 = 1 - T1 - T2; - // pulled to 0 - better for low power supply voltage - //float T0 = 0; - - // calculate the duty cycles(times) - float Ta,Tb,Tc; - switch(sector){ - case 1: - Ta = T1 + T2 + T0/2; - Tb = T2 + T0/2; - Tc = T0/2; - break; - case 2: - Ta = T1 + T0/2; - Tb = T1 + T2 + T0/2; - Tc = T0/2; - break; - case 3: - Ta = T0/2; - Tb = T1 + T2 + T0/2; - Tc = T2 + T0/2; - break; - case 4: - Ta = T0/2; - Tb = T1+ T0/2; - Tc = T1 + T2 + T0/2; - break; - case 5: - Ta = T2 + T0/2; - Tb = T0/2; - Tc = T1 + T2 + T0/2; - break; - case 6: - Ta = T1 + T2 + T0/2; - Tb = T0/2; - Tc = T1 + T0/2; - break; - default: - // possible error state - Ta = 0; - Tb = 0; - Tc = 0; - } - - // calculate the phase voltages and center - Ua = Ta*voltage_power_supply; - Ub = Tb*voltage_power_supply; - Uc = Tc*voltage_power_supply; - break; - } - - // set the voltages in hardware - setPwm(Ua, Ub, Uc); -} - - - -// Set voltage to the pwm pin -void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { - // calculate duty cycle - // limited in [0,1] - float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); - float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); - float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); - // hardware specific writing - _writeDutyCycleLow(dc_a, dc_b, dc_c, pwmA_L, pwmB_L, pwmC_L ); - _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); -} - -/** - Utility functions -*/ -// normalizing radian angle to [0,2PI] -float BLDCMotor::normalizeAngle(float angle){ - float a = fmod(angle, _2PI); - return a >= 0 ? a : (a + _2PI); -} -// determining if the enable pin has been provided -int BLDCMotor::hasEnable(){ - return enable_pin != NOT_SET; -} - -// low pass filter function -// - input -singal to be filtered -// - lpf -LPF_s structure with filter parameters -float BLDCMotor::lowPassFilter(float input, LPF_s& lpf){ - unsigned long now_us = _micros(); - float Ts = (now_us - lpf.timestamp) * 1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // calculate the filtering - float alpha = lpf.Tf/(lpf.Tf + Ts); - float out = alpha*lpf.prev + (1-alpha)*input; - - // save the variables - lpf.prev = out; - lpf.timestamp = now_us; - return out; -} - - -/** - Motor control functions -*/ -// PID controller function -float BLDCMotor::controllerPID(float tracking_error, PID_s& cont){ - // calculate the time from the last call - unsigned long now_us = _micros(); - float Ts = (now_us - cont.timestamp) * 1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // u(s) = (P + I/s + Ds)e(s) - // Discrete implementations - // proportional part - // u_p = P *e(k) - float proportional = cont.P * tracking_error; - // Tustin transform of the integral part - // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) - float integral = cont.integral_prev + cont.I*Ts*0.5*(tracking_error + cont.tracking_error_prev); - // antiwindup - limit the output voltage_q - integral = constrain(integral, -voltage_limit, voltage_limit); - // Discrete derivation - // u_dk = D(ek - ek_1)/Ts - float derivative = cont.D*(tracking_error - cont.tracking_error_prev)/Ts; - // sum all the components - float voltage = proportional + integral + derivative; - - // antiwindup - limit the output voltage_q - voltage = constrain(voltage, -voltage_limit, voltage_limit); - - // limit the acceleration by ramping the the voltage - float d_voltage = voltage - cont.output_prev; - if (abs(d_voltage)/Ts > cont.output_ramp) voltage = d_voltage > 0 ? cont.output_prev + cont.output_ramp*Ts : cont.output_prev - cont.output_ramp*Ts; - - // saving for the next pass - cont.integral_prev = integral; - cont.output_prev = voltage; - cont.tracking_error_prev = tracking_error; - cont.timestamp = now_us; - return voltage; -} -// velocity control loop PI controller -float BLDCMotor::velocityPID(float tracking_error) { - return controllerPID(tracking_error, PID_velocity); -} - -// P controller for position control loop -float BLDCMotor::positionP(float ek) { - // calculate the target velocity from the position error - float velocity_target = P_angle.P * ek; - // constrain velocity target value - velocity_target = constrain(velocity_target, -velocity_limit, velocity_limit); - return velocity_target; -} - -// Function (iterative) generating open loop movement for target velocity -// - target_velocity - rad/s -// it uses voltage_limit variable -void BLDCMotor::velocityOpenloop(float target_velocity){ - // get current timestamp - unsigned long now_us = _micros(); - // calculate the sample time from last call - float Ts = (now_us - open_loop_timestamp) * 1e-6; - - // calculate the necessary angle to achieve target velocity - shaft_angle += target_velocity*Ts; - - // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); - - // save timestamp for next call - open_loop_timestamp = now_us; -} - -// Function (iterative) generating open loop movement towards the target angle -// - target_angle - rad -// it uses voltage_limit and velocity_limit variables -void BLDCMotor::angleOpenloop(float target_angle){ - // get current timestamp - unsigned long now_us = _micros(); - // calculate the sample time from last call - float Ts = (now_us - open_loop_timestamp) * 1e-6; - - // calculate the necessary angle to move from current position towards target angle - // with maximal velocity (velocity_limit) - if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) - shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; - else - shaft_angle = target_angle; - - // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, electricAngle(shaft_angle)); - - // save timestamp for next call - open_loop_timestamp = now_us; -} - -/** - * Monitoring functions - */ -// function implementing the monitor_port setter -void BLDCMotor::useMonitoring(Print &print){ - monitor_port = &print; //operate on the address of print - if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); -} -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void BLDCMotor::monitor() { - if(!monitor_port) return; - switch (controller) { - case ControlType::velocity_openloop: - case ControlType::velocity: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_velocity_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - case ControlType::angle_openloop: - case ControlType::angle: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_angle); - break; - case ControlType::voltage: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - } -} - -int BLDCMotor::command(String user_command) { - // error flag - int errorFlag = 1; - // if empty string - if(user_command.length() < 1) return errorFlag; - - // parse command letter - char cmd = user_command.charAt(0); - // check if get command - char GET = user_command.charAt(1) == '\n'; - // parse command values - float value = user_command.substring(1).toFloat(); - - // a bit of optimisation of variable memory for Arduino UNO (atmega328) - switch(cmd){ - case 'P': // velocity P gain change - case 'I': // velocity I gain change - case 'D': // velocity D gain change - case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print(" PID velocity| "); - break; - case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print(" LPF velocity| "); - break; - case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print(" P angle| "); - break; - case 'L': // velocity voltage limit change - case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print(" Limits| "); - break; - - } - - // apply the the command - switch(cmd){ - case 'P': // velocity P gain change - if(monitor_port) monitor_port->print("P: "); - if(!GET) PID_velocity.P = value; - if(monitor_port) monitor_port->println(PID_velocity.P); - break; - case 'I': // velocity I gain change - if(monitor_port) monitor_port->print("I: "); - if(!GET) PID_velocity.I = value; - if(monitor_port) monitor_port->println(PID_velocity.I); - break; - case 'D': // velocity D gain change - if(monitor_port) monitor_port->print("D: "); - if(!GET) PID_velocity.D = value; - if(monitor_port) monitor_port->println(PID_velocity.D); - break; - case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print("volt_ramp: "); - if(!GET) PID_velocity.output_ramp = value; - if(monitor_port) monitor_port->println(PID_velocity.output_ramp); - break; - case 'L': // velocity voltage limit change - if(monitor_port) monitor_port->print("volt_limit: "); - if(!GET)voltage_limit = value; - if(monitor_port) monitor_port->println(voltage_limit); - break; - case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print("Tf: "); - if(!GET) LPF_velocity.Tf = value; - if(monitor_port) monitor_port->println(LPF_velocity.Tf); - break; - case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print(" P: "); - if(!GET) P_angle.P = value; - if(monitor_port) monitor_port->println(P_angle.P); - break; - case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print("vel_limit: "); - if(!GET) velocity_limit = value; - if(monitor_port) monitor_port->println(velocity_limit); - break; - case 'C': - // change control type - if(monitor_port) monitor_port->print("Control: "); - - if(GET){ // if get command - switch(controller){ - case ControlType::voltage: - if(monitor_port) monitor_port->println("voltage"); - break; - case ControlType::velocity: - if(monitor_port) monitor_port->println("velocity"); - break; - case ControlType::angle: - if(monitor_port) monitor_port->println("angle"); - break; - default: - if(monitor_port) monitor_port->println("open loop"); - } - }else{ // if set command - switch((int)value){ - case 0: - if(monitor_port) monitor_port->println("voltage"); - controller = ControlType::voltage; - break; - case 1: - if(monitor_port) monitor_port->println("velocity"); - controller = ControlType::velocity; - break; - case 2: - if(monitor_port) monitor_port->println("angle"); - controller = ControlType::angle; - break; - default: // not valid command - errorFlag = 0; - } - } - break; - case 'V': // get current values of the state variables - switch((int)value){ - case 0: // get voltage - if(monitor_port) monitor_port->print("Uq: "); - if(monitor_port) monitor_port->println(voltage_q); - break; - case 1: // get velocity - if(monitor_port) monitor_port->print("Velocity: "); - if(monitor_port) monitor_port->println(shaft_velocity); - break; - case 2: // get angle - if(monitor_port) monitor_port->print("Angle: "); - if(monitor_port) monitor_port->println(shaft_angle); - break; - case 3: // get angle - if(monitor_port) monitor_port->print("Target: "); - if(monitor_port) monitor_port->println(target); - break; - default: // not valid command - errorFlag = 0; - } - break; - default: // target change - if(monitor_port) monitor_port->print("Target : "); - target = user_command.toFloat(); - if(monitor_port) monitor_port->println(target); - } - // return 0 if error and 1 if ok - return errorFlag; -} diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.h b/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.h deleted file mode 100644 index 4191c29c..00000000 --- a/minimal_project_examples/arduino_foc_minimal_openloop/BLDCMotor.h +++ /dev/null @@ -1,326 +0,0 @@ -/** - * @file BLDCMotor.h - * - */ - -#ifndef BLDCMotor_h -#define BLDCMotor_h - -#include "Arduino.h" -#include "FOCutils.h" -#include "Sensor.h" -#include "defaults.h" - - -#define NOT_SET -12345.0 - -/** - * Motiron control type - */ -enum ControlType{ - voltage,//!< Torque control using voltage - velocity,//!< Velocity motion control - angle,//!< Position/angle motion control - velocity_openloop, - angle_openloop -}; - -/** - * FOC modulation type - */ -enum FOCModulationType{ - SinePWM, //!< Sinusoidal PWM modulation - SpaceVectorPWM //!< Space vector modulation method -}; - -/** - * PID controller structure - */ -struct PID_s{ - float P; //!< Proportional gain - float I; //!< Integral gain - float D; //!< Derivative gain - long timestamp; //!< Last execution timestamp - float integral_prev; //!< last integral component value - float output_prev; //!< last pid output value - float output_ramp; //!< Maximum speed of change of the output value - float tracking_error_prev; //!< last tracking error value -}; - -// P controller structure -struct P_s{ - float P; //!< Proportional gain - long timestamp; //!< Last execution timestamp -}; - -/** - * Low pass filter structure - */ -struct LPF_s{ - float Tf; //!< Low pass filter time constant - long timestamp; //!< Last execution timestamp - float prev; //!< filtered value in previous execution step -}; - - - - -/** - BLDC motor class -*/ -class BLDCMotor -{ - public: - /** - BLDCMotor class constructor - @param phA A phase pwm pin - @param phB B phase pwm pin - @param phC C phase pwm pin - @param pp pole pair number - @param cpr counts per rotation number (cpm=ppm*4) - @param en enable pin (optional input) - */ - BLDCMotor(int phA,int phB,int phC,int phAl,int phBl,int phCl,int pp, int en = NOT_SET); - - /** Motor hardware init function */ - void init(); - /** Motor disable function */ - void disable(); - /** Motor enable function */ - void enable(); - - /** - * Function linking a motor and a sensor - * - * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity - */ - void linkSensor(Sensor* sensor); - - /** - * Function initializing FOC algorithm - * and aligning sensor's and motors' zero position - * - * - If zero_electric_offset parameter is set the alignment procedure is skipped - * - * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. - * @param sensor_direction sensor natural direction - default is CW - * - */ - int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); - /** - * Function running FOC algorithm in real-time - * it calculates the gets motor angle and sets the appropriate voltages - * to the phase pwm signals - * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us - */ - void loopFOC(); - /** - * Function executing the control loops set by the controller parameter of the BLDCMotor. - * - * @param target Either voltage, angle or velocity based on the motor.controller - * If it is not set the motor will use the target set in its variable motor.target - * - * This function doesn't need to be run upon each loop execution - depends of the use case - */ - void move(float target = NOT_SET); - - // hardware variables - int pwmA; //!< phase A pwm pin number - int pwmB; //!< phase B pwm pin number - int pwmC; //!< phase C pwm pin number - int pwmA_L; //!< phase A pwm pin number - int pwmB_L; //!< phase B pwm pin number - int pwmC_L; //!< phase C pwm pin number - int enable_pin; //!< enable pin number - - - - - // State calculation methods - /** Shaft angle calculation in radians [rad] */ - float shaftAngle(); - /** - * Shaft angle calculation function in radian per second [rad/s] - * It implements low pass filtering - */ - float shaftVelocity(); - - // state variables - float target; //!< current target value - depends of the controller - float shaft_angle;//!< current motor angle - float shaft_velocity;//!< current motor velocity - float shaft_velocity_sp;//!< current target velocity - float shaft_angle_sp;//!< current target angle - float voltage_q;//!< current voltage u_q set - float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor - - // motor configuration parameters - float voltage_power_supply;//!< Power supply voltage - float voltage_sensor_align;//!< sensor and motor align voltage parameter - float velocity_index_search;//!< target velocity for index search - int pole_pairs;//!< Motor pole pairs number - - // limiting variables - float voltage_limit; //!< Voltage limitting variable - global limit - float velocity_limit; //!< Velocity limitting variable - global limit - - // configuration structures - ControlType controller; //!< parameter determining the control loop to be used - FOCModulationType foc_modulation;//!< parameter derterniming modulation algorithm - PID_s PID_velocity;//!< parameter determining the velocity PI configuration - P_s P_angle; //!< parameter determining the position P configuration - LPF_s LPF_velocity;//!< parameter determining the velocity Lpw pass filter configuration - - /** - * Sensor link: - * - Encoder - * - MagneticSensor - */ - Sensor* sensor; - - float zero_electric_angle;//!setMode(channelA, TIMER_OUTPUT_COMPARE_PWM1, pinA); - MyTimA->setOverflow(20, MICROSEC_FORMAT); // 50khz - MyTimA->resume(); - - // Automatically retrieve TIM instance and channel associated to pin - TIM_TypeDef *InstanceB = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinB), PinMap_PWM); - uint32_t channelB = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinB), PinMap_PWM)); - // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. - HardwareTimer *MyTimB = new HardwareTimer(InstanceB); - MyTimB->setMode(channelB, TIMER_OUTPUT_COMPARE_PWM1, pinB); - MyTimB->setOverflow(20, MICROSEC_FORMAT); // 50khz - MyTimB->resume(); - - // Automatically retrieve TIM instance and channel associated to pin - TIM_TypeDef *InstanceC = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinC), PinMap_PWM); - uint32_t channelC = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinC), PinMap_PWM)); - // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. - HardwareTimer *MyTimC = new HardwareTimer(InstanceC); - MyTimC->setMode(channelC, TIMER_OUTPUT_COMPARE_PWM1, pinC); - MyTimC->setOverflow(20, MICROSEC_FORMAT); // 50khz - MyTimC->resume(); - -#elif defined(ESP_H) // if esp32 boards - - motor_slots_t m_slot = {}; - - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 4; i++){ - if(esp32_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_motor_slots[i].pinA = pinA; - m_slot = esp32_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); - - mcpwm_config_t pwm_config; - pwm_config.frequency = 4000000; //frequency = 20000Hz - pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% - pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% - pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) - pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(m_slot.mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings - - _delay(100); - - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_0); - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_1); - mcpwm_stop(m_slot.mcpwm_unit, MCPWM_TIMER_2); - m_slot.mcpwm_num->clk_cfg.prescale = 0; - - m_slot.mcpwm_num->timer[0].period.prescale = 4; - m_slot.mcpwm_num->timer[1].period.prescale = 4; - m_slot.mcpwm_num->timer[2].period.prescale = 4; - _delay(1); - m_slot.mcpwm_num->timer[0].period.period = 2048; - m_slot.mcpwm_num->timer[1].period.period = 2048; - m_slot.mcpwm_num->timer[2].period.period = 2048; - _delay(1); - m_slot.mcpwm_num->timer[0].period.upmethod = 0; - m_slot.mcpwm_num->timer[1].period.upmethod = 0; - m_slot.mcpwm_num->timer[2].period.upmethod = 0; - _delay(1); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_0); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_1); - mcpwm_start(m_slot.mcpwm_unit, MCPWM_TIMER_2); - - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(m_slot.mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); - _delay(1); - m_slot.mcpwm_num->timer[0].sync.out_sel = 1; - _delay(1); - m_slot.mcpwm_num->timer[0].sync.out_sel = 0; -#endif -} - -void _setPwmFrequencyLow(const int pinA, const int pinB, const int pinC) { - - // Automatically retrieve TIM instance and channel associated to pin - TIM_TypeDef *InstanceA = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinA), PinMap_PWM); - uint32_t channelA = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinA), PinMap_PWM)); - // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. - HardwareTimer *MyTimA = new HardwareTimer(InstanceA); - MyTimA->setMode(channelA, TIMER_OUTPUT_COMPARE_PWM2, pinA); - MyTimA->setOverflow(20, MICROSEC_FORMAT); // 50khz - MyTimA->resume(); - - // Automatically retrieve TIM instance and channel associated to pin - TIM_TypeDef *InstanceB = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinB), PinMap_PWM); - uint32_t channelB = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinB), PinMap_PWM)); - // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. - HardwareTimer *MyTimB = new HardwareTimer(InstanceB); - MyTimB->setMode(channelB, TIMER_OUTPUT_COMPARE_PWM2, pinB); - MyTimB->setOverflow(20, MICROSEC_FORMAT); // 50khz - MyTimB->resume(); - - // Automatically retrieve TIM instance and channel associated to pin - TIM_TypeDef *InstanceC = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinC), PinMap_PWM); - uint32_t channelC = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinC), PinMap_PWM)); - // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. - HardwareTimer *MyTimC = new HardwareTimer(InstanceC); - MyTimC->setMode(channelC, TIMER_OUTPUT_COMPARE_PWM2, pinC); - MyTimC->setOverflow(20, MICROSEC_FORMAT); // 50khz - MyTimC->resume(); - - -} -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 4; i++){ - if(esp32_motor_slots[i].pinA == pinA){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; - esp32_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; - esp32_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; - break; - } - } - -#elif defined(_STM32_DEF_) // if stm chips - - // Automatically retrieve TIM instance and channel associated to pin - TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinA), PinMap_PWM); - uint32_t channel = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinA), PinMap_PWM)); - // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. - HardwareTimer *MyTim = new HardwareTimer(Instance); - MyTim->setCaptureCompare(channel, dc_a*100.0, PERCENT_COMPARE_FORMAT); // 50% - - // Automatically retrieve TIM instance and channel associated to pin - Instance = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinB), PinMap_PWM); - channel = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinB), PinMap_PWM)); - // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. - MyTim = new HardwareTimer(Instance); - MyTim->setCaptureCompare(channel, dc_b*100.0, PERCENT_COMPARE_FORMAT); // 50% - - // Automatically retrieve TIM instance and channel associated to pin - Instance = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinC), PinMap_PWM); - channel = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinC), PinMap_PWM)); - // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. - MyTim = new HardwareTimer(Instance); - MyTim->setCaptureCompare(channel, dc_c*100.0, PERCENT_COMPARE_FORMAT); // 50% - -// MyTimA->setPWM(channelA, pinA, 50000, dc_a*100.0); -// MyTimB->setPWM(channelB, pinB, 50000, dc_b*100.0); -// MyTimC->setPWM(channelC, pinC, 50000, dc_c*100.0); -#else // Arduino - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255*dc_a); - analogWrite(pinB, 255*dc_b); - analogWrite(pinC, 255*dc_c); -#endif -} -void _writeDutyCycleLow(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ -// -// // Automatically retrieve TIM instance and channel associated to pin -// TIM_TypeDef *InstanceA = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinA), PinMap_PWM); -// uint32_t channelA = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinA), PinMap_PWM)); -// // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. -// HardwareTimer *MyTimA = new HardwareTimer(InstanceA); -// -// // Automatically retrieve TIM instance and channel associated to pin -// TIM_TypeDef *InstanceB = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinB), PinMap_PWM); -// uint32_t channelB = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinB), PinMap_PWM)); -// // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. -// HardwareTimer *MyTimB = new HardwareTimer(InstanceB); -// -// // Automatically retrieve TIM instance and channel associated to pin -// TIM_TypeDef *InstanceC = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pinC), PinMap_PWM); -// uint32_t channelC = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pinC), PinMap_PWM)); -// // Instantiate HardwareTimer object. Thanks to 'new' instantiation, HardwareTimer is not destructed when setup function is finished. -// HardwareTimer *MyTimC = new HardwareTimer(InstanceC); -// -// -// MyTimA->setCaptureCompare(channelA, dc_a*100.0, PERCENT_COMPARE_FORMAT); // 50% -// MyTimB->setCaptureCompare(channelB, dc_b*100.0, PERCENT_COMPARE_FORMAT); // 50% -// MyTimC->setCaptureCompare(channelC, dc_c*100.0, PERCENT_COMPARE_FORMAT); // 50% -} - - -// function buffering delay() -// arduino uno function doesn't work well with interrupts -void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) - // if arduino uno and other atmega328p chips - // use while instad of delay, - // due to wrong measurement based on changed timer0 - unsigned long t = _micros() + ms*1000; - while( _micros() < t ){}; -#else - // regular micros - delay(ms); -#endif -} - - -// function buffering _micros() -// arduino function doesn't work well with interrupts -unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) -// if arduino uno and other atmega328p chips - //return the value based on the prescaler - if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); - else return (micros()); -#else - // regular micros - return micros(); -#endif -} - - -// int array instead of float array -// 2x storage save (int 2Byte float 4 Byte ) -// sin*10000 -int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,1103,1181,1260,1338,1416,1494,1572,1650,1728,1806,1883,1961,2038,2115,2192,2269,2346,2423,2499,2575,2652,2728,2804,2879,2955,3030,3105,3180,3255,3329,3404,3478,3552,3625,3699,3772,3845,3918,3990,4063,4135,4206,4278,4349,4420,4491,4561,4631,4701,4770,4840,4909,4977,5046,5113,5181,5249,5316,5382,5449,5515,5580,5646,5711,5775,5839,5903,5967,6030,6093,6155,6217,6279,6340,6401,6461,6521,6581,6640,6699,6758,6815,6873,6930,6987,7043,7099,7154,7209,7264,7318,7371,7424,7477,7529,7581,7632,7683,7733,7783,7832,7881,7930,7977,8025,8072,8118,8164,8209,8254,8298,8342,8385,8428,8470,8512,8553,8594,8634,8673,8712,8751,8789,8826,8863,8899,8935,8970,9005,9039,9072,9105,9138,9169,9201,9231,9261,9291,9320,9348,9376,9403,9429,9455,9481,9506,9530,9554,9577,9599,9621,9642,9663,9683,9702,9721,9739,9757,9774,9790,9806,9821,9836,9850,9863,9876,9888,9899,9910,9920,9930,9939,9947,9955,9962,9969,9975,9980,9985,9989,9992,9995,9997,9999,10000,10000}; - -// function approximating the sine calculation by using fixed size array -// ~40us (float array) -// ~50us (int array) -// precision +-0.005 -// it has to receive an angle in between 0 and 2PI -float _sin(float a){ - if(a < _PI_2){ - //return sine_array[(int)(199.0*( a / (_PI/2.0)))]; - //return sine_array[(int)(126.6873* a)]; // float array optimized - return 0.0001*sine_array[_round(126.6873* a)]; // int array optimized - }else if(a < _PI){ - // return sine_array[(int)(199.0*(1.0 - (a-_PI/2.0) / (_PI/2.0)))]; - //return sine_array[398 - (int)(126.6873*a)]; // float array optimized - return 0.0001*sine_array[398 - _round(126.6873*a)]; // int array optimized - }else if(a < _3PI_2){ - // return -sine_array[(int)(199.0*((a - _PI) / (_PI/2.0)))]; - //return -sine_array[-398 + (int)(126.6873*a)]; // float array optimized - return -0.0001*sine_array[-398 + _round(126.6873*a)]; // int array optimized - } else { - // return -sine_array[(int)(199.0*(1.0 - (a - 3*_PI/2) / (_PI/2.0)))]; - //return -sine_array[796 - (int)(126.6873*a)]; // float array optimized - return -0.0001*sine_array[796 - _round(126.6873*a)]; // int array optimized - } -} - -// function approximating cosine calculation by using fixed size array -// ~55us (float array) -// ~56us (int array) -// precision +-0.005 -// it has to receive an angle in between 0 and 2PI -float _cos(float a){ - float a_sin = a + _PI_2; - a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin; - return _sin(a_sin); -} diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.h b/minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.h deleted file mode 100644 index 72381ead..00000000 --- a/minimal_project_examples/arduino_foc_minimal_openloop/FOCutils.h +++ /dev/null @@ -1,88 +0,0 @@ -#ifndef FOCUTILS_LIB_H -#define FOCUTILS_LIB_H - -#include "Arduino.h" - - -#if defined(ESP_H) // if esp32 boards - -#include "driver/mcpwm.h" -#include "soc/mcpwm_reg.h" -#include "soc/mcpwm_struct.h" - -#endif - -// sign function -#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) -#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) - -// utility defines -#define _2_SQRT3 1.15470053838 -#define _SQRT3 1.73205080757 -#define _1_SQRT3 0.57735026919 -#define _SQRT3_2 0.86602540378 -#define _SQRT2 1.41421356237 -#define _120_D2R 2.09439510239 -#define _PI 3.14159265359 -#define _PI_2 1.57079632679 -#define _PI_3 1.0471975512 -#define _2PI 6.28318530718 -#define _3PI_2 4.71238898038 - -/** - * High PWM frequency setting function - * - hardware specific - * - * @param pinA pinA number to configure - * @param pinB pinB number to configure - * @param pinC pinC number to configure - */ -void _setPwmFrequency(int pinA, int pinB, int pinC); -void _setPwmFrequencyLow(int pinA, int pinB, int pinC); - -/** - * Function implementing delay() function in milliseconds - * - blocking function - * - hardware specific - - * @param ms number of milliseconds to wait - */ -void _delay(unsigned long ms); - -/** - * Function implementing timestamp getting function in microseconds - * hardware specific - */ -unsigned long _micros(); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_a duty cycle phase A [0, 1] - * @param dc_b duty cycle phase B [0, 1] - * @param dc_c duty cycle phase C [0, 1] - * @param pinA phase A hardware pin number - * @param pinB phase B hardware pin number - * @param pinC phase C hardware pin number - */ -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); -void _writeDutyCycleLow(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ); - - -/** - * Function approximating the sine calculation by using fixed size array - * - execution time ~40us (Arduino UNO) - * - * @param a angle in between 0 and 2PI - */ -float _sin(float a); -/** - * Function approximating cosine calculation by using fixed size array - * - execution time ~50us (Arduino UNO) - * - * @param a angle in between 0 and 2PI - */ -float _cos(float a); - -#endif diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/defaults.h b/minimal_project_examples/arduino_foc_minimal_openloop/defaults.h deleted file mode 100644 index bbb48c6e..00000000 --- a/minimal_project_examples/arduino_foc_minimal_openloop/defaults.h +++ /dev/null @@ -1,18 +0,0 @@ -// default configuration values -// change this file to optimal values for your application - -#define DEF_POWER_SUPPLY 12.0 //!< default power supply voltage -// velocity PI controller params -#define DEF_PID_VEL_P 0.5 //!< default PID controller P value -#define DEF_PID_VEL_I 10 //!< default PID controller I value -#define DEF_PID_VEL_D 0 //!< default PID controller D value -#define DEF_PID_VEL_U_RAMP 1000 //!< default PID controller voltage ramp value -// angle P params -#define DEF_P_ANGLE_P 20 //!< default P controller P value -#define DEF_VEL_LIM 20 //!< angle velocity limit default -// index search -#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1 //!< default index search velocity -// align voltage -#define DEF_VOLTAGE_SENSOR_ALIGN 6.0 //!< default voltage for sensor and motor zero alignemt -// low pass filter velocity -#define DEF_VEL_FILTER_Tf 0.005 //!< default velocity filter time constant \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino b/minimal_project_examples/arduino_foc_stepper_encoder/arduino_foc_stepper_encoder.ino similarity index 98% rename from minimal_project_examples/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino rename to minimal_project_examples/arduino_foc_stepper_encoder/arduino_foc_stepper_encoder.ino index 49c35cbf..bab9063c 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder/arduino_foc_minimal_encoder.ino +++ b/minimal_project_examples/arduino_foc_stepper_encoder/arduino_foc_stepper_encoder.ino @@ -1,5 +1,5 @@ /** - * Comprehensive BLDC motor control example using encoder + * Comprehensive Stepper motor control example using encoder * * Using serial terminal user can send motor commands and configure the motor and FOC in real-time: * - configure PID controller constants diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/Encoder.cpp b/minimal_project_examples/arduino_foc_stepper_encoder/src/Encoder.cpp similarity index 96% rename from minimal_project_examples/arduino_foc_minimal_encoder/src/Encoder.cpp rename to minimal_project_examples/arduino_foc_stepper_encoder/src/Encoder.cpp index 77631345..1965c015 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder/src/Encoder.cpp +++ b/minimal_project_examples/arduino_foc_stepper_encoder/src/Encoder.cpp @@ -9,7 +9,7 @@ */ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ - + // Encoder measurement structure init // hardware pins pinA = _encA; @@ -87,11 +87,11 @@ void Encoder::handleIndex() { if(hasIndex()){ int I = digitalRead(index_pin); if(I && !I_active){ - // align encoder on each index + // align encoder on each index if(index_pulse_counter){ long tmp = pulse_counter; // corrent the counter value - pulse_counter = round((float)pulse_counter/(float)cpr)*cpr; + pulse_counter = round((double)pulse_counter/(double)cpr)*cpr; // preserve relative speed prev_pulse_counter += pulse_counter - tmp; } else { @@ -119,8 +119,8 @@ float Encoder::getVelocity(){ // sampling time calculation float Ts = (timestamp_us - prev_timestamp_us) * 1e-6; // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + // time from last impulse float Th = (timestamp_us - pulse_timestamp) * 1e-6; long dN = pulse_counter - prev_pulse_counter; @@ -133,7 +133,7 @@ float Encoder::getVelocity(){ // only increment if some impulses received float dt = Ts + prev_Th - Th; pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second; - + // if more than 0.05 passed in between impulses if ( Th > 0.1) pulse_per_second = 0; @@ -176,10 +176,10 @@ int Encoder::hasIndex(){ } -// encoder initialisation of the hardware pins +// encoder initialisation of the hardware pins // and calculation variables void Encoder::init(){ - + // Encoder - check if pullup needed for your encoder if(pullup == Pullup::INTERN){ pinMode(pinA, INPUT_PULLUP); @@ -190,7 +190,7 @@ void Encoder::init(){ pinMode(pinB, INPUT); if(hasIndex()) pinMode(index_pin,INPUT); } - + // counter setup pulse_counter = 0; pulse_timestamp = _micros(); @@ -222,8 +222,7 @@ void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){ if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); break; } - + // if index used initialize the index interrupt if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE); } - diff --git a/minimal_project_examples/arduino_foc_minimal_encoder1/src/Encoder.h b/minimal_project_examples/arduino_foc_stepper_encoder/src/Encoder.h similarity index 91% rename from minimal_project_examples/arduino_foc_minimal_encoder1/src/Encoder.h rename to minimal_project_examples/arduino_foc_stepper_encoder/src/Encoder.h index 347cb261..d1a55f0e 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder1/src/Encoder.h +++ b/minimal_project_examples/arduino_foc_stepper_encoder/src/Encoder.h @@ -2,7 +2,8 @@ #define ENCODER_LIB_H #include "Arduino.h" -#include "common/FOCutils.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" #include "common/Sensor.h" @@ -59,31 +60,31 @@ class Encoder: public Sensor{ // Abstract functions of the Sensor class implementation /** get current angle (rad) */ - float getAngle(); + float getAngle() override; /** get current angular velocity (rad/s) */ - float getVelocity(); + float getVelocity() override; /** * set current angle as zero angle * return the angle [rad] difference */ - float initRelativeZero(); + float initRelativeZero() override; /** * set index angle as zero angle * return the angle [rad] difference */ - float initAbsoluteZero(); + float initAbsoluteZero() override; /** * returns 0 if it has no index * 0 - encoder without index * 1 - encoder with index */ - int hasAbsoluteZero(); + int hasAbsoluteZero() override; /** * returns 0 if it does need search for absolute zero * 0 - encoder without index * 1 - ecoder with index */ - int needsAbsoluteZeroSearch(); + int needsAbsoluteZeroSearch() override; private: int hasIndex(); //!< function returning 1 if encoder has index pin and 0 if not. diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/StepperMotor.cpp b/minimal_project_examples/arduino_foc_stepper_encoder/src/StepperMotor.cpp similarity index 97% rename from minimal_project_examples/arduino_foc_minimal_encoder/src/StepperMotor.cpp rename to minimal_project_examples/arduino_foc_stepper_encoder/src/StepperMotor.cpp index fca6b1b1..22ceb256 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder/src/StepperMotor.cpp +++ b/minimal_project_examples/arduino_foc_stepper_encoder/src/StepperMotor.cpp @@ -21,7 +21,7 @@ StepperMotor::StepperMotor(int ph1A, int ph1B, int ph2A, int ph2B, int pp, int e } // init hardware pins -void StepperMotor::init() { +void StepperMotor::init(long pwm_frequency) { if(monitor_port) monitor_port->println("MOT: Init pins."); // PWM pins pinMode(pwm1A, OUTPUT); @@ -34,12 +34,16 @@ void StepperMotor::init() { if(monitor_port) monitor_port->println("MOT: PWM config."); // Increase PWM frequency // make silent - _setPwmFrequency(pwm1A, pwm1B, pwm2A, pwm2B); + _setPwmFrequency(pwm_frequency, pwm1A, pwm1B, pwm2A, pwm2B); // sanity check for the voltage limit configuration if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; // constrain voltage for sensor alignment if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + + // update the controller limits + PID_velocity.limit = voltage_limit; + P_angle.limit = velocity_limit; _delay(500); // enable motor diff --git a/minimal_project_examples/arduino_foc_minimal_encoder/src/StepperMotor.h b/minimal_project_examples/arduino_foc_stepper_encoder/src/StepperMotor.h similarity index 94% rename from minimal_project_examples/arduino_foc_minimal_encoder/src/StepperMotor.h rename to minimal_project_examples/arduino_foc_stepper_encoder/src/StepperMotor.h index 8f10311f..bf14e096 100644 --- a/minimal_project_examples/arduino_foc_minimal_encoder/src/StepperMotor.h +++ b/minimal_project_examples/arduino_foc_stepper_encoder/src/StepperMotor.h @@ -32,11 +32,11 @@ class StepperMotor: public FOCMotor StepperMotor(int ph1A,int ph1B,int ph2A,int ph2B,int pp, int en1 = NOT_SET, int en2 = NOT_SET); /** Motor hardware init function */ - void init(); + void init(long pwm_frequency = NOT_SET) override; /** Motor disable function */ - void disable(); + void disable() override; /** Motor enable function */ - void enable(); + void enable() override; /** * Function initializing FOC algorithm @@ -48,14 +48,14 @@ class StepperMotor: public FOCMotor * @param sensor_direction sensor natural direction - default is CW * */ - int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW); + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW) override; /** * Function running FOC algorithm in real-time * it calculates the gets motor angle and sets the appropriate voltages * to the phase pwm signals * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us */ - void loopFOC(); + void loopFOC() override; /** * Function executing the control loops set by the controller parameter of the BLDCMotor. * @@ -64,7 +64,7 @@ class StepperMotor: public FOCMotor * * This function doesn't need to be run upon each loop execution - depends of the use case */ - void move(float target = NOT_SET); + void move(float target = NOT_SET) override; // hardware variables int pwm1A; //!< phase 1A pwm pin number diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/FOCMotor.cpp b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/FOCMotor.cpp new file mode 100644 index 00000000..adecbeec --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/FOCMotor.cpp @@ -0,0 +1,245 @@ +#include "FOCMotor.h" + +/** + * Default constructor - setting all variabels to default values + */ +FOCMotor::FOCMotor() +{ + // Power supply voltage + voltage_power_supply = DEF_POWER_SUPPLY; + + // maximum angular velocity to be used for positioning + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = voltage_power_supply; + + // index search velocity + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; + + // electric angle of comthe zero angle + zero_electric_angle = 0; + + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + + // default target value + target = 0; + + //monitor_port + monitor_port = nullptr; + //sensor + sensor = nullptr; +} + + +/** + Sensor communication methods +*/ +void FOCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} +// shaft angle calculation +float FOCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return shaft_angle; + return sensor->getAngle(); +} +// shaft velocity calculation +float FOCMotor::shaftVelocity() { + // if no sensor linked return 0 + if(!sensor) return 0; + return LPF_velocity(sensor->getVelocity()); +} + + + + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void FOCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void FOCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity_openloop: + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle_openloop: + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int FOCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'D': // velocity D gain change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PID velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P angle| "); + break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + } + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("P: "); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("I: "); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); + break; + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("volt_ramp: "); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET) { + voltage_limit = value; + PID_velocity.limit = value; + } + if(monitor_port) monitor_port->println(voltage_limit); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("Tf: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("vel_limit: "); + if(!GET){ + velocity_limit = value; + P_angle.limit = value; + } + if(monitor_port) monitor_port->println(velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Control: "); + + if(GET){ // if get command + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + default: + if(monitor_port) monitor_port->println("open loop"); + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/FOCMotor.h b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/FOCMotor.h new file mode 100644 index 00000000..40f7f6d4 --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/FOCMotor.h @@ -0,0 +1,195 @@ +#ifndef FOCMOTOR_H +#define FOCMOTOR_H + +#include "Arduino.h" +#include "hardware_utils.h" +#include "foc_utils.h" +#include "defaults.h" + +#include "Sensor.h" +#include "pid.h" +#include "lowpass_filter.h" + + +/** + * Motiron control type + */ +enum ControlType{ + voltage,//!< Torque control using voltage + velocity,//!< Velocity motion control + angle,//!< Position/angle motion control + velocity_openloop, + angle_openloop +}; + +/** + * FOC modulation type + */ +enum FOCModulationType{ + SinePWM, //!< Sinusoidal PWM modulation + SpaceVectorPWM //!< Space vector modulation method +}; + +/** + Generic motor class +*/ +class FOCMotor +{ + public: + /** + * Default constructor - setting all variabels to default values + */ + FOCMotor(); + + /** Motor hardware init function */ + virtual void init(long pwm_frequency)=0; + /** Motor disable function */ + virtual void disable()=0; + /** Motor enable function */ + virtual void enable()=0; + + /** + * Function linking a motor and a sensor + * + * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity + */ + void linkSensor(Sensor* sensor); + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + virtual int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW)=0; + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + virtual void loopFOC()=0; + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + virtual void move(float target = NOT_SET)=0; + + // State calculation methods + /** Shaft angle calculation in radians [rad] */ + float shaftAngle(); + /** + * Shaft angle calculation function in radian per second [rad/s] + * It implements low pass filtering + */ + float shaftVelocity(); + + // state variables + float target; //!< current target value - depends of the controller + float shaft_angle;//!< current motor angle + float shaft_velocity;//!< current motor velocity + float shaft_velocity_sp;//!< current target velocity + float shaft_angle_sp;//!< current target angle + float voltage_q;//!< current voltage u_q set + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform + + // motor configuration parameters + float voltage_power_supply;//!< Power supply voltage + float voltage_sensor_align;//!< sensor and motor align voltage parameter + float velocity_index_search;//!< target velocity for index search + int pole_pairs;//!< Motor pole pairs number + + // limiting variables + float voltage_limit; //!< Voltage limitting variable - global limit + float velocity_limit; //!< Velocity limitting variable - global limit + + float zero_electric_angle;//! _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} + + +// normalizing radian angle to [0,2PI] +float _normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} + +// Electrical angle calculation +float _electricalAngle(float shaft_angle, int pole_pairs) { + return (shaft_angle * pole_pairs); +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/foc_utils.h b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/foc_utils.h new file mode 100644 index 00000000..5ab34f42 --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/foc_utils.h @@ -0,0 +1,55 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + +// sign function +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + +// utility defines +#define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI 3.14159265359 +#define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + + +#define NOT_SET -12345.0 + +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _sin(float a); +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _cos(float a); + +/** + * normalizing radian angle to [0,2PI] + * @param angle - angle to be normalized + */ +float _normalizeAngle(float angle); + + +/** + * Electrical angle calculation + * + * @param shaft_angle - shaft angle of the motor + * @param pole_pairs - number of pole pairs + */ +float _electricalAngle(float shaft_angle, int pole_pairs); +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.cpp new file mode 100644 index 00000000..0d080bab --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.cpp @@ -0,0 +1,284 @@ +#include "hardware_utils.h" + +#if defined(ESP_H) // if ESP32 board +// empty motor slot +#define _EMPTY_SLOT -20 + +// structure containing motor slot configuration +// this library supports up to 4 motors +typedef struct { + int pinA; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; + mcpwm_io_signals_t mcpwm_c; +} bldc_motor_slots_t; +typedef struct { + int pin1A; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_1a; + mcpwm_io_signals_t mcpwm_1b; + mcpwm_io_signals_t mcpwm_2a; + mcpwm_io_signals_t mcpwm_2b; +} stepper_motor_slots_t; + +// define bldc motor slots array +bldc_motor_slots_t esp32_bldc_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B + }; + +// define stepper motor slots array +stepper_motor_slots_t esp32_stepper_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + }; + +// configuring high frequency pwm timer +// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller +void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ + + mcpwm_config_t pwm_config; + pwm_config.frequency = pwm_frequency; //frequency + pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% + pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + _delay(100); + + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); + mcpwm_num->clk_cfg.prescale = 0; + + mcpwm_num->timer[0].period.prescale = 4; + mcpwm_num->timer[1].period.prescale = 4; + mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + mcpwm_num->timer[0].period.period = 2048; + mcpwm_num->timer[1].period.period = 2048; + mcpwm_num->timer[2].period.period = 2048; + _delay(1); + mcpwm_num->timer[0].period.upmethod = 0; + mcpwm_num->timer[1].period.upmethod = 0; + mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 0; +} + +#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips +// set pwm frequency to 32KHz +void _pinHighFrequency(const int pin){ + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pin == 5 || pin == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pin == 9 || pin == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pin == 3 || pin == 11) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +} +#elif defined(_STM32_DEF_) // if stm chips +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); + analogWriteResolution(12); // resolution 12 bit 0 - 4096 +} +#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); +} +#endif + + +// function setting the high pwm frequency to the supplied pins +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); + _pinHighFrequency(pinC); + if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor + +#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards + if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor + +#elif defined(ESP_H) // if esp32 boards + if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency + + if(pinD == NOT_SET){ + bldc_motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_motor_slots[i].pinA = pinA; + m_slot = esp32_bldc_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + + }else{ + stepper_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_motor_slots[i].pin1A = pinA; + m_slot = esp32_stepper_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + } +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pinA, 4095.0*dc_a); + analogWrite(pinB, 4095.0*dc_b); + analogWrite(pinC, 4095.0*dc_c); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255*dc_a); + analogWrite(pinB, 255*dc_b); + analogWrite(pinC, 255*dc_c); +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pin1A, 4095.0*dc_1a); + analogWrite(pin1B, 4095.0*dc_1b); + analogWrite(pin2A, 4095.0*dc_2a); + analogWrite(pin2B, 4095.0*dc_2b); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255*dc_1a); + analogWrite(pin1B, 255*dc_1b); + analogWrite(pin2A, 255*dc_2a); + analogWrite(pin2B, 255*dc_2b); +#endif +} + + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.h b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.h new file mode 100644 index 00000000..f99c260a --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.h @@ -0,0 +1,72 @@ +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H + +#include "Arduino.h" +#include "foc_utils.h" + + +#if defined(ESP_H) // if esp32 boards + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +#endif + +/** + * High PWM frequency setting function + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc motor or pin1A stepper motor + * @param pinB pinB bldc motor or pin1B stepper motor + * @param pinC pinC bldc motor or pin2A stepper motor + * @param pinD pin2B stepper motor + */ +void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/lowpass_filter.cpp b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/lowpass_filter.cpp new file mode 100644 index 00000000..9bf4ab7a --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/lowpass_filter.cpp @@ -0,0 +1,25 @@ +#include "lowpass_filter.h" + +LowPassFilter::LowPassFilter(float time_constant) + : Tf(time_constant) + , y_prev(0.0f) +{ + timestamp_prev = _micros(); +} + + +float LowPassFilter::operator() (float x) +{ + unsigned long timestamp = _micros(); + float dt = (timestamp - timestamp_prev)*1e-6f; + + if (dt < 0.0f || dt > 0.5f) + dt = 1e-3f; + + float alpha = Tf/(Tf + dt); + float y = alpha*y_prev + (1.0f - alpha)*x; + + y_prev = y; + timestamp_prev = timestamp; + return y; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/lowpass_filter.h b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/lowpass_filter.h new file mode 100644 index 00000000..5a7619cf --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/lowpass_filter.h @@ -0,0 +1,29 @@ +#ifndef LOWPASS_FILTER_H +#define LOWPASS_FILTER_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + + +/** + * Low pass filter class + */ +class LowPassFilter +{ +public: + /** + * @param Tf - Low pass filter time constant + */ + LowPassFilter(float Tf); + ~LowPassFilter() = default; + + float operator() (float x); + float Tf; //!< Low pass filter time constant + +protected: + unsigned long timestamp_prev; //!< Last execution timestamp + float y_prev; //!< filtered value in previous execution step +}; + +#endif // LOWPASS_FILTER_H \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/pid.cpp b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/pid.cpp new file mode 100644 index 00000000..277e17ce --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/pid.cpp @@ -0,0 +1,56 @@ +#include "pid.h" + +PIDController::PIDController(float P, float I, float D, float ramp, float limit) + : P(P) + , I(I) + , D(D) + , output_ramp(ramp) // output derivative limit [volts/second] + , limit(limit) // output supply limit [volts] + , integral_prev(0.0) + , error_prev(0.0) + , output_prev(0.0) +{ + timestamp_prev = _micros()*1e-6; +} + +// PID controller function +float PIDController::operator() (float error){ + // calculate the time from the last call + unsigned long timestamp_now = _micros(); + float Ts = (timestamp_now - timestamp_prev) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = P * error_prev; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = integral_prev + I*Ts*0.5*(error + error_prev); + // antiwindup - limit the output voltage_q + integral = constrain(integral, -limit, limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = D*(error - error_prev)/Ts; + + // sum all the components + float output = proportional + integral + derivative; + // antiwindup - limit the output variable + output = constrain(output, -limit, limit); + + // limit the acceleration by ramping the output + float output_rate = (output - output_prev)/Ts; + if (output_rate > output_ramp) + output = output_prev + output_ramp*Ts; + else if (output_rate < -output_ramp) + output = output_prev - output_ramp*Ts; + + // saving for the next pass + integral_prev = integral; + output_prev = output; + error_prev = error; + timestamp_prev = timestamp_now; + return output; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/pid.h b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/pid.h new file mode 100644 index 00000000..7ee337c4 --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/pid.h @@ -0,0 +1,40 @@ +#ifndef PID_H +#define PID_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + +/** + * PID controller class + */ +class PIDController +{ +public: + /** + * + * @param P - Proportional gain + * @param I - Integral gain + * @param D - Derivative gain + * @param ramp - Maximum speed of change of the output value + * @param limit - Maximum output value + */ + PIDController(float P, float I, float D, float ramp, float limit); + ~PIDController() = default; + + float operator() (float error); + + float P; //!< Proportional gain + float I; //!< Integral gain + float D; //!< Derivative gain + float output_ramp; //!< Maximum speed of change of the output value + float limit; //!< Maximum output value + +protected: + float integral_prev; //!< last integral component value + float error_prev; //!< last tracking error value + float timestamp_prev; //!< Last execution timestamp + float output_prev; //!< last pid output value +}; + +#endif // PID_H \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/arduino_foc_stepper_magnetic_i2c.ino b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/arduino_foc_stepper_magnetic_i2c.ino new file mode 100644 index 00000000..3d3216d2 --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/arduino_foc_stepper_magnetic_i2c.ino @@ -0,0 +1,139 @@ +/** + * Comprehensive BLDC motor control example using magnetic sensor + * + * Using serial terminal user can send motor commands and configure the motor and FOC in real-time: + * - configure PID controller constants + * - change motion control loops + * - monitor motor variabels + * - set target values + * - check all the configuration values + * + * To check the config value just enter the command letter. + * For example: - to read velocity PI controller P gain run: P + * - to set velocity PI controller P gain to 1.2 run: P1.2 + * + * To change the target value just enter a number in the terminal: + * For example: - to change the target value to -0.1453 enter: -0.1453 + * - to get the current target value enter: V3 + * + * List of commands: + * - P: velocity PID controller P gain + * - I: velocity PID controller I gain + * - D: velocity PID controller D gain + * - R: velocity PID controller voltage ramp + * - F: velocity Low pass filter time constant + * - K: angle P controller P gain + * - N: angle P controller velocity limit + * - L: system voltage limit + * - C: control loop + * - 0: voltage + * - 1: velocity + * - 2: angle + * - V: get motor variables + * - 0: currently set voltage + * - 1: current velocity + * - 2: current angle + * - 3: current target value + * + */ +#include "src/StepperMotor.h" +#include "src/MagneticSensorI2C.h" + +// motor instance +StepperMotor motor = StepperMotor(10, 6, 5, 9, 50, 8); + +// motor instance +BLDCMotor motor = BLDCMotor(9, 5, 6, 11, 7); + +void setup() { + + // initialise magnetic sensor hardware + sensor.init(); + // link the motor to the sensor + motor.linkSensor(&sensor); + + // choose FOC modulation + motor.foc_modulation = FOCModulationType::SpaceVectorPWM; + + // power supply voltage [V] + motor.voltage_power_supply = 12; + + // set control loop type to be used + motor.controller = ControlType::voltage; + + // contoller configuration based on the control type + motor.PID_velocity.P = 0.2; + motor.PID_velocity.I = 20; + motor.PID_velocity.D = 0; + // default voltage_power_supply + motor.voltage_limit = 12; + + // velocity low pass filtering time constant + motor.LPF_velocity.Tf = 0.01; + + // angle loop controller + motor.P_angle.P = 20; + // angle loop velocity limit + motor.velocity_limit = 50; + + // use monitoring with serial for motor init + // monitoring port + Serial.begin(115200); + // comment out if not needed + motor.useMonitoring(Serial); + + // initialise motor + motor.init(); + // align encoder and start FOC + motor.initFOC(); + + // set the inital target value + motor.target = 2; + + + // Run user commands to configure and the motor (find the full command list in docs.simplefoc.com) + Serial.println("Motor commands sketch | Initial motion control > torque/voltage : target 2V."); + + _delay(1000); +} + + +void loop() { + // iterative setting FOC phase voltage + motor.loopFOC(); + + // iterative function setting the outter loop target + // velocity, position or voltage + // if tatget not set in parameter uses motor.target variable + motor.move(); + + // user communication + motor.command(serialReceiveUserCommand()); +} + +// utility function enabling serial communication the user +String serialReceiveUserCommand() { + + // a string to hold incoming data + static String received_chars; + + String command = ""; + + while (Serial.available()) { + // get the new byte: + char inChar = (char)Serial.read(); + // add it to the string buffer: + received_chars += inChar; + + // end of user input + if (inChar == '\n') { + + // execute the user command + command = received_chars; + + // reset the command buffer + received_chars = ""; + } + } + return command; +} diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorI2C.cpp b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/MagneticSensorI2C.cpp similarity index 75% rename from minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorI2C.cpp rename to minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/MagneticSensorI2C.cpp index eb94a753..a02b762b 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorI2C.cpp +++ b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/MagneticSensorI2C.cpp @@ -1,5 +1,24 @@ #include "MagneticSensorI2C.h" +/** Typical configuration for the 12bit AMS AS5600 magnetic sensor over I2C interface */ +MagneticSensorI2CConfig_s AS5600_I2C = { + .chip_address = 0x36, + .clock_speed = 1000000, + .bit_resolution = 12, + .angle_register = 0x0E, + .data_start_bit = 11 +}; + +/** Typical configuration for the 12bit AMS AS5048 magnetic sensor over I2C interface */ +MagneticSensorI2CConfig_s AS5048_I2C = { + .chip_address = 0x40, // highly configurable. if A1 and A2 are held low, this is probable value + .clock_speed = 1000000, + .bit_resolution = 14, + .angle_register = 0xFE, + .data_start_bit = 15 +}; + + // MagneticSensorI2C(uint8_t _chip_address, float _cpr, uint8_t _angle_register_msb) // @param _chip_address I2C chip address // @param _bit_resolution bit resolution of the sensor @@ -22,13 +41,47 @@ MagneticSensorI2C::MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, // extraction masks lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); msb_mask = (uint8_t)( (2 << _bits_used_msb) - 1 ); + clock_speed = 400000; + sda_pin = SDA; + scl_pin = SCL; + } +MagneticSensorI2C::MagneticSensorI2C(MagneticSensorI2CConfig_s config){ + chip_address = config.chip_address; + + // angle read register of the magnetic sensor + angle_register_msb = config.angle_register; + // register maximum value (counts per revolution) + cpr = pow(2, config.bit_resolution); + + int bits_used_msb = config.data_start_bit - 7; + lsb_used = config.bit_resolution - bits_used_msb; + // extraction masks + lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); + msb_mask = (uint8_t)( (2 << bits_used_msb) - 1 ); + clock_speed = 400000; + sda_pin = SDA; + scl_pin = SCL; + +} void MagneticSensorI2C::init(){ +#if defined(_STM32_DEF_) // if stm chips + // I2C communication begin + Wire.begin(); + Wire.setClock(clock_speed); + Wire.setSCL(scl_pin); + Wire.setSDA(sda_pin); +#elif defined(ESP_H) // if esp32 //I2C communication begin - Wire.begin(); + Wire.begin(sda_pin, scl_pin, clock_speed); +#else + // I2C communication begin + Wire.begin(); + Wire.setClock(clock_speed); +#endif // velocity calculation init angle_prev = 0; diff --git a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorI2C.h b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/MagneticSensorI2C.h similarity index 69% rename from minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorI2C.h rename to minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/MagneticSensorI2C.h index c5dc3489..88d74d35 100644 --- a/minimal_project_examples/arduino_foc_minimal_magnetic_spi/MagneticSensorI2C.h +++ b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/MagneticSensorI2C.h @@ -3,9 +3,19 @@ #include "Arduino.h" #include -#include "FOCutils.h" -#include "Sensor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" +struct MagneticSensorI2CConfig_s { + int chip_address; + long clock_speed; + int bit_resolution; + int angle_register; + int data_start_bit; +}; +// some predefined structures +extern MagneticSensorI2CConfig_s AS5600_I2C,AS5048_I2C; class MagneticSensorI2C: public Sensor{ public: @@ -17,31 +27,47 @@ class MagneticSensorI2C: public Sensor{ * @param _bits_used_msb number of used bits in msb */ MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _msb_bits_used); - + /** + * MagneticSensorI2C class constructor + * @param config I2C config + */ + MagneticSensorI2C(MagneticSensorI2CConfig_s config); + + static MagneticSensorI2C AS5600(); + /** sensor initialise pins */ void init(); // implementation of abstract functions of the Sensor class /** get current angle (rad) */ - float getAngle(); + float getAngle() override; /** get current angular velocity (rad/s) **/ - float getVelocity(); + float getVelocity() override; /** * set current angle as zero angle * return the angle [rad] difference */ - float initRelativeZero(); + float initRelativeZero() override; /** * set absolute zero angle as zero angle * return the angle [rad] difference */ - float initAbsoluteZero(); + float initAbsoluteZero() override; /** returns 1 because it is the absolute sensor */ - int hasAbsoluteZero(); + int hasAbsoluteZero() override; /** returns 0 maning it doesn't need search for absolute zero */ - int needsAbsoluteZeroSearch(); + + int needsAbsoluteZeroSearch() override; + + /* the speed of the i2c clock signal */ + long clock_speed; + + /* the pin used for i2c data */ + int sda_pin; + /* the pin used for i2c clock */ + int scl_pin; private: float cpr; //!< Maximum range of the magnetic sensor diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/StepperMotor.cpp b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/StepperMotor.cpp new file mode 100644 index 00000000..22ceb256 --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/StepperMotor.cpp @@ -0,0 +1,309 @@ +#include "StepperMotor.h" + +// StepperMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - ph1A, ph1B - motor phase 1 pwm pins +// - ph2A, ph2B - motor phase 2 pwm pins +// - pp - pole pair number +// - enable pin - (optional input) +StepperMotor::StepperMotor(int ph1A, int ph1B, int ph2A, int ph2B, int pp, int en1, int en2) +: FOCMotor() +{ + // Pin initialization + pwm1A = ph1A; + pwm1B = ph1B; + pwm2A = ph2A; + pwm2B = ph2B; + pole_pairs = pp; + + // enable_pin pin + enable_pin1 = en1; + enable_pin2 = en2; +} + +// init hardware pins +void StepperMotor::init(long pwm_frequency) { + if(monitor_port) monitor_port->println("MOT: Init pins."); + // PWM pins + pinMode(pwm1A, OUTPUT); + pinMode(pwm1B, OUTPUT); + pinMode(pwm2A, OUTPUT); + pinMode(pwm2B, OUTPUT); + if ( enable_pin1 != NOT_SET ) pinMode(enable_pin1, OUTPUT); + if ( enable_pin2 != NOT_SET ) pinMode(enable_pin2, OUTPUT); + + if(monitor_port) monitor_port->println("MOT: PWM config."); + // Increase PWM frequency + // make silent + _setPwmFrequency(pwm_frequency, pwm1A, pwm1B, pwm2A, pwm2B); + + // sanity check for the voltage limit configuration + if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + + // update the controller limits + PID_velocity.limit = voltage_limit; + P_angle.limit = velocity_limit; + + _delay(500); + // enable motor + if(monitor_port) monitor_port->println("MOT: Enable."); + enable(); + _delay(500); + +} + + +// disable motor driver +void StepperMotor::disable() +{ + // disable the driver - if enable_pin pin available + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, LOW); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, LOW); + // set zero to PWM + setPwm(0, 0); +} +// enable motor driver +void StepperMotor::enable() +{ + // set zero to PWM + setPwm(0, 0); + // enable_pin the driver - if enable_pin pin available + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, HIGH); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, HIGH); + +} + + +/** + FOC functions +*/ +// FOC initialization function +int StepperMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } + if(monitor_port) monitor_port->println("MOT: Motor ready."); + + return exit_flag; +} +// Encoder alignment to electrical 0 angle +int StepperMotor::alignSensor() { + if(monitor_port) monitor_port->println("MOT: Align sensor."); + // align the electrical phases of the motor and sensor + // set angle -90 degrees + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } + + // let the motor stabilize for 2 sec + _delay(2000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0,0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int StepperMotor::absoluteZeroAlign() { + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); + + // align absolute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = _normalizeAngle(_electricalAngle(zero_offset, pole_pairs)); + } + // return bool if zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void StepperMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); +} + +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function +// - if target is not set it uses motor.target value +void StepperMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; + // get angular velocity + shaft_velocity = shaftVelocity(); + // choose control loop + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = P_angle( shaft_angle_sp - shaft_angle ); + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // include velocity loop + shaft_velocity_sp = target; + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); + break; + } +} + + +// Method using FOC to set Uq to the motor at the optimal angle +// Function implementingSine PWM algorithms +// - space vector not implemented yet +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) +void StepperMotor::setPhaseVoltage(float Uq, float angle_el) { + // Sinusoidal PWM modulation + // Inverse Park transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + // set the voltages in hardware + setPwm(Ualpha,Ubeta); +} + + + +// Set voltage to the pwm pin +void StepperMotor::setPwm(float Ualpha, float Ubeta) { + float duty_cycle1A(0.0),duty_cycle1B(0.0),duty_cycle2A(0.0),duty_cycle2B(0.0); + // hardware specific writing + if( Ualpha > 0 ) + duty_cycle1B = constrain(abs(Ualpha)/voltage_power_supply,0,1); + else + duty_cycle1A = constrain(abs(Ualpha)/voltage_power_supply,0,1); + + if( Ubeta > 0 ) + duty_cycle2B = constrain(abs(Ubeta)/voltage_power_supply,0,1); + else + duty_cycle2A = constrain(abs(Ubeta)/voltage_power_supply,0,1); + // write to hardware + _writeDutyCycle(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, pwm1A, pwm1B, pwm2A, pwm2B); +} + +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void StepperMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle,pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void StepperMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle,pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/StepperMotor.h b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/StepperMotor.h new file mode 100644 index 00000000..bf14e096 --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/StepperMotor.h @@ -0,0 +1,122 @@ +/** + * @file StepperMotor.h + * + */ + +#ifndef StepperMotor_h +#define StepperMotor_h + +#include "Arduino.h" +#include "common/FOCMotor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" +#include "common/defaults.h" + +/** + Stepper Motor class +*/ +class StepperMotor: public FOCMotor +{ + public: + /** + StepperMotor class constructor + @param ph1A 1A phase pwm pin + @param ph1B 1B phase pwm pin + @param ph2A 2A phase pwm pin + @param ph2B 2B phase pwm pin + @param pp pole pair number - cpr counts per rotation number (cpm=ppm*4) + @param en1 enable pin phase 1 (optional input) + @param en2 enable pin phase 2 (optional input) + */ + StepperMotor(int ph1A,int ph1B,int ph2A,int ph2B,int pp, int en1 = NOT_SET, int en2 = NOT_SET); + + /** Motor hardware init function */ + void init(long pwm_frequency = NOT_SET) override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW) override; + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + void loopFOC() override; + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET) override; + + // hardware variables + int pwm1A; //!< phase 1A pwm pin number + int pwm1B; //!< phase 1B pwm pin number + int pwm2A; //!< phase 2A pwm pin number + int pwm2B; //!< phase 2B pwm pin number + int enable_pin1; //!< enable pin number phase 1 + int enable_pin2; //!< enable pin number phase 2 + + private: + + // FOC methods + /** + * Method using FOC to set Uq to the motor at the optimal angle + * Heart of the FOC algorithm + * + * @param Uq Current voltage in q axis to set to the motor + * @param angle_el current electrical angle of the motor + */ + void setPhaseVoltage(float Uq, float angle_el); + + /** Sensor alignment to electrical 0 angle of the motor */ + int alignSensor(); + /** Motor and sensor alignment to the sensors absolute 0 angle */ + int absoluteZeroAlign(); + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + * @param Uc phase C voltage + */ + void setPwm(float Ualpha, float Ubeta); + + // Open loop motion control + /** + * Function (iterative) generating open loop movement for target velocity + * it uses voltage_limit variable + * + * @param target_velocity - rad/s + */ + void velocityOpenloop(float target_velocity); + /** + * Function (iterative) generating open loop movement towards the target angle + * it uses voltage_limit and velocity_limit variables + * + * @param target_angle - rad + */ + void angleOpenloop(float target_angle); + // open loop variables + long open_loop_timestamp; +}; + + +#endif diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/FOCMotor.cpp b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/FOCMotor.cpp new file mode 100644 index 00000000..adecbeec --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/FOCMotor.cpp @@ -0,0 +1,245 @@ +#include "FOCMotor.h" + +/** + * Default constructor - setting all variabels to default values + */ +FOCMotor::FOCMotor() +{ + // Power supply voltage + voltage_power_supply = DEF_POWER_SUPPLY; + + // maximum angular velocity to be used for positioning + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = voltage_power_supply; + + // index search velocity + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; + + // electric angle of comthe zero angle + zero_electric_angle = 0; + + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + + // default target value + target = 0; + + //monitor_port + monitor_port = nullptr; + //sensor + sensor = nullptr; +} + + +/** + Sensor communication methods +*/ +void FOCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} +// shaft angle calculation +float FOCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return shaft_angle; + return sensor->getAngle(); +} +// shaft velocity calculation +float FOCMotor::shaftVelocity() { + // if no sensor linked return 0 + if(!sensor) return 0; + return LPF_velocity(sensor->getVelocity()); +} + + + + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void FOCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void FOCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity_openloop: + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle_openloop: + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int FOCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'D': // velocity D gain change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PID velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P angle| "); + break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + } + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("P: "); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("I: "); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); + break; + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("volt_ramp: "); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET) { + voltage_limit = value; + PID_velocity.limit = value; + } + if(monitor_port) monitor_port->println(voltage_limit); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("Tf: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("vel_limit: "); + if(!GET){ + velocity_limit = value; + P_angle.limit = value; + } + if(monitor_port) monitor_port->println(velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Control: "); + + if(GET){ // if get command + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + default: + if(monitor_port) monitor_port->println("open loop"); + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/FOCMotor.h b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/FOCMotor.h new file mode 100644 index 00000000..40f7f6d4 --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/FOCMotor.h @@ -0,0 +1,195 @@ +#ifndef FOCMOTOR_H +#define FOCMOTOR_H + +#include "Arduino.h" +#include "hardware_utils.h" +#include "foc_utils.h" +#include "defaults.h" + +#include "Sensor.h" +#include "pid.h" +#include "lowpass_filter.h" + + +/** + * Motiron control type + */ +enum ControlType{ + voltage,//!< Torque control using voltage + velocity,//!< Velocity motion control + angle,//!< Position/angle motion control + velocity_openloop, + angle_openloop +}; + +/** + * FOC modulation type + */ +enum FOCModulationType{ + SinePWM, //!< Sinusoidal PWM modulation + SpaceVectorPWM //!< Space vector modulation method +}; + +/** + Generic motor class +*/ +class FOCMotor +{ + public: + /** + * Default constructor - setting all variabels to default values + */ + FOCMotor(); + + /** Motor hardware init function */ + virtual void init(long pwm_frequency)=0; + /** Motor disable function */ + virtual void disable()=0; + /** Motor enable function */ + virtual void enable()=0; + + /** + * Function linking a motor and a sensor + * + * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity + */ + void linkSensor(Sensor* sensor); + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + virtual int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW)=0; + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + virtual void loopFOC()=0; + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + virtual void move(float target = NOT_SET)=0; + + // State calculation methods + /** Shaft angle calculation in radians [rad] */ + float shaftAngle(); + /** + * Shaft angle calculation function in radian per second [rad/s] + * It implements low pass filtering + */ + float shaftVelocity(); + + // state variables + float target; //!< current target value - depends of the controller + float shaft_angle;//!< current motor angle + float shaft_velocity;//!< current motor velocity + float shaft_velocity_sp;//!< current target velocity + float shaft_angle_sp;//!< current target angle + float voltage_q;//!< current voltage u_q set + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform + + // motor configuration parameters + float voltage_power_supply;//!< Power supply voltage + float voltage_sensor_align;//!< sensor and motor align voltage parameter + float velocity_index_search;//!< target velocity for index search + int pole_pairs;//!< Motor pole pairs number + + // limiting variables + float voltage_limit; //!< Voltage limitting variable - global limit + float velocity_limit; //!< Velocity limitting variable - global limit + + float zero_electric_angle;//! _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} + + +// normalizing radian angle to [0,2PI] +float _normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} + +// Electrical angle calculation +float _electricalAngle(float shaft_angle, int pole_pairs) { + return (shaft_angle * pole_pairs); +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/foc_utils.h b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/foc_utils.h new file mode 100644 index 00000000..5ab34f42 --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/foc_utils.h @@ -0,0 +1,55 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + +// sign function +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + +// utility defines +#define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI 3.14159265359 +#define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + + +#define NOT_SET -12345.0 + +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _sin(float a); +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _cos(float a); + +/** + * normalizing radian angle to [0,2PI] + * @param angle - angle to be normalized + */ +float _normalizeAngle(float angle); + + +/** + * Electrical angle calculation + * + * @param shaft_angle - shaft angle of the motor + * @param pole_pairs - number of pole pairs + */ +float _electricalAngle(float shaft_angle, int pole_pairs); +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.cpp new file mode 100644 index 00000000..0d080bab --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.cpp @@ -0,0 +1,284 @@ +#include "hardware_utils.h" + +#if defined(ESP_H) // if ESP32 board +// empty motor slot +#define _EMPTY_SLOT -20 + +// structure containing motor slot configuration +// this library supports up to 4 motors +typedef struct { + int pinA; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; + mcpwm_io_signals_t mcpwm_c; +} bldc_motor_slots_t; +typedef struct { + int pin1A; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_1a; + mcpwm_io_signals_t mcpwm_1b; + mcpwm_io_signals_t mcpwm_2a; + mcpwm_io_signals_t mcpwm_2b; +} stepper_motor_slots_t; + +// define bldc motor slots array +bldc_motor_slots_t esp32_bldc_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B + }; + +// define stepper motor slots array +stepper_motor_slots_t esp32_stepper_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + }; + +// configuring high frequency pwm timer +// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller +void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ + + mcpwm_config_t pwm_config; + pwm_config.frequency = pwm_frequency; //frequency + pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% + pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + _delay(100); + + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); + mcpwm_num->clk_cfg.prescale = 0; + + mcpwm_num->timer[0].period.prescale = 4; + mcpwm_num->timer[1].period.prescale = 4; + mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + mcpwm_num->timer[0].period.period = 2048; + mcpwm_num->timer[1].period.period = 2048; + mcpwm_num->timer[2].period.period = 2048; + _delay(1); + mcpwm_num->timer[0].period.upmethod = 0; + mcpwm_num->timer[1].period.upmethod = 0; + mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 0; +} + +#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips +// set pwm frequency to 32KHz +void _pinHighFrequency(const int pin){ + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pin == 5 || pin == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pin == 9 || pin == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pin == 3 || pin == 11) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +} +#elif defined(_STM32_DEF_) // if stm chips +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); + analogWriteResolution(12); // resolution 12 bit 0 - 4096 +} +#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); +} +#endif + + +// function setting the high pwm frequency to the supplied pins +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); + _pinHighFrequency(pinC); + if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor + +#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards + if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor + +#elif defined(ESP_H) // if esp32 boards + if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency + + if(pinD == NOT_SET){ + bldc_motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_motor_slots[i].pinA = pinA; + m_slot = esp32_bldc_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + + }else{ + stepper_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_motor_slots[i].pin1A = pinA; + m_slot = esp32_stepper_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + } +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pinA, 4095.0*dc_a); + analogWrite(pinB, 4095.0*dc_b); + analogWrite(pinC, 4095.0*dc_c); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255*dc_a); + analogWrite(pinB, 255*dc_b); + analogWrite(pinC, 255*dc_c); +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pin1A, 4095.0*dc_1a); + analogWrite(pin1B, 4095.0*dc_1b); + analogWrite(pin2A, 4095.0*dc_2a); + analogWrite(pin2B, 4095.0*dc_2b); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255*dc_1a); + analogWrite(pin1B, 255*dc_1b); + analogWrite(pin2A, 255*dc_2a); + analogWrite(pin2B, 255*dc_2b); +#endif +} + + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.h b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.h new file mode 100644 index 00000000..f99c260a --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.h @@ -0,0 +1,72 @@ +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H + +#include "Arduino.h" +#include "foc_utils.h" + + +#if defined(ESP_H) // if esp32 boards + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +#endif + +/** + * High PWM frequency setting function + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc motor or pin1A stepper motor + * @param pinB pinB bldc motor or pin1B stepper motor + * @param pinC pinC bldc motor or pin2A stepper motor + * @param pinD pin2B stepper motor + */ +void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/lowpass_filter.cpp b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/lowpass_filter.cpp new file mode 100644 index 00000000..9bf4ab7a --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/lowpass_filter.cpp @@ -0,0 +1,25 @@ +#include "lowpass_filter.h" + +LowPassFilter::LowPassFilter(float time_constant) + : Tf(time_constant) + , y_prev(0.0f) +{ + timestamp_prev = _micros(); +} + + +float LowPassFilter::operator() (float x) +{ + unsigned long timestamp = _micros(); + float dt = (timestamp - timestamp_prev)*1e-6f; + + if (dt < 0.0f || dt > 0.5f) + dt = 1e-3f; + + float alpha = Tf/(Tf + dt); + float y = alpha*y_prev + (1.0f - alpha)*x; + + y_prev = y; + timestamp_prev = timestamp; + return y; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/lowpass_filter.h b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/lowpass_filter.h new file mode 100644 index 00000000..5a7619cf --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/lowpass_filter.h @@ -0,0 +1,29 @@ +#ifndef LOWPASS_FILTER_H +#define LOWPASS_FILTER_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + + +/** + * Low pass filter class + */ +class LowPassFilter +{ +public: + /** + * @param Tf - Low pass filter time constant + */ + LowPassFilter(float Tf); + ~LowPassFilter() = default; + + float operator() (float x); + float Tf; //!< Low pass filter time constant + +protected: + unsigned long timestamp_prev; //!< Last execution timestamp + float y_prev; //!< filtered value in previous execution step +}; + +#endif // LOWPASS_FILTER_H \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/pid.cpp b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/pid.cpp new file mode 100644 index 00000000..277e17ce --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/pid.cpp @@ -0,0 +1,56 @@ +#include "pid.h" + +PIDController::PIDController(float P, float I, float D, float ramp, float limit) + : P(P) + , I(I) + , D(D) + , output_ramp(ramp) // output derivative limit [volts/second] + , limit(limit) // output supply limit [volts] + , integral_prev(0.0) + , error_prev(0.0) + , output_prev(0.0) +{ + timestamp_prev = _micros()*1e-6; +} + +// PID controller function +float PIDController::operator() (float error){ + // calculate the time from the last call + unsigned long timestamp_now = _micros(); + float Ts = (timestamp_now - timestamp_prev) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = P * error_prev; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = integral_prev + I*Ts*0.5*(error + error_prev); + // antiwindup - limit the output voltage_q + integral = constrain(integral, -limit, limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = D*(error - error_prev)/Ts; + + // sum all the components + float output = proportional + integral + derivative; + // antiwindup - limit the output variable + output = constrain(output, -limit, limit); + + // limit the acceleration by ramping the output + float output_rate = (output - output_prev)/Ts; + if (output_rate > output_ramp) + output = output_prev + output_ramp*Ts; + else if (output_rate < -output_ramp) + output = output_prev - output_ramp*Ts; + + // saving for the next pass + integral_prev = integral; + output_prev = output; + error_prev = error; + timestamp_prev = timestamp_now; + return output; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/pid.h b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/pid.h new file mode 100644 index 00000000..7ee337c4 --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/pid.h @@ -0,0 +1,40 @@ +#ifndef PID_H +#define PID_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + +/** + * PID controller class + */ +class PIDController +{ +public: + /** + * + * @param P - Proportional gain + * @param I - Integral gain + * @param D - Derivative gain + * @param ramp - Maximum speed of change of the output value + * @param limit - Maximum output value + */ + PIDController(float P, float I, float D, float ramp, float limit); + ~PIDController() = default; + + float operator() (float error); + + float P; //!< Proportional gain + float I; //!< Integral gain + float D; //!< Derivative gain + float output_ramp; //!< Maximum speed of change of the output value + float limit; //!< Maximum output value + +protected: + float integral_prev; //!< last integral component value + float error_prev; //!< last tracking error value + float timestamp_prev; //!< Last execution timestamp + float output_prev; //!< last pid output value +}; + +#endif // PID_H \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_minimal_openloop/arduino_foc_minimal_openloop.ino b/minimal_project_examples/arduino_foc_stepper_openloop/arduino_foc_bldc_openloop.ino similarity index 66% rename from minimal_project_examples/arduino_foc_minimal_openloop/arduino_foc_minimal_openloop.ino rename to minimal_project_examples/arduino_foc_stepper_openloop/arduino_foc_bldc_openloop.ino index fdc3359a..2a0f0c81 100644 --- a/minimal_project_examples/arduino_foc_minimal_openloop/arduino_foc_minimal_openloop.ino +++ b/minimal_project_examples/arduino_foc_stepper_openloop/arduino_foc_bldc_openloop.ino @@ -1,38 +1,9 @@ #include "BLDCMotor.h" - -// DRV8302 pins connections -// don't forget to connect the common ground pin -#define INH_A 5 -#define INH_B 4 -#define INH_C 3 -#define INL_A 8 -#define INL_B 9 -#define INL_C 10 -#define EN_GATE 13 -#define M_PWM A0 -#define M_OC A1 -#define OC_ADJ A3 - - // motor instance -BLDCMotor motor = BLDCMotor(INH_A, INH_B, INH_C, INL_A, INL_B, INL_C, 11, EN_GATE); +StepperMotor motor = StepperMotor(10, 6, 5, 9, 50, 8); void setup() { - - // DRV8302 specific code - // M_OC - enable overcurrent protection - pinMode(M_OC,OUTPUT); - digitalWrite(M_OC,LOW); - // M_PWM - enable 3pwm mode - pinMode(M_PWM,OUTPUT); - digitalWrite(M_PWM,HIGH); - // OD_ADJ - set the maximum overcurrent limit possible - // Better option would be to use voltage divisor to set exact value - pinMode(OC_ADJ,OUTPUT); - digitalWrite(OC_ADJ,HIGH); - - // power supply voltage // default 12V diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/StepperMotor.cpp b/minimal_project_examples/arduino_foc_stepper_openloop/src/StepperMotor.cpp new file mode 100644 index 00000000..22ceb256 --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_openloop/src/StepperMotor.cpp @@ -0,0 +1,309 @@ +#include "StepperMotor.h" + +// StepperMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// - ph1A, ph1B - motor phase 1 pwm pins +// - ph2A, ph2B - motor phase 2 pwm pins +// - pp - pole pair number +// - enable pin - (optional input) +StepperMotor::StepperMotor(int ph1A, int ph1B, int ph2A, int ph2B, int pp, int en1, int en2) +: FOCMotor() +{ + // Pin initialization + pwm1A = ph1A; + pwm1B = ph1B; + pwm2A = ph2A; + pwm2B = ph2B; + pole_pairs = pp; + + // enable_pin pin + enable_pin1 = en1; + enable_pin2 = en2; +} + +// init hardware pins +void StepperMotor::init(long pwm_frequency) { + if(monitor_port) monitor_port->println("MOT: Init pins."); + // PWM pins + pinMode(pwm1A, OUTPUT); + pinMode(pwm1B, OUTPUT); + pinMode(pwm2A, OUTPUT); + pinMode(pwm2B, OUTPUT); + if ( enable_pin1 != NOT_SET ) pinMode(enable_pin1, OUTPUT); + if ( enable_pin2 != NOT_SET ) pinMode(enable_pin2, OUTPUT); + + if(monitor_port) monitor_port->println("MOT: PWM config."); + // Increase PWM frequency + // make silent + _setPwmFrequency(pwm_frequency, pwm1A, pwm1B, pwm2A, pwm2B); + + // sanity check for the voltage limit configuration + if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + + // update the controller limits + PID_velocity.limit = voltage_limit; + P_angle.limit = velocity_limit; + + _delay(500); + // enable motor + if(monitor_port) monitor_port->println("MOT: Enable."); + enable(); + _delay(500); + +} + + +// disable motor driver +void StepperMotor::disable() +{ + // disable the driver - if enable_pin pin available + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, LOW); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, LOW); + // set zero to PWM + setPwm(0, 0); +} +// enable motor driver +void StepperMotor::enable() +{ + // set zero to PWM + setPwm(0, 0); + // enable_pin the driver - if enable_pin pin available + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, HIGH); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, HIGH); + +} + + +/** + FOC functions +*/ +// FOC initialization function +int StepperMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } + if(monitor_port) monitor_port->println("MOT: Motor ready."); + + return exit_flag; +} +// Encoder alignment to electrical 0 angle +int StepperMotor::alignSensor() { + if(monitor_port) monitor_port->println("MOT: Align sensor."); + // align the electrical phases of the motor and sensor + // set angle -90 degrees + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } + + // let the motor stabilize for 2 sec + _delay(2000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0,0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int StepperMotor::absoluteZeroAlign() { + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0,0); + + // align absolute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = _normalizeAngle(_electricalAngle(zero_offset, pole_pairs)); + } + // return bool if zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void StepperMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); +} + +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function +// - if target is not set it uses motor.target value +void StepperMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; + // get angular velocity + shaft_velocity = shaftVelocity(); + // choose control loop + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = P_angle( shaft_angle_sp - shaft_angle ); + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // include velocity loop + shaft_velocity_sp = target; + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); + break; + } +} + + +// Method using FOC to set Uq to the motor at the optimal angle +// Function implementingSine PWM algorithms +// - space vector not implemented yet +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) +void StepperMotor::setPhaseVoltage(float Uq, float angle_el) { + // Sinusoidal PWM modulation + // Inverse Park transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle); + // Inverse park transform + Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; + Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + // set the voltages in hardware + setPwm(Ualpha,Ubeta); +} + + + +// Set voltage to the pwm pin +void StepperMotor::setPwm(float Ualpha, float Ubeta) { + float duty_cycle1A(0.0),duty_cycle1B(0.0),duty_cycle2A(0.0),duty_cycle2B(0.0); + // hardware specific writing + if( Ualpha > 0 ) + duty_cycle1B = constrain(abs(Ualpha)/voltage_power_supply,0,1); + else + duty_cycle1A = constrain(abs(Ualpha)/voltage_power_supply,0,1); + + if( Ubeta > 0 ) + duty_cycle2B = constrain(abs(Ubeta)/voltage_power_supply,0,1); + else + duty_cycle2A = constrain(abs(Ubeta)/voltage_power_supply,0,1); + // write to hardware + _writeDutyCycle(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, pwm1A, pwm1B, pwm2A, pwm2B); +} + +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void StepperMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle,pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void StepperMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle,pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/StepperMotor.h b/minimal_project_examples/arduino_foc_stepper_openloop/src/StepperMotor.h new file mode 100644 index 00000000..bf14e096 --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_openloop/src/StepperMotor.h @@ -0,0 +1,122 @@ +/** + * @file StepperMotor.h + * + */ + +#ifndef StepperMotor_h +#define StepperMotor_h + +#include "Arduino.h" +#include "common/FOCMotor.h" +#include "common/foc_utils.h" +#include "common/hardware_utils.h" +#include "common/Sensor.h" +#include "common/defaults.h" + +/** + Stepper Motor class +*/ +class StepperMotor: public FOCMotor +{ + public: + /** + StepperMotor class constructor + @param ph1A 1A phase pwm pin + @param ph1B 1B phase pwm pin + @param ph2A 2A phase pwm pin + @param ph2B 2B phase pwm pin + @param pp pole pair number - cpr counts per rotation number (cpm=ppm*4) + @param en1 enable pin phase 1 (optional input) + @param en2 enable pin phase 2 (optional input) + */ + StepperMotor(int ph1A,int ph1B,int ph2A,int ph2B,int pp, int en1 = NOT_SET, int en2 = NOT_SET); + + /** Motor hardware init function */ + void init(long pwm_frequency = NOT_SET) override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW) override; + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + void loopFOC() override; + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + void move(float target = NOT_SET) override; + + // hardware variables + int pwm1A; //!< phase 1A pwm pin number + int pwm1B; //!< phase 1B pwm pin number + int pwm2A; //!< phase 2A pwm pin number + int pwm2B; //!< phase 2B pwm pin number + int enable_pin1; //!< enable pin number phase 1 + int enable_pin2; //!< enable pin number phase 2 + + private: + + // FOC methods + /** + * Method using FOC to set Uq to the motor at the optimal angle + * Heart of the FOC algorithm + * + * @param Uq Current voltage in q axis to set to the motor + * @param angle_el current electrical angle of the motor + */ + void setPhaseVoltage(float Uq, float angle_el); + + /** Sensor alignment to electrical 0 angle of the motor */ + int alignSensor(); + /** Motor and sensor alignment to the sensors absolute 0 angle */ + int absoluteZeroAlign(); + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + * @param Uc phase C voltage + */ + void setPwm(float Ualpha, float Ubeta); + + // Open loop motion control + /** + * Function (iterative) generating open loop movement for target velocity + * it uses voltage_limit variable + * + * @param target_velocity - rad/s + */ + void velocityOpenloop(float target_velocity); + /** + * Function (iterative) generating open loop movement towards the target angle + * it uses voltage_limit and velocity_limit variables + * + * @param target_angle - rad + */ + void angleOpenloop(float target_angle); + // open loop variables + long open_loop_timestamp; +}; + + +#endif diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/FOCMotor.cpp b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/FOCMotor.cpp new file mode 100644 index 00000000..adecbeec --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/FOCMotor.cpp @@ -0,0 +1,245 @@ +#include "FOCMotor.h" + +/** + * Default constructor - setting all variabels to default values + */ +FOCMotor::FOCMotor() +{ + // Power supply voltage + voltage_power_supply = DEF_POWER_SUPPLY; + + // maximum angular velocity to be used for positioning + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = voltage_power_supply; + + // index search velocity + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; + + // electric angle of comthe zero angle + zero_electric_angle = 0; + + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + + // default target value + target = 0; + + //monitor_port + monitor_port = nullptr; + //sensor + sensor = nullptr; +} + + +/** + Sensor communication methods +*/ +void FOCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} +// shaft angle calculation +float FOCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return shaft_angle; + return sensor->getAngle(); +} +// shaft velocity calculation +float FOCMotor::shaftVelocity() { + // if no sensor linked return 0 + if(!sensor) return 0; + return LPF_velocity(sensor->getVelocity()); +} + + + + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void FOCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void FOCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity_openloop: + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle_openloop: + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int FOCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'D': // velocity D gain change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PID velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P angle| "); + break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + } + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("P: "); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("I: "); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); + break; + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("volt_ramp: "); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET) { + voltage_limit = value; + PID_velocity.limit = value; + } + if(monitor_port) monitor_port->println(voltage_limit); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("Tf: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("vel_limit: "); + if(!GET){ + velocity_limit = value; + P_angle.limit = value; + } + if(monitor_port) monitor_port->println(velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Control: "); + + if(GET){ // if get command + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + default: + if(monitor_port) monitor_port->println("open loop"); + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/FOCMotor.h b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/FOCMotor.h new file mode 100644 index 00000000..40f7f6d4 --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/FOCMotor.h @@ -0,0 +1,195 @@ +#ifndef FOCMOTOR_H +#define FOCMOTOR_H + +#include "Arduino.h" +#include "hardware_utils.h" +#include "foc_utils.h" +#include "defaults.h" + +#include "Sensor.h" +#include "pid.h" +#include "lowpass_filter.h" + + +/** + * Motiron control type + */ +enum ControlType{ + voltage,//!< Torque control using voltage + velocity,//!< Velocity motion control + angle,//!< Position/angle motion control + velocity_openloop, + angle_openloop +}; + +/** + * FOC modulation type + */ +enum FOCModulationType{ + SinePWM, //!< Sinusoidal PWM modulation + SpaceVectorPWM //!< Space vector modulation method +}; + +/** + Generic motor class +*/ +class FOCMotor +{ + public: + /** + * Default constructor - setting all variabels to default values + */ + FOCMotor(); + + /** Motor hardware init function */ + virtual void init(long pwm_frequency)=0; + /** Motor disable function */ + virtual void disable()=0; + /** Motor enable function */ + virtual void enable()=0; + + /** + * Function linking a motor and a sensor + * + * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity + */ + void linkSensor(Sensor* sensor); + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + virtual int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW)=0; + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + virtual void loopFOC()=0; + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + virtual void move(float target = NOT_SET)=0; + + // State calculation methods + /** Shaft angle calculation in radians [rad] */ + float shaftAngle(); + /** + * Shaft angle calculation function in radian per second [rad/s] + * It implements low pass filtering + */ + float shaftVelocity(); + + // state variables + float target; //!< current target value - depends of the controller + float shaft_angle;//!< current motor angle + float shaft_velocity;//!< current motor velocity + float shaft_velocity_sp;//!< current target velocity + float shaft_angle_sp;//!< current target angle + float voltage_q;//!< current voltage u_q set + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform + + // motor configuration parameters + float voltage_power_supply;//!< Power supply voltage + float voltage_sensor_align;//!< sensor and motor align voltage parameter + float velocity_index_search;//!< target velocity for index search + int pole_pairs;//!< Motor pole pairs number + + // limiting variables + float voltage_limit; //!< Voltage limitting variable - global limit + float velocity_limit; //!< Velocity limitting variable - global limit + + float zero_electric_angle;//! _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} + + +// normalizing radian angle to [0,2PI] +float _normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} + +// Electrical angle calculation +float _electricalAngle(float shaft_angle, int pole_pairs) { + return (shaft_angle * pole_pairs); +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/foc_utils.h b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/foc_utils.h new file mode 100644 index 00000000..5ab34f42 --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/foc_utils.h @@ -0,0 +1,55 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + +// sign function +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) + +// utility defines +#define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI 3.14159265359 +#define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + + +#define NOT_SET -12345.0 + +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _sin(float a); +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _cos(float a); + +/** + * normalizing radian angle to [0,2PI] + * @param angle - angle to be normalized + */ +float _normalizeAngle(float angle); + + +/** + * Electrical angle calculation + * + * @param shaft_angle - shaft angle of the motor + * @param pole_pairs - number of pole pairs + */ +float _electricalAngle(float shaft_angle, int pole_pairs); +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.cpp new file mode 100644 index 00000000..0d080bab --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.cpp @@ -0,0 +1,284 @@ +#include "hardware_utils.h" + +#if defined(ESP_H) // if ESP32 board +// empty motor slot +#define _EMPTY_SLOT -20 + +// structure containing motor slot configuration +// this library supports up to 4 motors +typedef struct { + int pinA; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; + mcpwm_io_signals_t mcpwm_c; +} bldc_motor_slots_t; +typedef struct { + int pin1A; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_1a; + mcpwm_io_signals_t mcpwm_1b; + mcpwm_io_signals_t mcpwm_2a; + mcpwm_io_signals_t mcpwm_2b; +} stepper_motor_slots_t; + +// define bldc motor slots array +bldc_motor_slots_t esp32_bldc_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B + }; + +// define stepper motor slots array +stepper_motor_slots_t esp32_stepper_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + }; + +// configuring high frequency pwm timer +// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller +void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ + + mcpwm_config_t pwm_config; + pwm_config.frequency = pwm_frequency; //frequency + pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% + pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + _delay(100); + + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); + mcpwm_num->clk_cfg.prescale = 0; + + mcpwm_num->timer[0].period.prescale = 4; + mcpwm_num->timer[1].period.prescale = 4; + mcpwm_num->timer[2].period.prescale = 4; + _delay(1); + mcpwm_num->timer[0].period.period = 2048; + mcpwm_num->timer[1].period.period = 2048; + mcpwm_num->timer[2].period.period = 2048; + _delay(1); + mcpwm_num->timer[0].period.upmethod = 0; + mcpwm_num->timer[1].period.upmethod = 0; + mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); + + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 0; +} + +#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips +// set pwm frequency to 32KHz +void _pinHighFrequency(const int pin){ + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pin == 5 || pin == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pin == 9 || pin == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pin == 3 || pin == 11) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +} +#elif defined(_STM32_DEF_) // if stm chips +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); + analogWriteResolution(12); // resolution 12 bit 0 - 4096 +} +#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(freq); +} +#endif + + +// function setting the high pwm frequency to the supplied pins +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); + _pinHighFrequency(pinC); + if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor + +#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards + if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor + +#elif defined(ESP_H) // if esp32 boards + if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency + + if(pinD == NOT_SET){ + bldc_motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_motor_slots[i].pinA = pinA; + m_slot = esp32_bldc_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + + }else{ + stepper_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_motor_slots[i].pin1A = pinA; + m_slot = esp32_stepper_motor_slots[i]; + break; + } + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + } +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; + esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pinA, 4095.0*dc_a); + analogWrite(pinB, 4095.0*dc_b); + analogWrite(pinC, 4095.0*dc_c); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255*dc_a); + analogWrite(pinB, 255*dc_b); + analogWrite(pinC, 255*dc_c); +#endif +} + +// function setting the pwm duty cycle to the hardware +//- hardware speciffic +// +// Arduino and STM32 devices use analogWrite() +// ESP32 uses MCPWM +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ +#if defined(ESP_H) // if ESP32 boards + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,2047] + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; + esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; + break; + } + } +#elif defined(_STM32_DEF_) // STM32 devices + // transform duty cycle from [0,1] to [0,4095] + analogWrite(pin1A, 4095.0*dc_1a); + analogWrite(pin1B, 4095.0*dc_1b); + analogWrite(pin2A, 4095.0*dc_2a); + analogWrite(pin2B, 4095.0*dc_2b); +#else // Arduino & Teensy + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255*dc_1a); + analogWrite(pin1B, 255*dc_1b); + analogWrite(pin2A, 255*dc_2a); + analogWrite(pin2B, 255*dc_2b); +#endif +} + + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.h b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.h new file mode 100644 index 00000000..f99c260a --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.h @@ -0,0 +1,72 @@ +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H + +#include "Arduino.h" +#include "foc_utils.h" + + +#if defined(ESP_H) // if esp32 boards + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +#endif + +/** + * High PWM frequency setting function + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc motor or pin1A stepper motor + * @param pinB pinB bldc motor or pin1B stepper motor + * @param pinC pinC bldc motor or pin2A stepper motor + * @param pinD pin2B stepper motor + */ +void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/lowpass_filter.cpp b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/lowpass_filter.cpp new file mode 100644 index 00000000..9bf4ab7a --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/lowpass_filter.cpp @@ -0,0 +1,25 @@ +#include "lowpass_filter.h" + +LowPassFilter::LowPassFilter(float time_constant) + : Tf(time_constant) + , y_prev(0.0f) +{ + timestamp_prev = _micros(); +} + + +float LowPassFilter::operator() (float x) +{ + unsigned long timestamp = _micros(); + float dt = (timestamp - timestamp_prev)*1e-6f; + + if (dt < 0.0f || dt > 0.5f) + dt = 1e-3f; + + float alpha = Tf/(Tf + dt); + float y = alpha*y_prev + (1.0f - alpha)*x; + + y_prev = y; + timestamp_prev = timestamp; + return y; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/lowpass_filter.h b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/lowpass_filter.h new file mode 100644 index 00000000..5a7619cf --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/lowpass_filter.h @@ -0,0 +1,29 @@ +#ifndef LOWPASS_FILTER_H +#define LOWPASS_FILTER_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + + +/** + * Low pass filter class + */ +class LowPassFilter +{ +public: + /** + * @param Tf - Low pass filter time constant + */ + LowPassFilter(float Tf); + ~LowPassFilter() = default; + + float operator() (float x); + float Tf; //!< Low pass filter time constant + +protected: + unsigned long timestamp_prev; //!< Last execution timestamp + float y_prev; //!< filtered value in previous execution step +}; + +#endif // LOWPASS_FILTER_H \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/pid.cpp b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/pid.cpp new file mode 100644 index 00000000..277e17ce --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/pid.cpp @@ -0,0 +1,56 @@ +#include "pid.h" + +PIDController::PIDController(float P, float I, float D, float ramp, float limit) + : P(P) + , I(I) + , D(D) + , output_ramp(ramp) // output derivative limit [volts/second] + , limit(limit) // output supply limit [volts] + , integral_prev(0.0) + , error_prev(0.0) + , output_prev(0.0) +{ + timestamp_prev = _micros()*1e-6; +} + +// PID controller function +float PIDController::operator() (float error){ + // calculate the time from the last call + unsigned long timestamp_now = _micros(); + float Ts = (timestamp_now - timestamp_prev) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = P * error_prev; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = integral_prev + I*Ts*0.5*(error + error_prev); + // antiwindup - limit the output voltage_q + integral = constrain(integral, -limit, limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = D*(error - error_prev)/Ts; + + // sum all the components + float output = proportional + integral + derivative; + // antiwindup - limit the output variable + output = constrain(output, -limit, limit); + + // limit the acceleration by ramping the output + float output_rate = (output - output_prev)/Ts; + if (output_rate > output_ramp) + output = output_prev + output_ramp*Ts; + else if (output_rate < -output_ramp) + output = output_prev - output_ramp*Ts; + + // saving for the next pass + integral_prev = integral; + output_prev = output; + error_prev = error; + timestamp_prev = timestamp_now; + return output; +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/pid.h b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/pid.h new file mode 100644 index 00000000..7ee337c4 --- /dev/null +++ b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/pid.h @@ -0,0 +1,40 @@ +#ifndef PID_H +#define PID_H + + +#include "hardware_utils.h" +#include "foc_utils.h" + +/** + * PID controller class + */ +class PIDController +{ +public: + /** + * + * @param P - Proportional gain + * @param I - Integral gain + * @param D - Derivative gain + * @param ramp - Maximum speed of change of the output value + * @param limit - Maximum output value + */ + PIDController(float P, float I, float D, float ramp, float limit); + ~PIDController() = default; + + float operator() (float error); + + float P; //!< Proportional gain + float I; //!< Integral gain + float D; //!< Derivative gain + float output_ramp; //!< Maximum speed of change of the output value + float limit; //!< Maximum output value + +protected: + float integral_prev; //!< last integral component value + float error_prev; //!< last tracking error value + float timestamp_prev; //!< Last execution timestamp + float output_prev; //!< last pid output value +}; + +#endif // PID_H \ No newline at end of file From 180332656ed96eb7f457056d728273b5b1e42c44 Mon Sep 17 00:00:00 2001 From: askuric Date: Mon, 19 Oct 2020 23:19:49 +0200 Subject: [PATCH 60/65] FEAT v1.6.0 added --- .../arduino_foc_bldc_magnetic_spi.ino | 5 ++--- .../arduino_foc_stepper_magnetic_i2c.ino | 4 ++-- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/arduino_foc_bldc_magnetic_spi.ino b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/arduino_foc_bldc_magnetic_spi.ino index 31366bed..3a36fc43 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/arduino_foc_bldc_magnetic_spi.ino +++ b/minimal_project_examples/arduino_foc_bldc_magnetic_spi/arduino_foc_bldc_magnetic_spi.ino @@ -37,12 +37,11 @@ * */ #include "src/BLDCMotor.h" -#include "src/MagneticSensorI2C.h" +#include "src/MagneticSensorSPI.h" // SPI magnetic sensor instance -//MagneticSensorSPI sensor = MagneticSensorSPI(10, 14, 0x3FFF); +MagneticSensorSPI sensor = MagneticSensorSPI(10, 14, 0x3FFF); -MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0x0E, 4); // motor instance BLDCMotor motor = BLDCMotor(9, 5, 6, 11, 7); diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/arduino_foc_stepper_magnetic_i2c.ino b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/arduino_foc_stepper_magnetic_i2c.ino index 3d3216d2..adcba2c5 100644 --- a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/arduino_foc_stepper_magnetic_i2c.ino +++ b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/arduino_foc_stepper_magnetic_i2c.ino @@ -42,8 +42,8 @@ // motor instance StepperMotor motor = StepperMotor(10, 6, 5, 9, 50, 8); -// motor instance -BLDCMotor motor = BLDCMotor(9, 5, 6, 11, 7); +// I2C magnetic sensor instance +MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0x0E, 4); void setup() { From 168b66f5b313ed0af038318fb756795a6d6ff34d Mon Sep 17 00:00:00 2001 From: askuric Date: Mon, 19 Oct 2020 23:29:04 +0200 Subject: [PATCH 61/65] FEAT v1.6.0 fix stepper openloop --- ...o_foc_bldc_openloop.ino => arduino_foc_stepper_openloop.ino} | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) rename minimal_project_examples/arduino_foc_stepper_openloop/{arduino_foc_bldc_openloop.ino => arduino_foc_stepper_openloop.ino} (98%) diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/arduino_foc_bldc_openloop.ino b/minimal_project_examples/arduino_foc_stepper_openloop/arduino_foc_stepper_openloop.ino similarity index 98% rename from minimal_project_examples/arduino_foc_stepper_openloop/arduino_foc_bldc_openloop.ino rename to minimal_project_examples/arduino_foc_stepper_openloop/arduino_foc_stepper_openloop.ino index 2a0f0c81..080f5469 100644 --- a/minimal_project_examples/arduino_foc_stepper_openloop/arduino_foc_bldc_openloop.ino +++ b/minimal_project_examples/arduino_foc_stepper_openloop/arduino_foc_stepper_openloop.ino @@ -1,4 +1,4 @@ -#include "BLDCMotor.h" +#include "src/StepperMotor.h" // motor instance StepperMotor motor = StepperMotor(10, 6, 5, 9, 50, 8); From e86c1997c1da97472d4951be49d744a02c8484f7 Mon Sep 17 00:00:00 2001 From: Antun Skuric <36178713+askuric@users.noreply.github.com> Date: Tue, 20 Oct 2020 10:20:25 +0200 Subject: [PATCH 62/65] Update README.md --- README.md | 4 ---- 1 file changed, 4 deletions(-) diff --git a/README.md b/README.md index 1df71eaa..16f86cd9 100644 --- a/README.md +++ b/README.md @@ -70,10 +70,6 @@ Creating your own minimal project version is very simple and is done in four ste git clone -b minimal https://github.com/askuric/Arduino-FOC.git ``` -After this step you will be able to open the example projects directly with Arduino IDE. This code is completely independent and you can run it as any other Arduino Sketch without the need for any libraries. - -> **BEWARE** In some cases this minimal version of the code will produce conflicts with the *Simple FOC* library if it is installed through Arduino library manager. So you might need to uninstall the library to run minimal projects. - ## Step 1. Creating the Arduino project Open a directory you want to use as your arduino project directory `my_arduino_project` and create `my_arduino_project.ino` file. After this you create `src` folder in this directory and copy the folder named `common` from the `library_source` folder. Your project directory should now have structure: From c1509d088f58ea8debaddf08ed2e929f97403515 Mon Sep 17 00:00:00 2001 From: askuric Date: Thu, 17 Dec 2020 10:51:32 +0100 Subject: [PATCH 63/65] init v2.0.2 --- library_source/BLDCMotor.cpp | 179 +++++++---- library_source/BLDCMotor.h | 60 ++-- library_source/HallSensor.cpp | 186 ----------- library_source/SimpleFOC.h | 67 ++-- library_source/StepperMotor.cpp | 101 +++--- library_source/StepperMotor.h | 53 ++-- .../common/base_classes/BLDCDriver.h | 28 ++ .../common/{ => base_classes}/FOCMotor.cpp | 10 +- .../common/base_classes}/FOCMotor.h | 24 +- .../common/{ => base_classes}/Sensor.h | 0 .../common/base_classes/StepperDriver.h | 27 ++ library_source/common/foc_utils.h | 2 +- library_source/common/hardware_utils.cpp | 284 ----------------- library_source/common/hardware_utils.h | 72 ----- library_source/common/lowpass_filter.h | 2 +- library_source/common/pid.cpp | 6 +- library_source/common/pid.h | 2 +- library_source/common/time_utils.cpp | 31 ++ library_source/common/time_utils.h | 22 ++ library_source/drivers/BLDCDriver3PWM.cpp | 70 +++++ library_source/drivers/BLDCDriver3PWM.h | 52 +++ library_source/drivers/BLDCDriver6PWM.cpp | 78 +++++ library_source/drivers/BLDCDriver6PWM.h | 57 ++++ library_source/drivers/StepperDriver4PWM.cpp | 79 +++++ library_source/drivers/StepperDriver4PWM.h | 55 ++++ library_source/drivers/hardware_api.h | 100 ++++++ .../hardware_specific/atmega328_mcu.cpp | 133 ++++++++ .../drivers/hardware_specific/esp32_mcu.cpp | 296 ++++++++++++++++++ .../drivers/hardware_specific/generic_mcu.cpp | 68 ++++ .../drivers/hardware_specific/stm32_mcu.cpp | 291 +++++++++++++++++ .../drivers/hardware_specific/teensy_mcu.cpp | 71 +++++ library_source/{ => sensors}/Encoder.cpp | 0 library_source/{ => sensors}/Encoder.h | 6 +- library_source/sensors/HallSensor.cpp | 161 ++++++++++ library_source/{ => sensors}/HallSensor.h | 34 +- .../{ => sensors}/MagneticSensorAnalog.cpp | 0 .../{ => sensors}/MagneticSensorAnalog.h | 6 +- .../sensors}/MagneticSensorI2C.cpp | 85 +++-- .../sensors}/MagneticSensorI2C.h | 23 +- .../{ => sensors}/MagneticSensorSPI.cpp | 31 +- .../{ => sensors}/MagneticSensorSPI.h | 11 +- .../src/common/hardware_utils.cpp | 284 ----------------- .../src/common/hardware_utils.h | 72 ----- .../arduino_foc_bldc_hall/src/HallSensor.cpp | 186 ----------- .../src/common/hardware_utils.cpp | 284 ----------------- .../src/common/hardware_utils.h | 72 ----- .../src/common/hardware_utils.cpp | 284 ----------------- .../src/common/hardware_utils.h | 72 ----- .../src/common/FOCMotor.cpp | 245 --------------- .../src/common/FOCMotor.h | 195 ------------ .../src/common/hardware_utils.cpp | 284 ----------------- .../src/common/hardware_utils.h | 72 ----- .../atmega328_bldc_encoder.ino} | 30 +- .../src/BLDCMotor.cpp | 179 +++++++---- .../src/BLDCMotor.h | 60 ++-- .../src/common/base_classes/BLDCDriver.h | 28 ++ .../src/common/base_classes}/FOCMotor.cpp | 10 +- .../src/common/base_classes}/FOCMotor.h | 24 +- .../src/common/base_classes}/Sensor.h | 0 .../src/common/base_classes/StepperDriver.h | 27 ++ .../src/common/defaults.h | 0 .../src/common/foc_utils.cpp | 0 .../src/common/foc_utils.h | 2 +- .../src/common/lowpass_filter.cpp | 0 .../src/common/lowpass_filter.h | 2 +- .../src/common/pid.cpp | 6 +- .../src/common/pid.h | 2 +- .../src/common/time_utils.cpp | 31 ++ .../src/common/time_utils.h | 22 ++ .../src/drivers/BLDCDriver3PWM.cpp | 70 +++++ .../src/drivers/BLDCDriver3PWM.h | 52 +++ .../src/drivers/hardware_api.h | 100 ++++++ .../hardware_specific/atmega328_mcu.cpp | 133 ++++++++ .../drivers/hardware_specific/esp32_mcu.cpp | 296 ++++++++++++++++++ .../drivers/hardware_specific/generic_mcu.cpp | 68 ++++ .../drivers/hardware_specific/stm32_mcu.cpp | 291 +++++++++++++++++ .../drivers/hardware_specific/teensy_mcu.cpp | 71 +++++ .../src/sensors}/Encoder.cpp | 0 .../src/sensors}/Encoder.h | 6 +- .../atmega328_bldc_magnetic_i2c.ino} | 20 +- .../src/BLDCMotor.cpp | 179 +++++++---- .../src/BLDCMotor.h | 60 ++-- .../src/common/base_classes/BLDCDriver.h | 28 ++ .../src/common/base_classes}/FOCMotor.cpp | 10 +- .../src/common/base_classes}/FOCMotor.h | 24 +- .../src/common/base_classes}/Sensor.h | 0 .../src/common/base_classes/StepperDriver.h | 27 ++ .../src/common/defaults.h | 0 .../src/common/foc_utils.cpp | 0 .../src/common/foc_utils.h | 2 +- .../src/common/lowpass_filter.cpp | 0 .../src/common/lowpass_filter.h | 2 +- .../src/common/pid.cpp | 6 +- .../src/common/pid.h | 2 +- .../src/common/time_utils.cpp | 31 ++ .../src/common/time_utils.h | 22 ++ .../src/drivers/BLDCDriver3PWM.cpp | 70 +++++ .../src/drivers/BLDCDriver3PWM.h | 52 +++ .../src/drivers/hardware_api.h | 100 ++++++ .../hardware_specific/atmega328_mcu.cpp | 133 ++++++++ .../drivers/hardware_specific/generic_mcu.cpp | 68 ++++ .../src/sensors}/MagneticSensorI2C.cpp | 85 +++-- .../src/sensors}/MagneticSensorI2C.h | 23 +- .../atmega328_bldc_openloop.ino} | 49 +-- .../src/BLDCMotor.cpp | 179 +++++++---- .../src/BLDCMotor.h | 60 ++-- .../src/common/base_classes/BLDCDriver.h | 28 ++ .../src/common/base_classes}/FOCMotor.cpp | 10 +- .../src/common/base_classes}/FOCMotor.h | 24 +- .../src/common/base_classes}/Sensor.h | 0 .../src/common/base_classes/StepperDriver.h | 27 ++ .../src/common/defaults.h | 0 .../src/common/foc_utils.cpp | 0 .../src/common/foc_utils.h | 2 +- .../src/common/lowpass_filter.cpp | 0 .../src/common/lowpass_filter.h | 2 +- .../src/common/pid.cpp | 6 +- .../src/common/pid.h | 2 +- .../src/common/time_utils.cpp | 31 ++ .../src/common/time_utils.h | 22 ++ .../src/drivers/BLDCDriver3PWM.cpp | 70 +++++ .../src/drivers/BLDCDriver3PWM.h | 52 +++ .../src/drivers/hardware_api.h | 100 ++++++ .../hardware_specific/atmega328_mcu.cpp | 133 ++++++++ .../drivers/hardware_specific/esp32_mcu.cpp | 296 ++++++++++++++++++ .../drivers/hardware_specific/generic_mcu.cpp | 68 ++++ .../drivers/hardware_specific/stm32_mcu.cpp | 291 +++++++++++++++++ .../drivers/hardware_specific/teensy_mcu.cpp | 71 +++++ .../atmega328_driver_standalone.ino | 32 ++ .../src/common/base_classes/BLDCDriver.h | 28 ++ .../src/common/base_classes/FOCMotor.cpp | 241 ++++++++++++++ .../src/common/base_classes/FOCMotor.h | 197 ++++++++++++ .../src/common/base_classes}/Sensor.h | 0 .../src/common/base_classes/StepperDriver.h | 27 ++ .../src/common/defaults.h | 0 .../src/common/foc_utils.cpp | 0 .../src/common/foc_utils.h | 2 +- .../src/common/lowpass_filter.cpp | 0 .../src/common/lowpass_filter.h | 2 +- .../src/common/pid.cpp | 6 +- .../src/common/pid.h | 2 +- .../src/common/time_utils.cpp | 31 ++ .../src/common/time_utils.h | 22 ++ .../src/drivers/BLDCDriver3PWM.cpp | 70 +++++ .../src/drivers/BLDCDriver3PWM.h | 52 +++ .../src/drivers/hardware_api.h | 100 ++++++ .../hardware_specific/atmega328_mcu.cpp | 133 ++++++++ .../drivers/hardware_specific/esp32_mcu.cpp | 296 ++++++++++++++++++ .../drivers/hardware_specific/generic_mcu.cpp | 68 ++++ .../drivers/hardware_specific/stm32_mcu.cpp | 291 +++++++++++++++++ .../drivers/hardware_specific/teensy_mcu.cpp | 71 +++++ .../src/BLDCMotor.cpp | 179 +++++++---- .../src/BLDCMotor.h | 60 ++-- .../src/common/base_classes/BLDCDriver.h | 28 ++ .../src/common/base_classes/FOCMotor.cpp | 241 ++++++++++++++ .../src/common/base_classes/FOCMotor.h | 197 ++++++++++++ .../src/common/base_classes/Sensor.h | 59 ++++ .../src/common/base_classes/StepperDriver.h | 27 ++ .../stm32_bldc_hall/src/common/defaults.h | 18 ++ .../stm32_bldc_hall/src/common/foc_utils.cpp | 54 ++++ .../stm32_bldc_hall/src/common/foc_utils.h | 55 ++++ .../src/common/lowpass_filter.cpp | 25 ++ .../src/common/lowpass_filter.h | 29 ++ .../stm32_bldc_hall/src/common/pid.cpp | 56 ++++ .../stm32_bldc_hall/src/common/pid.h | 40 +++ .../stm32_bldc_hall/src/common/time_utils.cpp | 31 ++ .../stm32_bldc_hall/src/common/time_utils.h | 22 ++ .../src/drivers/BLDCDriver6PWM.cpp | 78 +++++ .../src/drivers/BLDCDriver6PWM.h | 57 ++++ .../src/drivers/hardware_api.h | 100 ++++++ .../drivers/hardware_specific/stm32_mcu.cpp | 291 +++++++++++++++++ .../src/sensors/HallSensor.cpp | 161 ++++++++++ .../src/sensors}/HallSensor.h | 34 +- .../stm32_bldc_hall.ino} | 31 +- 174 files changed, 8918 insertions(+), 3516 deletions(-) delete mode 100644 library_source/HallSensor.cpp create mode 100644 library_source/common/base_classes/BLDCDriver.h rename library_source/common/{ => base_classes}/FOCMotor.cpp (98%) rename {minimal_project_examples/arduino_foc_bldc_encoder/src/common => library_source/common/base_classes}/FOCMotor.h (93%) rename library_source/common/{ => base_classes}/Sensor.h (100%) create mode 100644 library_source/common/base_classes/StepperDriver.h delete mode 100644 library_source/common/hardware_utils.cpp delete mode 100644 library_source/common/hardware_utils.h create mode 100644 library_source/common/time_utils.cpp create mode 100644 library_source/common/time_utils.h create mode 100644 library_source/drivers/BLDCDriver3PWM.cpp create mode 100644 library_source/drivers/BLDCDriver3PWM.h create mode 100644 library_source/drivers/BLDCDriver6PWM.cpp create mode 100644 library_source/drivers/BLDCDriver6PWM.h create mode 100644 library_source/drivers/StepperDriver4PWM.cpp create mode 100644 library_source/drivers/StepperDriver4PWM.h create mode 100644 library_source/drivers/hardware_api.h create mode 100644 library_source/drivers/hardware_specific/atmega328_mcu.cpp create mode 100644 library_source/drivers/hardware_specific/esp32_mcu.cpp create mode 100644 library_source/drivers/hardware_specific/generic_mcu.cpp create mode 100644 library_source/drivers/hardware_specific/stm32_mcu.cpp create mode 100644 library_source/drivers/hardware_specific/teensy_mcu.cpp rename library_source/{ => sensors}/Encoder.cpp (100%) rename library_source/{ => sensors}/Encoder.h (96%) create mode 100644 library_source/sensors/HallSensor.cpp rename library_source/{ => sensors}/HallSensor.h (75%) rename library_source/{ => sensors}/MagneticSensorAnalog.cpp (100%) rename library_source/{ => sensors}/MagneticSensorAnalog.h (95%) rename {minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src => library_source/sensors}/MagneticSensorI2C.cpp (79%) rename {minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src => library_source/sensors}/MagneticSensorI2C.h (88%) rename library_source/{ => sensors}/MagneticSensorSPI.cpp (93%) rename library_source/{ => sensors}/MagneticSensorSPI.h (94%) delete mode 100644 minimal_project_examples/arduino_foc_bldc_encoder/src/common/hardware_utils.cpp delete mode 100644 minimal_project_examples/arduino_foc_bldc_encoder/src/common/hardware_utils.h delete mode 100644 minimal_project_examples/arduino_foc_bldc_hall/src/HallSensor.cpp delete mode 100644 minimal_project_examples/arduino_foc_bldc_hall/src/common/hardware_utils.cpp delete mode 100644 minimal_project_examples/arduino_foc_bldc_hall/src/common/hardware_utils.h delete mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.cpp delete mode 100644 minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.h delete mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.cpp delete mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.h delete mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/common/hardware_utils.cpp delete mode 100644 minimal_project_examples/arduino_foc_bldc_openloop/src/common/hardware_utils.h rename minimal_project_examples/{arduino_foc_bldc_encoder/arduino_foc_bldc_encoder.ino => atmega328_bldc_encoder/atmega328_bldc_encoder.ino} (87%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_i2c => atmega328_bldc_encoder}/src/BLDCMotor.cpp (68%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_i2c => atmega328_bldc_encoder}/src/BLDCMotor.h (71%) create mode 100644 minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/BLDCDriver.h rename minimal_project_examples/{arduino_foc_bldc_hall/src/common => atmega328_bldc_encoder/src/common/base_classes}/FOCMotor.cpp (98%) rename {library_source/common => minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes}/FOCMotor.h (93%) rename minimal_project_examples/{arduino_foc_bldc_encoder/src/common => atmega328_bldc_encoder/src/common/base_classes}/Sensor.h (100%) create mode 100644 minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/StepperDriver.h rename minimal_project_examples/{arduino_foc_bldc_encoder => atmega328_bldc_encoder}/src/common/defaults.h (100%) rename minimal_project_examples/{arduino_foc_bldc_encoder => atmega328_bldc_encoder}/src/common/foc_utils.cpp (100%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_i2c => atmega328_bldc_encoder}/src/common/foc_utils.h (94%) rename minimal_project_examples/{arduino_foc_bldc_encoder => atmega328_bldc_encoder}/src/common/lowpass_filter.cpp (100%) rename minimal_project_examples/{arduino_foc_bldc_encoder => atmega328_bldc_encoder}/src/common/lowpass_filter.h (94%) rename minimal_project_examples/{arduino_foc_bldc_encoder => atmega328_bldc_encoder}/src/common/pid.cpp (92%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_i2c => atmega328_bldc_encoder}/src/common/pid.h (97%) create mode 100644 minimal_project_examples/atmega328_bldc_encoder/src/common/time_utils.cpp create mode 100644 minimal_project_examples/atmega328_bldc_encoder/src/common/time_utils.h create mode 100644 minimal_project_examples/atmega328_bldc_encoder/src/drivers/BLDCDriver3PWM.cpp create mode 100644 minimal_project_examples/atmega328_bldc_encoder/src/drivers/BLDCDriver3PWM.h create mode 100644 minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_api.h create mode 100644 minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/atmega328_mcu.cpp create mode 100644 minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/esp32_mcu.cpp create mode 100644 minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/generic_mcu.cpp create mode 100644 minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/stm32_mcu.cpp create mode 100644 minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/teensy_mcu.cpp rename minimal_project_examples/{arduino_foc_bldc_encoder/src => atmega328_bldc_encoder/src/sensors}/Encoder.cpp (100%) rename minimal_project_examples/{arduino_foc_bldc_encoder/src => atmega328_bldc_encoder/src/sensors}/Encoder.h (96%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_i2c/arduino_foc_bldc_magnetic_i2c.ino => atmega328_bldc_magnetic_i2c/atmega328_bldc_magnetic_i2c.ino} (91%) rename minimal_project_examples/{arduino_foc_bldc_openloop => atmega328_bldc_magnetic_i2c}/src/BLDCMotor.cpp (68%) rename minimal_project_examples/{arduino_foc_bldc_encoder => atmega328_bldc_magnetic_i2c}/src/BLDCMotor.h (71%) create mode 100644 minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/BLDCDriver.h rename minimal_project_examples/{arduino_foc_bldc_encoder/src/common => atmega328_bldc_magnetic_i2c/src/common/base_classes}/FOCMotor.cpp (98%) rename minimal_project_examples/{arduino_foc_bldc_hall/src/common => atmega328_bldc_magnetic_i2c/src/common/base_classes}/FOCMotor.h (93%) rename minimal_project_examples/{arduino_foc_bldc_hall/src/common => atmega328_bldc_magnetic_i2c/src/common/base_classes}/Sensor.h (100%) create mode 100644 minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/StepperDriver.h rename minimal_project_examples/{arduino_foc_bldc_hall => atmega328_bldc_magnetic_i2c}/src/common/defaults.h (100%) rename minimal_project_examples/{arduino_foc_bldc_hall => atmega328_bldc_magnetic_i2c}/src/common/foc_utils.cpp (100%) rename minimal_project_examples/{arduino_foc_bldc_encoder => atmega328_bldc_magnetic_i2c}/src/common/foc_utils.h (94%) rename minimal_project_examples/{arduino_foc_bldc_hall => atmega328_bldc_magnetic_i2c}/src/common/lowpass_filter.cpp (100%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_i2c => atmega328_bldc_magnetic_i2c}/src/common/lowpass_filter.h (94%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_i2c => atmega328_bldc_magnetic_i2c}/src/common/pid.cpp (92%) rename minimal_project_examples/{arduino_foc_bldc_openloop => atmega328_bldc_magnetic_i2c}/src/common/pid.h (97%) create mode 100644 minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/time_utils.cpp create mode 100644 minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/time_utils.h create mode 100644 minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/BLDCDriver3PWM.cpp create mode 100644 minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/BLDCDriver3PWM.h create mode 100644 minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_api.h create mode 100644 minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/atmega328_mcu.cpp create mode 100644 minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/generic_mcu.cpp rename {library_source => minimal_project_examples/atmega328_bldc_magnetic_i2c/src/sensors}/MagneticSensorI2C.cpp (79%) rename {library_source => minimal_project_examples/atmega328_bldc_magnetic_i2c/src/sensors}/MagneticSensorI2C.h (88%) rename minimal_project_examples/{arduino_foc_bldc_openloop/arduino_foc_bldc_openloop.ino => atmega328_bldc_openloop/atmega328_bldc_openloop.ino} (54%) rename minimal_project_examples/{arduino_foc_bldc_hall => atmega328_bldc_openloop}/src/BLDCMotor.cpp (68%) rename minimal_project_examples/{arduino_foc_bldc_hall => atmega328_bldc_openloop}/src/BLDCMotor.h (71%) create mode 100644 minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/BLDCDriver.h rename minimal_project_examples/{arduino_foc_bldc_magnetic_i2c/src/common => atmega328_bldc_openloop/src/common/base_classes}/FOCMotor.cpp (98%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_i2c/src/common => atmega328_bldc_openloop/src/common/base_classes}/FOCMotor.h (93%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_i2c/src/common => atmega328_bldc_openloop/src/common/base_classes}/Sensor.h (100%) create mode 100644 minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/StepperDriver.h rename minimal_project_examples/{arduino_foc_bldc_magnetic_i2c => atmega328_bldc_openloop}/src/common/defaults.h (100%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_i2c => atmega328_bldc_openloop}/src/common/foc_utils.cpp (100%) rename minimal_project_examples/{arduino_foc_bldc_openloop => atmega328_bldc_openloop}/src/common/foc_utils.h (94%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_i2c => atmega328_bldc_openloop}/src/common/lowpass_filter.cpp (100%) rename minimal_project_examples/{arduino_foc_bldc_hall => atmega328_bldc_openloop}/src/common/lowpass_filter.h (94%) rename minimal_project_examples/{arduino_foc_bldc_hall => atmega328_bldc_openloop}/src/common/pid.cpp (92%) rename minimal_project_examples/{arduino_foc_bldc_hall => atmega328_bldc_openloop}/src/common/pid.h (97%) create mode 100644 minimal_project_examples/atmega328_bldc_openloop/src/common/time_utils.cpp create mode 100644 minimal_project_examples/atmega328_bldc_openloop/src/common/time_utils.h create mode 100644 minimal_project_examples/atmega328_bldc_openloop/src/drivers/BLDCDriver3PWM.cpp create mode 100644 minimal_project_examples/atmega328_bldc_openloop/src/drivers/BLDCDriver3PWM.h create mode 100644 minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_api.h create mode 100644 minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/atmega328_mcu.cpp create mode 100644 minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/esp32_mcu.cpp create mode 100644 minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/generic_mcu.cpp create mode 100644 minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/stm32_mcu.cpp create mode 100644 minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/teensy_mcu.cpp create mode 100644 minimal_project_examples/atmega328_driver_standalone/atmega328_driver_standalone.ino create mode 100644 minimal_project_examples/atmega328_driver_standalone/src/common/base_classes/BLDCDriver.h create mode 100644 minimal_project_examples/atmega328_driver_standalone/src/common/base_classes/FOCMotor.cpp create mode 100644 minimal_project_examples/atmega328_driver_standalone/src/common/base_classes/FOCMotor.h rename minimal_project_examples/{arduino_foc_bldc_openloop/src/common => atmega328_driver_standalone/src/common/base_classes}/Sensor.h (100%) create mode 100644 minimal_project_examples/atmega328_driver_standalone/src/common/base_classes/StepperDriver.h rename minimal_project_examples/{arduino_foc_bldc_openloop => atmega328_driver_standalone}/src/common/defaults.h (100%) rename minimal_project_examples/{arduino_foc_bldc_openloop => atmega328_driver_standalone}/src/common/foc_utils.cpp (100%) rename minimal_project_examples/{arduino_foc_bldc_hall => atmega328_driver_standalone}/src/common/foc_utils.h (94%) rename minimal_project_examples/{arduino_foc_bldc_openloop => atmega328_driver_standalone}/src/common/lowpass_filter.cpp (100%) rename minimal_project_examples/{arduino_foc_bldc_openloop => atmega328_driver_standalone}/src/common/lowpass_filter.h (94%) rename minimal_project_examples/{arduino_foc_bldc_openloop => atmega328_driver_standalone}/src/common/pid.cpp (92%) rename minimal_project_examples/{arduino_foc_bldc_encoder => atmega328_driver_standalone}/src/common/pid.h (97%) create mode 100644 minimal_project_examples/atmega328_driver_standalone/src/common/time_utils.cpp create mode 100644 minimal_project_examples/atmega328_driver_standalone/src/common/time_utils.h create mode 100644 minimal_project_examples/atmega328_driver_standalone/src/drivers/BLDCDriver3PWM.cpp create mode 100644 minimal_project_examples/atmega328_driver_standalone/src/drivers/BLDCDriver3PWM.h create mode 100644 minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_api.h create mode 100644 minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/atmega328_mcu.cpp create mode 100644 minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/esp32_mcu.cpp create mode 100644 minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/generic_mcu.cpp create mode 100644 minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/stm32_mcu.cpp create mode 100644 minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/teensy_mcu.cpp rename minimal_project_examples/{arduino_foc_bldc_encoder => stm32_bldc_hall}/src/BLDCMotor.cpp (68%) rename minimal_project_examples/{arduino_foc_bldc_openloop => stm32_bldc_hall}/src/BLDCMotor.h (71%) create mode 100644 minimal_project_examples/stm32_bldc_hall/src/common/base_classes/BLDCDriver.h create mode 100644 minimal_project_examples/stm32_bldc_hall/src/common/base_classes/FOCMotor.cpp create mode 100644 minimal_project_examples/stm32_bldc_hall/src/common/base_classes/FOCMotor.h create mode 100644 minimal_project_examples/stm32_bldc_hall/src/common/base_classes/Sensor.h create mode 100644 minimal_project_examples/stm32_bldc_hall/src/common/base_classes/StepperDriver.h create mode 100644 minimal_project_examples/stm32_bldc_hall/src/common/defaults.h create mode 100644 minimal_project_examples/stm32_bldc_hall/src/common/foc_utils.cpp create mode 100644 minimal_project_examples/stm32_bldc_hall/src/common/foc_utils.h create mode 100644 minimal_project_examples/stm32_bldc_hall/src/common/lowpass_filter.cpp create mode 100644 minimal_project_examples/stm32_bldc_hall/src/common/lowpass_filter.h create mode 100644 minimal_project_examples/stm32_bldc_hall/src/common/pid.cpp create mode 100644 minimal_project_examples/stm32_bldc_hall/src/common/pid.h create mode 100644 minimal_project_examples/stm32_bldc_hall/src/common/time_utils.cpp create mode 100644 minimal_project_examples/stm32_bldc_hall/src/common/time_utils.h create mode 100644 minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver6PWM.cpp create mode 100644 minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver6PWM.h create mode 100644 minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_api.h create mode 100644 minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_specific/stm32_mcu.cpp create mode 100644 minimal_project_examples/stm32_bldc_hall/src/sensors/HallSensor.cpp rename minimal_project_examples/{arduino_foc_bldc_hall/src => stm32_bldc_hall/src/sensors}/HallSensor.h (75%) rename minimal_project_examples/{arduino_foc_bldc_hall/arduino_foc_bldc_hall.ino => stm32_bldc_hall/stm32_bldc_hall.ino} (87%) diff --git a/library_source/BLDCMotor.cpp b/library_source/BLDCMotor.cpp index 989b74a9..bed4cd6a 100644 --- a/library_source/BLDCMotor.cpp +++ b/library_source/BLDCMotor.cpp @@ -1,41 +1,39 @@ #include "BLDCMotor.h" -// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// // BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// // - phA, phB, phC - motor A,B,C phase pwm pins +// // - pp - pole pair number +// // - cpr - counts per rotation number (cpm=ppm*4) +// // - enable pin - (optional input) +// BLDCMotor::BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en){ +// noop; +// } + +// BLDCMotor( int pp) // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - cpr - counts per rotation number (cpm=ppm*4) // - enable pin - (optional input) -BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +BLDCMotor::BLDCMotor(int pp) : FOCMotor() { - // Pin initialization - pwmA = phA; - pwmB = phB; - pwmC = phC; + // save pole pairs number pole_pairs = pp; +} - // enable_pin pin - enable_pin = en; +/** + Link the driver which controls the motor +*/ +void BLDCMotor::linkDriver(BLDCDriver* _driver) { + driver = _driver; } - // init hardware pins -void BLDCMotor::init(long pwm_frequency) { - if(monitor_port) monitor_port->println("MOT: Init pins."); - // PWM pins - pinMode(pwmA, OUTPUT); - pinMode(pwmB, OUTPUT); - pinMode(pwmC, OUTPUT); - if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); - - if(monitor_port) monitor_port->println("MOT: PWM config."); - // Increase PWM frequency to 32 kHz - // make silent - _setPwmFrequency(pwm_frequency, pwmA, pwmB, pwmC); - +void BLDCMotor::init() { + if(monitor_port) monitor_port->println("MOT: Initialise variables."); // sanity check for the voltage limit configuration - if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + if(voltage_limit > driver->voltage_limit) voltage_limit = driver->voltage_limit; // constrain voltage for sensor alignment if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; // update the controller limits @@ -44,7 +42,7 @@ void BLDCMotor::init(long pwm_frequency) { _delay(500); // enable motor - if(monitor_port) monitor_port->println("MOT: Enable."); + if(monitor_port) monitor_port->println("MOT: Enable driver."); enable(); _delay(500); } @@ -53,18 +51,18 @@ void BLDCMotor::init(long pwm_frequency) { // disable motor driver void BLDCMotor::disable() { - // disable the driver - if enable_pin pin available - if (enable_pin != NOT_SET) digitalWrite(enable_pin, LOW); // set zero to PWM - setPwm(0, 0, 0); + driver->setPwm(0, 0, 0); + // disable the driver + driver->disable(); } // enable motor driver void BLDCMotor::enable() { + // enable the driver + driver->enable(); // set zero to PWM - setPwm(0, 0, 0); - // enable_pin the driver - if enable_pin pin available - if (enable_pin != NOT_SET) digitalWrite(enable_pin, HIGH); + driver->setPwm(0, 0, 0); } @@ -100,13 +98,13 @@ int BLDCMotor::alignSensor() { float start_angle = shaftAngle(); for (int i = 0; i <=5; i++ ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } float mid_angle = shaftAngle(); for (int i = 5; i >=0; i-- ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } if (mid_angle < start_angle) { @@ -121,7 +119,7 @@ int BLDCMotor::alignSensor() { // set sensor to zero sensor->initRelativeZero(); _delay(500); - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); _delay(200); // find the index if available @@ -153,7 +151,7 @@ int BLDCMotor::absoluteZeroAlign() { } voltage_q = 0; // disable motor - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); // align absolute zero if it has been found if(!sensor->needsAbsoluteZeroSearch()){ @@ -172,7 +170,7 @@ void BLDCMotor::loopFOC() { // shaft angle shaft_angle = shaftAngle(); // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); + setPhaseVoltage(voltage_q, voltage_d, _electricalAngle(shaft_angle,pole_pairs)); } // Iterative function running outer loop of the FOC algorithm @@ -219,15 +217,60 @@ void BLDCMotor::move(float new_target) { } -// Method using FOC to set Uq to the motor at the optimal angle +// Method using FOC to set Uq and Ud to the motor at the optimal angle // Function implementing Space Vector PWM and Sine PWM algorithms // // Function using sine approximation // regular sin + cos ~300us (no memory usaage) // approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { +void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { + + const bool centered = true; + int sector; + float _ca,_sa; + switch (foc_modulation) { + case FOCModulationType::Trapezoid_120 : + // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 5 + static int trap_120_map[6][3] = { + {0,1,-1},{-1,1,0},{-1,0,1},{0,-1,1},{1,-1,0},{1,0,-1} // each is 60 degrees with values for 3 phases of 1=positive -1=negative 0=high-z + }; + // static int trap_120_state = 0; + sector = 6 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes + + Ua = Uq + trap_120_map[sector][0] * Uq; + Ub = Uq + trap_120_map[sector][1] * Uq; + Uc = Uq + trap_120_map[sector][2] * Uq; + + if (centered) { + Ua += (driver->voltage_limit)/2 -Uq; + Ub += (driver->voltage_limit)/2 -Uq; + Uc += (driver->voltage_limit)/2 -Uq; + } + break; + + case FOCModulationType::Trapezoid_150 : + // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 8 + static int trap_150_map[12][3] = { + {0,1,-1},{-1,1,-1},{-1,1,0},{-1,1,1},{-1,0,1},{-1,-1,1},{0,-1,1},{1,-1,1},{1,-1,0},{1,-1,-1},{1,0,-1},{1,1,-1} // each is 30 degrees with values for 3 phases of 1=positive -1=negative 0=high-z + }; + // static int trap_150_state = 0; + sector = 12 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes + + Ua = Uq + trap_150_map[sector][0] * Uq; + Ub = Uq + trap_150_map[sector][1] * Uq; + Uc = Uq + trap_150_map[sector][2] * Uq; + + //center + if (centered) { + Ua += (driver->voltage_limit)/2 -Uq; + Ub += (driver->voltage_limit)/2 -Uq; + Uc += (driver->voltage_limit)/2 -Uq; + } + + break; + case FOCModulationType::SinePWM : // Sinusoidal PWM modulation // Inverse Park + Clarke transformation @@ -235,14 +278,24 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // angle normalization in between 0 and 2pi // only necessary if using _sin and _cos - approximation functions angle_el = _normalizeAngle(angle_el + zero_electric_angle); + _ca = _cos(angle_el); + _sa = _sin(angle_el); // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + Ualpha = _ca * Ud - _sa * Uq; // -sin(angle) * Uq; + Ubeta = _sa * Ud + _ca * Uq; // cos(angle) * Uq; // Clarke transform - Ua = Ualpha + voltage_power_supply/2; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + Ua = Ualpha + driver->voltage_limit/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + driver->voltage_limit/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + driver->voltage_limit/2; + + if (!centered) { + float Umin = min(Ua, min(Ub, Uc)); + Ua -= Umin; + Ub -= Umin; + Uc -= Umin; + } + break; case FOCModulationType::SpaceVectorPWM : @@ -259,15 +312,15 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { angle_el = _normalizeAngle(angle_el + zero_electric_angle + _PI_2); // find the sector we are in currently - int sector = floor(angle_el / _PI_3) + 1; + sector = floor(angle_el / _PI_3) + 1; // calculate the duty cycles - float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; - float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/driver->voltage_limit; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/driver->voltage_limit; // two versions possible - // centered around voltage_power_supply/2 - float T0 = 1 - T1 - T2; - // pulled to 0 - better for low power supply voltage - //float T0 = 0; + float T0 = 0; // pulled to 0 - better for low power supply voltage + if (centered) { + T0 = 1 - T1 - T2; //centered around driver->voltage_limit/2 + } // calculate the duty cycles(times) float Ta,Tb,Tc; @@ -310,27 +363,15 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { } // calculate the phase voltages and center - Ua = Ta*voltage_power_supply; - Ub = Tb*voltage_power_supply; - Uc = Tc*voltage_power_supply; + Ua = Ta*driver->voltage_limit; + Ub = Tb*driver->voltage_limit; + Uc = Tc*driver->voltage_limit; break; + } - // set the voltages in hardware - setPwm(Ua, Ub, Uc); -} - - - -// Set voltage to the pwm pin -void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { - // calculate duty cycle - // limited in [0,1] - float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); - float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); - float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); - // hardware specific writing - _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); + // set the voltages in driver + driver->setPwm(Ua, Ub, Uc); } @@ -348,7 +389,7 @@ void BLDCMotor::velocityOpenloop(float target_velocity){ shaft_angle += target_velocity*Ts; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; @@ -371,7 +412,7 @@ void BLDCMotor::angleOpenloop(float target_angle){ shaft_angle = target_angle; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; diff --git a/library_source/BLDCMotor.h b/library_source/BLDCMotor.h index a4fbb678..164cc108 100644 --- a/library_source/BLDCMotor.h +++ b/library_source/BLDCMotor.h @@ -1,16 +1,12 @@ -/** - * @file BLDCMotor.h - * - */ - #ifndef BLDCMotor_h #define BLDCMotor_h #include "Arduino.h" -#include "common/FOCMotor.h" +#include "common/base_classes/FOCMotor.h" +#include "common/base_classes/Sensor.h" +#include "common/base_classes/BLDCDriver.h" #include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "common/time_utils.h" #include "common/defaults.h" /** @@ -20,18 +16,27 @@ class BLDCMotor: public FOCMotor { public: /** - BLDCMotor class constructor - @param phA A phase pwm pin - @param phB B phase pwm pin - @param phC C phase pwm pin - @param pp pole pair number - @param cpr counts per rotation number (cpm=ppm*4) - @param en enable pin (optional input) + BLDCMotor class constructor + @param pp pole pairs number + */ + BLDCMotor(int pp); + + /** + * Function linking a motor and a foc driver + * + * @param driver BLDCDriver class implementing all the hardware specific functions necessary PWM setting + */ + void linkDriver(BLDCDriver* driver); + + /** + * BLDCDriver link: + * - 3PWM + * - 6PWM */ - BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + BLDCDriver* driver; /** Motor hardware init function */ - void init(long pwm_frequency = NOT_SET) override; + void init() override; /** Motor disable function */ void disable() override; /** Motor enable function */ @@ -59,12 +64,9 @@ class BLDCMotor: public FOCMotor * This function doesn't need to be run upon each loop execution - depends of the use case */ void move(float target = NOT_SET) override; - - // hardware variables - int pwmA; //!< phase A pwm pin number - int pwmB; //!< phase B pwm pin number - int pwmC; //!< phase C pwm pin number - int enable_pin; //!< enable pin number + + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform private: @@ -74,21 +76,15 @@ class BLDCMotor: public FOCMotor * Heart of the FOC algorithm * * @param Uq Current voltage in q axis to set to the motor + * @param Ud Current voltage in d axis to set to the motor * @param angle_el current electrical angle of the motor */ - void setPhaseVoltage(float Uq, float angle_el); + void setPhaseVoltage(float Uq, float Ud, float angle_el); /** Sensor alignment to electrical 0 angle of the motor */ int alignSensor(); /** Motor and sensor alignment to the sensors absolute 0 angle */ int absoluteZeroAlign(); - /** - * Set phase voltages to the harware - * - * @param Ua phase A voltage - * @param Ub phase B voltage - * @param Uc phase C voltage - */ - void setPwm(float Ua, float Ub, float Uc); + // Open loop motion control /** diff --git a/library_source/HallSensor.cpp b/library_source/HallSensor.cpp deleted file mode 100644 index 7072a97a..00000000 --- a/library_source/HallSensor.cpp +++ /dev/null @@ -1,186 +0,0 @@ -#include "HallSensor.h" - - -/* - HallSensor(int hallA, int hallB , int cpr, int index) - - hallA, hallB, hallC - HallSensor A, B and C pins - - pp - pole pairs -*/ - -HallSensor::HallSensor(int _hallA, int _hallB, int _hallC, int _pp){ - - // HallSensor measurement structure init - // hardware pins - pinA = _hallA; - pinB = _hallB; - pinC = _hallC; - // counter setup - pulse_counter = 0; - pulse_timestamp = 0; - - cpr = _pp * 6; // hall has 6 segments per electrical revolution - A_active = 0; - B_active = 0; - C_active = 0; - - // velocity calculation variables - - prev_pulse_counter = 0; - prev_timestamp_us = _micros(); - - // extern pullup as default - pullup = Pullup::EXTERN; -} - -// HallSensor interrupt callback functions -// A channel -void HallSensor::handleA() { - A_active= digitalRead(pinA); - updateState(); -} -// B channel -void HallSensor::handleB() { - B_active = digitalRead(pinB); - updateState(); -} - -// C channel -void HallSensor::handleC() { - C_active = digitalRead(pinC); - updateState(); -} - -void HallSensor::updateState() { - int newState = C_active + (B_active << 1) + (A_active << 2); - Direction direction = decodeDirection(state, newState); - state = newState; - - pulse_counter += direction; - pulse_timestamp = _micros(); -} - -// determines whether the hallsensr state transition means that it has moved one step CW (+1), CCW (-1) or state transition is invalid (0) -// states are 3bits, one for each hall sensor -Direction HallSensor::decodeDirection(int oldState, int newState) -{ - // here are expected state transitions (oldState > newState). - // CW state transitions are: ( 6 > 2 > 3 > 1 > 5 > 4 > 6 ) - // CCW state transitions are: ( 6 > 4 > 5 > 1 > 3 > 2 > 6 ) - // invalid state transitions are oldState == newState or if newState or oldState == 0 | 7 as hallsensors can't be all on or all off - - int rawDirection; - - if ( - (oldState == 6 && newState == 2) || \ - (oldState == 2 && newState == 3) || \ - (oldState == 3 && newState == 1) || \ - (oldState == 1 && newState == 5) || \ - (oldState == 5 && newState == 4) || \ - (oldState == 4 && newState == 6) - ) { - rawDirection = Direction::CW; - } else if( - (oldState == 6 && newState == 4) || \ - (oldState == 4 && newState == 5) || \ - (oldState == 5 && newState == 1) || \ - (oldState == 1 && newState == 3) || \ - (oldState == 3 && newState == 2) || \ - (oldState == 2 && newState == 6) - ) { - rawDirection = Direction::CCW; - } else { - rawDirection = Direction::UNKNOWN; - } - - direction = static_cast(rawDirection * natural_direction); - return direction; // * goofy; -} - -/* - Shaft angle calculation -*/ -float HallSensor::getAngle(){ - - long dN = pulse_counter - prev_pulse_counter; - - if (dN != 0) - { - - // time from last impulse - float Th = (pulse_timestamp - prev_timestamp_us) * 1e-6; - if (Th <= 0 || Th > 0.5) - Th = 1e-3; - // save variables for next pass - prev_timestamp_us = pulse_timestamp; - prev_pulse_counter = pulse_counter; - velocity = (float) _2PI * dN / (cpr * Th); - } - angle = (float) _2PI * pulse_counter / cpr; - - return angle; -} -/* - Shaft velocity calculation - function using mixed time and frequency measurement technique -*/ -float HallSensor::getVelocity(){ - // this is calculated during the last call to getAngle(); - return velocity; -} - -// getter for index pin -// return -1 if no index -int HallSensor::needsAbsoluteZeroSearch(){ - return 0; -} -// getter for index pin -int HallSensor::hasAbsoluteZero(){ - return 0; -} -// initialize counter to zero -float HallSensor::initRelativeZero(){ - - pulse_counter = 0; - pulse_timestamp = _micros(); - velocity = 0; - return 0.0; -} -// initialize index to zero -float HallSensor::initAbsoluteZero(){ - return 0.0; -} - -// HallSensor initialisation of the hardware pins -// and calculation variables -void HallSensor::init(){ - - // HallSensor - check if pullup needed for your HallSensor - if(pullup == Pullup::INTERN){ - pinMode(pinA, INPUT_PULLUP); - pinMode(pinB, INPUT_PULLUP); - pinMode(pinC, INPUT_PULLUP); - }else{ - pinMode(pinA, INPUT); - pinMode(pinB, INPUT); - pinMode(pinC, INPUT); - } - - // counter setup - pulse_counter = 0; - pulse_timestamp = _micros(); - prev_pulse_counter = 0; - prev_timestamp_us = _micros(); - -} - -// function enabling hardware interrupts for the callback provided -// if callback is not provided then the interrupt is not enabled -void HallSensor::enableInterrupts(void (*doA)(), void(*doB)(), void(*doC)()){ - // attach interrupt if functions provided - - // A, B and C callback - if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); - if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); - if(doC != nullptr) attachInterrupt(digitalPinToInterrupt(pinC), doC, CHANGE); -} - diff --git a/library_source/SimpleFOC.h b/library_source/SimpleFOC.h index 5925e78d..41188c20 100644 --- a/library_source/SimpleFOC.h +++ b/library_source/SimpleFOC.h @@ -20,21 +20,33 @@ * - Plug & play: Arduino SimpleFOC shield * * @section dependencies Supported Hardware - * - * This library supports any arduino device and it is especially optimized for Arduino UNO boards and - * other Atmega328 boards. But it supports Arrduinio MEGA boards and similar. - * - * From the version 1.3.0 it will support the STM32 boards such as Bluepill and Nucelo devices.
- * The programming is done the same way as for the Arduino UNO but stm32 devices require STM32Duino package.
- * You can download it directly from library manager. + * - Motors + * - BLDC motors + * - Stepper motors + * - Drivers + * - BLDC drivers + * - Gimbal drivers + * - Stepper drivers + * - Position sensors + * - Encoders + * - Magnetic sensors + * - Hall sensors + * - Open-loop control + * - Microcontrollers + * - Arduino + * - STM32 + * - ESP32 + * - Teensy * * @section example_code Example code * @code #include -// initialize the motor -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); -// initialize the encoder +// BLDCMotor( pole_pairs ) +BLDCMotor motor = BLDCMotor(11); +// BLDCDriver( pin_pwmA, pin_pwmB, pin_pwmC, enable (optional) ) +BLDCDriver3PWM motor = BLDCDriver3PWM(9, 10, 11, 8); +// Encoder(pin_A, pin_B, CPR) Encoder encoder = Encoder(2, 3, 2048); // channel A and B callbacks void doA(){encoder.handleA();} @@ -46,20 +58,21 @@ void setup() { encoder.init(); // hardware interrupt enable encoder.enableInterrupts(doA, doB); - - // set control loop type to be used - motor.controller = ControlType::velocity; - - // use monitoring with the BLDCMotor - Serial.begin(115200); - // monitoring port - motor.useMonitoring(Serial); - // link the motor to the sensor motor.linkSensor(&encoder); + + // power supply voltage [V] + driver.voltage_power_supply = 12; + // initialise driver hardware + driver.init(); + // link driver + motor.linkDriver(&driver); + // set control loop type to be used + motor.controller = ControlType::velocity; // initialize motor motor.init(); + // align encoder and start FOC motor.initFOC(); } @@ -71,9 +84,6 @@ void loop() { // velocity control loop function // setting the target velocity or 2rad/s motor.move(2); - - // monitoring function outputting motor variables to the serial terminal - motor.monitor(); } * @endcode * @@ -88,10 +98,13 @@ void loop() { #include "BLDCMotor.h" #include "StepperMotor.h" -#include "Encoder.h" -#include "MagneticSensorSPI.h" -#include "MagneticSensorI2C.h" -#include "MagneticSensorAnalog.h" -#include "HallSensor.h" +#include "sensors/Encoder.h" +#include "sensors/MagneticSensorSPI.h" +#include "sensors/MagneticSensorI2C.h" +#include "sensors/MagneticSensorAnalog.h" +#include "sensors/HallSensor.h" +#include "drivers/BLDCDriver3PWM.h" +#include "drivers/BLDCDriver6PWM.h" +#include "drivers/StepperDriver4PWM.h" #endif diff --git a/library_source/StepperMotor.cpp b/library_source/StepperMotor.cpp index 22ceb256..e8e991cf 100644 --- a/library_source/StepperMotor.cpp +++ b/library_source/StepperMotor.cpp @@ -5,39 +5,26 @@ // - ph2A, ph2B - motor phase 2 pwm pins // - pp - pole pair number // - enable pin - (optional input) -StepperMotor::StepperMotor(int ph1A, int ph1B, int ph2A, int ph2B, int pp, int en1, int en2) +StepperMotor::StepperMotor(int pp) : FOCMotor() { - // Pin initialization - pwm1A = ph1A; - pwm1B = ph1B; - pwm2A = ph2A; - pwm2B = ph2B; + // number od pole pairs pole_pairs = pp; +} - // enable_pin pin - enable_pin1 = en1; - enable_pin2 = en2; +/** + Link the driver which controls the motor +*/ +void StepperMotor::linkDriver(StepperDriver* _driver) { + driver = _driver; } // init hardware pins -void StepperMotor::init(long pwm_frequency) { - if(monitor_port) monitor_port->println("MOT: Init pins."); - // PWM pins - pinMode(pwm1A, OUTPUT); - pinMode(pwm1B, OUTPUT); - pinMode(pwm2A, OUTPUT); - pinMode(pwm2B, OUTPUT); - if ( enable_pin1 != NOT_SET ) pinMode(enable_pin1, OUTPUT); - if ( enable_pin2 != NOT_SET ) pinMode(enable_pin2, OUTPUT); - - if(monitor_port) monitor_port->println("MOT: PWM config."); - // Increase PWM frequency - // make silent - _setPwmFrequency(pwm_frequency, pwm1A, pwm1B, pwm2A, pwm2B); +void StepperMotor::init() { + if(monitor_port) monitor_port->println("MOT: Init variables."); // sanity check for the voltage limit configuration - if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + if(voltage_limit > driver->voltage_limit) voltage_limit = driver->voltage_limit; // constrain voltage for sensor alignment if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; @@ -57,21 +44,18 @@ void StepperMotor::init(long pwm_frequency) { // disable motor driver void StepperMotor::disable() { - // disable the driver - if enable_pin pin available - if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, LOW); - if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, LOW); // set zero to PWM - setPwm(0, 0); + driver->setPwm(0, 0); + // disable driver + driver->disable(); } // enable motor driver void StepperMotor::enable() { + // disable enable + driver->enable(); // set zero to PWM - setPwm(0, 0); - // enable_pin the driver - if enable_pin pin available - if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, HIGH); - if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, HIGH); - + driver->setPwm(0, 0); } @@ -107,13 +91,13 @@ int StepperMotor::alignSensor() { float start_angle = shaftAngle(); for (int i = 0; i <=5; i++ ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } float mid_angle = shaftAngle(); for (int i = 5; i >=0; i-- ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } if (mid_angle < start_angle) { @@ -128,7 +112,7 @@ int StepperMotor::alignSensor() { // set sensor to zero sensor->initRelativeZero(); _delay(500); - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); _delay(200); // find the index if available @@ -159,8 +143,9 @@ int StepperMotor::absoluteZeroAlign() { voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); } voltage_q = 0; + voltage_d = 0; // disable motor - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); // align absolute zero if it has been found if(!sensor->needsAbsoluteZeroSearch()){ @@ -179,7 +164,7 @@ void StepperMotor::loopFOC() { // shaft angle shaft_angle = shaftAngle(); // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); + setPhaseVoltage(voltage_q, voltage_d, _electricalAngle(shaft_angle, pole_pairs)); } // Iterative function running outer loop of the FOC algorithm @@ -226,44 +211,28 @@ void StepperMotor::move(float new_target) { } -// Method using FOC to set Uq to the motor at the optimal angle -// Function implementingSine PWM algorithms +// Method using FOC to set Uq and Ud to the motor at the optimal angle +// Function implementing Sine PWM algorithms // - space vector not implemented yet // // Function using sine approximation // regular sin + cos ~300us (no memory usaage) // approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void StepperMotor::setPhaseVoltage(float Uq, float angle_el) { +void StepperMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { // Sinusoidal PWM modulation // Inverse Park transformation // angle normalization in between 0 and 2pi // only necessary if using _sin and _cos - approximation functions - angle_el = _normalizeAngle(angle_el + zero_electric_angle); + angle_el = _normalizeAngle(angle_el + zero_electric_angle); + float _ca = _cos(angle_el); + float _sa = _sin(angle_el); // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; - // set the voltages in hardware - setPwm(Ualpha,Ubeta); -} - - + Ualpha = _ca * Ud - _sa * Uq; // -sin(angle) * Uq; + Ubeta = _sa * Ud + _ca * Uq; // cos(angle) * Uq; -// Set voltage to the pwm pin -void StepperMotor::setPwm(float Ualpha, float Ubeta) { - float duty_cycle1A(0.0),duty_cycle1B(0.0),duty_cycle2A(0.0),duty_cycle2B(0.0); - // hardware specific writing - if( Ualpha > 0 ) - duty_cycle1B = constrain(abs(Ualpha)/voltage_power_supply,0,1); - else - duty_cycle1A = constrain(abs(Ualpha)/voltage_power_supply,0,1); - - if( Ubeta > 0 ) - duty_cycle2B = constrain(abs(Ubeta)/voltage_power_supply,0,1); - else - duty_cycle2A = constrain(abs(Ubeta)/voltage_power_supply,0,1); - // write to hardware - _writeDutyCycle(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, pwm1A, pwm1B, pwm2A, pwm2B); + // set the voltages in hardware + driver->setPwm(Ualpha, Ubeta); } // Function (iterative) generating open loop movement for target velocity @@ -279,7 +248,7 @@ void StepperMotor::velocityOpenloop(float target_velocity){ shaft_angle += target_velocity*Ts; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle,pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle,pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; @@ -302,7 +271,7 @@ void StepperMotor::angleOpenloop(float target_angle){ shaft_angle = target_angle; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle,pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle,pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; diff --git a/library_source/StepperMotor.h b/library_source/StepperMotor.h index bf14e096..af4783bf 100644 --- a/library_source/StepperMotor.h +++ b/library_source/StepperMotor.h @@ -7,10 +7,11 @@ #define StepperMotor_h #include "Arduino.h" -#include "common/FOCMotor.h" +#include "common/base_classes/FOCMotor.h" +#include "common/base_classes/StepperDriver.h" +#include "common/base_classes/Sensor.h" #include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "common/time_utils.h" #include "common/defaults.h" /** @@ -21,18 +22,25 @@ class StepperMotor: public FOCMotor public: /** StepperMotor class constructor - @param ph1A 1A phase pwm pin - @param ph1B 1B phase pwm pin - @param ph2A 2A phase pwm pin - @param ph2B 2B phase pwm pin @param pp pole pair number - cpr counts per rotation number (cpm=ppm*4) - @param en1 enable pin phase 1 (optional input) - @param en2 enable pin phase 2 (optional input) */ - StepperMotor(int ph1A,int ph1B,int ph2A,int ph2B,int pp, int en1 = NOT_SET, int en2 = NOT_SET); - + StepperMotor(int pp); + + /** + * Function linking a motor and a foc driver + * + * @param driver StepperDriver class implementing all the hardware specific functions necessary PWM setting + */ + void linkDriver(StepperDriver* driver); + + /** + * StepperDriver link: + * - 4PWM - L298N for example + */ + StepperDriver* driver; + /** Motor hardware init function */ - void init(long pwm_frequency = NOT_SET) override; + void init() override; /** Motor disable function */ void disable() override; /** Motor enable function */ @@ -65,14 +73,8 @@ class StepperMotor: public FOCMotor * This function doesn't need to be run upon each loop execution - depends of the use case */ void move(float target = NOT_SET) override; - - // hardware variables - int pwm1A; //!< phase 1A pwm pin number - int pwm1B; //!< phase 1B pwm pin number - int pwm2A; //!< phase 2A pwm pin number - int pwm2B; //!< phase 2B pwm pin number - int enable_pin1; //!< enable pin number phase 1 - int enable_pin2; //!< enable pin number phase 2 + + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform private: @@ -82,22 +84,15 @@ class StepperMotor: public FOCMotor * Heart of the FOC algorithm * * @param Uq Current voltage in q axis to set to the motor + * @param Ud Current voltage in d axis to set to the motor * @param angle_el current electrical angle of the motor */ - void setPhaseVoltage(float Uq, float angle_el); + void setPhaseVoltage(float Uq, float Ud , float angle_el); /** Sensor alignment to electrical 0 angle of the motor */ int alignSensor(); /** Motor and sensor alignment to the sensors absolute 0 angle */ int absoluteZeroAlign(); - /** - * Set phase voltages to the harware - * - * @param Ua phase A voltage - * @param Ub phase B voltage - * @param Uc phase C voltage - */ - void setPwm(float Ualpha, float Ubeta); // Open loop motion control /** diff --git a/library_source/common/base_classes/BLDCDriver.h b/library_source/common/base_classes/BLDCDriver.h new file mode 100644 index 00000000..708323fb --- /dev/null +++ b/library_source/common/base_classes/BLDCDriver.h @@ -0,0 +1,28 @@ +#ifndef BLDCDRIVER_H +#define BLDCDRIVER_H + +class BLDCDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + virtual void setPwm(float Ua, float Ub, float Uc); +}; + +#endif \ No newline at end of file diff --git a/library_source/common/FOCMotor.cpp b/library_source/common/base_classes/FOCMotor.cpp similarity index 98% rename from library_source/common/FOCMotor.cpp rename to library_source/common/base_classes/FOCMotor.cpp index adecbeec..1d1a0f43 100644 --- a/library_source/common/FOCMotor.cpp +++ b/library_source/common/base_classes/FOCMotor.cpp @@ -5,13 +5,10 @@ */ FOCMotor::FOCMotor() { - // Power supply voltage - voltage_power_supply = DEF_POWER_SUPPLY; - // maximum angular velocity to be used for positioning velocity_limit = DEF_VEL_LIM; // maximum voltage to be set to the motor - voltage_limit = voltage_power_supply; + voltage_limit = DEF_POWER_SUPPLY; // index search velocity velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; @@ -26,6 +23,8 @@ FOCMotor::FOCMotor() // default target value target = 0; + voltage_d = 0; + voltage_q = 0; //monitor_port monitor_port = nullptr; @@ -53,9 +52,6 @@ float FOCMotor::shaftVelocity() { return LPF_velocity(sensor->getVelocity()); } - - - /** * Monitoring functions */ diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/FOCMotor.h b/library_source/common/base_classes/FOCMotor.h similarity index 93% rename from minimal_project_examples/arduino_foc_bldc_encoder/src/common/FOCMotor.h rename to library_source/common/base_classes/FOCMotor.h index 40f7f6d4..986e1ab2 100644 --- a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/FOCMotor.h +++ b/library_source/common/base_classes/FOCMotor.h @@ -2,13 +2,14 @@ #define FOCMOTOR_H #include "Arduino.h" -#include "hardware_utils.h" -#include "foc_utils.h" -#include "defaults.h" - #include "Sensor.h" -#include "pid.h" -#include "lowpass_filter.h" +#include "BLDCDriver.h" + +#include "../time_utils.h" +#include "../foc_utils.h" +#include "../defaults.h" +#include "../pid.h" +#include "../lowpass_filter.h" /** @@ -27,7 +28,9 @@ enum ControlType{ */ enum FOCModulationType{ SinePWM, //!< Sinusoidal PWM modulation - SpaceVectorPWM //!< Space vector modulation method + SpaceVectorPWM, //!< Space vector modulation method + Trapezoid_120, + Trapezoid_150 }; /** @@ -42,7 +45,7 @@ class FOCMotor FOCMotor(); /** Motor hardware init function */ - virtual void init(long pwm_frequency)=0; + virtual void init()=0; /** Motor disable function */ virtual void disable()=0; /** Motor enable function */ @@ -55,6 +58,7 @@ class FOCMotor */ void linkSensor(Sensor* sensor); + /** * Function initializing FOC algorithm * and aligning sensor's and motors' zero position @@ -99,11 +103,9 @@ class FOCMotor float shaft_velocity_sp;//!< current target velocity float shaft_angle_sp;//!< current target angle float voltage_q;//!< current voltage u_q set - float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor - float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform + float voltage_d;//!< current voltage u_d set // motor configuration parameters - float voltage_power_supply;//!< Power supply voltage float voltage_sensor_align;//!< sensor and motor align voltage parameter float velocity_index_search;//!< target velocity for index search int pole_pairs;//!< Motor pole pairs number diff --git a/library_source/common/Sensor.h b/library_source/common/base_classes/Sensor.h similarity index 100% rename from library_source/common/Sensor.h rename to library_source/common/base_classes/Sensor.h diff --git a/library_source/common/base_classes/StepperDriver.h b/library_source/common/base_classes/StepperDriver.h new file mode 100644 index 00000000..7800a4e7 --- /dev/null +++ b/library_source/common/base_classes/StepperDriver.h @@ -0,0 +1,27 @@ +#ifndef STEPPERDRIVER_H +#define STEPPERDRIVER_H + +class StepperDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + */ + virtual void setPwm(float Ua, float Ub); +}; + +#endif \ No newline at end of file diff --git a/library_source/common/foc_utils.h b/library_source/common/foc_utils.h index 5ab34f42..7da3f7bc 100644 --- a/library_source/common/foc_utils.h +++ b/library_source/common/foc_utils.h @@ -6,6 +6,7 @@ // sign function #define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) #define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) +#define _constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt))) // utility defines #define _2_SQRT3 1.15470053838 @@ -20,7 +21,6 @@ #define _2PI 6.28318530718 #define _3PI_2 4.71238898038 - #define NOT_SET -12345.0 /** diff --git a/library_source/common/hardware_utils.cpp b/library_source/common/hardware_utils.cpp deleted file mode 100644 index 0d080bab..00000000 --- a/library_source/common/hardware_utils.cpp +++ /dev/null @@ -1,284 +0,0 @@ -#include "hardware_utils.h" - -#if defined(ESP_H) // if ESP32 board -// empty motor slot -#define _EMPTY_SLOT -20 - -// structure containing motor slot configuration -// this library supports up to 4 motors -typedef struct { - int pinA; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator; - mcpwm_io_signals_t mcpwm_a; - mcpwm_io_signals_t mcpwm_b; - mcpwm_io_signals_t mcpwm_c; -} bldc_motor_slots_t; -typedef struct { - int pin1A; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator1; - mcpwm_operator_t mcpwm_operator2; - mcpwm_io_signals_t mcpwm_1a; - mcpwm_io_signals_t mcpwm_1b; - mcpwm_io_signals_t mcpwm_2a; - mcpwm_io_signals_t mcpwm_2b; -} stepper_motor_slots_t; - -// define bldc motor slots array -bldc_motor_slots_t esp32_bldc_motor_slots[4] = { - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B - }; - -// define stepper motor slots array -stepper_motor_slots_t esp32_stepper_motor_slots[2] = { - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 - }; - -// configuring high frequency pwm timer -// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller -void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ - - mcpwm_config_t pwm_config; - pwm_config.frequency = pwm_frequency; //frequency - pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% - pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% - pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) - pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH - mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings - - _delay(100); - - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); - mcpwm_num->clk_cfg.prescale = 0; - - mcpwm_num->timer[0].period.prescale = 4; - mcpwm_num->timer[1].period.prescale = 4; - mcpwm_num->timer[2].period.prescale = 4; - _delay(1); - mcpwm_num->timer[0].period.period = 2048; - mcpwm_num->timer[1].period.period = 2048; - mcpwm_num->timer[2].period.period = 2048; - _delay(1); - mcpwm_num->timer[0].period.upmethod = 0; - mcpwm_num->timer[1].period.upmethod = 0; - mcpwm_num->timer[2].period.upmethod = 0; - _delay(1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); - - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 1; - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 0; -} - -#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips -// set pwm frequency to 32KHz -void _pinHighFrequency(const int pin){ - // High PWM frequency - // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pin == 5 || pin == 6 ) { - TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode - TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - } - if (pin == 9 || pin == 10 ) - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pin == 3 || pin == 11) - TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 - -} -#elif defined(_STM32_DEF_) // if stm chips -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); - analogWriteResolution(12); // resolution 12 bit 0 - 4096 -} -#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); -} -#endif - - -// function setting the high pwm frequency to the supplied pins -// - hardware speciffic -// supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips - // High PWM frequency - // - always max 32kHz - _pinHighFrequency(pinA); - _pinHighFrequency(pinB); - _pinHighFrequency(pinC); - if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor - -#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards - if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz - else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max - _setHighFrequency(pwm_frequency, pinA); - _setHighFrequency(pwm_frequency, pinB); - _setHighFrequency(pwm_frequency, pinC); - if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor - -#elif defined(ESP_H) // if esp32 boards - if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency - - if(pinD == NOT_SET){ - bldc_motor_slots_t m_slot = {}; - - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_bldc_motor_slots[i].pinA = pinA; - m_slot = esp32_bldc_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - - }else{ - stepper_motor_slots_t m_slot = {}; - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_stepper_motor_slots[i].pin1A = pinA; - m_slot = esp32_stepper_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - } -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pinA, 4095.0*dc_a); - analogWrite(pinB, 4095.0*dc_b); - analogWrite(pinC, 4095.0*dc_c); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255*dc_a); - analogWrite(pinB, 255*dc_b); - analogWrite(pinC, 255*dc_c); -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pin1A, 4095.0*dc_1a); - analogWrite(pin1B, 4095.0*dc_1b); - analogWrite(pin2A, 4095.0*dc_2a); - analogWrite(pin2B, 4095.0*dc_2b); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255*dc_1a); - analogWrite(pin1B, 255*dc_1b); - analogWrite(pin2A, 255*dc_2a); - analogWrite(pin2B, 255*dc_2b); -#endif -} - - -// function buffering delay() -// arduino uno function doesn't work well with interrupts -void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) - // if arduino uno and other atmega328p chips - // use while instad of delay, - // due to wrong measurement based on changed timer0 - unsigned long t = _micros() + ms*1000; - while( _micros() < t ){}; -#else - // regular micros - delay(ms); -#endif -} - - -// function buffering _micros() -// arduino function doesn't work well with interrupts -unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) -// if arduino uno and other atmega328p chips - //return the value based on the prescaler - if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); - else return (micros()); -#else - // regular micros - return micros(); -#endif -} diff --git a/library_source/common/hardware_utils.h b/library_source/common/hardware_utils.h deleted file mode 100644 index f99c260a..00000000 --- a/library_source/common/hardware_utils.h +++ /dev/null @@ -1,72 +0,0 @@ -#ifndef HARDWARE_UTILS_H -#define HARDWARE_UTILS_H - -#include "Arduino.h" -#include "foc_utils.h" - - -#if defined(ESP_H) // if esp32 boards - -#include "driver/mcpwm.h" -#include "soc/mcpwm_reg.h" -#include "soc/mcpwm_struct.h" - -#endif - -/** - * High PWM frequency setting function - * - hardware specific - * - * @param pwm_frequency - frequency in hertz - if applicable - * @param pinA pinA bldc motor or pin1A stepper motor - * @param pinB pinB bldc motor or pin1B stepper motor - * @param pinC pinC bldc motor or pin2A stepper motor - * @param pinD pin2B stepper motor - */ -void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_a duty cycle phase A [0, 1] - * @param dc_b duty cycle phase B [0, 1] - * @param dc_c duty cycle phase C [0, 1] - * @param pinA phase A hardware pin number - * @param pinB phase B hardware pin number - * @param pinC phase C hardware pin number - */ -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_1a duty cycle phase 1A [0, 1] - * @param dc_1b duty cycle phase 1B [0, 1] - * @param dc_2a duty cycle phase 2A [0, 1] - * @param dc_2b duty cycle phase 2B [0, 1] - * @param pin1A phase 1A hardware pin number - * @param pin1B phase 1B hardware pin number - * @param pin2A phase 2A hardware pin number - * @param pin2B phase 2B hardware pin number - */ -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); - -/** - * Function implementing delay() function in milliseconds - * - blocking function - * - hardware specific - - * @param ms number of milliseconds to wait - */ -void _delay(unsigned long ms); - -/** - * Function implementing timestamp getting function in microseconds - * hardware specific - */ -unsigned long _micros(); - - -#endif \ No newline at end of file diff --git a/library_source/common/lowpass_filter.h b/library_source/common/lowpass_filter.h index 5a7619cf..7c51be54 100644 --- a/library_source/common/lowpass_filter.h +++ b/library_source/common/lowpass_filter.h @@ -2,7 +2,7 @@ #define LOWPASS_FILTER_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" diff --git a/library_source/common/pid.cpp b/library_source/common/pid.cpp index 277e17ce..1a0a9828 100644 --- a/library_source/common/pid.cpp +++ b/library_source/common/pid.cpp @@ -25,12 +25,12 @@ float PIDController::operator() (float error){ // Discrete implementations // proportional part // u_p = P *e(k) - float proportional = P * error_prev; + float proportional = P * error; // Tustin transform of the integral part // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) float integral = integral_prev + I*Ts*0.5*(error + error_prev); // antiwindup - limit the output voltage_q - integral = constrain(integral, -limit, limit); + integral = _constrain(integral, -limit, limit); // Discrete derivation // u_dk = D(ek - ek_1)/Ts float derivative = D*(error - error_prev)/Ts; @@ -38,7 +38,7 @@ float PIDController::operator() (float error){ // sum all the components float output = proportional + integral + derivative; // antiwindup - limit the output variable - output = constrain(output, -limit, limit); + output = _constrain(output, -limit, limit); // limit the acceleration by ramping the output float output_rate = (output - output_prev)/Ts; diff --git a/library_source/common/pid.h b/library_source/common/pid.h index 7ee337c4..0e9ddf54 100644 --- a/library_source/common/pid.h +++ b/library_source/common/pid.h @@ -2,7 +2,7 @@ #define PID_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" /** diff --git a/library_source/common/time_utils.cpp b/library_source/common/time_utils.cpp new file mode 100644 index 00000000..181d03cf --- /dev/null +++ b/library_source/common/time_utils.cpp @@ -0,0 +1,31 @@ +#include "time_utils.h" + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/library_source/common/time_utils.h b/library_source/common/time_utils.h new file mode 100644 index 00000000..143d4853 --- /dev/null +++ b/library_source/common/time_utils.h @@ -0,0 +1,22 @@ +#ifndef TIME_UTILS_H +#define TIME_UTILS_H + +#include "foc_utils.h" + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + + +#endif \ No newline at end of file diff --git a/library_source/drivers/BLDCDriver3PWM.cpp b/library_source/drivers/BLDCDriver3PWM.cpp new file mode 100644 index 00000000..bacb4ec5 --- /dev/null +++ b/library_source/drivers/BLDCDriver3PWM.cpp @@ -0,0 +1,70 @@ +#include "BLDCDriver3PWM.h" + +BLDCDriver3PWM::BLDCDriver3PWM(int phA, int phB, int phC, int en){ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + + // enable_pin pin + enable_pin = en; + + // default power-supply value + voltage_power_supply = DEF_POWER_SUPPLY; + voltage_limit = NOT_SET; + +} + +// enable motor driver +void BLDCDriver3PWM::enable(){ + // enable_pin the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, HIGH); + // set zero to PWM + setPwm(0,0,0); +} + +// disable motor driver +void BLDCDriver3PWM::disable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // disable the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, LOW); + +} + +// init hardware pins +int BLDCDriver3PWM::init() { + + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); + + + // sanity check for the voltage limit configuration + if(voltage_limit == NOT_SET || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + + // Set the pwm frequency to the pins + // hardware specific function - depending on driver and mcu + _configure3PWM(pwm_frequency, pwmA, pwmB, pwmC); + return 0; +} + + +// Set voltage to the pwm pin +void BLDCDriver3PWM::setPwm(float Ua, float Ub, float Uc) { + // limit the voltage in driver + Ua = _constrain(Ua, -voltage_limit, voltage_limit); + Ub = _constrain(Ub, -voltage_limit, voltage_limit); + Uc = _constrain(Uc, -voltage_limit, voltage_limit); + // calculate duty cycle + // limited in [0,1] + float dc_a = _constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = _constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = _constrain(Uc / voltage_power_supply, 0 , 1 ); + // hardware specific writing + // hardware specific function - depending on driver and mcu + _writeDutyCycle3PWM(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC); +} \ No newline at end of file diff --git a/library_source/drivers/BLDCDriver3PWM.h b/library_source/drivers/BLDCDriver3PWM.h new file mode 100644 index 00000000..b6f7d7f8 --- /dev/null +++ b/library_source/drivers/BLDCDriver3PWM.h @@ -0,0 +1,52 @@ +#ifndef BLDCDriver3PWM_h +#define BLDCDriver3PWM_h + +#include "../common/base_classes/BLDCDriver.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#include "../common/defaults.h" +#include "hardware_api.h" + +/** + 3 pwm bldc driver class +*/ +class BLDCDriver3PWM: public BLDCDriver +{ + public: + /** + BLDCDriver class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param en enable pin (optional input) + */ + BLDCDriver3PWM(int phA,int phB,int phC, int en = NOT_SET); + + /** Motor hardware init function */ + int init() override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc) override; + + private: + +}; + + +#endif diff --git a/library_source/drivers/BLDCDriver6PWM.cpp b/library_source/drivers/BLDCDriver6PWM.cpp new file mode 100644 index 00000000..b1f2e884 --- /dev/null +++ b/library_source/drivers/BLDCDriver6PWM.cpp @@ -0,0 +1,78 @@ +#include "BLDCDriver6PWM.h" + +BLDCDriver6PWM::BLDCDriver6PWM(int phA_h,int phA_l,int phB_h,int phB_l,int phC_h,int phC_l, int en){ + // Pin initialization + pwmA_h = phA_h; + pwmB_h = phB_h; + pwmC_h = phC_h; + pwmA_l = phA_l; + pwmB_l = phB_l; + pwmC_l = phC_l; + + // enable_pin pin + enable_pin = en; + + // default power-supply value + voltage_power_supply = DEF_POWER_SUPPLY; + voltage_limit = NOT_SET; + + // dead zone initial - 2% + dead_zone = 0.02; + +} + +// enable motor driver +void BLDCDriver6PWM::enable(){ + // enable_pin the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, HIGH); + // set zero to PWM + setPwm(0, 0, 0); +} + +// disable motor driver +void BLDCDriver6PWM::disable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // disable the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, LOW); + +} + +// init hardware pins +int BLDCDriver6PWM::init() { + + // PWM pins + pinMode(pwmA_l, OUTPUT); + pinMode(pwmB_h, OUTPUT); + pinMode(pwmC_h, OUTPUT); + pinMode(pwmA_l, OUTPUT); + pinMode(pwmB_l, OUTPUT); + pinMode(pwmC_l, OUTPUT); + if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); + + + // sanity check for the voltage limit configuration + if(voltage_limit == NOT_SET || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + + // configure 6pwm + // hardware specific function - depending on driver and mcu + return _configure6PWM(pwm_frequency, dead_zone, pwmA_h,pwmA_l, pwmB_h,pwmB_l, pwmC_h,pwmC_l); +} + + +// Set voltage to the pwm pin +void BLDCDriver6PWM::setPwm(float Ua, float Ub, float Uc) { + // limit the voltage in driver + Ua = _constrain(Ua, -voltage_limit, voltage_limit); + Ub = _constrain(Ub, -voltage_limit, voltage_limit); + Uc = _constrain(Uc, -voltage_limit, voltage_limit); + // calculate duty cycle + // limited in [0,1] + float dc_a = _constrain(Ua / voltage_power_supply, 0.0 , 1.0 ); + float dc_b = _constrain(Ub / voltage_power_supply, 0.0 , 1.0 ); + float dc_c = _constrain(Uc / voltage_power_supply, 0.0 , 1.0 ); + // hardware specific writing + // hardware specific function - depending on driver and mcu + _writeDutyCycle6PWM(dc_a, dc_b, dc_c, dead_zone, pwmA_h,pwmA_l, pwmB_h,pwmB_l, pwmC_h,pwmC_l); +} \ No newline at end of file diff --git a/library_source/drivers/BLDCDriver6PWM.h b/library_source/drivers/BLDCDriver6PWM.h new file mode 100644 index 00000000..d13b69fd --- /dev/null +++ b/library_source/drivers/BLDCDriver6PWM.h @@ -0,0 +1,57 @@ +#ifndef BLDCDriver6PWM_h +#define BLDCDriver6PWM_h + +#include "../common/base_classes/BLDCDriver.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#include "../common/defaults.h" +#include "hardware_api.h" + +/** + 6 pwm bldc driver class +*/ +class BLDCDriver6PWM: public BLDCDriver +{ + public: + /** + BLDCDriver class constructor + @param phA_h A phase pwm pin + @param phA_l A phase pwm pin + @param phB_h B phase pwm pin + @param phB_l A phase pwm pin + @param phC_h C phase pwm pin + @param phC_l A phase pwm pin + @param en enable pin (optional input) + */ + BLDCDriver6PWM(int phA_h,int phA_l,int phB_h,int phB_l,int phC_h,int phC_l, int en = NOT_SET); + + /** Motor hardware init function */ + int init() override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + // hardware variables + int pwmA_h,pwmA_l; //!< phase A pwm pin number + int pwmB_h,pwmB_l; //!< phase B pwm pin number + int pwmC_h,pwmC_l; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + float dead_zone; //!< a percentage of dead-time(zone) (both high and low side in low) for each pwm cycle [0,1] + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc) override; + + private: + +}; + + +#endif diff --git a/library_source/drivers/StepperDriver4PWM.cpp b/library_source/drivers/StepperDriver4PWM.cpp new file mode 100644 index 00000000..e7eec6ff --- /dev/null +++ b/library_source/drivers/StepperDriver4PWM.cpp @@ -0,0 +1,79 @@ +#include "StepperDriver4PWM.h" + +StepperDriver4PWM::StepperDriver4PWM(int ph1A,int ph1B,int ph2A,int ph2B,int en1, int en2){ + // Pin initialization + pwm1A = ph1A; + pwm1B = ph1B; + pwm2A = ph2A; + pwm2B = ph2B; + + // enable_pin pin + enable_pin1 = en1; + enable_pin2 = en2; + + // default power-supply value + voltage_power_supply = DEF_POWER_SUPPLY; + voltage_limit = NOT_SET; + +} + +// enable motor driver +void StepperDriver4PWM::enable(){ + // enable_pin the driver - if enable_pin pin available + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, HIGH); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, HIGH); + // set zero to PWM + setPwm(0,0); +} + +// disable motor driver +void StepperDriver4PWM::disable() +{ + // set zero to PWM + setPwm(0, 0); + // disable the driver - if enable_pin pin available + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, LOW); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, LOW); + +} + +// init hardware pins +int StepperDriver4PWM::init() { + + // PWM pins + pinMode(pwm1A, OUTPUT); + pinMode(pwm1B, OUTPUT); + pinMode(pwm2A, OUTPUT); + pinMode(pwm2B, OUTPUT); + if(enable_pin1 != NOT_SET) pinMode(enable_pin1, OUTPUT); + if(enable_pin2 != NOT_SET) pinMode(enable_pin2, OUTPUT); + + // sanity check for the voltage limit configuration + if(voltage_limit == NOT_SET || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + + // Set the pwm frequency to the pins + // hardware specific function - depending on driver and mcu + _configure4PWM(pwm_frequency, pwm1A, pwm1B, pwm2A, pwm2B); + return 0; +} + + +// Set voltage to the pwm pin +void StepperDriver4PWM::setPwm(float Ualpha, float Ubeta) { + float duty_cycle1A(0.0),duty_cycle1B(0.0),duty_cycle2A(0.0),duty_cycle2B(0.0); + // limit the voltage in driver + Ualpha = _constrain(Ualpha,-voltage_limit,voltage_limit); + Ubeta = _constrain(Ubeta,-voltage_limit,voltage_limit); + // hardware specific writing + if( Ualpha > 0 ) + duty_cycle1B = _constrain(abs(Ualpha)/voltage_power_supply,0,1); + else + duty_cycle1A = _constrain(abs(Ualpha)/voltage_power_supply,0,1); + + if( Ubeta > 0 ) + duty_cycle2B = _constrain(abs(Ubeta)/voltage_power_supply,0,1); + else + duty_cycle2A = _constrain(abs(Ubeta)/voltage_power_supply,0,1); + // write to hardware + _writeDutyCycle4PWM(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, pwm1A, pwm1B, pwm2A, pwm2B); +} \ No newline at end of file diff --git a/library_source/drivers/StepperDriver4PWM.h b/library_source/drivers/StepperDriver4PWM.h new file mode 100644 index 00000000..e4b2ee42 --- /dev/null +++ b/library_source/drivers/StepperDriver4PWM.h @@ -0,0 +1,55 @@ +#ifndef STEPPER_DRIVER_4PWM_h +#define STEPPER_DRIVER_4PWM_h + +#include "../common/base_classes/StepperDriver.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#include "../common/defaults.h" +#include "hardware_api.h" + +/** + 4 pwm stepper driver class +*/ +class StepperDriver4PWM: public StepperDriver +{ + public: + /** + StepperMotor class constructor + @param ph1A 1A phase pwm pin + @param ph1B 1B phase pwm pin + @param ph2A 2A phase pwm pin + @param ph2B 2B phase pwm pin + @param en1 enable pin phase 1 (optional input) + @param en2 enable pin phase 2 (optional input) + */ + StepperDriver4PWM(int ph1A,int ph1B,int ph2A,int ph2B, int en1 = NOT_SET, int en2 = NOT_SET); + + /** Motor hardware init function */ + int init() override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + // hardware variables + int pwm1A; //!< phase 1A pwm pin number + int pwm1B; //!< phase 1B pwm pin number + int pwm2A; //!< phase 2A pwm pin number + int pwm2B; //!< phase 2B pwm pin number + int enable_pin1; //!< enable pin number phase 1 + int enable_pin2; //!< enable pin number phase 2 + + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + */ + void setPwm(float Ua, float Ub) override; + + private: + +}; + + +#endif diff --git a/library_source/drivers/hardware_api.h b/library_source/drivers/hardware_api.h new file mode 100644 index 00000000..da5ddf51 --- /dev/null +++ b/library_source/drivers/hardware_api.h @@ -0,0 +1,100 @@ +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H + +#include "../common/foc_utils.h" +#include "../common/time_utils.h" + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + * @param pinC pinC bldc driver + */ +void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC); + +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pin1A pin1A stepper driver + * @param pin1B pin1B stepper driver + * @param pin2A pin2A stepper driver + * @param pin2B pin2B stepper driver + */ +void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B); + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low - if applicable + * @param pinA_h pinA high-side bldc driver + * @param pinA_l pinA low-side bldc driver + * @param pinB_h pinA high-side bldc driver + * @param pinB_l pinA low-side bldc driver + * @param pinC_h pinA high-side bldc driver + * @param pinC_l pinA low-side bldc driver + * + * @return 0 if config good, -1 if failed + */ +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low + * @param pinA_h phase A high-side hardware pin number + * @param pinA_l phase A low-side hardware pin number + * @param pinB_h phase B high-side hardware pin number + * @param pinB_l phase B low-side hardware pin number + * @param pinC_h phase C high-side hardware pin number + * @param pinC_l phase C low-side hardware pin number + * + */ +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l); + +#endif \ No newline at end of file diff --git a/library_source/drivers/hardware_specific/atmega328_mcu.cpp b/library_source/drivers/hardware_specific/atmega328_mcu.cpp new file mode 100644 index 00000000..58b368f7 --- /dev/null +++ b/library_source/drivers/hardware_specific/atmega328_mcu.cpp @@ -0,0 +1,133 @@ +#include "../hardware_api.h" + +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + +// set pwm frequency to 32KHz +void _pinHighFrequency(const int pin){ + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pin == 5 || pin == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pin == 9 || pin == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pin == 3 || pin == 11) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +} + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +// supports Arudino/ATmega328 +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); + _pinHighFrequency(pinC); +} + + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); + analogWrite(pinC, 255.0*dc_c); +} + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +// supports Arudino/ATmega328 +void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pin1A); + _pinHighFrequency(pin1B); + _pinHighFrequency(pin2A); + _pinHighFrequency(pin2B); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255.0*dc_1a); + analogWrite(pin1B, 255.0*dc_1b); + analogWrite(pin2A, 255.0*dc_2a); + analogWrite(pin2B, 255.0*dc_2b); +} + + +// function configuring pair of high-low side pwm channels, 32khz frequency and center aligned pwm +int _configureComplementaryPair(int pinH, int pinL) { + if( (pinH == 5 && pinL == 6 ) || (pinH == 6 && pinL == 5 ) ){ + // configure the pwm phase-corrected mode + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); + // configure complementary pwm on low side + if(pinH == 6 ) TCCR0A = 0b10110000 | (TCCR0A & 0b00001111) ; + else TCCR0A = 0b11100000 | (TCCR0A & 0b00001111) ; + // set prescaler to 1 - 32kHz freq + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); + }else if( (pinH == 9 && pinL == 10 ) || (pinH == 10 && pinL == 9 ) ){ + // set prescaler to 1 - 32kHz freq + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); + // configure complementary pwm on low side + if(pinH == 9 ) TCCR1A = 0b10110000 | (TCCR1A & 0b00001111) ; + else TCCR1A = 0b11100000 | (TCCR1A & 0b00001111) ; + }else if((pinH == 3 && pinL == 11 ) || (pinH == 11 && pinL == 3 ) ){ + // set prescaler to 1 - 32kHz freq + TCCR2B = ((TCCR2B & 0b11111000) | 0x01); + // configure complementary pwm on low side + if(pinH == 11 ) TCCR2A = 0b10110000 | (TCCR2A & 0b00001111) ; + else TCCR2A = 0b11100000 | (TCCR2A & 0b00001111) ; + }else{ + return -1; + } + return 0; +} + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +// supports Arudino/ATmega328 +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) { + // High PWM frequency + // - always max 32kHz + int ret_flag = 0; + ret_flag += _configureComplementaryPair(pinA_h, pinA_l); + ret_flag += _configureComplementaryPair(pinB_h, pinB_l); + ret_flag += _configureComplementaryPair(pinC_h, pinC_l); + return ret_flag; // returns -1 if not well configured +} + +// function setting the +void _setPwmPair(int pinH, int pinL, float val, int dead_time) +{ + int pwm_h = _constrain(val-dead_time/2,0,255); + int pwm_l = _constrain(val+dead_time/2,0,255); + + analogWrite(pinH, pwm_h); + if(pwm_l == 255 || pwm_l == 0) + digitalWrite(pinL, pwm_l ? LOW : HIGH); + else + analogWrite(pinL, pwm_l); +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +// supports Arudino/ATmega328 +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + _setPwmPair(pinA_h, pinA_l, dc_a*255.0, dead_zone*255.0); + _setPwmPair(pinB_h, pinB_l, dc_b*255.0, dead_zone*255.0); + _setPwmPair(pinC_h, pinC_l, dc_c*255.0, dead_zone*255.0); +} + +#endif \ No newline at end of file diff --git a/library_source/drivers/hardware_specific/esp32_mcu.cpp b/library_source/drivers/hardware_specific/esp32_mcu.cpp new file mode 100644 index 00000000..3c07a445 --- /dev/null +++ b/library_source/drivers/hardware_specific/esp32_mcu.cpp @@ -0,0 +1,296 @@ +#include "../hardware_api.h" + +#if defined(ESP_H) + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +// empty motor slot +#define _EMPTY_SLOT -20 +#define _TAKEN_SLOT -21 + +// structure containing motor slot configuration +// this library supports up to 4 motors +typedef struct { + int pinA; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; + mcpwm_io_signals_t mcpwm_c; +} bldc_3pwm_motor_slots_t; +typedef struct { + int pin1A; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_1a; + mcpwm_io_signals_t mcpwm_1b; + mcpwm_io_signals_t mcpwm_2a; + mcpwm_io_signals_t mcpwm_2b; +} stepper_motor_slots_t; + +typedef struct { + int pinAH; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_ah; + mcpwm_io_signals_t mcpwm_bh; + mcpwm_io_signals_t mcpwm_ch; + mcpwm_io_signals_t mcpwm_al; + mcpwm_io_signals_t mcpwm_bl; + mcpwm_io_signals_t mcpwm_cl; +} bldc_6pwm_motor_slots_t; + +// define bldc motor slots array +bldc_3pwm_motor_slots_t esp32_bldc_3pwm_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B + }; + +// define stepper motor slots array +stepper_motor_slots_t esp32_stepper_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + }; + +// define stepper motor slots array +bldc_6pwm_motor_slots_t esp32_bldc_6pwm_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0 + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0 + }; + +// configuring high frequency pwm timer +// a lot of help from this post from Paul Gauld +// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller +void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit, float dead_zone = NOT_SET){ + + mcpwm_config_t pwm_config; + pwm_config.frequency = pwm_frequency; //frequency + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + if (dead_zone != NOT_SET){ + // dead zone is configured in dead_time x 100 nanoseconds + float dead_time = (float)(1e7 / pwm_frequency) * dead_zone; + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); + } + + _delay(100); + + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 0; +} + + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(2*pwm_frequency, 0, 100000); // constrain to 50kHz max - centered pwm has twice lower frequency + + bldc_3pwm_motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + int slot_num; + for(slot_num = 0; slot_num < 4; slot_num++){ + if(esp32_bldc_3pwm_motor_slots[slot_num].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_3pwm_motor_slots[slot_num].pinA = pinA; + m_slot = esp32_bldc_3pwm_motor_slots[slot_num]; + break; + } + } + // disable all the slots with the same MCPWM + if( slot_num < 2 ){ + // slot 0 of the stepper + esp32_stepper_motor_slots[0].pin1A = _TAKEN_SLOT; + // slot 0 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; + }else{ + // slot 1 of the stepper + esp32_stepper_motor_slots[1].pin1A = _TAKEN_SLOT; + // slot 1 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; + } + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + +} + + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(2*pwm_frequency, 0, 100000); // constrain to 50kHz max - centered pwm has twice lower frequency + stepper_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + int slot_num; + for(slot_num = 0; slot_num < 2; slot_num++){ + if(esp32_stepper_motor_slots[slot_num].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_motor_slots[slot_num].pin1A = pinA; + m_slot = esp32_stepper_motor_slots[slot_num]; + break; + } + } + // disable all the slots with the same MCPWM + if( slot_num == 0 ){ + // slots 0 and 1 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT; + // slot 0 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; + }else{ + // slots 2 and 3 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT; + // slot 1 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); +} + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +// ESP32 uses MCPWM +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_bldc_3pwm_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,100] + mcpwm_set_duty(esp32_bldc_3pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_bldc_3pwm_motor_slots[i].mcpwm_operator, dc_a*100.0); + mcpwm_set_duty(esp32_bldc_3pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_bldc_3pwm_motor_slots[i].mcpwm_operator, dc_b*100.0); + mcpwm_set_duty(esp32_bldc_3pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, esp32_bldc_3pwm_motor_slots[i].mcpwm_operator, dc_c*100.0); + break; + } + } +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +// ESP32 uses MCPWM +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,100] + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_motor_slots[i].mcpwm_operator1, dc_1a*100.0); + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_motor_slots[i].mcpwm_operator1, dc_1b*100.0); + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_motor_slots[i].mcpwm_operator2, dc_2a*100.0); + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_motor_slots[i].mcpwm_operator2, dc_2b*100.0); + break; + } + } +} + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency + bldc_6pwm_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + int slot_num; + for(slot_num = 0; slot_num < 2; slot_num++){ + if(esp32_bldc_6pwm_motor_slots[slot_num].pinAH == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_6pwm_motor_slots[slot_num].pinAH = pinA_h; + m_slot = esp32_bldc_6pwm_motor_slots[slot_num]; + break; + } + } + // if no slots available + if(slot_num >= 2) return -1; + + // disable all the slots with the same MCPWM + if( slot_num == 0 ){ + // slots 0 and 1 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT; + // slot 0 of the 6pwm bldc + esp32_stepper_motor_slots[0].pin1A = _TAKEN_SLOT; + }else{ + // slots 2 and 3 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT; + // slot 1 of the 6pwm bldc + esp32_stepper_motor_slots[1].pin1A = _TAKEN_SLOT; + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_ah, pinA_h); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_al, pinA_l); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_bh, pinB_h); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_bl, pinB_l); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_ch, pinC_h); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_cl, pinC_l); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit, dead_zone); + // return + return 0; +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_bldc_6pwm_motor_slots[i].pinAH == pinA_h){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,100.0] + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_A, dc_a*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_B, dc_a*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_A, dc_b*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_B, dc_b*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_A, dc_c*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_B, dc_c*100.0); + break; + } + } +} +#endif \ No newline at end of file diff --git a/library_source/drivers/hardware_specific/generic_mcu.cpp b/library_source/drivers/hardware_specific/generic_mcu.cpp new file mode 100644 index 00000000..dc322746 --- /dev/null +++ b/library_source/drivers/hardware_specific/generic_mcu.cpp @@ -0,0 +1,68 @@ +#include "../hardware_api.h" + +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if mcu is not atmega328 + +#elif defined(__arm__) && defined(CORE_TEENSY) // or teensy + +#elif defined(ESP_H) // or esp32 + +#elif defined(_STM32_DEF_) // or stm32 + +#else + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +// in generic case dont do anything +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + return; +} + + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +// in generic case dont do anything +void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) { + return; +} + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + return -1; +} + + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); + analogWrite(pinC, 255.0*dc_c); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255.0*dc_1a); + analogWrite(pin1B, 255.0*dc_1b); + analogWrite(pin2A, 255.0*dc_2a); + analogWrite(pin2B, 255.0*dc_2b); +} + + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + return; +} + + +#endif \ No newline at end of file diff --git a/library_source/drivers/hardware_specific/stm32_mcu.cpp b/library_source/drivers/hardware_specific/stm32_mcu.cpp new file mode 100644 index 00000000..85d0bd65 --- /dev/null +++ b/library_source/drivers/hardware_specific/stm32_mcu.cpp @@ -0,0 +1,291 @@ + +#include "../hardware_api.h" + +#if defined(_STM32_DEF_) + +#define _PWM_RESOLUTION 12 // 12bit +#define _PWM_RANGE 4095.0// 2^12 -1 = 4095 +#define _PWM_FREQUENCY 50000 // 50khz + + +#define _HARDWARE_6PWM 1 +#define _SOFTWARE_6PWM 0 +#define _ERROR_6PWM -1 + + +// setting pwm to hardware pin - instead analogWrite() +void _setPwm(int ulPin, uint32_t value, int resolution) +{ + PinName pin = digitalPinToPinName(ulPin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); + uint32_t index = get_timer_index(Instance); + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HT->setCaptureCompare(channel, value, (TimerCompareFormat_t)resolution); +} + + +// init pin pwm +HardwareTimer* _initPinPWM(uint32_t PWM_freq, int ulPin) +{ + PinName pin = digitalPinToPinName(ulPin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); + + uint32_t index = get_timer_index(Instance); + if (HardwareTimer_Handle[index] == NULL) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM)); + HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); + } + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, pin); + HT->setOverflow(PWM_freq, HERTZ_FORMAT); + HT->pause(); + HT->refresh(); + return HT; +} + + +// init high side pin +HardwareTimer* _initPinPWMHigh(uint32_t PWM_freq, int ulPin) +{ + return _initPinPWM(PWM_freq, ulPin); +} + +// init low side pin +HardwareTimer* _initPinPWMLow(uint32_t PWM_freq, int ulPin) +{ + PinName pin = digitalPinToPinName(ulPin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); + uint32_t index = get_timer_index(Instance); + + if (HardwareTimer_Handle[index] == NULL) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM)); + HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); + TIM_OC_InitTypeDef sConfigOC = TIM_OC_InitTypeDef(); + sConfigOC.OCMode = TIM_OCMODE_PWM2; + sConfigOC.Pulse = 100; + sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW; + sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH; + sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; + sConfigOC.OCIdleState = TIM_OCIDLESTATE_SET; + sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET; + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HAL_TIM_PWM_ConfigChannel(&(HardwareTimer_Handle[index]->handle), &sConfigOC, channel); + } + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM2, pin); + HT->setOverflow(PWM_freq, HERTZ_FORMAT); + HT->pause(); + HT->refresh(); + return HT; +} + + +// align the timers to end the init +void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3) +{ + HT1->pause(); + HT1->refresh(); + HT2->pause(); + HT2->refresh(); + HT3->pause(); + HT3->refresh(); + HT1->resume(); + HT2->resume(); + HT3->resume(); +} + +// align the timers to end the init +void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3,HardwareTimer *HT4) +{ + HT1->pause(); + HT1->refresh(); + HT2->pause(); + HT2->refresh(); + HT3->pause(); + HT3->refresh(); + HT4->pause(); + HT4->refresh(); + HT1->resume(); + HT2->resume(); + HT3->resume(); + HT4->resume(); +} + +HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l) +{ + PinName uhPinName = digitalPinToPinName(pinA_h); + PinName ulPinName = digitalPinToPinName(pinA_l); + PinName vhPinName = digitalPinToPinName(pinB_h); + PinName vlPinName = digitalPinToPinName(pinB_l); + PinName whPinName = digitalPinToPinName(pinC_h); + PinName wlPinName = digitalPinToPinName(pinC_l); + + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM); + + uint32_t index = get_timer_index(Instance); + + if (HardwareTimer_Handle[index] == NULL) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM)); + HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); + ((HardwareTimer *)HardwareTimer_Handle[index]->__this)->setOverflow(PWM_freq, HERTZ_FORMAT); + } + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + + HT->setMode(STM_PIN_CHANNEL(pinmap_function(uhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, uhPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(ulPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, ulPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(vhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vhPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(vlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vlPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(whPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, whPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(wlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, wlPinName); + + // dead time is set in nanoseconds + uint32_t dead_time_ns = (float)(1e9/PWM_freq)*dead_zone; + uint32_t dead_time = __LL_TIM_CALC_DEADTIME(SystemCoreClock, LL_TIM_GetClockDivision(HT->getHandle()->Instance), dead_time_ns); + LL_TIM_OC_SetDeadTime(HT->getHandle()->Instance, dead_time); // deadtime is non linear! + LL_TIM_CC_EnableChannel(HT->getHandle()->Instance, LL_TIM_CHANNEL_CH1 | LL_TIM_CHANNEL_CH1N | LL_TIM_CHANNEL_CH2 | LL_TIM_CHANNEL_CH2N | LL_TIM_CHANNEL_CH3 | LL_TIM_CHANNEL_CH3N); + + HT->pause(); + HT->refresh(); + HT->resume(); + return HT; +} + + +// returns 0 if each pair of pwm channels has same channel +// returns 1 all the channels belong to the same timer - hardware inverted channels +// returns -1 if neither - avoid configuring - error!!! +int _interfaceType(const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + PinName nameAH = digitalPinToPinName(pinA_h); + PinName nameAL = digitalPinToPinName(pinA_l); + PinName nameBH = digitalPinToPinName(pinB_h); + PinName nameBL = digitalPinToPinName(pinB_l); + PinName nameCH = digitalPinToPinName(pinC_h); + PinName nameCL = digitalPinToPinName(pinC_l); + int tim1 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAH, PinMap_PWM)); + int tim2 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAL, PinMap_PWM)); + int tim3 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBH, PinMap_PWM)); + int tim4 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBL, PinMap_PWM)); + int tim5 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCH, PinMap_PWM)); + int tim6 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCL, PinMap_PWM)); + if(tim1 == tim2 && tim2==tim3 && tim3==tim4 && tim4==tim5 && tim5==tim6) + return _HARDWARE_6PWM; // hardware 6pwm interface - only on timer + else if(tim1 == tim2 && tim3==tim4 && tim5==tim6) + return _SOFTWARE_6PWM; // software 6pwm interface - each pair of high-low side same timer + else + return _ERROR_6PWM; // might be error avoid configuration +} + + + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); + HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); + HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); + // allign the timers + _alignPWMTimers(HT1, HT2, HT3); +} + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); + HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); + HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); + HardwareTimer* HT4 = _initPinPWM(pwm_frequency, pinD); + // allign the timers + _alignPWMTimers(HT1, HT2, HT3, HT4); +} + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +//- hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,4095] + _setPwm(pinA, _PWM_RANGE*dc_a, _PWM_RESOLUTION); + _setPwm(pinB, _PWM_RANGE*dc_b, _PWM_RESOLUTION); + _setPwm(pinC, _PWM_RANGE*dc_c, _PWM_RESOLUTION); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +//- hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,4095] + _setPwm(pin1A, _PWM_RANGE*dc_1a, _PWM_RESOLUTION); + _setPwm(pin1B, _PWM_RANGE*dc_1b, _PWM_RESOLUTION); + _setPwm(pin2A, _PWM_RANGE*dc_2a, _PWM_RESOLUTION); + _setPwm(pin2B, _PWM_RANGE*dc_2b, _PWM_RESOLUTION); +} + + + + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, 100000); // constrain to 100kHz max + + // find configuration + int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); + // configure accordingly + switch(config){ + case _ERROR_6PWM: + return -1; // fail + break; + case _HARDWARE_6PWM: + _initHardware6PWMInterface(pwm_frequency, dead_zone, pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); + break; + case _SOFTWARE_6PWM: + HardwareTimer* HT1 = _initPinPWMHigh(pwm_frequency, pinA_h); + _initPinPWMLow(pwm_frequency, pinA_l); + HardwareTimer* HT2 = _initPinPWMHigh(pwm_frequency,pinB_h); + _initPinPWMLow(pwm_frequency, pinB_l); + HardwareTimer* HT3 = _initPinPWMHigh(pwm_frequency,pinC_h); + _initPinPWMLow(pwm_frequency, pinC_l); + _alignPWMTimers(HT1, HT2, HT3); + break; + } + return 0; // success +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + // find configuration + int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); + // set pwm accordingly + switch(config){ + case _HARDWARE_6PWM: + _setPwm(pinA_h, _PWM_RANGE*dc_a, _PWM_RESOLUTION); + _setPwm(pinB_h, _PWM_RANGE*dc_b, _PWM_RESOLUTION); + _setPwm(pinC_h, _PWM_RANGE*dc_c, _PWM_RESOLUTION); + break; + case _SOFTWARE_6PWM: + _setPwm(pinA_l, _constrain(dc_a + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinA_h, _constrain(dc_a - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinB_l, _constrain(dc_b + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinB_h, _constrain(dc_b - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinC_l, _constrain(dc_c + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinC_h, _constrain(dc_c - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + break; + } +} +#endif \ No newline at end of file diff --git a/library_source/drivers/hardware_specific/teensy_mcu.cpp b/library_source/drivers/hardware_specific/teensy_mcu.cpp new file mode 100644 index 00000000..10bd24c5 --- /dev/null +++ b/library_source/drivers/hardware_specific/teensy_mcu.cpp @@ -0,0 +1,71 @@ +#include "../hardware_api.h" + +#if defined(__arm__) && defined(CORE_TEENSY) + +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(pin, freq); +} + + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor +} + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + _setHighFrequency(pwm_frequency, pinD); +} + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); + analogWrite(pinC, 255.0*dc_c); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255.0*dc_1a); + analogWrite(pin1B, 255.0*dc_1b); + analogWrite(pin2A, 255.0*dc_2a); + analogWrite(pin2B, 255.0*dc_2b); +} + + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + return -1; +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + return; +} +#endif \ No newline at end of file diff --git a/library_source/Encoder.cpp b/library_source/sensors/Encoder.cpp similarity index 100% rename from library_source/Encoder.cpp rename to library_source/sensors/Encoder.cpp diff --git a/library_source/Encoder.h b/library_source/sensors/Encoder.h similarity index 96% rename from library_source/Encoder.h rename to library_source/sensors/Encoder.h index d1a55f0e..29122888 100644 --- a/library_source/Encoder.h +++ b/library_source/sensors/Encoder.h @@ -2,9 +2,9 @@ #define ENCODER_LIB_H #include "Arduino.h" -#include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#include "../common/base_classes/Sensor.h" /** diff --git a/library_source/sensors/HallSensor.cpp b/library_source/sensors/HallSensor.cpp new file mode 100644 index 00000000..47dc53d0 --- /dev/null +++ b/library_source/sensors/HallSensor.cpp @@ -0,0 +1,161 @@ +#include "HallSensor.h" + + +/* + HallSensor(int hallA, int hallB , int cpr, int index) + - hallA, hallB, hallC - HallSensor A, B and C pins + - pp - pole pairs +*/ +HallSensor::HallSensor(int _hallA, int _hallB, int _hallC, int _pp){ + + // hardware pins + pinA = _hallA; + pinB = _hallB; + pinC = _hallC; + + // hall has 6 segments per electrical revolution + cpr = _pp * 6; + + // extern pullup as default + pullup = Pullup::EXTERN; +} + +// HallSensor interrupt callback functions +// A channel +void HallSensor::handleA() { + A_active= digitalRead(pinA); + updateState(); +} +// B channel +void HallSensor::handleB() { + B_active = digitalRead(pinB); + updateState(); +} + +// C channel +void HallSensor::handleC() { + C_active = digitalRead(pinC); + updateState(); +} + +/** + * Updates the state and sector following an interrupt + */ +void HallSensor::updateState() { + long new_pulse_timestamp = _micros(); + hall_state = C_active + (B_active << 1) + (A_active << 2); + int8_t new_electric_sector = ELECTRIC_SECTORS[hall_state]; + if (new_electric_sector - electric_sector > 3) { + //underflow + direction = static_cast(natural_direction * -1); + electric_rotations += direction; + } else if (new_electric_sector - electric_sector < (-3)) { + //overflow + direction = static_cast(natural_direction); + electric_rotations += direction; + } else { + direction = (new_electric_sector > electric_sector)? static_cast(natural_direction) : static_cast(natural_direction * (-1)); + } + electric_sector = new_electric_sector; + pulse_diff = new_pulse_timestamp - pulse_timestamp; + pulse_timestamp = new_pulse_timestamp; + total_interrupts++; + if (onSectorChange != nullptr) onSectorChange(electric_sector); +} + +/** + * Optionally set a function callback to be fired when sector changes + * void onSectorChange(int sector) { + * ... // for debug or call driver directly? + * } + * sensor.attachSectorCallback(onSectorChange); + */ +void HallSensor::attachSectorCallback(void (*_onSectorChange)(int sector)) { + onSectorChange = _onSectorChange; +} + +/* + Shaft angle calculation +*/ +float HallSensor::getAngle() { + return natural_direction * ((electric_rotations * 6 + electric_sector) / cpr) * _2PI; +} + +/* + Shaft velocity calculation + function using mixed time and frequency measurement technique +*/ +float HallSensor::getVelocity(){ + + if (pulse_diff == 0 || ((_micros() - pulse_timestamp) > STALE_HALL_DATA_MICROS) ) { // last velocity isn't accurate if too old + return 0; + } else { + return direction * (_2PI / cpr) / (pulse_diff / 1000000.0); + } + +} + +// getter for index pin +// return -1 if no index +int HallSensor::needsAbsoluteZeroSearch(){ + return 0; +} + +int HallSensor::hasAbsoluteZero(){ + return 1; +} + +// set current angle as zero angle +// return the angle [rad] difference +float HallSensor::initRelativeZero(){ + + // nothing to do. The interrupts should have changed sector. + electric_rotations = 0; + return 0; + +} + +// set absolute zero angle as zero angle +// return the angle [rad] difference +float HallSensor::initAbsoluteZero(){ + + return -getAngle(); + +} + +// HallSensor initialisation of the hardware pins +// and calculation variables +void HallSensor::init(){ + + // HallSensor - check if pullup needed for your HallSensor + if(pullup == Pullup::INTERN){ + pinMode(pinA, INPUT_PULLUP); + pinMode(pinB, INPUT_PULLUP); + pinMode(pinC, INPUT_PULLUP); + }else{ + pinMode(pinA, INPUT); + pinMode(pinB, INPUT); + pinMode(pinC, INPUT); + } + + // init hall_state + A_active= digitalRead(pinA); + B_active = digitalRead(pinB); + C_active = digitalRead(pinC); + updateState(); + + pulse_timestamp = _micros(); + +} + +// function enabling hardware interrupts for the callback provided +// if callback is not provided then the interrupt is not enabled +void HallSensor::enableInterrupts(void (*doA)(), void(*doB)(), void(*doC)()){ + // attach interrupt if functions provided + + // A, B and C callback + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); + if(doC != nullptr) attachInterrupt(digitalPinToInterrupt(pinC), doC, CHANGE); +} + diff --git a/library_source/HallSensor.h b/library_source/sensors/HallSensor.h similarity index 75% rename from library_source/HallSensor.h rename to library_source/sensors/HallSensor.h index 9b467b0a..0eb42286 100644 --- a/library_source/HallSensor.h +++ b/library_source/sensors/HallSensor.h @@ -2,10 +2,16 @@ #define HALL_SENSOR_LIB_H #include "Arduino.h" -#include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "../common/base_classes/Sensor.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#ifndef STALE_HALL_DATA_MICROS + #define STALE_HALL_DATA_MICROS 500000 +#endif + +// seq 1 > 5 > 4 > 6 > 2 > 3 > 1 000 001 010 011 100 101 110 111 +const int8_t ELECTRIC_SECTORS[8] = { -1, 0, 4, 5, 2, 1, 3 , -1 }; class HallSensor: public Sensor{ public: @@ -81,26 +87,32 @@ class HallSensor: public Sensor{ // whether last step was CW (+1) or CCW (-1) direction Direction direction; - // the current 3bit state of the hall sensors - int state; + void attachSectorCallback(void (*onSectorChange)(int a) = nullptr); - volatile float angle; // rad/s - volatile float velocity; // rad/s + // the current 3bit state of the hall sensors + volatile int8_t hall_state; + // the current sector of the sensor. Each sector is 60deg electrical + volatile int8_t electric_sector; + // the number of electric rotations + volatile long electric_rotations; + // this is sometimes useful to identify interrupt issues (e.g. weak or no pullup resulting in 1000s of interrupts) + volatile long total_interrupts; private: Direction decodeDirection(int oldState, int newState); void updateState(); - volatile long pulse_counter;//!< current pulse counter + int zero_offset; volatile long pulse_timestamp;//!< last impulse timestamp in us volatile int A_active; //!< current active states of A channel volatile int B_active; //!< current active states of B channel volatile int C_active; //!< current active states of C channel - // velocity calculation variables - // float prev_Th, pulse_per_second; - volatile long prev_pulse_counter, prev_timestamp_us; + // function pointer for on sector change call back + void (*onSectorChange)(int sector) = nullptr; + + volatile long pulse_diff; }; diff --git a/library_source/MagneticSensorAnalog.cpp b/library_source/sensors/MagneticSensorAnalog.cpp similarity index 100% rename from library_source/MagneticSensorAnalog.cpp rename to library_source/sensors/MagneticSensorAnalog.cpp diff --git a/library_source/MagneticSensorAnalog.h b/library_source/sensors/MagneticSensorAnalog.h similarity index 95% rename from library_source/MagneticSensorAnalog.h rename to library_source/sensors/MagneticSensorAnalog.h index cfe1b905..d76b6eb4 100644 --- a/library_source/MagneticSensorAnalog.h +++ b/library_source/sensors/MagneticSensorAnalog.h @@ -2,9 +2,9 @@ #define MAGNETICSENSORANALOG_LIB_H #include "Arduino.h" -#include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "../common/base_classes/Sensor.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" /** * This sensor has been tested with AS5600 running in 'analog mode'. This is where output pin of AS6000 is connected to an analog pin on your microcontroller. diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/MagneticSensorI2C.cpp b/library_source/sensors/MagneticSensorI2C.cpp similarity index 79% rename from minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/MagneticSensorI2C.cpp rename to library_source/sensors/MagneticSensorI2C.cpp index a02b762b..accce08a 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/MagneticSensorI2C.cpp +++ b/library_source/sensors/MagneticSensorI2C.cpp @@ -3,7 +3,6 @@ /** Typical configuration for the 12bit AMS AS5600 magnetic sensor over I2C interface */ MagneticSensorI2CConfig_s AS5600_I2C = { .chip_address = 0x36, - .clock_speed = 1000000, .bit_resolution = 12, .angle_register = 0x0E, .data_start_bit = 11 @@ -12,7 +11,6 @@ MagneticSensorI2CConfig_s AS5600_I2C = { /** Typical configuration for the 12bit AMS AS5048 magnetic sensor over I2C interface */ MagneticSensorI2CConfig_s AS5048_I2C = { .chip_address = 0x40, // highly configurable. if A1 and A2 are held low, this is probable value - .clock_speed = 1000000, .bit_resolution = 14, .angle_register = 0xFE, .data_start_bit = 15 @@ -41,10 +39,7 @@ MagneticSensorI2C::MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, // extraction masks lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); msb_mask = (uint8_t)( (2 << _bits_used_msb) - 1 ); - clock_speed = 400000; - sda_pin = SDA; - scl_pin = SCL; - + wire = &Wire; } MagneticSensorI2C::MagneticSensorI2C(MagneticSensorI2CConfig_s config){ @@ -60,29 +55,16 @@ MagneticSensorI2C::MagneticSensorI2C(MagneticSensorI2CConfig_s config){ // extraction masks lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); msb_mask = (uint8_t)( (2 << bits_used_msb) - 1 ); - clock_speed = 400000; - sda_pin = SDA; - scl_pin = SCL; - + wire = &Wire; } -void MagneticSensorI2C::init(){ +void MagneticSensorI2C::init(TwoWire* _wire){ + + wire = _wire; -#if defined(_STM32_DEF_) // if stm chips // I2C communication begin - Wire.begin(); - Wire.setClock(clock_speed); - Wire.setSCL(scl_pin); - Wire.setSDA(sda_pin); -#elif defined(ESP_H) // if esp32 - //I2C communication begin - Wire.begin(sda_pin, scl_pin, clock_speed); -#else - // I2C communication begin - Wire.begin(); - Wire.setClock(clock_speed); -#endif - + wire->begin(); + // velocity calculation init angle_prev = 0; velocity_calc_timestamp = _micros(); @@ -187,14 +169,14 @@ int MagneticSensorI2C::read(uint8_t angle_reg_msb) { byte readArray[2]; uint16_t readValue = 0; // notify the device that is aboout to be read - Wire.beginTransmission(chip_address); - Wire.write(angle_reg_msb); - Wire.endTransmission(false); + wire->beginTransmission(chip_address); + wire->write(angle_reg_msb); + wire->endTransmission(false); // read the data msb and lsb - Wire.requestFrom(chip_address, (uint8_t)2); + wire->requestFrom(chip_address, (uint8_t)2); for (byte i=0; i < 2; i++) { - readArray[i] = Wire.read(); + readArray[i] = wire->read(); } // depending on the sensor architecture there are different combinations of @@ -205,3 +187,46 @@ int MagneticSensorI2C::read(uint8_t angle_reg_msb) { readValue += ( ( readArray[0] & msb_mask ) << lsb_used ); return readValue; } + +/* +* Checks whether other devices have locked the bus. Can clear SDA locks. +* This should be called before sensor.init() on devices that suffer i2c slaves locking sda +* e.g some stm32 boards with AS5600 chips +* Takes the sda_pin and scl_pin +* Returns 0 for OK, 1 for other master and 2 for unfixable sda locked LOW +*/ +int MagneticSensorI2C::checkBus(byte sda_pin, byte scl_pin) { + + pinMode(scl_pin, INPUT_PULLUP); + pinMode(sda_pin, INPUT_PULLUP); + delay(250); + + if (digitalRead(scl_pin) == LOW) { + // Someone else has claimed master!"); + return 1; + } + + if(digitalRead(sda_pin) == LOW) { + // slave is communicating and awaiting clocks, we are blocked + pinMode(scl_pin, OUTPUT); + for (byte i = 0; i < 16; i++) { + // toggle clock for 2 bytes of data + digitalWrite(scl_pin, LOW); + delayMicroseconds(20); + digitalWrite(scl_pin, HIGH); + delayMicroseconds(20); + } + pinMode(sda_pin, INPUT); + delayMicroseconds(20); + if (digitalRead(sda_pin) == LOW) { + // SDA still blocked + return 2; + } + _delay(1000); + } + // SDA is clear (HIGH) + pinMode(sda_pin, INPUT); + pinMode(scl_pin, INPUT); + + return 0; +} diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/MagneticSensorI2C.h b/library_source/sensors/MagneticSensorI2C.h similarity index 88% rename from minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/MagneticSensorI2C.h rename to library_source/sensors/MagneticSensorI2C.h index 88d74d35..7fe4efeb 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/MagneticSensorI2C.h +++ b/library_source/sensors/MagneticSensorI2C.h @@ -3,13 +3,12 @@ #include "Arduino.h" #include -#include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "../common/base_classes/Sensor.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" struct MagneticSensorI2CConfig_s { int chip_address; - long clock_speed; int bit_resolution; int angle_register; int data_start_bit; @@ -37,7 +36,7 @@ class MagneticSensorI2C: public Sensor{ static MagneticSensorI2C AS5600(); /** sensor initialise pins */ - void init(); + void init(TwoWire* _wire = &Wire); // implementation of abstract functions of the Sensor class /** get current angle (rad) */ @@ -60,14 +59,8 @@ class MagneticSensorI2C: public Sensor{ int needsAbsoluteZeroSearch() override; - /* the speed of the i2c clock signal */ - long clock_speed; - - /* the pin used for i2c data */ - int sda_pin; - - /* the pin used for i2c clock */ - int scl_pin; + /** experimental function to check and fix SDA locked LOW issues */ + int checkBus(byte sda_pin = SDA, byte scl_pin = SCL); private: float cpr; //!< Maximum range of the magnetic sensor @@ -98,6 +91,10 @@ class MagneticSensorI2C: public Sensor{ float angle_prev; //!< angle in previous velocity calculation step long velocity_calc_timestamp; //!< last velocity calculation timestamp + /* the two wire instance for this sensor */ + TwoWire* wire; + + }; diff --git a/library_source/MagneticSensorSPI.cpp b/library_source/sensors/MagneticSensorSPI.cpp similarity index 93% rename from library_source/MagneticSensorSPI.cpp rename to library_source/sensors/MagneticSensorSPI.cpp index 1f63bc11..58660e0b 100644 --- a/library_source/MagneticSensorSPI.cpp +++ b/library_source/sensors/MagneticSensorSPI.cpp @@ -5,7 +5,7 @@ MagneticSensorSPIConfig_s AS5147_SPI = { .spi_mode = SPI_MODE1, .clock_speed = 1000000, .bit_resolution = 14, - .angle_register = 0xCFFF, + .angle_register = 0x3FFF, .data_start_bit = 13, .command_rw_bit = 14, .command_parity_bit = 15 @@ -31,7 +31,7 @@ MagneticSensorSPI::MagneticSensorSPI(int cs, float _bit_resolution, int _angle_r chip_select_pin = cs; // angle read register of the magnetic sensor - angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTAR; + angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTER; // register maximum value (counts per revolution) cpr = pow(2,_bit_resolution); spi_mode = SPI_MODE1; @@ -47,7 +47,7 @@ MagneticSensorSPI::MagneticSensorSPI(int cs, float _bit_resolution, int _angle_r MagneticSensorSPI::MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs){ chip_select_pin = cs; // angle read register of the magnetic sensor - angle_register = config.angle_register ? config.angle_register : DEF_ANGLE_REGISTAR; + angle_register = config.angle_register ? config.angle_register : DEF_ANGLE_REGISTER; // register maximum value (counts per revolution) cpr = pow(2, config.bit_resolution); spi_mode = config.spi_mode; @@ -59,7 +59,10 @@ MagneticSensorSPI::MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs){ data_start_bit = config.data_start_bit; // for backwards compatibilty } -void MagneticSensorSPI::init(){ +void MagneticSensorSPI::init(SPIClass* _spi){ + + spi = _spi; + // 1MHz clock (AMS should be able to accept up to 10MHz) settings = SPISettings(clock_speed, MSBFIRST, spi_mode); @@ -67,11 +70,11 @@ void MagneticSensorSPI::init(){ pinMode(chip_select_pin, OUTPUT); //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices - SPI.begin(); + spi->begin(); #ifndef ESP_H // if not ESP32 board - SPI.setBitOrder(MSBFIRST); // Set the SPI_1 bit order - SPI.setDataMode(spi_mode) ; - SPI.setClockDivider(SPI_CLOCK_DIV8); + spi->setBitOrder(MSBFIRST); // Set the SPI_1 bit order + spi->setDataMode(spi_mode) ; + spi->setClockDivider(SPI_CLOCK_DIV8); #endif digitalWrite(chip_select_pin, HIGH); @@ -203,13 +206,13 @@ word MagneticSensorSPI::read(word angle_register){ #if !defined(_STM32_DEF_) // if not stm chips //SPI - begin transaction - SPI.beginTransaction(settings); + spi->beginTransaction(settings); #endif //Send the command digitalWrite(chip_select_pin, LOW); digitalWrite(chip_select_pin, LOW); - SPI.transfer16(command); + spi->transfer16(command); digitalWrite(chip_select_pin,HIGH); digitalWrite(chip_select_pin,HIGH); @@ -222,18 +225,18 @@ word MagneticSensorSPI::read(word angle_register){ //Now read the response digitalWrite(chip_select_pin, LOW); digitalWrite(chip_select_pin, LOW); - word register_value = SPI.transfer16(0x00); + word register_value = spi->transfer16(0x00); digitalWrite(chip_select_pin, HIGH); digitalWrite(chip_select_pin,HIGH); #if !defined(_STM32_DEF_) // if not stm chips //SPI - end transaction - SPI.endTransaction(); + spi->endTransaction(); #endif register_value = register_value >> (1 + data_start_bit - bit_resolution); //this should shift data to the rightmost bits of the word - const static word data_mask = ~(0 >> (16 - bit_resolution)); + const static word data_mask = 0xFFFF >> (16 - bit_resolution); return register_value & data_mask; // Return the data, stripping the non data (e.g parity) bits } @@ -243,5 +246,5 @@ word MagneticSensorSPI::read(word angle_register){ * SPI has an internal SPI-device counter, for each init()-call the close() function must be called exactly 1 time */ void MagneticSensorSPI::close(){ - SPI.end(); + spi->end(); } diff --git a/library_source/MagneticSensorSPI.h b/library_source/sensors/MagneticSensorSPI.h similarity index 94% rename from library_source/MagneticSensorSPI.h rename to library_source/sensors/MagneticSensorSPI.h index 8e884cf4..05fb9091 100644 --- a/library_source/MagneticSensorSPI.h +++ b/library_source/sensors/MagneticSensorSPI.h @@ -3,11 +3,11 @@ #include "Arduino.h" #include -#include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "../common/base_classes/Sensor.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" -#define DEF_ANGLE_REGISTAR 0x3FFF +#define DEF_ANGLE_REGISTER 0x3FFF struct MagneticSensorSPIConfig_s { int spi_mode; @@ -38,7 +38,7 @@ class MagneticSensorSPI: public Sensor{ MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs); /** sensor initialise pins */ - void init(); + void init(SPIClass* _spi = &SPI); // implementation of abstract functions of the Sensor class /** get current angle (rad) */ @@ -103,6 +103,7 @@ class MagneticSensorSPI: public Sensor{ int command_rw_bit; //!< the bit where read/write flag is stored in command int data_start_bit; //!< the the position of first bit + SPIClass* spi; }; diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/hardware_utils.cpp deleted file mode 100644 index 0d080bab..00000000 --- a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/hardware_utils.cpp +++ /dev/null @@ -1,284 +0,0 @@ -#include "hardware_utils.h" - -#if defined(ESP_H) // if ESP32 board -// empty motor slot -#define _EMPTY_SLOT -20 - -// structure containing motor slot configuration -// this library supports up to 4 motors -typedef struct { - int pinA; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator; - mcpwm_io_signals_t mcpwm_a; - mcpwm_io_signals_t mcpwm_b; - mcpwm_io_signals_t mcpwm_c; -} bldc_motor_slots_t; -typedef struct { - int pin1A; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator1; - mcpwm_operator_t mcpwm_operator2; - mcpwm_io_signals_t mcpwm_1a; - mcpwm_io_signals_t mcpwm_1b; - mcpwm_io_signals_t mcpwm_2a; - mcpwm_io_signals_t mcpwm_2b; -} stepper_motor_slots_t; - -// define bldc motor slots array -bldc_motor_slots_t esp32_bldc_motor_slots[4] = { - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B - }; - -// define stepper motor slots array -stepper_motor_slots_t esp32_stepper_motor_slots[2] = { - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 - }; - -// configuring high frequency pwm timer -// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller -void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ - - mcpwm_config_t pwm_config; - pwm_config.frequency = pwm_frequency; //frequency - pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% - pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% - pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) - pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH - mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings - - _delay(100); - - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); - mcpwm_num->clk_cfg.prescale = 0; - - mcpwm_num->timer[0].period.prescale = 4; - mcpwm_num->timer[1].period.prescale = 4; - mcpwm_num->timer[2].period.prescale = 4; - _delay(1); - mcpwm_num->timer[0].period.period = 2048; - mcpwm_num->timer[1].period.period = 2048; - mcpwm_num->timer[2].period.period = 2048; - _delay(1); - mcpwm_num->timer[0].period.upmethod = 0; - mcpwm_num->timer[1].period.upmethod = 0; - mcpwm_num->timer[2].period.upmethod = 0; - _delay(1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); - - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 1; - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 0; -} - -#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips -// set pwm frequency to 32KHz -void _pinHighFrequency(const int pin){ - // High PWM frequency - // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pin == 5 || pin == 6 ) { - TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode - TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - } - if (pin == 9 || pin == 10 ) - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pin == 3 || pin == 11) - TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 - -} -#elif defined(_STM32_DEF_) // if stm chips -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); - analogWriteResolution(12); // resolution 12 bit 0 - 4096 -} -#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); -} -#endif - - -// function setting the high pwm frequency to the supplied pins -// - hardware speciffic -// supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips - // High PWM frequency - // - always max 32kHz - _pinHighFrequency(pinA); - _pinHighFrequency(pinB); - _pinHighFrequency(pinC); - if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor - -#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards - if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz - else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max - _setHighFrequency(pwm_frequency, pinA); - _setHighFrequency(pwm_frequency, pinB); - _setHighFrequency(pwm_frequency, pinC); - if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor - -#elif defined(ESP_H) // if esp32 boards - if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency - - if(pinD == NOT_SET){ - bldc_motor_slots_t m_slot = {}; - - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_bldc_motor_slots[i].pinA = pinA; - m_slot = esp32_bldc_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - - }else{ - stepper_motor_slots_t m_slot = {}; - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_stepper_motor_slots[i].pin1A = pinA; - m_slot = esp32_stepper_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - } -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pinA, 4095.0*dc_a); - analogWrite(pinB, 4095.0*dc_b); - analogWrite(pinC, 4095.0*dc_c); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255*dc_a); - analogWrite(pinB, 255*dc_b); - analogWrite(pinC, 255*dc_c); -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pin1A, 4095.0*dc_1a); - analogWrite(pin1B, 4095.0*dc_1b); - analogWrite(pin2A, 4095.0*dc_2a); - analogWrite(pin2B, 4095.0*dc_2b); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255*dc_1a); - analogWrite(pin1B, 255*dc_1b); - analogWrite(pin2A, 255*dc_2a); - analogWrite(pin2B, 255*dc_2b); -#endif -} - - -// function buffering delay() -// arduino uno function doesn't work well with interrupts -void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) - // if arduino uno and other atmega328p chips - // use while instad of delay, - // due to wrong measurement based on changed timer0 - unsigned long t = _micros() + ms*1000; - while( _micros() < t ){}; -#else - // regular micros - delay(ms); -#endif -} - - -// function buffering _micros() -// arduino function doesn't work well with interrupts -unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) -// if arduino uno and other atmega328p chips - //return the value based on the prescaler - if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); - else return (micros()); -#else - // regular micros - return micros(); -#endif -} diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/hardware_utils.h b/minimal_project_examples/arduino_foc_bldc_encoder/src/common/hardware_utils.h deleted file mode 100644 index f99c260a..00000000 --- a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/hardware_utils.h +++ /dev/null @@ -1,72 +0,0 @@ -#ifndef HARDWARE_UTILS_H -#define HARDWARE_UTILS_H - -#include "Arduino.h" -#include "foc_utils.h" - - -#if defined(ESP_H) // if esp32 boards - -#include "driver/mcpwm.h" -#include "soc/mcpwm_reg.h" -#include "soc/mcpwm_struct.h" - -#endif - -/** - * High PWM frequency setting function - * - hardware specific - * - * @param pwm_frequency - frequency in hertz - if applicable - * @param pinA pinA bldc motor or pin1A stepper motor - * @param pinB pinB bldc motor or pin1B stepper motor - * @param pinC pinC bldc motor or pin2A stepper motor - * @param pinD pin2B stepper motor - */ -void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_a duty cycle phase A [0, 1] - * @param dc_b duty cycle phase B [0, 1] - * @param dc_c duty cycle phase C [0, 1] - * @param pinA phase A hardware pin number - * @param pinB phase B hardware pin number - * @param pinC phase C hardware pin number - */ -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_1a duty cycle phase 1A [0, 1] - * @param dc_1b duty cycle phase 1B [0, 1] - * @param dc_2a duty cycle phase 2A [0, 1] - * @param dc_2b duty cycle phase 2B [0, 1] - * @param pin1A phase 1A hardware pin number - * @param pin1B phase 1B hardware pin number - * @param pin2A phase 2A hardware pin number - * @param pin2B phase 2B hardware pin number - */ -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); - -/** - * Function implementing delay() function in milliseconds - * - blocking function - * - hardware specific - - * @param ms number of milliseconds to wait - */ -void _delay(unsigned long ms); - -/** - * Function implementing timestamp getting function in microseconds - * hardware specific - */ -unsigned long _micros(); - - -#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/HallSensor.cpp b/minimal_project_examples/arduino_foc_bldc_hall/src/HallSensor.cpp deleted file mode 100644 index 7072a97a..00000000 --- a/minimal_project_examples/arduino_foc_bldc_hall/src/HallSensor.cpp +++ /dev/null @@ -1,186 +0,0 @@ -#include "HallSensor.h" - - -/* - HallSensor(int hallA, int hallB , int cpr, int index) - - hallA, hallB, hallC - HallSensor A, B and C pins - - pp - pole pairs -*/ - -HallSensor::HallSensor(int _hallA, int _hallB, int _hallC, int _pp){ - - // HallSensor measurement structure init - // hardware pins - pinA = _hallA; - pinB = _hallB; - pinC = _hallC; - // counter setup - pulse_counter = 0; - pulse_timestamp = 0; - - cpr = _pp * 6; // hall has 6 segments per electrical revolution - A_active = 0; - B_active = 0; - C_active = 0; - - // velocity calculation variables - - prev_pulse_counter = 0; - prev_timestamp_us = _micros(); - - // extern pullup as default - pullup = Pullup::EXTERN; -} - -// HallSensor interrupt callback functions -// A channel -void HallSensor::handleA() { - A_active= digitalRead(pinA); - updateState(); -} -// B channel -void HallSensor::handleB() { - B_active = digitalRead(pinB); - updateState(); -} - -// C channel -void HallSensor::handleC() { - C_active = digitalRead(pinC); - updateState(); -} - -void HallSensor::updateState() { - int newState = C_active + (B_active << 1) + (A_active << 2); - Direction direction = decodeDirection(state, newState); - state = newState; - - pulse_counter += direction; - pulse_timestamp = _micros(); -} - -// determines whether the hallsensr state transition means that it has moved one step CW (+1), CCW (-1) or state transition is invalid (0) -// states are 3bits, one for each hall sensor -Direction HallSensor::decodeDirection(int oldState, int newState) -{ - // here are expected state transitions (oldState > newState). - // CW state transitions are: ( 6 > 2 > 3 > 1 > 5 > 4 > 6 ) - // CCW state transitions are: ( 6 > 4 > 5 > 1 > 3 > 2 > 6 ) - // invalid state transitions are oldState == newState or if newState or oldState == 0 | 7 as hallsensors can't be all on or all off - - int rawDirection; - - if ( - (oldState == 6 && newState == 2) || \ - (oldState == 2 && newState == 3) || \ - (oldState == 3 && newState == 1) || \ - (oldState == 1 && newState == 5) || \ - (oldState == 5 && newState == 4) || \ - (oldState == 4 && newState == 6) - ) { - rawDirection = Direction::CW; - } else if( - (oldState == 6 && newState == 4) || \ - (oldState == 4 && newState == 5) || \ - (oldState == 5 && newState == 1) || \ - (oldState == 1 && newState == 3) || \ - (oldState == 3 && newState == 2) || \ - (oldState == 2 && newState == 6) - ) { - rawDirection = Direction::CCW; - } else { - rawDirection = Direction::UNKNOWN; - } - - direction = static_cast(rawDirection * natural_direction); - return direction; // * goofy; -} - -/* - Shaft angle calculation -*/ -float HallSensor::getAngle(){ - - long dN = pulse_counter - prev_pulse_counter; - - if (dN != 0) - { - - // time from last impulse - float Th = (pulse_timestamp - prev_timestamp_us) * 1e-6; - if (Th <= 0 || Th > 0.5) - Th = 1e-3; - // save variables for next pass - prev_timestamp_us = pulse_timestamp; - prev_pulse_counter = pulse_counter; - velocity = (float) _2PI * dN / (cpr * Th); - } - angle = (float) _2PI * pulse_counter / cpr; - - return angle; -} -/* - Shaft velocity calculation - function using mixed time and frequency measurement technique -*/ -float HallSensor::getVelocity(){ - // this is calculated during the last call to getAngle(); - return velocity; -} - -// getter for index pin -// return -1 if no index -int HallSensor::needsAbsoluteZeroSearch(){ - return 0; -} -// getter for index pin -int HallSensor::hasAbsoluteZero(){ - return 0; -} -// initialize counter to zero -float HallSensor::initRelativeZero(){ - - pulse_counter = 0; - pulse_timestamp = _micros(); - velocity = 0; - return 0.0; -} -// initialize index to zero -float HallSensor::initAbsoluteZero(){ - return 0.0; -} - -// HallSensor initialisation of the hardware pins -// and calculation variables -void HallSensor::init(){ - - // HallSensor - check if pullup needed for your HallSensor - if(pullup == Pullup::INTERN){ - pinMode(pinA, INPUT_PULLUP); - pinMode(pinB, INPUT_PULLUP); - pinMode(pinC, INPUT_PULLUP); - }else{ - pinMode(pinA, INPUT); - pinMode(pinB, INPUT); - pinMode(pinC, INPUT); - } - - // counter setup - pulse_counter = 0; - pulse_timestamp = _micros(); - prev_pulse_counter = 0; - prev_timestamp_us = _micros(); - -} - -// function enabling hardware interrupts for the callback provided -// if callback is not provided then the interrupt is not enabled -void HallSensor::enableInterrupts(void (*doA)(), void(*doB)(), void(*doC)()){ - // attach interrupt if functions provided - - // A, B and C callback - if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); - if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); - if(doC != nullptr) attachInterrupt(digitalPinToInterrupt(pinC), doC, CHANGE); -} - diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_bldc_hall/src/common/hardware_utils.cpp deleted file mode 100644 index 0d080bab..00000000 --- a/minimal_project_examples/arduino_foc_bldc_hall/src/common/hardware_utils.cpp +++ /dev/null @@ -1,284 +0,0 @@ -#include "hardware_utils.h" - -#if defined(ESP_H) // if ESP32 board -// empty motor slot -#define _EMPTY_SLOT -20 - -// structure containing motor slot configuration -// this library supports up to 4 motors -typedef struct { - int pinA; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator; - mcpwm_io_signals_t mcpwm_a; - mcpwm_io_signals_t mcpwm_b; - mcpwm_io_signals_t mcpwm_c; -} bldc_motor_slots_t; -typedef struct { - int pin1A; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator1; - mcpwm_operator_t mcpwm_operator2; - mcpwm_io_signals_t mcpwm_1a; - mcpwm_io_signals_t mcpwm_1b; - mcpwm_io_signals_t mcpwm_2a; - mcpwm_io_signals_t mcpwm_2b; -} stepper_motor_slots_t; - -// define bldc motor slots array -bldc_motor_slots_t esp32_bldc_motor_slots[4] = { - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B - }; - -// define stepper motor slots array -stepper_motor_slots_t esp32_stepper_motor_slots[2] = { - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 - }; - -// configuring high frequency pwm timer -// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller -void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ - - mcpwm_config_t pwm_config; - pwm_config.frequency = pwm_frequency; //frequency - pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% - pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% - pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) - pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH - mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings - - _delay(100); - - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); - mcpwm_num->clk_cfg.prescale = 0; - - mcpwm_num->timer[0].period.prescale = 4; - mcpwm_num->timer[1].period.prescale = 4; - mcpwm_num->timer[2].period.prescale = 4; - _delay(1); - mcpwm_num->timer[0].period.period = 2048; - mcpwm_num->timer[1].period.period = 2048; - mcpwm_num->timer[2].period.period = 2048; - _delay(1); - mcpwm_num->timer[0].period.upmethod = 0; - mcpwm_num->timer[1].period.upmethod = 0; - mcpwm_num->timer[2].period.upmethod = 0; - _delay(1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); - - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 1; - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 0; -} - -#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips -// set pwm frequency to 32KHz -void _pinHighFrequency(const int pin){ - // High PWM frequency - // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pin == 5 || pin == 6 ) { - TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode - TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - } - if (pin == 9 || pin == 10 ) - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pin == 3 || pin == 11) - TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 - -} -#elif defined(_STM32_DEF_) // if stm chips -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); - analogWriteResolution(12); // resolution 12 bit 0 - 4096 -} -#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); -} -#endif - - -// function setting the high pwm frequency to the supplied pins -// - hardware speciffic -// supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips - // High PWM frequency - // - always max 32kHz - _pinHighFrequency(pinA); - _pinHighFrequency(pinB); - _pinHighFrequency(pinC); - if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor - -#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards - if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz - else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max - _setHighFrequency(pwm_frequency, pinA); - _setHighFrequency(pwm_frequency, pinB); - _setHighFrequency(pwm_frequency, pinC); - if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor - -#elif defined(ESP_H) // if esp32 boards - if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency - - if(pinD == NOT_SET){ - bldc_motor_slots_t m_slot = {}; - - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_bldc_motor_slots[i].pinA = pinA; - m_slot = esp32_bldc_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - - }else{ - stepper_motor_slots_t m_slot = {}; - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_stepper_motor_slots[i].pin1A = pinA; - m_slot = esp32_stepper_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - } -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pinA, 4095.0*dc_a); - analogWrite(pinB, 4095.0*dc_b); - analogWrite(pinC, 4095.0*dc_c); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255*dc_a); - analogWrite(pinB, 255*dc_b); - analogWrite(pinC, 255*dc_c); -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pin1A, 4095.0*dc_1a); - analogWrite(pin1B, 4095.0*dc_1b); - analogWrite(pin2A, 4095.0*dc_2a); - analogWrite(pin2B, 4095.0*dc_2b); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255*dc_1a); - analogWrite(pin1B, 255*dc_1b); - analogWrite(pin2A, 255*dc_2a); - analogWrite(pin2B, 255*dc_2b); -#endif -} - - -// function buffering delay() -// arduino uno function doesn't work well with interrupts -void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) - // if arduino uno and other atmega328p chips - // use while instad of delay, - // due to wrong measurement based on changed timer0 - unsigned long t = _micros() + ms*1000; - while( _micros() < t ){}; -#else - // regular micros - delay(ms); -#endif -} - - -// function buffering _micros() -// arduino function doesn't work well with interrupts -unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) -// if arduino uno and other atmega328p chips - //return the value based on the prescaler - if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); - else return (micros()); -#else - // regular micros - return micros(); -#endif -} diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/common/hardware_utils.h b/minimal_project_examples/arduino_foc_bldc_hall/src/common/hardware_utils.h deleted file mode 100644 index f99c260a..00000000 --- a/minimal_project_examples/arduino_foc_bldc_hall/src/common/hardware_utils.h +++ /dev/null @@ -1,72 +0,0 @@ -#ifndef HARDWARE_UTILS_H -#define HARDWARE_UTILS_H - -#include "Arduino.h" -#include "foc_utils.h" - - -#if defined(ESP_H) // if esp32 boards - -#include "driver/mcpwm.h" -#include "soc/mcpwm_reg.h" -#include "soc/mcpwm_struct.h" - -#endif - -/** - * High PWM frequency setting function - * - hardware specific - * - * @param pwm_frequency - frequency in hertz - if applicable - * @param pinA pinA bldc motor or pin1A stepper motor - * @param pinB pinB bldc motor or pin1B stepper motor - * @param pinC pinC bldc motor or pin2A stepper motor - * @param pinD pin2B stepper motor - */ -void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_a duty cycle phase A [0, 1] - * @param dc_b duty cycle phase B [0, 1] - * @param dc_c duty cycle phase C [0, 1] - * @param pinA phase A hardware pin number - * @param pinB phase B hardware pin number - * @param pinC phase C hardware pin number - */ -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_1a duty cycle phase 1A [0, 1] - * @param dc_1b duty cycle phase 1B [0, 1] - * @param dc_2a duty cycle phase 2A [0, 1] - * @param dc_2b duty cycle phase 2B [0, 1] - * @param pin1A phase 1A hardware pin number - * @param pin1B phase 1B hardware pin number - * @param pin2A phase 2A hardware pin number - * @param pin2B phase 2B hardware pin number - */ -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); - -/** - * Function implementing delay() function in milliseconds - * - blocking function - * - hardware specific - - * @param ms number of milliseconds to wait - */ -void _delay(unsigned long ms); - -/** - * Function implementing timestamp getting function in microseconds - * hardware specific - */ -unsigned long _micros(); - - -#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.cpp deleted file mode 100644 index 0d080bab..00000000 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.cpp +++ /dev/null @@ -1,284 +0,0 @@ -#include "hardware_utils.h" - -#if defined(ESP_H) // if ESP32 board -// empty motor slot -#define _EMPTY_SLOT -20 - -// structure containing motor slot configuration -// this library supports up to 4 motors -typedef struct { - int pinA; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator; - mcpwm_io_signals_t mcpwm_a; - mcpwm_io_signals_t mcpwm_b; - mcpwm_io_signals_t mcpwm_c; -} bldc_motor_slots_t; -typedef struct { - int pin1A; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator1; - mcpwm_operator_t mcpwm_operator2; - mcpwm_io_signals_t mcpwm_1a; - mcpwm_io_signals_t mcpwm_1b; - mcpwm_io_signals_t mcpwm_2a; - mcpwm_io_signals_t mcpwm_2b; -} stepper_motor_slots_t; - -// define bldc motor slots array -bldc_motor_slots_t esp32_bldc_motor_slots[4] = { - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B - }; - -// define stepper motor slots array -stepper_motor_slots_t esp32_stepper_motor_slots[2] = { - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 - }; - -// configuring high frequency pwm timer -// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller -void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ - - mcpwm_config_t pwm_config; - pwm_config.frequency = pwm_frequency; //frequency - pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% - pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% - pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) - pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH - mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings - - _delay(100); - - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); - mcpwm_num->clk_cfg.prescale = 0; - - mcpwm_num->timer[0].period.prescale = 4; - mcpwm_num->timer[1].period.prescale = 4; - mcpwm_num->timer[2].period.prescale = 4; - _delay(1); - mcpwm_num->timer[0].period.period = 2048; - mcpwm_num->timer[1].period.period = 2048; - mcpwm_num->timer[2].period.period = 2048; - _delay(1); - mcpwm_num->timer[0].period.upmethod = 0; - mcpwm_num->timer[1].period.upmethod = 0; - mcpwm_num->timer[2].period.upmethod = 0; - _delay(1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); - - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 1; - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 0; -} - -#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips -// set pwm frequency to 32KHz -void _pinHighFrequency(const int pin){ - // High PWM frequency - // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pin == 5 || pin == 6 ) { - TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode - TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - } - if (pin == 9 || pin == 10 ) - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pin == 3 || pin == 11) - TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 - -} -#elif defined(_STM32_DEF_) // if stm chips -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); - analogWriteResolution(12); // resolution 12 bit 0 - 4096 -} -#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); -} -#endif - - -// function setting the high pwm frequency to the supplied pins -// - hardware speciffic -// supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips - // High PWM frequency - // - always max 32kHz - _pinHighFrequency(pinA); - _pinHighFrequency(pinB); - _pinHighFrequency(pinC); - if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor - -#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards - if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz - else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max - _setHighFrequency(pwm_frequency, pinA); - _setHighFrequency(pwm_frequency, pinB); - _setHighFrequency(pwm_frequency, pinC); - if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor - -#elif defined(ESP_H) // if esp32 boards - if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency - - if(pinD == NOT_SET){ - bldc_motor_slots_t m_slot = {}; - - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_bldc_motor_slots[i].pinA = pinA; - m_slot = esp32_bldc_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - - }else{ - stepper_motor_slots_t m_slot = {}; - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_stepper_motor_slots[i].pin1A = pinA; - m_slot = esp32_stepper_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - } -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pinA, 4095.0*dc_a); - analogWrite(pinB, 4095.0*dc_b); - analogWrite(pinC, 4095.0*dc_c); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255*dc_a); - analogWrite(pinB, 255*dc_b); - analogWrite(pinC, 255*dc_c); -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pin1A, 4095.0*dc_1a); - analogWrite(pin1B, 4095.0*dc_1b); - analogWrite(pin2A, 4095.0*dc_2a); - analogWrite(pin2B, 4095.0*dc_2b); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255*dc_1a); - analogWrite(pin1B, 255*dc_1b); - analogWrite(pin2A, 255*dc_2a); - analogWrite(pin2B, 255*dc_2b); -#endif -} - - -// function buffering delay() -// arduino uno function doesn't work well with interrupts -void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) - // if arduino uno and other atmega328p chips - // use while instad of delay, - // due to wrong measurement based on changed timer0 - unsigned long t = _micros() + ms*1000; - while( _micros() < t ){}; -#else - // regular micros - delay(ms); -#endif -} - - -// function buffering _micros() -// arduino function doesn't work well with interrupts -unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) -// if arduino uno and other atmega328p chips - //return the value based on the prescaler - if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); - else return (micros()); -#else - // regular micros - return micros(); -#endif -} diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.h b/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.h deleted file mode 100644 index f99c260a..00000000 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/hardware_utils.h +++ /dev/null @@ -1,72 +0,0 @@ -#ifndef HARDWARE_UTILS_H -#define HARDWARE_UTILS_H - -#include "Arduino.h" -#include "foc_utils.h" - - -#if defined(ESP_H) // if esp32 boards - -#include "driver/mcpwm.h" -#include "soc/mcpwm_reg.h" -#include "soc/mcpwm_struct.h" - -#endif - -/** - * High PWM frequency setting function - * - hardware specific - * - * @param pwm_frequency - frequency in hertz - if applicable - * @param pinA pinA bldc motor or pin1A stepper motor - * @param pinB pinB bldc motor or pin1B stepper motor - * @param pinC pinC bldc motor or pin2A stepper motor - * @param pinD pin2B stepper motor - */ -void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_a duty cycle phase A [0, 1] - * @param dc_b duty cycle phase B [0, 1] - * @param dc_c duty cycle phase C [0, 1] - * @param pinA phase A hardware pin number - * @param pinB phase B hardware pin number - * @param pinC phase C hardware pin number - */ -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_1a duty cycle phase 1A [0, 1] - * @param dc_1b duty cycle phase 1B [0, 1] - * @param dc_2a duty cycle phase 2A [0, 1] - * @param dc_2b duty cycle phase 2B [0, 1] - * @param pin1A phase 1A hardware pin number - * @param pin1B phase 1B hardware pin number - * @param pin2A phase 2A hardware pin number - * @param pin2B phase 2B hardware pin number - */ -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); - -/** - * Function implementing delay() function in milliseconds - * - blocking function - * - hardware specific - - * @param ms number of milliseconds to wait - */ -void _delay(unsigned long ms); - -/** - * Function implementing timestamp getting function in microseconds - * hardware specific - */ -unsigned long _micros(); - - -#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.cpp b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.cpp deleted file mode 100644 index adecbeec..00000000 --- a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.cpp +++ /dev/null @@ -1,245 +0,0 @@ -#include "FOCMotor.h" - -/** - * Default constructor - setting all variabels to default values - */ -FOCMotor::FOCMotor() -{ - // Power supply voltage - voltage_power_supply = DEF_POWER_SUPPLY; - - // maximum angular velocity to be used for positioning - velocity_limit = DEF_VEL_LIM; - // maximum voltage to be set to the motor - voltage_limit = voltage_power_supply; - - // index search velocity - velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; - // sensor and motor align voltage - voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; - - // electric angle of comthe zero angle - zero_electric_angle = 0; - - // default modulation is SinePWM - foc_modulation = FOCModulationType::SinePWM; - - // default target value - target = 0; - - //monitor_port - monitor_port = nullptr; - //sensor - sensor = nullptr; -} - - -/** - Sensor communication methods -*/ -void FOCMotor::linkSensor(Sensor* _sensor) { - sensor = _sensor; -} -// shaft angle calculation -float FOCMotor::shaftAngle() { - // if no sensor linked return 0 - if(!sensor) return shaft_angle; - return sensor->getAngle(); -} -// shaft velocity calculation -float FOCMotor::shaftVelocity() { - // if no sensor linked return 0 - if(!sensor) return 0; - return LPF_velocity(sensor->getVelocity()); -} - - - - -/** - * Monitoring functions - */ -// function implementing the monitor_port setter -void FOCMotor::useMonitoring(Print &print){ - monitor_port = &print; //operate on the address of print - if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); -} -// utility function intended to be used with serial plotter to monitor motor variables -// significantly slowing the execution down!!!! -void FOCMotor::monitor() { - if(!monitor_port) return; - switch (controller) { - case ControlType::velocity_openloop: - case ControlType::velocity: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_velocity_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - case ControlType::angle_openloop: - case ControlType::angle: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle_sp); - monitor_port->print("\t"); - monitor_port->println(shaft_angle); - break; - case ControlType::voltage: - monitor_port->print(voltage_q); - monitor_port->print("\t"); - monitor_port->print(shaft_angle); - monitor_port->print("\t"); - monitor_port->println(shaft_velocity); - break; - } -} - -int FOCMotor::command(String user_command) { - // error flag - int errorFlag = 1; - // if empty string - if(user_command.length() < 1) return errorFlag; - - // parse command letter - char cmd = user_command.charAt(0); - // check if get command - char GET = user_command.charAt(1) == '\n'; - // parse command values - float value = user_command.substring(1).toFloat(); - - // a bit of optimisation of variable memory for Arduino UNO (atmega328) - switch(cmd){ - case 'P': // velocity P gain change - case 'I': // velocity I gain change - case 'D': // velocity D gain change - case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print(" PID velocity| "); - break; - case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print(" LPF velocity| "); - break; - case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print(" P angle| "); - break; - case 'L': // velocity voltage limit change - case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print(" Limits| "); - break; - } - - // apply the the command - switch(cmd){ - case 'P': // velocity P gain change - if(monitor_port) monitor_port->print("P: "); - if(!GET) PID_velocity.P = value; - if(monitor_port) monitor_port->println(PID_velocity.P); - break; - case 'I': // velocity I gain change - if(monitor_port) monitor_port->print("I: "); - if(!GET) PID_velocity.I = value; - if(monitor_port) monitor_port->println(PID_velocity.I); - break; - case 'D': // velocity D gain change - if(monitor_port) monitor_port->print("D: "); - if(!GET) PID_velocity.D = value; - if(monitor_port) monitor_port->println(PID_velocity.D); - break; - case 'R': // velocity voltage ramp change - if(monitor_port) monitor_port->print("volt_ramp: "); - if(!GET) PID_velocity.output_ramp = value; - if(monitor_port) monitor_port->println(PID_velocity.output_ramp); - break; - case 'L': // velocity voltage limit change - if(monitor_port) monitor_port->print("volt_limit: "); - if(!GET) { - voltage_limit = value; - PID_velocity.limit = value; - } - if(monitor_port) monitor_port->println(voltage_limit); - break; - case 'F': // velocity Tf low pass filter change - if(monitor_port) monitor_port->print("Tf: "); - if(!GET) LPF_velocity.Tf = value; - if(monitor_port) monitor_port->println(LPF_velocity.Tf); - break; - case 'K': // angle loop gain P change - if(monitor_port) monitor_port->print(" P: "); - if(!GET) P_angle.P = value; - if(monitor_port) monitor_port->println(P_angle.P); - break; - case 'N': // angle loop gain velocity_limit change - if(monitor_port) monitor_port->print("vel_limit: "); - if(!GET){ - velocity_limit = value; - P_angle.limit = value; - } - if(monitor_port) monitor_port->println(velocity_limit); - break; - case 'C': - // change control type - if(monitor_port) monitor_port->print("Control: "); - - if(GET){ // if get command - switch(controller){ - case ControlType::voltage: - if(monitor_port) monitor_port->println("voltage"); - break; - case ControlType::velocity: - if(monitor_port) monitor_port->println("velocity"); - break; - case ControlType::angle: - if(monitor_port) monitor_port->println("angle"); - break; - default: - if(monitor_port) monitor_port->println("open loop"); - } - }else{ // if set command - switch((int)value){ - case 0: - if(monitor_port) monitor_port->println("voltage"); - controller = ControlType::voltage; - break; - case 1: - if(monitor_port) monitor_port->println("velocity"); - controller = ControlType::velocity; - break; - case 2: - if(monitor_port) monitor_port->println("angle"); - controller = ControlType::angle; - break; - default: // not valid command - errorFlag = 0; - } - } - break; - case 'V': // get current values of the state variables - switch((int)value){ - case 0: // get voltage - if(monitor_port) monitor_port->print("Uq: "); - if(monitor_port) monitor_port->println(voltage_q); - break; - case 1: // get velocity - if(monitor_port) monitor_port->print("Velocity: "); - if(monitor_port) monitor_port->println(shaft_velocity); - break; - case 2: // get angle - if(monitor_port) monitor_port->print("Angle: "); - if(monitor_port) monitor_port->println(shaft_angle); - break; - case 3: // get angle - if(monitor_port) monitor_port->print("Target: "); - if(monitor_port) monitor_port->println(target); - break; - default: // not valid command - errorFlag = 0; - } - break; - default: // target change - if(monitor_port) monitor_port->print("Target : "); - target = user_command.toFloat(); - if(monitor_port) monitor_port->println(target); - } - // return 0 if error and 1 if ok - return errorFlag; -} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.h b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.h deleted file mode 100644 index 40f7f6d4..00000000 --- a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/FOCMotor.h +++ /dev/null @@ -1,195 +0,0 @@ -#ifndef FOCMOTOR_H -#define FOCMOTOR_H - -#include "Arduino.h" -#include "hardware_utils.h" -#include "foc_utils.h" -#include "defaults.h" - -#include "Sensor.h" -#include "pid.h" -#include "lowpass_filter.h" - - -/** - * Motiron control type - */ -enum ControlType{ - voltage,//!< Torque control using voltage - velocity,//!< Velocity motion control - angle,//!< Position/angle motion control - velocity_openloop, - angle_openloop -}; - -/** - * FOC modulation type - */ -enum FOCModulationType{ - SinePWM, //!< Sinusoidal PWM modulation - SpaceVectorPWM //!< Space vector modulation method -}; - -/** - Generic motor class -*/ -class FOCMotor -{ - public: - /** - * Default constructor - setting all variabels to default values - */ - FOCMotor(); - - /** Motor hardware init function */ - virtual void init(long pwm_frequency)=0; - /** Motor disable function */ - virtual void disable()=0; - /** Motor enable function */ - virtual void enable()=0; - - /** - * Function linking a motor and a sensor - * - * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity - */ - void linkSensor(Sensor* sensor); - - /** - * Function initializing FOC algorithm - * and aligning sensor's and motors' zero position - * - * - If zero_electric_offset parameter is set the alignment procedure is skipped - * - * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. - * @param sensor_direction sensor natural direction - default is CW - * - */ - virtual int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW)=0; - /** - * Function running FOC algorithm in real-time - * it calculates the gets motor angle and sets the appropriate voltages - * to the phase pwm signals - * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us - */ - virtual void loopFOC()=0; - /** - * Function executing the control loops set by the controller parameter of the BLDCMotor. - * - * @param target Either voltage, angle or velocity based on the motor.controller - * If it is not set the motor will use the target set in its variable motor.target - * - * This function doesn't need to be run upon each loop execution - depends of the use case - */ - virtual void move(float target = NOT_SET)=0; - - // State calculation methods - /** Shaft angle calculation in radians [rad] */ - float shaftAngle(); - /** - * Shaft angle calculation function in radian per second [rad/s] - * It implements low pass filtering - */ - float shaftVelocity(); - - // state variables - float target; //!< current target value - depends of the controller - float shaft_angle;//!< current motor angle - float shaft_velocity;//!< current motor velocity - float shaft_velocity_sp;//!< current target velocity - float shaft_angle_sp;//!< current target angle - float voltage_q;//!< current voltage u_q set - float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor - float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform - - // motor configuration parameters - float voltage_power_supply;//!< Power supply voltage - float voltage_sensor_align;//!< sensor and motor align voltage parameter - float velocity_index_search;//!< target velocity for index search - int pole_pairs;//!< Motor pole pairs number - - // limiting variables - float voltage_limit; //!< Voltage limitting variable - global limit - float velocity_limit; //!< Velocity limitting variable - global limit - - float zero_electric_angle;//!clk_cfg.prescale = 0; - - mcpwm_num->timer[0].period.prescale = 4; - mcpwm_num->timer[1].period.prescale = 4; - mcpwm_num->timer[2].period.prescale = 4; - _delay(1); - mcpwm_num->timer[0].period.period = 2048; - mcpwm_num->timer[1].period.period = 2048; - mcpwm_num->timer[2].period.period = 2048; - _delay(1); - mcpwm_num->timer[0].period.upmethod = 0; - mcpwm_num->timer[1].period.upmethod = 0; - mcpwm_num->timer[2].period.upmethod = 0; - _delay(1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); - - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 1; - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 0; -} - -#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips -// set pwm frequency to 32KHz -void _pinHighFrequency(const int pin){ - // High PWM frequency - // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pin == 5 || pin == 6 ) { - TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode - TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - } - if (pin == 9 || pin == 10 ) - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pin == 3 || pin == 11) - TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 - -} -#elif defined(_STM32_DEF_) // if stm chips -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); - analogWriteResolution(12); // resolution 12 bit 0 - 4096 -} -#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); -} -#endif - - -// function setting the high pwm frequency to the supplied pins -// - hardware speciffic -// supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips - // High PWM frequency - // - always max 32kHz - _pinHighFrequency(pinA); - _pinHighFrequency(pinB); - _pinHighFrequency(pinC); - if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor - -#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards - if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz - else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max - _setHighFrequency(pwm_frequency, pinA); - _setHighFrequency(pwm_frequency, pinB); - _setHighFrequency(pwm_frequency, pinC); - if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor - -#elif defined(ESP_H) // if esp32 boards - if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency - - if(pinD == NOT_SET){ - bldc_motor_slots_t m_slot = {}; - - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_bldc_motor_slots[i].pinA = pinA; - m_slot = esp32_bldc_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - - }else{ - stepper_motor_slots_t m_slot = {}; - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_stepper_motor_slots[i].pin1A = pinA; - m_slot = esp32_stepper_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - } -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pinA, 4095.0*dc_a); - analogWrite(pinB, 4095.0*dc_b); - analogWrite(pinC, 4095.0*dc_c); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255*dc_a); - analogWrite(pinB, 255*dc_b); - analogWrite(pinC, 255*dc_c); -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pin1A, 4095.0*dc_1a); - analogWrite(pin1B, 4095.0*dc_1b); - analogWrite(pin2A, 4095.0*dc_2a); - analogWrite(pin2B, 4095.0*dc_2b); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255*dc_1a); - analogWrite(pin1B, 255*dc_1b); - analogWrite(pin2A, 255*dc_2a); - analogWrite(pin2B, 255*dc_2b); -#endif -} - - -// function buffering delay() -// arduino uno function doesn't work well with interrupts -void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) - // if arduino uno and other atmega328p chips - // use while instad of delay, - // due to wrong measurement based on changed timer0 - unsigned long t = _micros() + ms*1000; - while( _micros() < t ){}; -#else - // regular micros - delay(ms); -#endif -} - - -// function buffering _micros() -// arduino function doesn't work well with interrupts -unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) -// if arduino uno and other atmega328p chips - //return the value based on the prescaler - if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); - else return (micros()); -#else - // regular micros - return micros(); -#endif -} diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/hardware_utils.h b/minimal_project_examples/arduino_foc_bldc_openloop/src/common/hardware_utils.h deleted file mode 100644 index f99c260a..00000000 --- a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/hardware_utils.h +++ /dev/null @@ -1,72 +0,0 @@ -#ifndef HARDWARE_UTILS_H -#define HARDWARE_UTILS_H - -#include "Arduino.h" -#include "foc_utils.h" - - -#if defined(ESP_H) // if esp32 boards - -#include "driver/mcpwm.h" -#include "soc/mcpwm_reg.h" -#include "soc/mcpwm_struct.h" - -#endif - -/** - * High PWM frequency setting function - * - hardware specific - * - * @param pwm_frequency - frequency in hertz - if applicable - * @param pinA pinA bldc motor or pin1A stepper motor - * @param pinB pinB bldc motor or pin1B stepper motor - * @param pinC pinC bldc motor or pin2A stepper motor - * @param pinD pin2B stepper motor - */ -void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_a duty cycle phase A [0, 1] - * @param dc_b duty cycle phase B [0, 1] - * @param dc_c duty cycle phase C [0, 1] - * @param pinA phase A hardware pin number - * @param pinB phase B hardware pin number - * @param pinC phase C hardware pin number - */ -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_1a duty cycle phase 1A [0, 1] - * @param dc_1b duty cycle phase 1B [0, 1] - * @param dc_2a duty cycle phase 2A [0, 1] - * @param dc_2b duty cycle phase 2B [0, 1] - * @param pin1A phase 1A hardware pin number - * @param pin1B phase 1B hardware pin number - * @param pin2A phase 2A hardware pin number - * @param pin2B phase 2B hardware pin number - */ -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); - -/** - * Function implementing delay() function in milliseconds - * - blocking function - * - hardware specific - - * @param ms number of milliseconds to wait - */ -void _delay(unsigned long ms); - -/** - * Function implementing timestamp getting function in microseconds - * hardware specific - */ -unsigned long _micros(); - - -#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/arduino_foc_bldc_encoder.ino b/minimal_project_examples/atmega328_bldc_encoder/atmega328_bldc_encoder.ino similarity index 87% rename from minimal_project_examples/arduino_foc_bldc_encoder/arduino_foc_bldc_encoder.ino rename to minimal_project_examples/atmega328_bldc_encoder/atmega328_bldc_encoder.ino index e7a8a26b..5a9e2e98 100644 --- a/minimal_project_examples/arduino_foc_bldc_encoder/arduino_foc_bldc_encoder.ino +++ b/minimal_project_examples/atmega328_bldc_encoder/atmega328_bldc_encoder.ino @@ -32,24 +32,26 @@ * - V: get motor variables * - 0: currently set voltage * - 1: current velocity - * - 2: current angle + * - 2: current anglex * - 3: current target value * */ #include "src/BLDCMotor.h" -#include "src/Encoder.h" +#include "src/sensors/Encoder.h" +#include "src/drivers/BLDCDriver3PWM.h" + +// BLDC motor & driver instance +BLDCMotor motor = BLDCMotor(11); +BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8); -// motor instance -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 7); -// // encoder instance -Encoder encoder = Encoder(2,3, 2048); +Encoder encoder = Encoder(2, 3, 500); // Interrupt routine intialisation // channel A and B callbacks void doA(){encoder.handleA();} void doB(){encoder.handleB();} - + void setup() { // initialize encoder sensor hardware @@ -58,12 +60,18 @@ void setup() { // link the motor to the sensor motor.linkSensor(&encoder); + // driver config // power supply voltage [V] - motor.voltage_power_supply = 12; - motor.voltage_sensor_align = 10; + driver.voltage_power_supply = 12; + driver.init(); + // link driver + motor.linkDriver(&driver); + + // choose FOC modulation + motor.foc_modulation = FOCModulationType::SpaceVectorPWM; // set control loop type to be used - motor.controller = ControlType::velocity; + motor.controller = ControlType::voltage; // contoller configuration based on the controll type motor.PID_velocity.P = 0.2; @@ -140,4 +148,4 @@ String serialReceiveUserCommand() { } } return command; -} +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/BLDCMotor.cpp b/minimal_project_examples/atmega328_bldc_encoder/src/BLDCMotor.cpp similarity index 68% rename from minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/BLDCMotor.cpp rename to minimal_project_examples/atmega328_bldc_encoder/src/BLDCMotor.cpp index 989b74a9..bed4cd6a 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/BLDCMotor.cpp +++ b/minimal_project_examples/atmega328_bldc_encoder/src/BLDCMotor.cpp @@ -1,41 +1,39 @@ #include "BLDCMotor.h" -// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// // BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// // - phA, phB, phC - motor A,B,C phase pwm pins +// // - pp - pole pair number +// // - cpr - counts per rotation number (cpm=ppm*4) +// // - enable pin - (optional input) +// BLDCMotor::BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en){ +// noop; +// } + +// BLDCMotor( int pp) // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - cpr - counts per rotation number (cpm=ppm*4) // - enable pin - (optional input) -BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +BLDCMotor::BLDCMotor(int pp) : FOCMotor() { - // Pin initialization - pwmA = phA; - pwmB = phB; - pwmC = phC; + // save pole pairs number pole_pairs = pp; +} - // enable_pin pin - enable_pin = en; +/** + Link the driver which controls the motor +*/ +void BLDCMotor::linkDriver(BLDCDriver* _driver) { + driver = _driver; } - // init hardware pins -void BLDCMotor::init(long pwm_frequency) { - if(monitor_port) monitor_port->println("MOT: Init pins."); - // PWM pins - pinMode(pwmA, OUTPUT); - pinMode(pwmB, OUTPUT); - pinMode(pwmC, OUTPUT); - if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); - - if(monitor_port) monitor_port->println("MOT: PWM config."); - // Increase PWM frequency to 32 kHz - // make silent - _setPwmFrequency(pwm_frequency, pwmA, pwmB, pwmC); - +void BLDCMotor::init() { + if(monitor_port) monitor_port->println("MOT: Initialise variables."); // sanity check for the voltage limit configuration - if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + if(voltage_limit > driver->voltage_limit) voltage_limit = driver->voltage_limit; // constrain voltage for sensor alignment if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; // update the controller limits @@ -44,7 +42,7 @@ void BLDCMotor::init(long pwm_frequency) { _delay(500); // enable motor - if(monitor_port) monitor_port->println("MOT: Enable."); + if(monitor_port) monitor_port->println("MOT: Enable driver."); enable(); _delay(500); } @@ -53,18 +51,18 @@ void BLDCMotor::init(long pwm_frequency) { // disable motor driver void BLDCMotor::disable() { - // disable the driver - if enable_pin pin available - if (enable_pin != NOT_SET) digitalWrite(enable_pin, LOW); // set zero to PWM - setPwm(0, 0, 0); + driver->setPwm(0, 0, 0); + // disable the driver + driver->disable(); } // enable motor driver void BLDCMotor::enable() { + // enable the driver + driver->enable(); // set zero to PWM - setPwm(0, 0, 0); - // enable_pin the driver - if enable_pin pin available - if (enable_pin != NOT_SET) digitalWrite(enable_pin, HIGH); + driver->setPwm(0, 0, 0); } @@ -100,13 +98,13 @@ int BLDCMotor::alignSensor() { float start_angle = shaftAngle(); for (int i = 0; i <=5; i++ ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } float mid_angle = shaftAngle(); for (int i = 5; i >=0; i-- ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } if (mid_angle < start_angle) { @@ -121,7 +119,7 @@ int BLDCMotor::alignSensor() { // set sensor to zero sensor->initRelativeZero(); _delay(500); - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); _delay(200); // find the index if available @@ -153,7 +151,7 @@ int BLDCMotor::absoluteZeroAlign() { } voltage_q = 0; // disable motor - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); // align absolute zero if it has been found if(!sensor->needsAbsoluteZeroSearch()){ @@ -172,7 +170,7 @@ void BLDCMotor::loopFOC() { // shaft angle shaft_angle = shaftAngle(); // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); + setPhaseVoltage(voltage_q, voltage_d, _electricalAngle(shaft_angle,pole_pairs)); } // Iterative function running outer loop of the FOC algorithm @@ -219,15 +217,60 @@ void BLDCMotor::move(float new_target) { } -// Method using FOC to set Uq to the motor at the optimal angle +// Method using FOC to set Uq and Ud to the motor at the optimal angle // Function implementing Space Vector PWM and Sine PWM algorithms // // Function using sine approximation // regular sin + cos ~300us (no memory usaage) // approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { +void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { + + const bool centered = true; + int sector; + float _ca,_sa; + switch (foc_modulation) { + case FOCModulationType::Trapezoid_120 : + // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 5 + static int trap_120_map[6][3] = { + {0,1,-1},{-1,1,0},{-1,0,1},{0,-1,1},{1,-1,0},{1,0,-1} // each is 60 degrees with values for 3 phases of 1=positive -1=negative 0=high-z + }; + // static int trap_120_state = 0; + sector = 6 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes + + Ua = Uq + trap_120_map[sector][0] * Uq; + Ub = Uq + trap_120_map[sector][1] * Uq; + Uc = Uq + trap_120_map[sector][2] * Uq; + + if (centered) { + Ua += (driver->voltage_limit)/2 -Uq; + Ub += (driver->voltage_limit)/2 -Uq; + Uc += (driver->voltage_limit)/2 -Uq; + } + break; + + case FOCModulationType::Trapezoid_150 : + // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 8 + static int trap_150_map[12][3] = { + {0,1,-1},{-1,1,-1},{-1,1,0},{-1,1,1},{-1,0,1},{-1,-1,1},{0,-1,1},{1,-1,1},{1,-1,0},{1,-1,-1},{1,0,-1},{1,1,-1} // each is 30 degrees with values for 3 phases of 1=positive -1=negative 0=high-z + }; + // static int trap_150_state = 0; + sector = 12 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes + + Ua = Uq + trap_150_map[sector][0] * Uq; + Ub = Uq + trap_150_map[sector][1] * Uq; + Uc = Uq + trap_150_map[sector][2] * Uq; + + //center + if (centered) { + Ua += (driver->voltage_limit)/2 -Uq; + Ub += (driver->voltage_limit)/2 -Uq; + Uc += (driver->voltage_limit)/2 -Uq; + } + + break; + case FOCModulationType::SinePWM : // Sinusoidal PWM modulation // Inverse Park + Clarke transformation @@ -235,14 +278,24 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // angle normalization in between 0 and 2pi // only necessary if using _sin and _cos - approximation functions angle_el = _normalizeAngle(angle_el + zero_electric_angle); + _ca = _cos(angle_el); + _sa = _sin(angle_el); // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + Ualpha = _ca * Ud - _sa * Uq; // -sin(angle) * Uq; + Ubeta = _sa * Ud + _ca * Uq; // cos(angle) * Uq; // Clarke transform - Ua = Ualpha + voltage_power_supply/2; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + Ua = Ualpha + driver->voltage_limit/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + driver->voltage_limit/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + driver->voltage_limit/2; + + if (!centered) { + float Umin = min(Ua, min(Ub, Uc)); + Ua -= Umin; + Ub -= Umin; + Uc -= Umin; + } + break; case FOCModulationType::SpaceVectorPWM : @@ -259,15 +312,15 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { angle_el = _normalizeAngle(angle_el + zero_electric_angle + _PI_2); // find the sector we are in currently - int sector = floor(angle_el / _PI_3) + 1; + sector = floor(angle_el / _PI_3) + 1; // calculate the duty cycles - float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; - float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/driver->voltage_limit; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/driver->voltage_limit; // two versions possible - // centered around voltage_power_supply/2 - float T0 = 1 - T1 - T2; - // pulled to 0 - better for low power supply voltage - //float T0 = 0; + float T0 = 0; // pulled to 0 - better for low power supply voltage + if (centered) { + T0 = 1 - T1 - T2; //centered around driver->voltage_limit/2 + } // calculate the duty cycles(times) float Ta,Tb,Tc; @@ -310,27 +363,15 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { } // calculate the phase voltages and center - Ua = Ta*voltage_power_supply; - Ub = Tb*voltage_power_supply; - Uc = Tc*voltage_power_supply; + Ua = Ta*driver->voltage_limit; + Ub = Tb*driver->voltage_limit; + Uc = Tc*driver->voltage_limit; break; + } - // set the voltages in hardware - setPwm(Ua, Ub, Uc); -} - - - -// Set voltage to the pwm pin -void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { - // calculate duty cycle - // limited in [0,1] - float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); - float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); - float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); - // hardware specific writing - _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); + // set the voltages in driver + driver->setPwm(Ua, Ub, Uc); } @@ -348,7 +389,7 @@ void BLDCMotor::velocityOpenloop(float target_velocity){ shaft_angle += target_velocity*Ts; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; @@ -371,7 +412,7 @@ void BLDCMotor::angleOpenloop(float target_angle){ shaft_angle = target_angle; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/BLDCMotor.h b/minimal_project_examples/atmega328_bldc_encoder/src/BLDCMotor.h similarity index 71% rename from minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/BLDCMotor.h rename to minimal_project_examples/atmega328_bldc_encoder/src/BLDCMotor.h index a4fbb678..164cc108 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/BLDCMotor.h +++ b/minimal_project_examples/atmega328_bldc_encoder/src/BLDCMotor.h @@ -1,16 +1,12 @@ -/** - * @file BLDCMotor.h - * - */ - #ifndef BLDCMotor_h #define BLDCMotor_h #include "Arduino.h" -#include "common/FOCMotor.h" +#include "common/base_classes/FOCMotor.h" +#include "common/base_classes/Sensor.h" +#include "common/base_classes/BLDCDriver.h" #include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "common/time_utils.h" #include "common/defaults.h" /** @@ -20,18 +16,27 @@ class BLDCMotor: public FOCMotor { public: /** - BLDCMotor class constructor - @param phA A phase pwm pin - @param phB B phase pwm pin - @param phC C phase pwm pin - @param pp pole pair number - @param cpr counts per rotation number (cpm=ppm*4) - @param en enable pin (optional input) + BLDCMotor class constructor + @param pp pole pairs number + */ + BLDCMotor(int pp); + + /** + * Function linking a motor and a foc driver + * + * @param driver BLDCDriver class implementing all the hardware specific functions necessary PWM setting + */ + void linkDriver(BLDCDriver* driver); + + /** + * BLDCDriver link: + * - 3PWM + * - 6PWM */ - BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + BLDCDriver* driver; /** Motor hardware init function */ - void init(long pwm_frequency = NOT_SET) override; + void init() override; /** Motor disable function */ void disable() override; /** Motor enable function */ @@ -59,12 +64,9 @@ class BLDCMotor: public FOCMotor * This function doesn't need to be run upon each loop execution - depends of the use case */ void move(float target = NOT_SET) override; - - // hardware variables - int pwmA; //!< phase A pwm pin number - int pwmB; //!< phase B pwm pin number - int pwmC; //!< phase C pwm pin number - int enable_pin; //!< enable pin number + + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform private: @@ -74,21 +76,15 @@ class BLDCMotor: public FOCMotor * Heart of the FOC algorithm * * @param Uq Current voltage in q axis to set to the motor + * @param Ud Current voltage in d axis to set to the motor * @param angle_el current electrical angle of the motor */ - void setPhaseVoltage(float Uq, float angle_el); + void setPhaseVoltage(float Uq, float Ud, float angle_el); /** Sensor alignment to electrical 0 angle of the motor */ int alignSensor(); /** Motor and sensor alignment to the sensors absolute 0 angle */ int absoluteZeroAlign(); - /** - * Set phase voltages to the harware - * - * @param Ua phase A voltage - * @param Ub phase B voltage - * @param Uc phase C voltage - */ - void setPwm(float Ua, float Ub, float Uc); + // Open loop motion control /** diff --git a/minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/BLDCDriver.h b/minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/BLDCDriver.h new file mode 100644 index 00000000..708323fb --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/BLDCDriver.h @@ -0,0 +1,28 @@ +#ifndef BLDCDRIVER_H +#define BLDCDRIVER_H + +class BLDCDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + virtual void setPwm(float Ua, float Ub, float Uc); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/common/FOCMotor.cpp b/minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/FOCMotor.cpp similarity index 98% rename from minimal_project_examples/arduino_foc_bldc_hall/src/common/FOCMotor.cpp rename to minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/FOCMotor.cpp index adecbeec..1d1a0f43 100644 --- a/minimal_project_examples/arduino_foc_bldc_hall/src/common/FOCMotor.cpp +++ b/minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/FOCMotor.cpp @@ -5,13 +5,10 @@ */ FOCMotor::FOCMotor() { - // Power supply voltage - voltage_power_supply = DEF_POWER_SUPPLY; - // maximum angular velocity to be used for positioning velocity_limit = DEF_VEL_LIM; // maximum voltage to be set to the motor - voltage_limit = voltage_power_supply; + voltage_limit = DEF_POWER_SUPPLY; // index search velocity velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; @@ -26,6 +23,8 @@ FOCMotor::FOCMotor() // default target value target = 0; + voltage_d = 0; + voltage_q = 0; //monitor_port monitor_port = nullptr; @@ -53,9 +52,6 @@ float FOCMotor::shaftVelocity() { return LPF_velocity(sensor->getVelocity()); } - - - /** * Monitoring functions */ diff --git a/library_source/common/FOCMotor.h b/minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/FOCMotor.h similarity index 93% rename from library_source/common/FOCMotor.h rename to minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/FOCMotor.h index 40f7f6d4..986e1ab2 100644 --- a/library_source/common/FOCMotor.h +++ b/minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/FOCMotor.h @@ -2,13 +2,14 @@ #define FOCMOTOR_H #include "Arduino.h" -#include "hardware_utils.h" -#include "foc_utils.h" -#include "defaults.h" - #include "Sensor.h" -#include "pid.h" -#include "lowpass_filter.h" +#include "BLDCDriver.h" + +#include "../time_utils.h" +#include "../foc_utils.h" +#include "../defaults.h" +#include "../pid.h" +#include "../lowpass_filter.h" /** @@ -27,7 +28,9 @@ enum ControlType{ */ enum FOCModulationType{ SinePWM, //!< Sinusoidal PWM modulation - SpaceVectorPWM //!< Space vector modulation method + SpaceVectorPWM, //!< Space vector modulation method + Trapezoid_120, + Trapezoid_150 }; /** @@ -42,7 +45,7 @@ class FOCMotor FOCMotor(); /** Motor hardware init function */ - virtual void init(long pwm_frequency)=0; + virtual void init()=0; /** Motor disable function */ virtual void disable()=0; /** Motor enable function */ @@ -55,6 +58,7 @@ class FOCMotor */ void linkSensor(Sensor* sensor); + /** * Function initializing FOC algorithm * and aligning sensor's and motors' zero position @@ -99,11 +103,9 @@ class FOCMotor float shaft_velocity_sp;//!< current target velocity float shaft_angle_sp;//!< current target angle float voltage_q;//!< current voltage u_q set - float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor - float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform + float voltage_d;//!< current voltage u_d set // motor configuration parameters - float voltage_power_supply;//!< Power supply voltage float voltage_sensor_align;//!< sensor and motor align voltage parameter float velocity_index_search;//!< target velocity for index search int pole_pairs;//!< Motor pole pairs number diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/Sensor.h b/minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/Sensor.h similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_encoder/src/common/Sensor.h rename to minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/Sensor.h diff --git a/minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/StepperDriver.h b/minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/StepperDriver.h new file mode 100644 index 00000000..7800a4e7 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_encoder/src/common/base_classes/StepperDriver.h @@ -0,0 +1,27 @@ +#ifndef STEPPERDRIVER_H +#define STEPPERDRIVER_H + +class StepperDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + */ + virtual void setPwm(float Ua, float Ub); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/defaults.h b/minimal_project_examples/atmega328_bldc_encoder/src/common/defaults.h similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_encoder/src/common/defaults.h rename to minimal_project_examples/atmega328_bldc_encoder/src/common/defaults.h diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/foc_utils.cpp b/minimal_project_examples/atmega328_bldc_encoder/src/common/foc_utils.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_encoder/src/common/foc_utils.cpp rename to minimal_project_examples/atmega328_bldc_encoder/src/common/foc_utils.cpp diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/foc_utils.h b/minimal_project_examples/atmega328_bldc_encoder/src/common/foc_utils.h similarity index 94% rename from minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/foc_utils.h rename to minimal_project_examples/atmega328_bldc_encoder/src/common/foc_utils.h index 5ab34f42..7da3f7bc 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/foc_utils.h +++ b/minimal_project_examples/atmega328_bldc_encoder/src/common/foc_utils.h @@ -6,6 +6,7 @@ // sign function #define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) #define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) +#define _constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt))) // utility defines #define _2_SQRT3 1.15470053838 @@ -20,7 +21,6 @@ #define _2PI 6.28318530718 #define _3PI_2 4.71238898038 - #define NOT_SET -12345.0 /** diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/lowpass_filter.cpp b/minimal_project_examples/atmega328_bldc_encoder/src/common/lowpass_filter.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_encoder/src/common/lowpass_filter.cpp rename to minimal_project_examples/atmega328_bldc_encoder/src/common/lowpass_filter.cpp diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/lowpass_filter.h b/minimal_project_examples/atmega328_bldc_encoder/src/common/lowpass_filter.h similarity index 94% rename from minimal_project_examples/arduino_foc_bldc_encoder/src/common/lowpass_filter.h rename to minimal_project_examples/atmega328_bldc_encoder/src/common/lowpass_filter.h index 5a7619cf..7c51be54 100644 --- a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/lowpass_filter.h +++ b/minimal_project_examples/atmega328_bldc_encoder/src/common/lowpass_filter.h @@ -2,7 +2,7 @@ #define LOWPASS_FILTER_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/pid.cpp b/minimal_project_examples/atmega328_bldc_encoder/src/common/pid.cpp similarity index 92% rename from minimal_project_examples/arduino_foc_bldc_encoder/src/common/pid.cpp rename to minimal_project_examples/atmega328_bldc_encoder/src/common/pid.cpp index 277e17ce..1a0a9828 100644 --- a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/pid.cpp +++ b/minimal_project_examples/atmega328_bldc_encoder/src/common/pid.cpp @@ -25,12 +25,12 @@ float PIDController::operator() (float error){ // Discrete implementations // proportional part // u_p = P *e(k) - float proportional = P * error_prev; + float proportional = P * error; // Tustin transform of the integral part // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) float integral = integral_prev + I*Ts*0.5*(error + error_prev); // antiwindup - limit the output voltage_q - integral = constrain(integral, -limit, limit); + integral = _constrain(integral, -limit, limit); // Discrete derivation // u_dk = D(ek - ek_1)/Ts float derivative = D*(error - error_prev)/Ts; @@ -38,7 +38,7 @@ float PIDController::operator() (float error){ // sum all the components float output = proportional + integral + derivative; // antiwindup - limit the output variable - output = constrain(output, -limit, limit); + output = _constrain(output, -limit, limit); // limit the acceleration by ramping the output float output_rate = (output - output_prev)/Ts; diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/pid.h b/minimal_project_examples/atmega328_bldc_encoder/src/common/pid.h similarity index 97% rename from minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/pid.h rename to minimal_project_examples/atmega328_bldc_encoder/src/common/pid.h index 7ee337c4..0e9ddf54 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/pid.h +++ b/minimal_project_examples/atmega328_bldc_encoder/src/common/pid.h @@ -2,7 +2,7 @@ #define PID_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" /** diff --git a/minimal_project_examples/atmega328_bldc_encoder/src/common/time_utils.cpp b/minimal_project_examples/atmega328_bldc_encoder/src/common/time_utils.cpp new file mode 100644 index 00000000..181d03cf --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_encoder/src/common/time_utils.cpp @@ -0,0 +1,31 @@ +#include "time_utils.h" + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/atmega328_bldc_encoder/src/common/time_utils.h b/minimal_project_examples/atmega328_bldc_encoder/src/common/time_utils.h new file mode 100644 index 00000000..143d4853 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_encoder/src/common/time_utils.h @@ -0,0 +1,22 @@ +#ifndef TIME_UTILS_H +#define TIME_UTILS_H + +#include "foc_utils.h" + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_encoder/src/drivers/BLDCDriver3PWM.cpp b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/BLDCDriver3PWM.cpp new file mode 100644 index 00000000..bacb4ec5 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/BLDCDriver3PWM.cpp @@ -0,0 +1,70 @@ +#include "BLDCDriver3PWM.h" + +BLDCDriver3PWM::BLDCDriver3PWM(int phA, int phB, int phC, int en){ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + + // enable_pin pin + enable_pin = en; + + // default power-supply value + voltage_power_supply = DEF_POWER_SUPPLY; + voltage_limit = NOT_SET; + +} + +// enable motor driver +void BLDCDriver3PWM::enable(){ + // enable_pin the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, HIGH); + // set zero to PWM + setPwm(0,0,0); +} + +// disable motor driver +void BLDCDriver3PWM::disable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // disable the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, LOW); + +} + +// init hardware pins +int BLDCDriver3PWM::init() { + + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); + + + // sanity check for the voltage limit configuration + if(voltage_limit == NOT_SET || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + + // Set the pwm frequency to the pins + // hardware specific function - depending on driver and mcu + _configure3PWM(pwm_frequency, pwmA, pwmB, pwmC); + return 0; +} + + +// Set voltage to the pwm pin +void BLDCDriver3PWM::setPwm(float Ua, float Ub, float Uc) { + // limit the voltage in driver + Ua = _constrain(Ua, -voltage_limit, voltage_limit); + Ub = _constrain(Ub, -voltage_limit, voltage_limit); + Uc = _constrain(Uc, -voltage_limit, voltage_limit); + // calculate duty cycle + // limited in [0,1] + float dc_a = _constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = _constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = _constrain(Uc / voltage_power_supply, 0 , 1 ); + // hardware specific writing + // hardware specific function - depending on driver and mcu + _writeDutyCycle3PWM(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC); +} \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_encoder/src/drivers/BLDCDriver3PWM.h b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/BLDCDriver3PWM.h new file mode 100644 index 00000000..b6f7d7f8 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/BLDCDriver3PWM.h @@ -0,0 +1,52 @@ +#ifndef BLDCDriver3PWM_h +#define BLDCDriver3PWM_h + +#include "../common/base_classes/BLDCDriver.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#include "../common/defaults.h" +#include "hardware_api.h" + +/** + 3 pwm bldc driver class +*/ +class BLDCDriver3PWM: public BLDCDriver +{ + public: + /** + BLDCDriver class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param en enable pin (optional input) + */ + BLDCDriver3PWM(int phA,int phB,int phC, int en = NOT_SET); + + /** Motor hardware init function */ + int init() override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc) override; + + private: + +}; + + +#endif diff --git a/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_api.h b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_api.h new file mode 100644 index 00000000..da5ddf51 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_api.h @@ -0,0 +1,100 @@ +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H + +#include "../common/foc_utils.h" +#include "../common/time_utils.h" + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + * @param pinC pinC bldc driver + */ +void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC); + +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pin1A pin1A stepper driver + * @param pin1B pin1B stepper driver + * @param pin2A pin2A stepper driver + * @param pin2B pin2B stepper driver + */ +void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B); + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low - if applicable + * @param pinA_h pinA high-side bldc driver + * @param pinA_l pinA low-side bldc driver + * @param pinB_h pinA high-side bldc driver + * @param pinB_l pinA low-side bldc driver + * @param pinC_h pinA high-side bldc driver + * @param pinC_l pinA low-side bldc driver + * + * @return 0 if config good, -1 if failed + */ +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low + * @param pinA_h phase A high-side hardware pin number + * @param pinA_l phase A low-side hardware pin number + * @param pinB_h phase B high-side hardware pin number + * @param pinB_l phase B low-side hardware pin number + * @param pinC_h phase C high-side hardware pin number + * @param pinC_l phase C low-side hardware pin number + * + */ +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l); + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/atmega328_mcu.cpp b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/atmega328_mcu.cpp new file mode 100644 index 00000000..58b368f7 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/atmega328_mcu.cpp @@ -0,0 +1,133 @@ +#include "../hardware_api.h" + +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + +// set pwm frequency to 32KHz +void _pinHighFrequency(const int pin){ + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pin == 5 || pin == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pin == 9 || pin == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pin == 3 || pin == 11) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +} + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +// supports Arudino/ATmega328 +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); + _pinHighFrequency(pinC); +} + + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); + analogWrite(pinC, 255.0*dc_c); +} + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +// supports Arudino/ATmega328 +void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pin1A); + _pinHighFrequency(pin1B); + _pinHighFrequency(pin2A); + _pinHighFrequency(pin2B); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255.0*dc_1a); + analogWrite(pin1B, 255.0*dc_1b); + analogWrite(pin2A, 255.0*dc_2a); + analogWrite(pin2B, 255.0*dc_2b); +} + + +// function configuring pair of high-low side pwm channels, 32khz frequency and center aligned pwm +int _configureComplementaryPair(int pinH, int pinL) { + if( (pinH == 5 && pinL == 6 ) || (pinH == 6 && pinL == 5 ) ){ + // configure the pwm phase-corrected mode + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); + // configure complementary pwm on low side + if(pinH == 6 ) TCCR0A = 0b10110000 | (TCCR0A & 0b00001111) ; + else TCCR0A = 0b11100000 | (TCCR0A & 0b00001111) ; + // set prescaler to 1 - 32kHz freq + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); + }else if( (pinH == 9 && pinL == 10 ) || (pinH == 10 && pinL == 9 ) ){ + // set prescaler to 1 - 32kHz freq + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); + // configure complementary pwm on low side + if(pinH == 9 ) TCCR1A = 0b10110000 | (TCCR1A & 0b00001111) ; + else TCCR1A = 0b11100000 | (TCCR1A & 0b00001111) ; + }else if((pinH == 3 && pinL == 11 ) || (pinH == 11 && pinL == 3 ) ){ + // set prescaler to 1 - 32kHz freq + TCCR2B = ((TCCR2B & 0b11111000) | 0x01); + // configure complementary pwm on low side + if(pinH == 11 ) TCCR2A = 0b10110000 | (TCCR2A & 0b00001111) ; + else TCCR2A = 0b11100000 | (TCCR2A & 0b00001111) ; + }else{ + return -1; + } + return 0; +} + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +// supports Arudino/ATmega328 +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) { + // High PWM frequency + // - always max 32kHz + int ret_flag = 0; + ret_flag += _configureComplementaryPair(pinA_h, pinA_l); + ret_flag += _configureComplementaryPair(pinB_h, pinB_l); + ret_flag += _configureComplementaryPair(pinC_h, pinC_l); + return ret_flag; // returns -1 if not well configured +} + +// function setting the +void _setPwmPair(int pinH, int pinL, float val, int dead_time) +{ + int pwm_h = _constrain(val-dead_time/2,0,255); + int pwm_l = _constrain(val+dead_time/2,0,255); + + analogWrite(pinH, pwm_h); + if(pwm_l == 255 || pwm_l == 0) + digitalWrite(pinL, pwm_l ? LOW : HIGH); + else + analogWrite(pinL, pwm_l); +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +// supports Arudino/ATmega328 +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + _setPwmPair(pinA_h, pinA_l, dc_a*255.0, dead_zone*255.0); + _setPwmPair(pinB_h, pinB_l, dc_b*255.0, dead_zone*255.0); + _setPwmPair(pinC_h, pinC_l, dc_c*255.0, dead_zone*255.0); +} + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/esp32_mcu.cpp b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/esp32_mcu.cpp new file mode 100644 index 00000000..3c07a445 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/esp32_mcu.cpp @@ -0,0 +1,296 @@ +#include "../hardware_api.h" + +#if defined(ESP_H) + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +// empty motor slot +#define _EMPTY_SLOT -20 +#define _TAKEN_SLOT -21 + +// structure containing motor slot configuration +// this library supports up to 4 motors +typedef struct { + int pinA; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; + mcpwm_io_signals_t mcpwm_c; +} bldc_3pwm_motor_slots_t; +typedef struct { + int pin1A; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_1a; + mcpwm_io_signals_t mcpwm_1b; + mcpwm_io_signals_t mcpwm_2a; + mcpwm_io_signals_t mcpwm_2b; +} stepper_motor_slots_t; + +typedef struct { + int pinAH; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_ah; + mcpwm_io_signals_t mcpwm_bh; + mcpwm_io_signals_t mcpwm_ch; + mcpwm_io_signals_t mcpwm_al; + mcpwm_io_signals_t mcpwm_bl; + mcpwm_io_signals_t mcpwm_cl; +} bldc_6pwm_motor_slots_t; + +// define bldc motor slots array +bldc_3pwm_motor_slots_t esp32_bldc_3pwm_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B + }; + +// define stepper motor slots array +stepper_motor_slots_t esp32_stepper_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + }; + +// define stepper motor slots array +bldc_6pwm_motor_slots_t esp32_bldc_6pwm_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0 + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0 + }; + +// configuring high frequency pwm timer +// a lot of help from this post from Paul Gauld +// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller +void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit, float dead_zone = NOT_SET){ + + mcpwm_config_t pwm_config; + pwm_config.frequency = pwm_frequency; //frequency + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + if (dead_zone != NOT_SET){ + // dead zone is configured in dead_time x 100 nanoseconds + float dead_time = (float)(1e7 / pwm_frequency) * dead_zone; + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); + } + + _delay(100); + + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 0; +} + + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(2*pwm_frequency, 0, 100000); // constrain to 50kHz max - centered pwm has twice lower frequency + + bldc_3pwm_motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + int slot_num; + for(slot_num = 0; slot_num < 4; slot_num++){ + if(esp32_bldc_3pwm_motor_slots[slot_num].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_3pwm_motor_slots[slot_num].pinA = pinA; + m_slot = esp32_bldc_3pwm_motor_slots[slot_num]; + break; + } + } + // disable all the slots with the same MCPWM + if( slot_num < 2 ){ + // slot 0 of the stepper + esp32_stepper_motor_slots[0].pin1A = _TAKEN_SLOT; + // slot 0 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; + }else{ + // slot 1 of the stepper + esp32_stepper_motor_slots[1].pin1A = _TAKEN_SLOT; + // slot 1 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; + } + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + +} + + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(2*pwm_frequency, 0, 100000); // constrain to 50kHz max - centered pwm has twice lower frequency + stepper_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + int slot_num; + for(slot_num = 0; slot_num < 2; slot_num++){ + if(esp32_stepper_motor_slots[slot_num].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_motor_slots[slot_num].pin1A = pinA; + m_slot = esp32_stepper_motor_slots[slot_num]; + break; + } + } + // disable all the slots with the same MCPWM + if( slot_num == 0 ){ + // slots 0 and 1 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT; + // slot 0 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; + }else{ + // slots 2 and 3 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT; + // slot 1 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); +} + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +// ESP32 uses MCPWM +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_bldc_3pwm_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,100] + mcpwm_set_duty(esp32_bldc_3pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_bldc_3pwm_motor_slots[i].mcpwm_operator, dc_a*100.0); + mcpwm_set_duty(esp32_bldc_3pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_bldc_3pwm_motor_slots[i].mcpwm_operator, dc_b*100.0); + mcpwm_set_duty(esp32_bldc_3pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, esp32_bldc_3pwm_motor_slots[i].mcpwm_operator, dc_c*100.0); + break; + } + } +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +// ESP32 uses MCPWM +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,100] + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_motor_slots[i].mcpwm_operator1, dc_1a*100.0); + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_motor_slots[i].mcpwm_operator1, dc_1b*100.0); + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_motor_slots[i].mcpwm_operator2, dc_2a*100.0); + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_motor_slots[i].mcpwm_operator2, dc_2b*100.0); + break; + } + } +} + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency + bldc_6pwm_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + int slot_num; + for(slot_num = 0; slot_num < 2; slot_num++){ + if(esp32_bldc_6pwm_motor_slots[slot_num].pinAH == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_6pwm_motor_slots[slot_num].pinAH = pinA_h; + m_slot = esp32_bldc_6pwm_motor_slots[slot_num]; + break; + } + } + // if no slots available + if(slot_num >= 2) return -1; + + // disable all the slots with the same MCPWM + if( slot_num == 0 ){ + // slots 0 and 1 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT; + // slot 0 of the 6pwm bldc + esp32_stepper_motor_slots[0].pin1A = _TAKEN_SLOT; + }else{ + // slots 2 and 3 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT; + // slot 1 of the 6pwm bldc + esp32_stepper_motor_slots[1].pin1A = _TAKEN_SLOT; + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_ah, pinA_h); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_al, pinA_l); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_bh, pinB_h); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_bl, pinB_l); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_ch, pinC_h); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_cl, pinC_l); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit, dead_zone); + // return + return 0; +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_bldc_6pwm_motor_slots[i].pinAH == pinA_h){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,100.0] + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_A, dc_a*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_B, dc_a*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_A, dc_b*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_B, dc_b*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_A, dc_c*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_B, dc_c*100.0); + break; + } + } +} +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/generic_mcu.cpp b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/generic_mcu.cpp new file mode 100644 index 00000000..dc322746 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/generic_mcu.cpp @@ -0,0 +1,68 @@ +#include "../hardware_api.h" + +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if mcu is not atmega328 + +#elif defined(__arm__) && defined(CORE_TEENSY) // or teensy + +#elif defined(ESP_H) // or esp32 + +#elif defined(_STM32_DEF_) // or stm32 + +#else + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +// in generic case dont do anything +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + return; +} + + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +// in generic case dont do anything +void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) { + return; +} + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + return -1; +} + + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); + analogWrite(pinC, 255.0*dc_c); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255.0*dc_1a); + analogWrite(pin1B, 255.0*dc_1b); + analogWrite(pin2A, 255.0*dc_2a); + analogWrite(pin2B, 255.0*dc_2b); +} + + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + return; +} + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/stm32_mcu.cpp b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/stm32_mcu.cpp new file mode 100644 index 00000000..85d0bd65 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/stm32_mcu.cpp @@ -0,0 +1,291 @@ + +#include "../hardware_api.h" + +#if defined(_STM32_DEF_) + +#define _PWM_RESOLUTION 12 // 12bit +#define _PWM_RANGE 4095.0// 2^12 -1 = 4095 +#define _PWM_FREQUENCY 50000 // 50khz + + +#define _HARDWARE_6PWM 1 +#define _SOFTWARE_6PWM 0 +#define _ERROR_6PWM -1 + + +// setting pwm to hardware pin - instead analogWrite() +void _setPwm(int ulPin, uint32_t value, int resolution) +{ + PinName pin = digitalPinToPinName(ulPin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); + uint32_t index = get_timer_index(Instance); + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HT->setCaptureCompare(channel, value, (TimerCompareFormat_t)resolution); +} + + +// init pin pwm +HardwareTimer* _initPinPWM(uint32_t PWM_freq, int ulPin) +{ + PinName pin = digitalPinToPinName(ulPin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); + + uint32_t index = get_timer_index(Instance); + if (HardwareTimer_Handle[index] == NULL) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM)); + HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); + } + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, pin); + HT->setOverflow(PWM_freq, HERTZ_FORMAT); + HT->pause(); + HT->refresh(); + return HT; +} + + +// init high side pin +HardwareTimer* _initPinPWMHigh(uint32_t PWM_freq, int ulPin) +{ + return _initPinPWM(PWM_freq, ulPin); +} + +// init low side pin +HardwareTimer* _initPinPWMLow(uint32_t PWM_freq, int ulPin) +{ + PinName pin = digitalPinToPinName(ulPin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); + uint32_t index = get_timer_index(Instance); + + if (HardwareTimer_Handle[index] == NULL) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM)); + HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); + TIM_OC_InitTypeDef sConfigOC = TIM_OC_InitTypeDef(); + sConfigOC.OCMode = TIM_OCMODE_PWM2; + sConfigOC.Pulse = 100; + sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW; + sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH; + sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; + sConfigOC.OCIdleState = TIM_OCIDLESTATE_SET; + sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET; + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HAL_TIM_PWM_ConfigChannel(&(HardwareTimer_Handle[index]->handle), &sConfigOC, channel); + } + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM2, pin); + HT->setOverflow(PWM_freq, HERTZ_FORMAT); + HT->pause(); + HT->refresh(); + return HT; +} + + +// align the timers to end the init +void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3) +{ + HT1->pause(); + HT1->refresh(); + HT2->pause(); + HT2->refresh(); + HT3->pause(); + HT3->refresh(); + HT1->resume(); + HT2->resume(); + HT3->resume(); +} + +// align the timers to end the init +void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3,HardwareTimer *HT4) +{ + HT1->pause(); + HT1->refresh(); + HT2->pause(); + HT2->refresh(); + HT3->pause(); + HT3->refresh(); + HT4->pause(); + HT4->refresh(); + HT1->resume(); + HT2->resume(); + HT3->resume(); + HT4->resume(); +} + +HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l) +{ + PinName uhPinName = digitalPinToPinName(pinA_h); + PinName ulPinName = digitalPinToPinName(pinA_l); + PinName vhPinName = digitalPinToPinName(pinB_h); + PinName vlPinName = digitalPinToPinName(pinB_l); + PinName whPinName = digitalPinToPinName(pinC_h); + PinName wlPinName = digitalPinToPinName(pinC_l); + + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM); + + uint32_t index = get_timer_index(Instance); + + if (HardwareTimer_Handle[index] == NULL) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM)); + HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); + ((HardwareTimer *)HardwareTimer_Handle[index]->__this)->setOverflow(PWM_freq, HERTZ_FORMAT); + } + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + + HT->setMode(STM_PIN_CHANNEL(pinmap_function(uhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, uhPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(ulPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, ulPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(vhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vhPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(vlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vlPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(whPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, whPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(wlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, wlPinName); + + // dead time is set in nanoseconds + uint32_t dead_time_ns = (float)(1e9/PWM_freq)*dead_zone; + uint32_t dead_time = __LL_TIM_CALC_DEADTIME(SystemCoreClock, LL_TIM_GetClockDivision(HT->getHandle()->Instance), dead_time_ns); + LL_TIM_OC_SetDeadTime(HT->getHandle()->Instance, dead_time); // deadtime is non linear! + LL_TIM_CC_EnableChannel(HT->getHandle()->Instance, LL_TIM_CHANNEL_CH1 | LL_TIM_CHANNEL_CH1N | LL_TIM_CHANNEL_CH2 | LL_TIM_CHANNEL_CH2N | LL_TIM_CHANNEL_CH3 | LL_TIM_CHANNEL_CH3N); + + HT->pause(); + HT->refresh(); + HT->resume(); + return HT; +} + + +// returns 0 if each pair of pwm channels has same channel +// returns 1 all the channels belong to the same timer - hardware inverted channels +// returns -1 if neither - avoid configuring - error!!! +int _interfaceType(const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + PinName nameAH = digitalPinToPinName(pinA_h); + PinName nameAL = digitalPinToPinName(pinA_l); + PinName nameBH = digitalPinToPinName(pinB_h); + PinName nameBL = digitalPinToPinName(pinB_l); + PinName nameCH = digitalPinToPinName(pinC_h); + PinName nameCL = digitalPinToPinName(pinC_l); + int tim1 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAH, PinMap_PWM)); + int tim2 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAL, PinMap_PWM)); + int tim3 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBH, PinMap_PWM)); + int tim4 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBL, PinMap_PWM)); + int tim5 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCH, PinMap_PWM)); + int tim6 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCL, PinMap_PWM)); + if(tim1 == tim2 && tim2==tim3 && tim3==tim4 && tim4==tim5 && tim5==tim6) + return _HARDWARE_6PWM; // hardware 6pwm interface - only on timer + else if(tim1 == tim2 && tim3==tim4 && tim5==tim6) + return _SOFTWARE_6PWM; // software 6pwm interface - each pair of high-low side same timer + else + return _ERROR_6PWM; // might be error avoid configuration +} + + + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); + HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); + HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); + // allign the timers + _alignPWMTimers(HT1, HT2, HT3); +} + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); + HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); + HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); + HardwareTimer* HT4 = _initPinPWM(pwm_frequency, pinD); + // allign the timers + _alignPWMTimers(HT1, HT2, HT3, HT4); +} + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +//- hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,4095] + _setPwm(pinA, _PWM_RANGE*dc_a, _PWM_RESOLUTION); + _setPwm(pinB, _PWM_RANGE*dc_b, _PWM_RESOLUTION); + _setPwm(pinC, _PWM_RANGE*dc_c, _PWM_RESOLUTION); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +//- hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,4095] + _setPwm(pin1A, _PWM_RANGE*dc_1a, _PWM_RESOLUTION); + _setPwm(pin1B, _PWM_RANGE*dc_1b, _PWM_RESOLUTION); + _setPwm(pin2A, _PWM_RANGE*dc_2a, _PWM_RESOLUTION); + _setPwm(pin2B, _PWM_RANGE*dc_2b, _PWM_RESOLUTION); +} + + + + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, 100000); // constrain to 100kHz max + + // find configuration + int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); + // configure accordingly + switch(config){ + case _ERROR_6PWM: + return -1; // fail + break; + case _HARDWARE_6PWM: + _initHardware6PWMInterface(pwm_frequency, dead_zone, pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); + break; + case _SOFTWARE_6PWM: + HardwareTimer* HT1 = _initPinPWMHigh(pwm_frequency, pinA_h); + _initPinPWMLow(pwm_frequency, pinA_l); + HardwareTimer* HT2 = _initPinPWMHigh(pwm_frequency,pinB_h); + _initPinPWMLow(pwm_frequency, pinB_l); + HardwareTimer* HT3 = _initPinPWMHigh(pwm_frequency,pinC_h); + _initPinPWMLow(pwm_frequency, pinC_l); + _alignPWMTimers(HT1, HT2, HT3); + break; + } + return 0; // success +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + // find configuration + int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); + // set pwm accordingly + switch(config){ + case _HARDWARE_6PWM: + _setPwm(pinA_h, _PWM_RANGE*dc_a, _PWM_RESOLUTION); + _setPwm(pinB_h, _PWM_RANGE*dc_b, _PWM_RESOLUTION); + _setPwm(pinC_h, _PWM_RANGE*dc_c, _PWM_RESOLUTION); + break; + case _SOFTWARE_6PWM: + _setPwm(pinA_l, _constrain(dc_a + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinA_h, _constrain(dc_a - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinB_l, _constrain(dc_b + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinB_h, _constrain(dc_b - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinC_l, _constrain(dc_c + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinC_h, _constrain(dc_c - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + break; + } +} +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/teensy_mcu.cpp b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/teensy_mcu.cpp new file mode 100644 index 00000000..10bd24c5 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_encoder/src/drivers/hardware_specific/teensy_mcu.cpp @@ -0,0 +1,71 @@ +#include "../hardware_api.h" + +#if defined(__arm__) && defined(CORE_TEENSY) + +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(pin, freq); +} + + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor +} + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + _setHighFrequency(pwm_frequency, pinD); +} + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); + analogWrite(pinC, 255.0*dc_c); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255.0*dc_1a); + analogWrite(pin1B, 255.0*dc_1b); + analogWrite(pin2A, 255.0*dc_2a); + analogWrite(pin2B, 255.0*dc_2b); +} + + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + return -1; +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + return; +} +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/Encoder.cpp b/minimal_project_examples/atmega328_bldc_encoder/src/sensors/Encoder.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_encoder/src/Encoder.cpp rename to minimal_project_examples/atmega328_bldc_encoder/src/sensors/Encoder.cpp diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/Encoder.h b/minimal_project_examples/atmega328_bldc_encoder/src/sensors/Encoder.h similarity index 96% rename from minimal_project_examples/arduino_foc_bldc_encoder/src/Encoder.h rename to minimal_project_examples/atmega328_bldc_encoder/src/sensors/Encoder.h index d1a55f0e..29122888 100644 --- a/minimal_project_examples/arduino_foc_bldc_encoder/src/Encoder.h +++ b/minimal_project_examples/atmega328_bldc_encoder/src/sensors/Encoder.h @@ -2,9 +2,9 @@ #define ENCODER_LIB_H #include "Arduino.h" -#include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#include "../common/base_classes/Sensor.h" /** diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/arduino_foc_bldc_magnetic_i2c.ino b/minimal_project_examples/atmega328_bldc_magnetic_i2c/atmega328_bldc_magnetic_i2c.ino similarity index 91% rename from minimal_project_examples/arduino_foc_bldc_magnetic_i2c/arduino_foc_bldc_magnetic_i2c.ino rename to minimal_project_examples/atmega328_bldc_magnetic_i2c/atmega328_bldc_magnetic_i2c.ino index e62ad0cd..cf1142c5 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/arduino_foc_bldc_magnetic_i2c.ino +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/atmega328_bldc_magnetic_i2c.ino @@ -37,13 +37,15 @@ * */ #include "src/BLDCMotor.h" -#include "src/MagneticSensorI2C.h" +#include "src/drivers/BLDCDriver3PWM.h" +#include "src/sensors/MagneticSensorI2C.h" // I2C magnetic sensor instance MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0x0E, 4); -// motor instance -BLDCMotor motor = BLDCMotor(9, 5, 6, 11, 7); +// BLDC motor & driver instance +BLDCMotor motor = BLDCMotor(11); +BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8); void setup() { @@ -52,12 +54,16 @@ void setup() { // link the motor to the sensor motor.linkSensor(&sensor); + // driver config + // power supply voltage [V] + driver.voltage_power_supply = 12; + driver.init(); + // link driver + motor.linkDriver(&driver); + // choose FOC modulation motor.foc_modulation = FOCModulationType::SpaceVectorPWM; - // power supply voltage [V] - motor.voltage_power_supply = 12; - // set control loop type to be used motor.controller = ControlType::voltage; @@ -136,4 +142,4 @@ String serialReceiveUserCommand() { } } return command; -} +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/BLDCMotor.cpp b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/BLDCMotor.cpp similarity index 68% rename from minimal_project_examples/arduino_foc_bldc_openloop/src/BLDCMotor.cpp rename to minimal_project_examples/atmega328_bldc_magnetic_i2c/src/BLDCMotor.cpp index 989b74a9..bed4cd6a 100644 --- a/minimal_project_examples/arduino_foc_bldc_openloop/src/BLDCMotor.cpp +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/BLDCMotor.cpp @@ -1,41 +1,39 @@ #include "BLDCMotor.h" -// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// // BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// // - phA, phB, phC - motor A,B,C phase pwm pins +// // - pp - pole pair number +// // - cpr - counts per rotation number (cpm=ppm*4) +// // - enable pin - (optional input) +// BLDCMotor::BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en){ +// noop; +// } + +// BLDCMotor( int pp) // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - cpr - counts per rotation number (cpm=ppm*4) // - enable pin - (optional input) -BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +BLDCMotor::BLDCMotor(int pp) : FOCMotor() { - // Pin initialization - pwmA = phA; - pwmB = phB; - pwmC = phC; + // save pole pairs number pole_pairs = pp; +} - // enable_pin pin - enable_pin = en; +/** + Link the driver which controls the motor +*/ +void BLDCMotor::linkDriver(BLDCDriver* _driver) { + driver = _driver; } - // init hardware pins -void BLDCMotor::init(long pwm_frequency) { - if(monitor_port) monitor_port->println("MOT: Init pins."); - // PWM pins - pinMode(pwmA, OUTPUT); - pinMode(pwmB, OUTPUT); - pinMode(pwmC, OUTPUT); - if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); - - if(monitor_port) monitor_port->println("MOT: PWM config."); - // Increase PWM frequency to 32 kHz - // make silent - _setPwmFrequency(pwm_frequency, pwmA, pwmB, pwmC); - +void BLDCMotor::init() { + if(monitor_port) monitor_port->println("MOT: Initialise variables."); // sanity check for the voltage limit configuration - if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + if(voltage_limit > driver->voltage_limit) voltage_limit = driver->voltage_limit; // constrain voltage for sensor alignment if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; // update the controller limits @@ -44,7 +42,7 @@ void BLDCMotor::init(long pwm_frequency) { _delay(500); // enable motor - if(monitor_port) monitor_port->println("MOT: Enable."); + if(monitor_port) monitor_port->println("MOT: Enable driver."); enable(); _delay(500); } @@ -53,18 +51,18 @@ void BLDCMotor::init(long pwm_frequency) { // disable motor driver void BLDCMotor::disable() { - // disable the driver - if enable_pin pin available - if (enable_pin != NOT_SET) digitalWrite(enable_pin, LOW); // set zero to PWM - setPwm(0, 0, 0); + driver->setPwm(0, 0, 0); + // disable the driver + driver->disable(); } // enable motor driver void BLDCMotor::enable() { + // enable the driver + driver->enable(); // set zero to PWM - setPwm(0, 0, 0); - // enable_pin the driver - if enable_pin pin available - if (enable_pin != NOT_SET) digitalWrite(enable_pin, HIGH); + driver->setPwm(0, 0, 0); } @@ -100,13 +98,13 @@ int BLDCMotor::alignSensor() { float start_angle = shaftAngle(); for (int i = 0; i <=5; i++ ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } float mid_angle = shaftAngle(); for (int i = 5; i >=0; i-- ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } if (mid_angle < start_angle) { @@ -121,7 +119,7 @@ int BLDCMotor::alignSensor() { // set sensor to zero sensor->initRelativeZero(); _delay(500); - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); _delay(200); // find the index if available @@ -153,7 +151,7 @@ int BLDCMotor::absoluteZeroAlign() { } voltage_q = 0; // disable motor - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); // align absolute zero if it has been found if(!sensor->needsAbsoluteZeroSearch()){ @@ -172,7 +170,7 @@ void BLDCMotor::loopFOC() { // shaft angle shaft_angle = shaftAngle(); // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); + setPhaseVoltage(voltage_q, voltage_d, _electricalAngle(shaft_angle,pole_pairs)); } // Iterative function running outer loop of the FOC algorithm @@ -219,15 +217,60 @@ void BLDCMotor::move(float new_target) { } -// Method using FOC to set Uq to the motor at the optimal angle +// Method using FOC to set Uq and Ud to the motor at the optimal angle // Function implementing Space Vector PWM and Sine PWM algorithms // // Function using sine approximation // regular sin + cos ~300us (no memory usaage) // approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { +void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { + + const bool centered = true; + int sector; + float _ca,_sa; + switch (foc_modulation) { + case FOCModulationType::Trapezoid_120 : + // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 5 + static int trap_120_map[6][3] = { + {0,1,-1},{-1,1,0},{-1,0,1},{0,-1,1},{1,-1,0},{1,0,-1} // each is 60 degrees with values for 3 phases of 1=positive -1=negative 0=high-z + }; + // static int trap_120_state = 0; + sector = 6 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes + + Ua = Uq + trap_120_map[sector][0] * Uq; + Ub = Uq + trap_120_map[sector][1] * Uq; + Uc = Uq + trap_120_map[sector][2] * Uq; + + if (centered) { + Ua += (driver->voltage_limit)/2 -Uq; + Ub += (driver->voltage_limit)/2 -Uq; + Uc += (driver->voltage_limit)/2 -Uq; + } + break; + + case FOCModulationType::Trapezoid_150 : + // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 8 + static int trap_150_map[12][3] = { + {0,1,-1},{-1,1,-1},{-1,1,0},{-1,1,1},{-1,0,1},{-1,-1,1},{0,-1,1},{1,-1,1},{1,-1,0},{1,-1,-1},{1,0,-1},{1,1,-1} // each is 30 degrees with values for 3 phases of 1=positive -1=negative 0=high-z + }; + // static int trap_150_state = 0; + sector = 12 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes + + Ua = Uq + trap_150_map[sector][0] * Uq; + Ub = Uq + trap_150_map[sector][1] * Uq; + Uc = Uq + trap_150_map[sector][2] * Uq; + + //center + if (centered) { + Ua += (driver->voltage_limit)/2 -Uq; + Ub += (driver->voltage_limit)/2 -Uq; + Uc += (driver->voltage_limit)/2 -Uq; + } + + break; + case FOCModulationType::SinePWM : // Sinusoidal PWM modulation // Inverse Park + Clarke transformation @@ -235,14 +278,24 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // angle normalization in between 0 and 2pi // only necessary if using _sin and _cos - approximation functions angle_el = _normalizeAngle(angle_el + zero_electric_angle); + _ca = _cos(angle_el); + _sa = _sin(angle_el); // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + Ualpha = _ca * Ud - _sa * Uq; // -sin(angle) * Uq; + Ubeta = _sa * Ud + _ca * Uq; // cos(angle) * Uq; // Clarke transform - Ua = Ualpha + voltage_power_supply/2; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + Ua = Ualpha + driver->voltage_limit/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + driver->voltage_limit/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + driver->voltage_limit/2; + + if (!centered) { + float Umin = min(Ua, min(Ub, Uc)); + Ua -= Umin; + Ub -= Umin; + Uc -= Umin; + } + break; case FOCModulationType::SpaceVectorPWM : @@ -259,15 +312,15 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { angle_el = _normalizeAngle(angle_el + zero_electric_angle + _PI_2); // find the sector we are in currently - int sector = floor(angle_el / _PI_3) + 1; + sector = floor(angle_el / _PI_3) + 1; // calculate the duty cycles - float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; - float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/driver->voltage_limit; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/driver->voltage_limit; // two versions possible - // centered around voltage_power_supply/2 - float T0 = 1 - T1 - T2; - // pulled to 0 - better for low power supply voltage - //float T0 = 0; + float T0 = 0; // pulled to 0 - better for low power supply voltage + if (centered) { + T0 = 1 - T1 - T2; //centered around driver->voltage_limit/2 + } // calculate the duty cycles(times) float Ta,Tb,Tc; @@ -310,27 +363,15 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { } // calculate the phase voltages and center - Ua = Ta*voltage_power_supply; - Ub = Tb*voltage_power_supply; - Uc = Tc*voltage_power_supply; + Ua = Ta*driver->voltage_limit; + Ub = Tb*driver->voltage_limit; + Uc = Tc*driver->voltage_limit; break; + } - // set the voltages in hardware - setPwm(Ua, Ub, Uc); -} - - - -// Set voltage to the pwm pin -void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { - // calculate duty cycle - // limited in [0,1] - float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); - float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); - float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); - // hardware specific writing - _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); + // set the voltages in driver + driver->setPwm(Ua, Ub, Uc); } @@ -348,7 +389,7 @@ void BLDCMotor::velocityOpenloop(float target_velocity){ shaft_angle += target_velocity*Ts; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; @@ -371,7 +412,7 @@ void BLDCMotor::angleOpenloop(float target_angle){ shaft_angle = target_angle; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/BLDCMotor.h b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/BLDCMotor.h similarity index 71% rename from minimal_project_examples/arduino_foc_bldc_encoder/src/BLDCMotor.h rename to minimal_project_examples/atmega328_bldc_magnetic_i2c/src/BLDCMotor.h index a4fbb678..164cc108 100644 --- a/minimal_project_examples/arduino_foc_bldc_encoder/src/BLDCMotor.h +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/BLDCMotor.h @@ -1,16 +1,12 @@ -/** - * @file BLDCMotor.h - * - */ - #ifndef BLDCMotor_h #define BLDCMotor_h #include "Arduino.h" -#include "common/FOCMotor.h" +#include "common/base_classes/FOCMotor.h" +#include "common/base_classes/Sensor.h" +#include "common/base_classes/BLDCDriver.h" #include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "common/time_utils.h" #include "common/defaults.h" /** @@ -20,18 +16,27 @@ class BLDCMotor: public FOCMotor { public: /** - BLDCMotor class constructor - @param phA A phase pwm pin - @param phB B phase pwm pin - @param phC C phase pwm pin - @param pp pole pair number - @param cpr counts per rotation number (cpm=ppm*4) - @param en enable pin (optional input) + BLDCMotor class constructor + @param pp pole pairs number + */ + BLDCMotor(int pp); + + /** + * Function linking a motor and a foc driver + * + * @param driver BLDCDriver class implementing all the hardware specific functions necessary PWM setting + */ + void linkDriver(BLDCDriver* driver); + + /** + * BLDCDriver link: + * - 3PWM + * - 6PWM */ - BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + BLDCDriver* driver; /** Motor hardware init function */ - void init(long pwm_frequency = NOT_SET) override; + void init() override; /** Motor disable function */ void disable() override; /** Motor enable function */ @@ -59,12 +64,9 @@ class BLDCMotor: public FOCMotor * This function doesn't need to be run upon each loop execution - depends of the use case */ void move(float target = NOT_SET) override; - - // hardware variables - int pwmA; //!< phase A pwm pin number - int pwmB; //!< phase B pwm pin number - int pwmC; //!< phase C pwm pin number - int enable_pin; //!< enable pin number + + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform private: @@ -74,21 +76,15 @@ class BLDCMotor: public FOCMotor * Heart of the FOC algorithm * * @param Uq Current voltage in q axis to set to the motor + * @param Ud Current voltage in d axis to set to the motor * @param angle_el current electrical angle of the motor */ - void setPhaseVoltage(float Uq, float angle_el); + void setPhaseVoltage(float Uq, float Ud, float angle_el); /** Sensor alignment to electrical 0 angle of the motor */ int alignSensor(); /** Motor and sensor alignment to the sensors absolute 0 angle */ int absoluteZeroAlign(); - /** - * Set phase voltages to the harware - * - * @param Ua phase A voltage - * @param Ub phase B voltage - * @param Uc phase C voltage - */ - void setPwm(float Ua, float Ub, float Uc); + // Open loop motion control /** diff --git a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/BLDCDriver.h b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/BLDCDriver.h new file mode 100644 index 00000000..708323fb --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/BLDCDriver.h @@ -0,0 +1,28 @@ +#ifndef BLDCDRIVER_H +#define BLDCDRIVER_H + +class BLDCDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + virtual void setPwm(float Ua, float Ub, float Uc); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/FOCMotor.cpp b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/FOCMotor.cpp similarity index 98% rename from minimal_project_examples/arduino_foc_bldc_encoder/src/common/FOCMotor.cpp rename to minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/FOCMotor.cpp index adecbeec..1d1a0f43 100644 --- a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/FOCMotor.cpp +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/FOCMotor.cpp @@ -5,13 +5,10 @@ */ FOCMotor::FOCMotor() { - // Power supply voltage - voltage_power_supply = DEF_POWER_SUPPLY; - // maximum angular velocity to be used for positioning velocity_limit = DEF_VEL_LIM; // maximum voltage to be set to the motor - voltage_limit = voltage_power_supply; + voltage_limit = DEF_POWER_SUPPLY; // index search velocity velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; @@ -26,6 +23,8 @@ FOCMotor::FOCMotor() // default target value target = 0; + voltage_d = 0; + voltage_q = 0; //monitor_port monitor_port = nullptr; @@ -53,9 +52,6 @@ float FOCMotor::shaftVelocity() { return LPF_velocity(sensor->getVelocity()); } - - - /** * Monitoring functions */ diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/common/FOCMotor.h b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/FOCMotor.h similarity index 93% rename from minimal_project_examples/arduino_foc_bldc_hall/src/common/FOCMotor.h rename to minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/FOCMotor.h index 40f7f6d4..986e1ab2 100644 --- a/minimal_project_examples/arduino_foc_bldc_hall/src/common/FOCMotor.h +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/FOCMotor.h @@ -2,13 +2,14 @@ #define FOCMOTOR_H #include "Arduino.h" -#include "hardware_utils.h" -#include "foc_utils.h" -#include "defaults.h" - #include "Sensor.h" -#include "pid.h" -#include "lowpass_filter.h" +#include "BLDCDriver.h" + +#include "../time_utils.h" +#include "../foc_utils.h" +#include "../defaults.h" +#include "../pid.h" +#include "../lowpass_filter.h" /** @@ -27,7 +28,9 @@ enum ControlType{ */ enum FOCModulationType{ SinePWM, //!< Sinusoidal PWM modulation - SpaceVectorPWM //!< Space vector modulation method + SpaceVectorPWM, //!< Space vector modulation method + Trapezoid_120, + Trapezoid_150 }; /** @@ -42,7 +45,7 @@ class FOCMotor FOCMotor(); /** Motor hardware init function */ - virtual void init(long pwm_frequency)=0; + virtual void init()=0; /** Motor disable function */ virtual void disable()=0; /** Motor enable function */ @@ -55,6 +58,7 @@ class FOCMotor */ void linkSensor(Sensor* sensor); + /** * Function initializing FOC algorithm * and aligning sensor's and motors' zero position @@ -99,11 +103,9 @@ class FOCMotor float shaft_velocity_sp;//!< current target velocity float shaft_angle_sp;//!< current target angle float voltage_q;//!< current voltage u_q set - float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor - float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform + float voltage_d;//!< current voltage u_d set // motor configuration parameters - float voltage_power_supply;//!< Power supply voltage float voltage_sensor_align;//!< sensor and motor align voltage parameter float velocity_index_search;//!< target velocity for index search int pole_pairs;//!< Motor pole pairs number diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/common/Sensor.h b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/Sensor.h similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_hall/src/common/Sensor.h rename to minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/Sensor.h diff --git a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/StepperDriver.h b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/StepperDriver.h new file mode 100644 index 00000000..7800a4e7 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/base_classes/StepperDriver.h @@ -0,0 +1,27 @@ +#ifndef STEPPERDRIVER_H +#define STEPPERDRIVER_H + +class StepperDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + */ + virtual void setPwm(float Ua, float Ub); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/common/defaults.h b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/defaults.h similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_hall/src/common/defaults.h rename to minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/defaults.h diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/common/foc_utils.cpp b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/foc_utils.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_hall/src/common/foc_utils.cpp rename to minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/foc_utils.cpp diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/foc_utils.h b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/foc_utils.h similarity index 94% rename from minimal_project_examples/arduino_foc_bldc_encoder/src/common/foc_utils.h rename to minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/foc_utils.h index 5ab34f42..7da3f7bc 100644 --- a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/foc_utils.h +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/foc_utils.h @@ -6,6 +6,7 @@ // sign function #define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) #define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) +#define _constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt))) // utility defines #define _2_SQRT3 1.15470053838 @@ -20,7 +21,6 @@ #define _2PI 6.28318530718 #define _3PI_2 4.71238898038 - #define NOT_SET -12345.0 /** diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/common/lowpass_filter.cpp b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/lowpass_filter.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_hall/src/common/lowpass_filter.cpp rename to minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/lowpass_filter.cpp diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/lowpass_filter.h b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/lowpass_filter.h similarity index 94% rename from minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/lowpass_filter.h rename to minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/lowpass_filter.h index 5a7619cf..7c51be54 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/lowpass_filter.h +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/lowpass_filter.h @@ -2,7 +2,7 @@ #define LOWPASS_FILTER_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/pid.cpp b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/pid.cpp similarity index 92% rename from minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/pid.cpp rename to minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/pid.cpp index 277e17ce..1a0a9828 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/pid.cpp +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/pid.cpp @@ -25,12 +25,12 @@ float PIDController::operator() (float error){ // Discrete implementations // proportional part // u_p = P *e(k) - float proportional = P * error_prev; + float proportional = P * error; // Tustin transform of the integral part // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) float integral = integral_prev + I*Ts*0.5*(error + error_prev); // antiwindup - limit the output voltage_q - integral = constrain(integral, -limit, limit); + integral = _constrain(integral, -limit, limit); // Discrete derivation // u_dk = D(ek - ek_1)/Ts float derivative = D*(error - error_prev)/Ts; @@ -38,7 +38,7 @@ float PIDController::operator() (float error){ // sum all the components float output = proportional + integral + derivative; // antiwindup - limit the output variable - output = constrain(output, -limit, limit); + output = _constrain(output, -limit, limit); // limit the acceleration by ramping the output float output_rate = (output - output_prev)/Ts; diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/pid.h b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/pid.h similarity index 97% rename from minimal_project_examples/arduino_foc_bldc_openloop/src/common/pid.h rename to minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/pid.h index 7ee337c4..0e9ddf54 100644 --- a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/pid.h +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/pid.h @@ -2,7 +2,7 @@ #define PID_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" /** diff --git a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/time_utils.cpp b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/time_utils.cpp new file mode 100644 index 00000000..181d03cf --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/time_utils.cpp @@ -0,0 +1,31 @@ +#include "time_utils.h" + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/time_utils.h b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/time_utils.h new file mode 100644 index 00000000..143d4853 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/common/time_utils.h @@ -0,0 +1,22 @@ +#ifndef TIME_UTILS_H +#define TIME_UTILS_H + +#include "foc_utils.h" + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/BLDCDriver3PWM.cpp b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/BLDCDriver3PWM.cpp new file mode 100644 index 00000000..bacb4ec5 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/BLDCDriver3PWM.cpp @@ -0,0 +1,70 @@ +#include "BLDCDriver3PWM.h" + +BLDCDriver3PWM::BLDCDriver3PWM(int phA, int phB, int phC, int en){ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + + // enable_pin pin + enable_pin = en; + + // default power-supply value + voltage_power_supply = DEF_POWER_SUPPLY; + voltage_limit = NOT_SET; + +} + +// enable motor driver +void BLDCDriver3PWM::enable(){ + // enable_pin the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, HIGH); + // set zero to PWM + setPwm(0,0,0); +} + +// disable motor driver +void BLDCDriver3PWM::disable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // disable the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, LOW); + +} + +// init hardware pins +int BLDCDriver3PWM::init() { + + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); + + + // sanity check for the voltage limit configuration + if(voltage_limit == NOT_SET || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + + // Set the pwm frequency to the pins + // hardware specific function - depending on driver and mcu + _configure3PWM(pwm_frequency, pwmA, pwmB, pwmC); + return 0; +} + + +// Set voltage to the pwm pin +void BLDCDriver3PWM::setPwm(float Ua, float Ub, float Uc) { + // limit the voltage in driver + Ua = _constrain(Ua, -voltage_limit, voltage_limit); + Ub = _constrain(Ub, -voltage_limit, voltage_limit); + Uc = _constrain(Uc, -voltage_limit, voltage_limit); + // calculate duty cycle + // limited in [0,1] + float dc_a = _constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = _constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = _constrain(Uc / voltage_power_supply, 0 , 1 ); + // hardware specific writing + // hardware specific function - depending on driver and mcu + _writeDutyCycle3PWM(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC); +} \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/BLDCDriver3PWM.h b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/BLDCDriver3PWM.h new file mode 100644 index 00000000..b6f7d7f8 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/BLDCDriver3PWM.h @@ -0,0 +1,52 @@ +#ifndef BLDCDriver3PWM_h +#define BLDCDriver3PWM_h + +#include "../common/base_classes/BLDCDriver.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#include "../common/defaults.h" +#include "hardware_api.h" + +/** + 3 pwm bldc driver class +*/ +class BLDCDriver3PWM: public BLDCDriver +{ + public: + /** + BLDCDriver class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param en enable pin (optional input) + */ + BLDCDriver3PWM(int phA,int phB,int phC, int en = NOT_SET); + + /** Motor hardware init function */ + int init() override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc) override; + + private: + +}; + + +#endif diff --git a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_api.h b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_api.h new file mode 100644 index 00000000..da5ddf51 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_api.h @@ -0,0 +1,100 @@ +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H + +#include "../common/foc_utils.h" +#include "../common/time_utils.h" + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + * @param pinC pinC bldc driver + */ +void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC); + +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pin1A pin1A stepper driver + * @param pin1B pin1B stepper driver + * @param pin2A pin2A stepper driver + * @param pin2B pin2B stepper driver + */ +void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B); + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low - if applicable + * @param pinA_h pinA high-side bldc driver + * @param pinA_l pinA low-side bldc driver + * @param pinB_h pinA high-side bldc driver + * @param pinB_l pinA low-side bldc driver + * @param pinC_h pinA high-side bldc driver + * @param pinC_l pinA low-side bldc driver + * + * @return 0 if config good, -1 if failed + */ +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low + * @param pinA_h phase A high-side hardware pin number + * @param pinA_l phase A low-side hardware pin number + * @param pinB_h phase B high-side hardware pin number + * @param pinB_l phase B low-side hardware pin number + * @param pinC_h phase C high-side hardware pin number + * @param pinC_l phase C low-side hardware pin number + * + */ +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l); + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/atmega328_mcu.cpp b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/atmega328_mcu.cpp new file mode 100644 index 00000000..58b368f7 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/atmega328_mcu.cpp @@ -0,0 +1,133 @@ +#include "../hardware_api.h" + +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + +// set pwm frequency to 32KHz +void _pinHighFrequency(const int pin){ + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pin == 5 || pin == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pin == 9 || pin == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pin == 3 || pin == 11) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +} + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +// supports Arudino/ATmega328 +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); + _pinHighFrequency(pinC); +} + + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); + analogWrite(pinC, 255.0*dc_c); +} + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +// supports Arudino/ATmega328 +void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pin1A); + _pinHighFrequency(pin1B); + _pinHighFrequency(pin2A); + _pinHighFrequency(pin2B); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255.0*dc_1a); + analogWrite(pin1B, 255.0*dc_1b); + analogWrite(pin2A, 255.0*dc_2a); + analogWrite(pin2B, 255.0*dc_2b); +} + + +// function configuring pair of high-low side pwm channels, 32khz frequency and center aligned pwm +int _configureComplementaryPair(int pinH, int pinL) { + if( (pinH == 5 && pinL == 6 ) || (pinH == 6 && pinL == 5 ) ){ + // configure the pwm phase-corrected mode + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); + // configure complementary pwm on low side + if(pinH == 6 ) TCCR0A = 0b10110000 | (TCCR0A & 0b00001111) ; + else TCCR0A = 0b11100000 | (TCCR0A & 0b00001111) ; + // set prescaler to 1 - 32kHz freq + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); + }else if( (pinH == 9 && pinL == 10 ) || (pinH == 10 && pinL == 9 ) ){ + // set prescaler to 1 - 32kHz freq + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); + // configure complementary pwm on low side + if(pinH == 9 ) TCCR1A = 0b10110000 | (TCCR1A & 0b00001111) ; + else TCCR1A = 0b11100000 | (TCCR1A & 0b00001111) ; + }else if((pinH == 3 && pinL == 11 ) || (pinH == 11 && pinL == 3 ) ){ + // set prescaler to 1 - 32kHz freq + TCCR2B = ((TCCR2B & 0b11111000) | 0x01); + // configure complementary pwm on low side + if(pinH == 11 ) TCCR2A = 0b10110000 | (TCCR2A & 0b00001111) ; + else TCCR2A = 0b11100000 | (TCCR2A & 0b00001111) ; + }else{ + return -1; + } + return 0; +} + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +// supports Arudino/ATmega328 +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) { + // High PWM frequency + // - always max 32kHz + int ret_flag = 0; + ret_flag += _configureComplementaryPair(pinA_h, pinA_l); + ret_flag += _configureComplementaryPair(pinB_h, pinB_l); + ret_flag += _configureComplementaryPair(pinC_h, pinC_l); + return ret_flag; // returns -1 if not well configured +} + +// function setting the +void _setPwmPair(int pinH, int pinL, float val, int dead_time) +{ + int pwm_h = _constrain(val-dead_time/2,0,255); + int pwm_l = _constrain(val+dead_time/2,0,255); + + analogWrite(pinH, pwm_h); + if(pwm_l == 255 || pwm_l == 0) + digitalWrite(pinL, pwm_l ? LOW : HIGH); + else + analogWrite(pinL, pwm_l); +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +// supports Arudino/ATmega328 +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + _setPwmPair(pinA_h, pinA_l, dc_a*255.0, dead_zone*255.0); + _setPwmPair(pinB_h, pinB_l, dc_b*255.0, dead_zone*255.0); + _setPwmPair(pinC_h, pinC_l, dc_c*255.0, dead_zone*255.0); +} + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/generic_mcu.cpp b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/generic_mcu.cpp new file mode 100644 index 00000000..dc322746 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/generic_mcu.cpp @@ -0,0 +1,68 @@ +#include "../hardware_api.h" + +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if mcu is not atmega328 + +#elif defined(__arm__) && defined(CORE_TEENSY) // or teensy + +#elif defined(ESP_H) // or esp32 + +#elif defined(_STM32_DEF_) // or stm32 + +#else + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +// in generic case dont do anything +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + return; +} + + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +// in generic case dont do anything +void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) { + return; +} + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + return -1; +} + + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); + analogWrite(pinC, 255.0*dc_c); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255.0*dc_1a); + analogWrite(pin1B, 255.0*dc_1b); + analogWrite(pin2A, 255.0*dc_2a); + analogWrite(pin2B, 255.0*dc_2b); +} + + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + return; +} + + +#endif \ No newline at end of file diff --git a/library_source/MagneticSensorI2C.cpp b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/sensors/MagneticSensorI2C.cpp similarity index 79% rename from library_source/MagneticSensorI2C.cpp rename to minimal_project_examples/atmega328_bldc_magnetic_i2c/src/sensors/MagneticSensorI2C.cpp index a02b762b..accce08a 100644 --- a/library_source/MagneticSensorI2C.cpp +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/sensors/MagneticSensorI2C.cpp @@ -3,7 +3,6 @@ /** Typical configuration for the 12bit AMS AS5600 magnetic sensor over I2C interface */ MagneticSensorI2CConfig_s AS5600_I2C = { .chip_address = 0x36, - .clock_speed = 1000000, .bit_resolution = 12, .angle_register = 0x0E, .data_start_bit = 11 @@ -12,7 +11,6 @@ MagneticSensorI2CConfig_s AS5600_I2C = { /** Typical configuration for the 12bit AMS AS5048 magnetic sensor over I2C interface */ MagneticSensorI2CConfig_s AS5048_I2C = { .chip_address = 0x40, // highly configurable. if A1 and A2 are held low, this is probable value - .clock_speed = 1000000, .bit_resolution = 14, .angle_register = 0xFE, .data_start_bit = 15 @@ -41,10 +39,7 @@ MagneticSensorI2C::MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, // extraction masks lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); msb_mask = (uint8_t)( (2 << _bits_used_msb) - 1 ); - clock_speed = 400000; - sda_pin = SDA; - scl_pin = SCL; - + wire = &Wire; } MagneticSensorI2C::MagneticSensorI2C(MagneticSensorI2CConfig_s config){ @@ -60,29 +55,16 @@ MagneticSensorI2C::MagneticSensorI2C(MagneticSensorI2CConfig_s config){ // extraction masks lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); msb_mask = (uint8_t)( (2 << bits_used_msb) - 1 ); - clock_speed = 400000; - sda_pin = SDA; - scl_pin = SCL; - + wire = &Wire; } -void MagneticSensorI2C::init(){ +void MagneticSensorI2C::init(TwoWire* _wire){ + + wire = _wire; -#if defined(_STM32_DEF_) // if stm chips // I2C communication begin - Wire.begin(); - Wire.setClock(clock_speed); - Wire.setSCL(scl_pin); - Wire.setSDA(sda_pin); -#elif defined(ESP_H) // if esp32 - //I2C communication begin - Wire.begin(sda_pin, scl_pin, clock_speed); -#else - // I2C communication begin - Wire.begin(); - Wire.setClock(clock_speed); -#endif - + wire->begin(); + // velocity calculation init angle_prev = 0; velocity_calc_timestamp = _micros(); @@ -187,14 +169,14 @@ int MagneticSensorI2C::read(uint8_t angle_reg_msb) { byte readArray[2]; uint16_t readValue = 0; // notify the device that is aboout to be read - Wire.beginTransmission(chip_address); - Wire.write(angle_reg_msb); - Wire.endTransmission(false); + wire->beginTransmission(chip_address); + wire->write(angle_reg_msb); + wire->endTransmission(false); // read the data msb and lsb - Wire.requestFrom(chip_address, (uint8_t)2); + wire->requestFrom(chip_address, (uint8_t)2); for (byte i=0; i < 2; i++) { - readArray[i] = Wire.read(); + readArray[i] = wire->read(); } // depending on the sensor architecture there are different combinations of @@ -205,3 +187,46 @@ int MagneticSensorI2C::read(uint8_t angle_reg_msb) { readValue += ( ( readArray[0] & msb_mask ) << lsb_used ); return readValue; } + +/* +* Checks whether other devices have locked the bus. Can clear SDA locks. +* This should be called before sensor.init() on devices that suffer i2c slaves locking sda +* e.g some stm32 boards with AS5600 chips +* Takes the sda_pin and scl_pin +* Returns 0 for OK, 1 for other master and 2 for unfixable sda locked LOW +*/ +int MagneticSensorI2C::checkBus(byte sda_pin, byte scl_pin) { + + pinMode(scl_pin, INPUT_PULLUP); + pinMode(sda_pin, INPUT_PULLUP); + delay(250); + + if (digitalRead(scl_pin) == LOW) { + // Someone else has claimed master!"); + return 1; + } + + if(digitalRead(sda_pin) == LOW) { + // slave is communicating and awaiting clocks, we are blocked + pinMode(scl_pin, OUTPUT); + for (byte i = 0; i < 16; i++) { + // toggle clock for 2 bytes of data + digitalWrite(scl_pin, LOW); + delayMicroseconds(20); + digitalWrite(scl_pin, HIGH); + delayMicroseconds(20); + } + pinMode(sda_pin, INPUT); + delayMicroseconds(20); + if (digitalRead(sda_pin) == LOW) { + // SDA still blocked + return 2; + } + _delay(1000); + } + // SDA is clear (HIGH) + pinMode(sda_pin, INPUT); + pinMode(scl_pin, INPUT); + + return 0; +} diff --git a/library_source/MagneticSensorI2C.h b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/sensors/MagneticSensorI2C.h similarity index 88% rename from library_source/MagneticSensorI2C.h rename to minimal_project_examples/atmega328_bldc_magnetic_i2c/src/sensors/MagneticSensorI2C.h index 88d74d35..7fe4efeb 100644 --- a/library_source/MagneticSensorI2C.h +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/sensors/MagneticSensorI2C.h @@ -3,13 +3,12 @@ #include "Arduino.h" #include -#include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "../common/base_classes/Sensor.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" struct MagneticSensorI2CConfig_s { int chip_address; - long clock_speed; int bit_resolution; int angle_register; int data_start_bit; @@ -37,7 +36,7 @@ class MagneticSensorI2C: public Sensor{ static MagneticSensorI2C AS5600(); /** sensor initialise pins */ - void init(); + void init(TwoWire* _wire = &Wire); // implementation of abstract functions of the Sensor class /** get current angle (rad) */ @@ -60,14 +59,8 @@ class MagneticSensorI2C: public Sensor{ int needsAbsoluteZeroSearch() override; - /* the speed of the i2c clock signal */ - long clock_speed; - - /* the pin used for i2c data */ - int sda_pin; - - /* the pin used for i2c clock */ - int scl_pin; + /** experimental function to check and fix SDA locked LOW issues */ + int checkBus(byte sda_pin = SDA, byte scl_pin = SCL); private: float cpr; //!< Maximum range of the magnetic sensor @@ -98,6 +91,10 @@ class MagneticSensorI2C: public Sensor{ float angle_prev; //!< angle in previous velocity calculation step long velocity_calc_timestamp; //!< last velocity calculation timestamp + /* the two wire instance for this sensor */ + TwoWire* wire; + + }; diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/arduino_foc_bldc_openloop.ino b/minimal_project_examples/atmega328_bldc_openloop/atmega328_bldc_openloop.ino similarity index 54% rename from minimal_project_examples/arduino_foc_bldc_openloop/arduino_foc_bldc_openloop.ino rename to minimal_project_examples/atmega328_bldc_openloop/atmega328_bldc_openloop.ino index fa632c9b..20cf0295 100644 --- a/minimal_project_examples/arduino_foc_bldc_openloop/arduino_foc_bldc_openloop.ino +++ b/minimal_project_examples/atmega328_bldc_openloop/atmega328_bldc_openloop.ino @@ -1,49 +1,54 @@ #include "src/BLDCMotor.h" +#include "src/drivers/BLDCDriver3PWM.h" -// motor instance -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 7); +// BLDC motor & driver instance +// BLDCMotor motor = BLDCMotor(pole pair number); +BLDCMotor motor = BLDCMotor(11); +// BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional)); +BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8); void setup() { - // power supply voltage - // default 12V - motor.voltage_power_supply = 12; + // driver config + // power supply voltage [V] + driver.voltage_power_supply = 12; + driver.init(); + // link the motor and the driver + motor.linkDriver(&driver); // limiting motor movements - motor.voltage_limit = 3; // rad/s - motor.velocity_limit = 20; // rad/s + motor.voltage_limit = 3; // [V] + motor.velocity_limit = 20; // [rad/s] + // open loop control config motor.controller = ControlType::velocity_openloop; // init motor hardware motor.init(); - Serial.begin(115200); Serial.println("Motor ready!"); _delay(1000); } -float target_position = 0; // rad/s - +float target_velocity = 0; // [rad/s] void loop() { - // open loop angle movements + // open loop velocity movement // using motor.voltage_limit and motor.velocity_limit - motor.move(2); + motor.move(target_velocity); // receive the used commands from serial serialReceiveUserCommand(); - Serial.println(micros()); } // utility function enabling serial communication with the user to set the target values // this function can be implemented in serialEvent function as well void serialReceiveUserCommand() { - + // a string to hold incoming data static String received_chars; - + while (Serial.available()) { // get the new byte: char inChar = (char)Serial.read(); @@ -51,14 +56,14 @@ void serialReceiveUserCommand() { received_chars += inChar; // end of user input if (inChar == '\n') { - + // change the motor target - target_position = received_chars.toFloat(); - Serial.print("Target position: "); - Serial.println(target_position); - - // reset the command buffer + target_velocity = received_chars.toFloat(); + Serial.print("Target velocity "); + Serial.println(target_velocity); + + // reset the command buffer received_chars = ""; } } -} +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/BLDCMotor.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/BLDCMotor.cpp similarity index 68% rename from minimal_project_examples/arduino_foc_bldc_hall/src/BLDCMotor.cpp rename to minimal_project_examples/atmega328_bldc_openloop/src/BLDCMotor.cpp index 989b74a9..bed4cd6a 100644 --- a/minimal_project_examples/arduino_foc_bldc_hall/src/BLDCMotor.cpp +++ b/minimal_project_examples/atmega328_bldc_openloop/src/BLDCMotor.cpp @@ -1,41 +1,39 @@ #include "BLDCMotor.h" -// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// // BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// // - phA, phB, phC - motor A,B,C phase pwm pins +// // - pp - pole pair number +// // - cpr - counts per rotation number (cpm=ppm*4) +// // - enable pin - (optional input) +// BLDCMotor::BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en){ +// noop; +// } + +// BLDCMotor( int pp) // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - cpr - counts per rotation number (cpm=ppm*4) // - enable pin - (optional input) -BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +BLDCMotor::BLDCMotor(int pp) : FOCMotor() { - // Pin initialization - pwmA = phA; - pwmB = phB; - pwmC = phC; + // save pole pairs number pole_pairs = pp; +} - // enable_pin pin - enable_pin = en; +/** + Link the driver which controls the motor +*/ +void BLDCMotor::linkDriver(BLDCDriver* _driver) { + driver = _driver; } - // init hardware pins -void BLDCMotor::init(long pwm_frequency) { - if(monitor_port) monitor_port->println("MOT: Init pins."); - // PWM pins - pinMode(pwmA, OUTPUT); - pinMode(pwmB, OUTPUT); - pinMode(pwmC, OUTPUT); - if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); - - if(monitor_port) monitor_port->println("MOT: PWM config."); - // Increase PWM frequency to 32 kHz - // make silent - _setPwmFrequency(pwm_frequency, pwmA, pwmB, pwmC); - +void BLDCMotor::init() { + if(monitor_port) monitor_port->println("MOT: Initialise variables."); // sanity check for the voltage limit configuration - if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + if(voltage_limit > driver->voltage_limit) voltage_limit = driver->voltage_limit; // constrain voltage for sensor alignment if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; // update the controller limits @@ -44,7 +42,7 @@ void BLDCMotor::init(long pwm_frequency) { _delay(500); // enable motor - if(monitor_port) monitor_port->println("MOT: Enable."); + if(monitor_port) monitor_port->println("MOT: Enable driver."); enable(); _delay(500); } @@ -53,18 +51,18 @@ void BLDCMotor::init(long pwm_frequency) { // disable motor driver void BLDCMotor::disable() { - // disable the driver - if enable_pin pin available - if (enable_pin != NOT_SET) digitalWrite(enable_pin, LOW); // set zero to PWM - setPwm(0, 0, 0); + driver->setPwm(0, 0, 0); + // disable the driver + driver->disable(); } // enable motor driver void BLDCMotor::enable() { + // enable the driver + driver->enable(); // set zero to PWM - setPwm(0, 0, 0); - // enable_pin the driver - if enable_pin pin available - if (enable_pin != NOT_SET) digitalWrite(enable_pin, HIGH); + driver->setPwm(0, 0, 0); } @@ -100,13 +98,13 @@ int BLDCMotor::alignSensor() { float start_angle = shaftAngle(); for (int i = 0; i <=5; i++ ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } float mid_angle = shaftAngle(); for (int i = 5; i >=0; i-- ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } if (mid_angle < start_angle) { @@ -121,7 +119,7 @@ int BLDCMotor::alignSensor() { // set sensor to zero sensor->initRelativeZero(); _delay(500); - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); _delay(200); // find the index if available @@ -153,7 +151,7 @@ int BLDCMotor::absoluteZeroAlign() { } voltage_q = 0; // disable motor - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); // align absolute zero if it has been found if(!sensor->needsAbsoluteZeroSearch()){ @@ -172,7 +170,7 @@ void BLDCMotor::loopFOC() { // shaft angle shaft_angle = shaftAngle(); // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); + setPhaseVoltage(voltage_q, voltage_d, _electricalAngle(shaft_angle,pole_pairs)); } // Iterative function running outer loop of the FOC algorithm @@ -219,15 +217,60 @@ void BLDCMotor::move(float new_target) { } -// Method using FOC to set Uq to the motor at the optimal angle +// Method using FOC to set Uq and Ud to the motor at the optimal angle // Function implementing Space Vector PWM and Sine PWM algorithms // // Function using sine approximation // regular sin + cos ~300us (no memory usaage) // approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { +void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { + + const bool centered = true; + int sector; + float _ca,_sa; + switch (foc_modulation) { + case FOCModulationType::Trapezoid_120 : + // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 5 + static int trap_120_map[6][3] = { + {0,1,-1},{-1,1,0},{-1,0,1},{0,-1,1},{1,-1,0},{1,0,-1} // each is 60 degrees with values for 3 phases of 1=positive -1=negative 0=high-z + }; + // static int trap_120_state = 0; + sector = 6 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes + + Ua = Uq + trap_120_map[sector][0] * Uq; + Ub = Uq + trap_120_map[sector][1] * Uq; + Uc = Uq + trap_120_map[sector][2] * Uq; + + if (centered) { + Ua += (driver->voltage_limit)/2 -Uq; + Ub += (driver->voltage_limit)/2 -Uq; + Uc += (driver->voltage_limit)/2 -Uq; + } + break; + + case FOCModulationType::Trapezoid_150 : + // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 8 + static int trap_150_map[12][3] = { + {0,1,-1},{-1,1,-1},{-1,1,0},{-1,1,1},{-1,0,1},{-1,-1,1},{0,-1,1},{1,-1,1},{1,-1,0},{1,-1,-1},{1,0,-1},{1,1,-1} // each is 30 degrees with values for 3 phases of 1=positive -1=negative 0=high-z + }; + // static int trap_150_state = 0; + sector = 12 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes + + Ua = Uq + trap_150_map[sector][0] * Uq; + Ub = Uq + trap_150_map[sector][1] * Uq; + Uc = Uq + trap_150_map[sector][2] * Uq; + + //center + if (centered) { + Ua += (driver->voltage_limit)/2 -Uq; + Ub += (driver->voltage_limit)/2 -Uq; + Uc += (driver->voltage_limit)/2 -Uq; + } + + break; + case FOCModulationType::SinePWM : // Sinusoidal PWM modulation // Inverse Park + Clarke transformation @@ -235,14 +278,24 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // angle normalization in between 0 and 2pi // only necessary if using _sin and _cos - approximation functions angle_el = _normalizeAngle(angle_el + zero_electric_angle); + _ca = _cos(angle_el); + _sa = _sin(angle_el); // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + Ualpha = _ca * Ud - _sa * Uq; // -sin(angle) * Uq; + Ubeta = _sa * Ud + _ca * Uq; // cos(angle) * Uq; // Clarke transform - Ua = Ualpha + voltage_power_supply/2; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + Ua = Ualpha + driver->voltage_limit/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + driver->voltage_limit/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + driver->voltage_limit/2; + + if (!centered) { + float Umin = min(Ua, min(Ub, Uc)); + Ua -= Umin; + Ub -= Umin; + Uc -= Umin; + } + break; case FOCModulationType::SpaceVectorPWM : @@ -259,15 +312,15 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { angle_el = _normalizeAngle(angle_el + zero_electric_angle + _PI_2); // find the sector we are in currently - int sector = floor(angle_el / _PI_3) + 1; + sector = floor(angle_el / _PI_3) + 1; // calculate the duty cycles - float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; - float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/driver->voltage_limit; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/driver->voltage_limit; // two versions possible - // centered around voltage_power_supply/2 - float T0 = 1 - T1 - T2; - // pulled to 0 - better for low power supply voltage - //float T0 = 0; + float T0 = 0; // pulled to 0 - better for low power supply voltage + if (centered) { + T0 = 1 - T1 - T2; //centered around driver->voltage_limit/2 + } // calculate the duty cycles(times) float Ta,Tb,Tc; @@ -310,27 +363,15 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { } // calculate the phase voltages and center - Ua = Ta*voltage_power_supply; - Ub = Tb*voltage_power_supply; - Uc = Tc*voltage_power_supply; + Ua = Ta*driver->voltage_limit; + Ub = Tb*driver->voltage_limit; + Uc = Tc*driver->voltage_limit; break; + } - // set the voltages in hardware - setPwm(Ua, Ub, Uc); -} - - - -// Set voltage to the pwm pin -void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { - // calculate duty cycle - // limited in [0,1] - float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); - float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); - float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); - // hardware specific writing - _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); + // set the voltages in driver + driver->setPwm(Ua, Ub, Uc); } @@ -348,7 +389,7 @@ void BLDCMotor::velocityOpenloop(float target_velocity){ shaft_angle += target_velocity*Ts; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; @@ -371,7 +412,7 @@ void BLDCMotor::angleOpenloop(float target_angle){ shaft_angle = target_angle; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/BLDCMotor.h b/minimal_project_examples/atmega328_bldc_openloop/src/BLDCMotor.h similarity index 71% rename from minimal_project_examples/arduino_foc_bldc_hall/src/BLDCMotor.h rename to minimal_project_examples/atmega328_bldc_openloop/src/BLDCMotor.h index a4fbb678..164cc108 100644 --- a/minimal_project_examples/arduino_foc_bldc_hall/src/BLDCMotor.h +++ b/minimal_project_examples/atmega328_bldc_openloop/src/BLDCMotor.h @@ -1,16 +1,12 @@ -/** - * @file BLDCMotor.h - * - */ - #ifndef BLDCMotor_h #define BLDCMotor_h #include "Arduino.h" -#include "common/FOCMotor.h" +#include "common/base_classes/FOCMotor.h" +#include "common/base_classes/Sensor.h" +#include "common/base_classes/BLDCDriver.h" #include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "common/time_utils.h" #include "common/defaults.h" /** @@ -20,18 +16,27 @@ class BLDCMotor: public FOCMotor { public: /** - BLDCMotor class constructor - @param phA A phase pwm pin - @param phB B phase pwm pin - @param phC C phase pwm pin - @param pp pole pair number - @param cpr counts per rotation number (cpm=ppm*4) - @param en enable pin (optional input) + BLDCMotor class constructor + @param pp pole pairs number + */ + BLDCMotor(int pp); + + /** + * Function linking a motor and a foc driver + * + * @param driver BLDCDriver class implementing all the hardware specific functions necessary PWM setting + */ + void linkDriver(BLDCDriver* driver); + + /** + * BLDCDriver link: + * - 3PWM + * - 6PWM */ - BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + BLDCDriver* driver; /** Motor hardware init function */ - void init(long pwm_frequency = NOT_SET) override; + void init() override; /** Motor disable function */ void disable() override; /** Motor enable function */ @@ -59,12 +64,9 @@ class BLDCMotor: public FOCMotor * This function doesn't need to be run upon each loop execution - depends of the use case */ void move(float target = NOT_SET) override; - - // hardware variables - int pwmA; //!< phase A pwm pin number - int pwmB; //!< phase B pwm pin number - int pwmC; //!< phase C pwm pin number - int enable_pin; //!< enable pin number + + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform private: @@ -74,21 +76,15 @@ class BLDCMotor: public FOCMotor * Heart of the FOC algorithm * * @param Uq Current voltage in q axis to set to the motor + * @param Ud Current voltage in d axis to set to the motor * @param angle_el current electrical angle of the motor */ - void setPhaseVoltage(float Uq, float angle_el); + void setPhaseVoltage(float Uq, float Ud, float angle_el); /** Sensor alignment to electrical 0 angle of the motor */ int alignSensor(); /** Motor and sensor alignment to the sensors absolute 0 angle */ int absoluteZeroAlign(); - /** - * Set phase voltages to the harware - * - * @param Ua phase A voltage - * @param Ub phase B voltage - * @param Uc phase C voltage - */ - void setPwm(float Ua, float Ub, float Uc); + // Open loop motion control /** diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/BLDCDriver.h b/minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/BLDCDriver.h new file mode 100644 index 00000000..708323fb --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/BLDCDriver.h @@ -0,0 +1,28 @@ +#ifndef BLDCDRIVER_H +#define BLDCDRIVER_H + +class BLDCDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + virtual void setPwm(float Ua, float Ub, float Uc); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/FOCMotor.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/FOCMotor.cpp similarity index 98% rename from minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/FOCMotor.cpp rename to minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/FOCMotor.cpp index adecbeec..1d1a0f43 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/FOCMotor.cpp +++ b/minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/FOCMotor.cpp @@ -5,13 +5,10 @@ */ FOCMotor::FOCMotor() { - // Power supply voltage - voltage_power_supply = DEF_POWER_SUPPLY; - // maximum angular velocity to be used for positioning velocity_limit = DEF_VEL_LIM; // maximum voltage to be set to the motor - voltage_limit = voltage_power_supply; + voltage_limit = DEF_POWER_SUPPLY; // index search velocity velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; @@ -26,6 +23,8 @@ FOCMotor::FOCMotor() // default target value target = 0; + voltage_d = 0; + voltage_q = 0; //monitor_port monitor_port = nullptr; @@ -53,9 +52,6 @@ float FOCMotor::shaftVelocity() { return LPF_velocity(sensor->getVelocity()); } - - - /** * Monitoring functions */ diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/FOCMotor.h b/minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/FOCMotor.h similarity index 93% rename from minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/FOCMotor.h rename to minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/FOCMotor.h index 40f7f6d4..986e1ab2 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/FOCMotor.h +++ b/minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/FOCMotor.h @@ -2,13 +2,14 @@ #define FOCMOTOR_H #include "Arduino.h" -#include "hardware_utils.h" -#include "foc_utils.h" -#include "defaults.h" - #include "Sensor.h" -#include "pid.h" -#include "lowpass_filter.h" +#include "BLDCDriver.h" + +#include "../time_utils.h" +#include "../foc_utils.h" +#include "../defaults.h" +#include "../pid.h" +#include "../lowpass_filter.h" /** @@ -27,7 +28,9 @@ enum ControlType{ */ enum FOCModulationType{ SinePWM, //!< Sinusoidal PWM modulation - SpaceVectorPWM //!< Space vector modulation method + SpaceVectorPWM, //!< Space vector modulation method + Trapezoid_120, + Trapezoid_150 }; /** @@ -42,7 +45,7 @@ class FOCMotor FOCMotor(); /** Motor hardware init function */ - virtual void init(long pwm_frequency)=0; + virtual void init()=0; /** Motor disable function */ virtual void disable()=0; /** Motor enable function */ @@ -55,6 +58,7 @@ class FOCMotor */ void linkSensor(Sensor* sensor); + /** * Function initializing FOC algorithm * and aligning sensor's and motors' zero position @@ -99,11 +103,9 @@ class FOCMotor float shaft_velocity_sp;//!< current target velocity float shaft_angle_sp;//!< current target angle float voltage_q;//!< current voltage u_q set - float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor - float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform + float voltage_d;//!< current voltage u_d set // motor configuration parameters - float voltage_power_supply;//!< Power supply voltage float voltage_sensor_align;//!< sensor and motor align voltage parameter float velocity_index_search;//!< target velocity for index search int pole_pairs;//!< Motor pole pairs number diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/Sensor.h b/minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/Sensor.h similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/Sensor.h rename to minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/Sensor.h diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/StepperDriver.h b/minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/StepperDriver.h new file mode 100644 index 00000000..7800a4e7 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_openloop/src/common/base_classes/StepperDriver.h @@ -0,0 +1,27 @@ +#ifndef STEPPERDRIVER_H +#define STEPPERDRIVER_H + +class StepperDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + */ + virtual void setPwm(float Ua, float Ub); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/defaults.h b/minimal_project_examples/atmega328_bldc_openloop/src/common/defaults.h similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/defaults.h rename to minimal_project_examples/atmega328_bldc_openloop/src/common/defaults.h diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/foc_utils.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/common/foc_utils.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/foc_utils.cpp rename to minimal_project_examples/atmega328_bldc_openloop/src/common/foc_utils.cpp diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/foc_utils.h b/minimal_project_examples/atmega328_bldc_openloop/src/common/foc_utils.h similarity index 94% rename from minimal_project_examples/arduino_foc_bldc_openloop/src/common/foc_utils.h rename to minimal_project_examples/atmega328_bldc_openloop/src/common/foc_utils.h index 5ab34f42..7da3f7bc 100644 --- a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/foc_utils.h +++ b/minimal_project_examples/atmega328_bldc_openloop/src/common/foc_utils.h @@ -6,6 +6,7 @@ // sign function #define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) #define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) +#define _constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt))) // utility defines #define _2_SQRT3 1.15470053838 @@ -20,7 +21,6 @@ #define _2PI 6.28318530718 #define _3PI_2 4.71238898038 - #define NOT_SET -12345.0 /** diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/lowpass_filter.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/common/lowpass_filter.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_i2c/src/common/lowpass_filter.cpp rename to minimal_project_examples/atmega328_bldc_openloop/src/common/lowpass_filter.cpp diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/common/lowpass_filter.h b/minimal_project_examples/atmega328_bldc_openloop/src/common/lowpass_filter.h similarity index 94% rename from minimal_project_examples/arduino_foc_bldc_hall/src/common/lowpass_filter.h rename to minimal_project_examples/atmega328_bldc_openloop/src/common/lowpass_filter.h index 5a7619cf..7c51be54 100644 --- a/minimal_project_examples/arduino_foc_bldc_hall/src/common/lowpass_filter.h +++ b/minimal_project_examples/atmega328_bldc_openloop/src/common/lowpass_filter.h @@ -2,7 +2,7 @@ #define LOWPASS_FILTER_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/common/pid.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/common/pid.cpp similarity index 92% rename from minimal_project_examples/arduino_foc_bldc_hall/src/common/pid.cpp rename to minimal_project_examples/atmega328_bldc_openloop/src/common/pid.cpp index 277e17ce..1a0a9828 100644 --- a/minimal_project_examples/arduino_foc_bldc_hall/src/common/pid.cpp +++ b/minimal_project_examples/atmega328_bldc_openloop/src/common/pid.cpp @@ -25,12 +25,12 @@ float PIDController::operator() (float error){ // Discrete implementations // proportional part // u_p = P *e(k) - float proportional = P * error_prev; + float proportional = P * error; // Tustin transform of the integral part // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) float integral = integral_prev + I*Ts*0.5*(error + error_prev); // antiwindup - limit the output voltage_q - integral = constrain(integral, -limit, limit); + integral = _constrain(integral, -limit, limit); // Discrete derivation // u_dk = D(ek - ek_1)/Ts float derivative = D*(error - error_prev)/Ts; @@ -38,7 +38,7 @@ float PIDController::operator() (float error){ // sum all the components float output = proportional + integral + derivative; // antiwindup - limit the output variable - output = constrain(output, -limit, limit); + output = _constrain(output, -limit, limit); // limit the acceleration by ramping the output float output_rate = (output - output_prev)/Ts; diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/common/pid.h b/minimal_project_examples/atmega328_bldc_openloop/src/common/pid.h similarity index 97% rename from minimal_project_examples/arduino_foc_bldc_hall/src/common/pid.h rename to minimal_project_examples/atmega328_bldc_openloop/src/common/pid.h index 7ee337c4..0e9ddf54 100644 --- a/minimal_project_examples/arduino_foc_bldc_hall/src/common/pid.h +++ b/minimal_project_examples/atmega328_bldc_openloop/src/common/pid.h @@ -2,7 +2,7 @@ #define PID_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" /** diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/common/time_utils.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/common/time_utils.cpp new file mode 100644 index 00000000..181d03cf --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_openloop/src/common/time_utils.cpp @@ -0,0 +1,31 @@ +#include "time_utils.h" + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/common/time_utils.h b/minimal_project_examples/atmega328_bldc_openloop/src/common/time_utils.h new file mode 100644 index 00000000..143d4853 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_openloop/src/common/time_utils.h @@ -0,0 +1,22 @@ +#ifndef TIME_UTILS_H +#define TIME_UTILS_H + +#include "foc_utils.h" + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/BLDCDriver3PWM.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/BLDCDriver3PWM.cpp new file mode 100644 index 00000000..bacb4ec5 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/BLDCDriver3PWM.cpp @@ -0,0 +1,70 @@ +#include "BLDCDriver3PWM.h" + +BLDCDriver3PWM::BLDCDriver3PWM(int phA, int phB, int phC, int en){ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + + // enable_pin pin + enable_pin = en; + + // default power-supply value + voltage_power_supply = DEF_POWER_SUPPLY; + voltage_limit = NOT_SET; + +} + +// enable motor driver +void BLDCDriver3PWM::enable(){ + // enable_pin the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, HIGH); + // set zero to PWM + setPwm(0,0,0); +} + +// disable motor driver +void BLDCDriver3PWM::disable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // disable the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, LOW); + +} + +// init hardware pins +int BLDCDriver3PWM::init() { + + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); + + + // sanity check for the voltage limit configuration + if(voltage_limit == NOT_SET || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + + // Set the pwm frequency to the pins + // hardware specific function - depending on driver and mcu + _configure3PWM(pwm_frequency, pwmA, pwmB, pwmC); + return 0; +} + + +// Set voltage to the pwm pin +void BLDCDriver3PWM::setPwm(float Ua, float Ub, float Uc) { + // limit the voltage in driver + Ua = _constrain(Ua, -voltage_limit, voltage_limit); + Ub = _constrain(Ub, -voltage_limit, voltage_limit); + Uc = _constrain(Uc, -voltage_limit, voltage_limit); + // calculate duty cycle + // limited in [0,1] + float dc_a = _constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = _constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = _constrain(Uc / voltage_power_supply, 0 , 1 ); + // hardware specific writing + // hardware specific function - depending on driver and mcu + _writeDutyCycle3PWM(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC); +} \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/BLDCDriver3PWM.h b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/BLDCDriver3PWM.h new file mode 100644 index 00000000..b6f7d7f8 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/BLDCDriver3PWM.h @@ -0,0 +1,52 @@ +#ifndef BLDCDriver3PWM_h +#define BLDCDriver3PWM_h + +#include "../common/base_classes/BLDCDriver.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#include "../common/defaults.h" +#include "hardware_api.h" + +/** + 3 pwm bldc driver class +*/ +class BLDCDriver3PWM: public BLDCDriver +{ + public: + /** + BLDCDriver class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param en enable pin (optional input) + */ + BLDCDriver3PWM(int phA,int phB,int phC, int en = NOT_SET); + + /** Motor hardware init function */ + int init() override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc) override; + + private: + +}; + + +#endif diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_api.h b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_api.h new file mode 100644 index 00000000..da5ddf51 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_api.h @@ -0,0 +1,100 @@ +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H + +#include "../common/foc_utils.h" +#include "../common/time_utils.h" + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + * @param pinC pinC bldc driver + */ +void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC); + +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pin1A pin1A stepper driver + * @param pin1B pin1B stepper driver + * @param pin2A pin2A stepper driver + * @param pin2B pin2B stepper driver + */ +void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B); + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low - if applicable + * @param pinA_h pinA high-side bldc driver + * @param pinA_l pinA low-side bldc driver + * @param pinB_h pinA high-side bldc driver + * @param pinB_l pinA low-side bldc driver + * @param pinC_h pinA high-side bldc driver + * @param pinC_l pinA low-side bldc driver + * + * @return 0 if config good, -1 if failed + */ +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low + * @param pinA_h phase A high-side hardware pin number + * @param pinA_l phase A low-side hardware pin number + * @param pinB_h phase B high-side hardware pin number + * @param pinB_l phase B low-side hardware pin number + * @param pinC_h phase C high-side hardware pin number + * @param pinC_l phase C low-side hardware pin number + * + */ +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l); + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/atmega328_mcu.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/atmega328_mcu.cpp new file mode 100644 index 00000000..58b368f7 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/atmega328_mcu.cpp @@ -0,0 +1,133 @@ +#include "../hardware_api.h" + +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + +// set pwm frequency to 32KHz +void _pinHighFrequency(const int pin){ + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pin == 5 || pin == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pin == 9 || pin == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pin == 3 || pin == 11) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +} + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +// supports Arudino/ATmega328 +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); + _pinHighFrequency(pinC); +} + + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); + analogWrite(pinC, 255.0*dc_c); +} + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +// supports Arudino/ATmega328 +void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pin1A); + _pinHighFrequency(pin1B); + _pinHighFrequency(pin2A); + _pinHighFrequency(pin2B); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255.0*dc_1a); + analogWrite(pin1B, 255.0*dc_1b); + analogWrite(pin2A, 255.0*dc_2a); + analogWrite(pin2B, 255.0*dc_2b); +} + + +// function configuring pair of high-low side pwm channels, 32khz frequency and center aligned pwm +int _configureComplementaryPair(int pinH, int pinL) { + if( (pinH == 5 && pinL == 6 ) || (pinH == 6 && pinL == 5 ) ){ + // configure the pwm phase-corrected mode + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); + // configure complementary pwm on low side + if(pinH == 6 ) TCCR0A = 0b10110000 | (TCCR0A & 0b00001111) ; + else TCCR0A = 0b11100000 | (TCCR0A & 0b00001111) ; + // set prescaler to 1 - 32kHz freq + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); + }else if( (pinH == 9 && pinL == 10 ) || (pinH == 10 && pinL == 9 ) ){ + // set prescaler to 1 - 32kHz freq + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); + // configure complementary pwm on low side + if(pinH == 9 ) TCCR1A = 0b10110000 | (TCCR1A & 0b00001111) ; + else TCCR1A = 0b11100000 | (TCCR1A & 0b00001111) ; + }else if((pinH == 3 && pinL == 11 ) || (pinH == 11 && pinL == 3 ) ){ + // set prescaler to 1 - 32kHz freq + TCCR2B = ((TCCR2B & 0b11111000) | 0x01); + // configure complementary pwm on low side + if(pinH == 11 ) TCCR2A = 0b10110000 | (TCCR2A & 0b00001111) ; + else TCCR2A = 0b11100000 | (TCCR2A & 0b00001111) ; + }else{ + return -1; + } + return 0; +} + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +// supports Arudino/ATmega328 +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) { + // High PWM frequency + // - always max 32kHz + int ret_flag = 0; + ret_flag += _configureComplementaryPair(pinA_h, pinA_l); + ret_flag += _configureComplementaryPair(pinB_h, pinB_l); + ret_flag += _configureComplementaryPair(pinC_h, pinC_l); + return ret_flag; // returns -1 if not well configured +} + +// function setting the +void _setPwmPair(int pinH, int pinL, float val, int dead_time) +{ + int pwm_h = _constrain(val-dead_time/2,0,255); + int pwm_l = _constrain(val+dead_time/2,0,255); + + analogWrite(pinH, pwm_h); + if(pwm_l == 255 || pwm_l == 0) + digitalWrite(pinL, pwm_l ? LOW : HIGH); + else + analogWrite(pinL, pwm_l); +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +// supports Arudino/ATmega328 +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + _setPwmPair(pinA_h, pinA_l, dc_a*255.0, dead_zone*255.0); + _setPwmPair(pinB_h, pinB_l, dc_b*255.0, dead_zone*255.0); + _setPwmPair(pinC_h, pinC_l, dc_c*255.0, dead_zone*255.0); +} + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/esp32_mcu.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/esp32_mcu.cpp new file mode 100644 index 00000000..3c07a445 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/esp32_mcu.cpp @@ -0,0 +1,296 @@ +#include "../hardware_api.h" + +#if defined(ESP_H) + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +// empty motor slot +#define _EMPTY_SLOT -20 +#define _TAKEN_SLOT -21 + +// structure containing motor slot configuration +// this library supports up to 4 motors +typedef struct { + int pinA; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; + mcpwm_io_signals_t mcpwm_c; +} bldc_3pwm_motor_slots_t; +typedef struct { + int pin1A; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_1a; + mcpwm_io_signals_t mcpwm_1b; + mcpwm_io_signals_t mcpwm_2a; + mcpwm_io_signals_t mcpwm_2b; +} stepper_motor_slots_t; + +typedef struct { + int pinAH; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_ah; + mcpwm_io_signals_t mcpwm_bh; + mcpwm_io_signals_t mcpwm_ch; + mcpwm_io_signals_t mcpwm_al; + mcpwm_io_signals_t mcpwm_bl; + mcpwm_io_signals_t mcpwm_cl; +} bldc_6pwm_motor_slots_t; + +// define bldc motor slots array +bldc_3pwm_motor_slots_t esp32_bldc_3pwm_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B + }; + +// define stepper motor slots array +stepper_motor_slots_t esp32_stepper_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + }; + +// define stepper motor slots array +bldc_6pwm_motor_slots_t esp32_bldc_6pwm_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0 + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0 + }; + +// configuring high frequency pwm timer +// a lot of help from this post from Paul Gauld +// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller +void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit, float dead_zone = NOT_SET){ + + mcpwm_config_t pwm_config; + pwm_config.frequency = pwm_frequency; //frequency + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + if (dead_zone != NOT_SET){ + // dead zone is configured in dead_time x 100 nanoseconds + float dead_time = (float)(1e7 / pwm_frequency) * dead_zone; + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); + } + + _delay(100); + + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 0; +} + + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(2*pwm_frequency, 0, 100000); // constrain to 50kHz max - centered pwm has twice lower frequency + + bldc_3pwm_motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + int slot_num; + for(slot_num = 0; slot_num < 4; slot_num++){ + if(esp32_bldc_3pwm_motor_slots[slot_num].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_3pwm_motor_slots[slot_num].pinA = pinA; + m_slot = esp32_bldc_3pwm_motor_slots[slot_num]; + break; + } + } + // disable all the slots with the same MCPWM + if( slot_num < 2 ){ + // slot 0 of the stepper + esp32_stepper_motor_slots[0].pin1A = _TAKEN_SLOT; + // slot 0 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; + }else{ + // slot 1 of the stepper + esp32_stepper_motor_slots[1].pin1A = _TAKEN_SLOT; + // slot 1 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; + } + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + +} + + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(2*pwm_frequency, 0, 100000); // constrain to 50kHz max - centered pwm has twice lower frequency + stepper_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + int slot_num; + for(slot_num = 0; slot_num < 2; slot_num++){ + if(esp32_stepper_motor_slots[slot_num].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_motor_slots[slot_num].pin1A = pinA; + m_slot = esp32_stepper_motor_slots[slot_num]; + break; + } + } + // disable all the slots with the same MCPWM + if( slot_num == 0 ){ + // slots 0 and 1 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT; + // slot 0 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; + }else{ + // slots 2 and 3 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT; + // slot 1 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); +} + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +// ESP32 uses MCPWM +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_bldc_3pwm_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,100] + mcpwm_set_duty(esp32_bldc_3pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_bldc_3pwm_motor_slots[i].mcpwm_operator, dc_a*100.0); + mcpwm_set_duty(esp32_bldc_3pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_bldc_3pwm_motor_slots[i].mcpwm_operator, dc_b*100.0); + mcpwm_set_duty(esp32_bldc_3pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, esp32_bldc_3pwm_motor_slots[i].mcpwm_operator, dc_c*100.0); + break; + } + } +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +// ESP32 uses MCPWM +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,100] + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_motor_slots[i].mcpwm_operator1, dc_1a*100.0); + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_motor_slots[i].mcpwm_operator1, dc_1b*100.0); + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_motor_slots[i].mcpwm_operator2, dc_2a*100.0); + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_motor_slots[i].mcpwm_operator2, dc_2b*100.0); + break; + } + } +} + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency + bldc_6pwm_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + int slot_num; + for(slot_num = 0; slot_num < 2; slot_num++){ + if(esp32_bldc_6pwm_motor_slots[slot_num].pinAH == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_6pwm_motor_slots[slot_num].pinAH = pinA_h; + m_slot = esp32_bldc_6pwm_motor_slots[slot_num]; + break; + } + } + // if no slots available + if(slot_num >= 2) return -1; + + // disable all the slots with the same MCPWM + if( slot_num == 0 ){ + // slots 0 and 1 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT; + // slot 0 of the 6pwm bldc + esp32_stepper_motor_slots[0].pin1A = _TAKEN_SLOT; + }else{ + // slots 2 and 3 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT; + // slot 1 of the 6pwm bldc + esp32_stepper_motor_slots[1].pin1A = _TAKEN_SLOT; + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_ah, pinA_h); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_al, pinA_l); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_bh, pinB_h); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_bl, pinB_l); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_ch, pinC_h); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_cl, pinC_l); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit, dead_zone); + // return + return 0; +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_bldc_6pwm_motor_slots[i].pinAH == pinA_h){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,100.0] + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_A, dc_a*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_B, dc_a*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_A, dc_b*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_B, dc_b*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_A, dc_c*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_B, dc_c*100.0); + break; + } + } +} +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/generic_mcu.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/generic_mcu.cpp new file mode 100644 index 00000000..dc322746 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/generic_mcu.cpp @@ -0,0 +1,68 @@ +#include "../hardware_api.h" + +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if mcu is not atmega328 + +#elif defined(__arm__) && defined(CORE_TEENSY) // or teensy + +#elif defined(ESP_H) // or esp32 + +#elif defined(_STM32_DEF_) // or stm32 + +#else + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +// in generic case dont do anything +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + return; +} + + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +// in generic case dont do anything +void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) { + return; +} + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + return -1; +} + + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); + analogWrite(pinC, 255.0*dc_c); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255.0*dc_1a); + analogWrite(pin1B, 255.0*dc_1b); + analogWrite(pin2A, 255.0*dc_2a); + analogWrite(pin2B, 255.0*dc_2b); +} + + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + return; +} + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/stm32_mcu.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/stm32_mcu.cpp new file mode 100644 index 00000000..85d0bd65 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/stm32_mcu.cpp @@ -0,0 +1,291 @@ + +#include "../hardware_api.h" + +#if defined(_STM32_DEF_) + +#define _PWM_RESOLUTION 12 // 12bit +#define _PWM_RANGE 4095.0// 2^12 -1 = 4095 +#define _PWM_FREQUENCY 50000 // 50khz + + +#define _HARDWARE_6PWM 1 +#define _SOFTWARE_6PWM 0 +#define _ERROR_6PWM -1 + + +// setting pwm to hardware pin - instead analogWrite() +void _setPwm(int ulPin, uint32_t value, int resolution) +{ + PinName pin = digitalPinToPinName(ulPin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); + uint32_t index = get_timer_index(Instance); + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HT->setCaptureCompare(channel, value, (TimerCompareFormat_t)resolution); +} + + +// init pin pwm +HardwareTimer* _initPinPWM(uint32_t PWM_freq, int ulPin) +{ + PinName pin = digitalPinToPinName(ulPin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); + + uint32_t index = get_timer_index(Instance); + if (HardwareTimer_Handle[index] == NULL) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM)); + HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); + } + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, pin); + HT->setOverflow(PWM_freq, HERTZ_FORMAT); + HT->pause(); + HT->refresh(); + return HT; +} + + +// init high side pin +HardwareTimer* _initPinPWMHigh(uint32_t PWM_freq, int ulPin) +{ + return _initPinPWM(PWM_freq, ulPin); +} + +// init low side pin +HardwareTimer* _initPinPWMLow(uint32_t PWM_freq, int ulPin) +{ + PinName pin = digitalPinToPinName(ulPin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); + uint32_t index = get_timer_index(Instance); + + if (HardwareTimer_Handle[index] == NULL) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM)); + HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); + TIM_OC_InitTypeDef sConfigOC = TIM_OC_InitTypeDef(); + sConfigOC.OCMode = TIM_OCMODE_PWM2; + sConfigOC.Pulse = 100; + sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW; + sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH; + sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; + sConfigOC.OCIdleState = TIM_OCIDLESTATE_SET; + sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET; + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HAL_TIM_PWM_ConfigChannel(&(HardwareTimer_Handle[index]->handle), &sConfigOC, channel); + } + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM2, pin); + HT->setOverflow(PWM_freq, HERTZ_FORMAT); + HT->pause(); + HT->refresh(); + return HT; +} + + +// align the timers to end the init +void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3) +{ + HT1->pause(); + HT1->refresh(); + HT2->pause(); + HT2->refresh(); + HT3->pause(); + HT3->refresh(); + HT1->resume(); + HT2->resume(); + HT3->resume(); +} + +// align the timers to end the init +void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3,HardwareTimer *HT4) +{ + HT1->pause(); + HT1->refresh(); + HT2->pause(); + HT2->refresh(); + HT3->pause(); + HT3->refresh(); + HT4->pause(); + HT4->refresh(); + HT1->resume(); + HT2->resume(); + HT3->resume(); + HT4->resume(); +} + +HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l) +{ + PinName uhPinName = digitalPinToPinName(pinA_h); + PinName ulPinName = digitalPinToPinName(pinA_l); + PinName vhPinName = digitalPinToPinName(pinB_h); + PinName vlPinName = digitalPinToPinName(pinB_l); + PinName whPinName = digitalPinToPinName(pinC_h); + PinName wlPinName = digitalPinToPinName(pinC_l); + + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM); + + uint32_t index = get_timer_index(Instance); + + if (HardwareTimer_Handle[index] == NULL) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM)); + HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); + ((HardwareTimer *)HardwareTimer_Handle[index]->__this)->setOverflow(PWM_freq, HERTZ_FORMAT); + } + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + + HT->setMode(STM_PIN_CHANNEL(pinmap_function(uhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, uhPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(ulPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, ulPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(vhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vhPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(vlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vlPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(whPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, whPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(wlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, wlPinName); + + // dead time is set in nanoseconds + uint32_t dead_time_ns = (float)(1e9/PWM_freq)*dead_zone; + uint32_t dead_time = __LL_TIM_CALC_DEADTIME(SystemCoreClock, LL_TIM_GetClockDivision(HT->getHandle()->Instance), dead_time_ns); + LL_TIM_OC_SetDeadTime(HT->getHandle()->Instance, dead_time); // deadtime is non linear! + LL_TIM_CC_EnableChannel(HT->getHandle()->Instance, LL_TIM_CHANNEL_CH1 | LL_TIM_CHANNEL_CH1N | LL_TIM_CHANNEL_CH2 | LL_TIM_CHANNEL_CH2N | LL_TIM_CHANNEL_CH3 | LL_TIM_CHANNEL_CH3N); + + HT->pause(); + HT->refresh(); + HT->resume(); + return HT; +} + + +// returns 0 if each pair of pwm channels has same channel +// returns 1 all the channels belong to the same timer - hardware inverted channels +// returns -1 if neither - avoid configuring - error!!! +int _interfaceType(const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + PinName nameAH = digitalPinToPinName(pinA_h); + PinName nameAL = digitalPinToPinName(pinA_l); + PinName nameBH = digitalPinToPinName(pinB_h); + PinName nameBL = digitalPinToPinName(pinB_l); + PinName nameCH = digitalPinToPinName(pinC_h); + PinName nameCL = digitalPinToPinName(pinC_l); + int tim1 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAH, PinMap_PWM)); + int tim2 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAL, PinMap_PWM)); + int tim3 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBH, PinMap_PWM)); + int tim4 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBL, PinMap_PWM)); + int tim5 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCH, PinMap_PWM)); + int tim6 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCL, PinMap_PWM)); + if(tim1 == tim2 && tim2==tim3 && tim3==tim4 && tim4==tim5 && tim5==tim6) + return _HARDWARE_6PWM; // hardware 6pwm interface - only on timer + else if(tim1 == tim2 && tim3==tim4 && tim5==tim6) + return _SOFTWARE_6PWM; // software 6pwm interface - each pair of high-low side same timer + else + return _ERROR_6PWM; // might be error avoid configuration +} + + + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); + HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); + HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); + // allign the timers + _alignPWMTimers(HT1, HT2, HT3); +} + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); + HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); + HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); + HardwareTimer* HT4 = _initPinPWM(pwm_frequency, pinD); + // allign the timers + _alignPWMTimers(HT1, HT2, HT3, HT4); +} + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +//- hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,4095] + _setPwm(pinA, _PWM_RANGE*dc_a, _PWM_RESOLUTION); + _setPwm(pinB, _PWM_RANGE*dc_b, _PWM_RESOLUTION); + _setPwm(pinC, _PWM_RANGE*dc_c, _PWM_RESOLUTION); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +//- hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,4095] + _setPwm(pin1A, _PWM_RANGE*dc_1a, _PWM_RESOLUTION); + _setPwm(pin1B, _PWM_RANGE*dc_1b, _PWM_RESOLUTION); + _setPwm(pin2A, _PWM_RANGE*dc_2a, _PWM_RESOLUTION); + _setPwm(pin2B, _PWM_RANGE*dc_2b, _PWM_RESOLUTION); +} + + + + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, 100000); // constrain to 100kHz max + + // find configuration + int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); + // configure accordingly + switch(config){ + case _ERROR_6PWM: + return -1; // fail + break; + case _HARDWARE_6PWM: + _initHardware6PWMInterface(pwm_frequency, dead_zone, pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); + break; + case _SOFTWARE_6PWM: + HardwareTimer* HT1 = _initPinPWMHigh(pwm_frequency, pinA_h); + _initPinPWMLow(pwm_frequency, pinA_l); + HardwareTimer* HT2 = _initPinPWMHigh(pwm_frequency,pinB_h); + _initPinPWMLow(pwm_frequency, pinB_l); + HardwareTimer* HT3 = _initPinPWMHigh(pwm_frequency,pinC_h); + _initPinPWMLow(pwm_frequency, pinC_l); + _alignPWMTimers(HT1, HT2, HT3); + break; + } + return 0; // success +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + // find configuration + int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); + // set pwm accordingly + switch(config){ + case _HARDWARE_6PWM: + _setPwm(pinA_h, _PWM_RANGE*dc_a, _PWM_RESOLUTION); + _setPwm(pinB_h, _PWM_RANGE*dc_b, _PWM_RESOLUTION); + _setPwm(pinC_h, _PWM_RANGE*dc_c, _PWM_RESOLUTION); + break; + case _SOFTWARE_6PWM: + _setPwm(pinA_l, _constrain(dc_a + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinA_h, _constrain(dc_a - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinB_l, _constrain(dc_b + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinB_h, _constrain(dc_b - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinC_l, _constrain(dc_c + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinC_h, _constrain(dc_c - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + break; + } +} +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/teensy_mcu.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/teensy_mcu.cpp new file mode 100644 index 00000000..10bd24c5 --- /dev/null +++ b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/teensy_mcu.cpp @@ -0,0 +1,71 @@ +#include "../hardware_api.h" + +#if defined(__arm__) && defined(CORE_TEENSY) + +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(pin, freq); +} + + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor +} + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + _setHighFrequency(pwm_frequency, pinD); +} + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); + analogWrite(pinC, 255.0*dc_c); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255.0*dc_1a); + analogWrite(pin1B, 255.0*dc_1b); + analogWrite(pin2A, 255.0*dc_2a); + analogWrite(pin2B, 255.0*dc_2b); +} + + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + return -1; +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + return; +} +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_driver_standalone/atmega328_driver_standalone.ino b/minimal_project_examples/atmega328_driver_standalone/atmega328_driver_standalone.ino new file mode 100644 index 00000000..e5d64dd2 --- /dev/null +++ b/minimal_project_examples/atmega328_driver_standalone/atmega328_driver_standalone.ino @@ -0,0 +1,32 @@ +#include "src/drivers/BLDCDriver3PWM.h" + +// BLDC driver instance +BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8); + +void setup() { + + // pwm frequency to be used [Hz] + // for atmega328 fixed to 32kHz + // esp32/stm32/teensy configurable + driver.pwm_frequency = 50000; + // power supply voltage [V] + driver.voltage_power_supply = 12; + // Max DC voltage allowed - default voltage_power_supply + driver.voltage_limit = 12; + + // driver init + driver.init(); + + // enable driver + driver.enable(); + + _delay(1000); +} + +void loop() { + // setting pwm + // phase A: 3V + // phase B: 6V + // phase C: 5V + driver.setPwm(3,6,5); +} \ No newline at end of file diff --git a/minimal_project_examples/atmega328_driver_standalone/src/common/base_classes/BLDCDriver.h b/minimal_project_examples/atmega328_driver_standalone/src/common/base_classes/BLDCDriver.h new file mode 100644 index 00000000..708323fb --- /dev/null +++ b/minimal_project_examples/atmega328_driver_standalone/src/common/base_classes/BLDCDriver.h @@ -0,0 +1,28 @@ +#ifndef BLDCDRIVER_H +#define BLDCDRIVER_H + +class BLDCDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + virtual void setPwm(float Ua, float Ub, float Uc); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_driver_standalone/src/common/base_classes/FOCMotor.cpp b/minimal_project_examples/atmega328_driver_standalone/src/common/base_classes/FOCMotor.cpp new file mode 100644 index 00000000..1d1a0f43 --- /dev/null +++ b/minimal_project_examples/atmega328_driver_standalone/src/common/base_classes/FOCMotor.cpp @@ -0,0 +1,241 @@ +#include "FOCMotor.h" + +/** + * Default constructor - setting all variabels to default values + */ +FOCMotor::FOCMotor() +{ + // maximum angular velocity to be used for positioning + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = DEF_POWER_SUPPLY; + + // index search velocity + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; + + // electric angle of comthe zero angle + zero_electric_angle = 0; + + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + + // default target value + target = 0; + voltage_d = 0; + voltage_q = 0; + + //monitor_port + monitor_port = nullptr; + //sensor + sensor = nullptr; +} + + +/** + Sensor communication methods +*/ +void FOCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} +// shaft angle calculation +float FOCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return shaft_angle; + return sensor->getAngle(); +} +// shaft velocity calculation +float FOCMotor::shaftVelocity() { + // if no sensor linked return 0 + if(!sensor) return 0; + return LPF_velocity(sensor->getVelocity()); +} + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void FOCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void FOCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity_openloop: + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle_openloop: + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int FOCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'D': // velocity D gain change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PID velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P angle| "); + break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + } + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("P: "); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("I: "); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); + break; + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("volt_ramp: "); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET) { + voltage_limit = value; + PID_velocity.limit = value; + } + if(monitor_port) monitor_port->println(voltage_limit); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("Tf: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("vel_limit: "); + if(!GET){ + velocity_limit = value; + P_angle.limit = value; + } + if(monitor_port) monitor_port->println(velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Control: "); + + if(GET){ // if get command + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + default: + if(monitor_port) monitor_port->println("open loop"); + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} \ No newline at end of file diff --git a/minimal_project_examples/atmega328_driver_standalone/src/common/base_classes/FOCMotor.h b/minimal_project_examples/atmega328_driver_standalone/src/common/base_classes/FOCMotor.h new file mode 100644 index 00000000..986e1ab2 --- /dev/null +++ b/minimal_project_examples/atmega328_driver_standalone/src/common/base_classes/FOCMotor.h @@ -0,0 +1,197 @@ +#ifndef FOCMOTOR_H +#define FOCMOTOR_H + +#include "Arduino.h" +#include "Sensor.h" +#include "BLDCDriver.h" + +#include "../time_utils.h" +#include "../foc_utils.h" +#include "../defaults.h" +#include "../pid.h" +#include "../lowpass_filter.h" + + +/** + * Motiron control type + */ +enum ControlType{ + voltage,//!< Torque control using voltage + velocity,//!< Velocity motion control + angle,//!< Position/angle motion control + velocity_openloop, + angle_openloop +}; + +/** + * FOC modulation type + */ +enum FOCModulationType{ + SinePWM, //!< Sinusoidal PWM modulation + SpaceVectorPWM, //!< Space vector modulation method + Trapezoid_120, + Trapezoid_150 +}; + +/** + Generic motor class +*/ +class FOCMotor +{ + public: + /** + * Default constructor - setting all variabels to default values + */ + FOCMotor(); + + /** Motor hardware init function */ + virtual void init()=0; + /** Motor disable function */ + virtual void disable()=0; + /** Motor enable function */ + virtual void enable()=0; + + /** + * Function linking a motor and a sensor + * + * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity + */ + void linkSensor(Sensor* sensor); + + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + virtual int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW)=0; + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + virtual void loopFOC()=0; + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + virtual void move(float target = NOT_SET)=0; + + // State calculation methods + /** Shaft angle calculation in radians [rad] */ + float shaftAngle(); + /** + * Shaft angle calculation function in radian per second [rad/s] + * It implements low pass filtering + */ + float shaftVelocity(); + + // state variables + float target; //!< current target value - depends of the controller + float shaft_angle;//!< current motor angle + float shaft_velocity;//!< current motor velocity + float shaft_velocity_sp;//!< current target velocity + float shaft_angle_sp;//!< current target angle + float voltage_q;//!< current voltage u_q set + float voltage_d;//!< current voltage u_d set + + // motor configuration parameters + float voltage_sensor_align;//!< sensor and motor align voltage parameter + float velocity_index_search;//!< target velocity for index search + int pole_pairs;//!< Motor pole pairs number + + // limiting variables + float voltage_limit; //!< Voltage limitting variable - global limit + float velocity_limit; //!< Velocity limitting variable - global limit + + float zero_electric_angle;//! 0 ) ) #define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) +#define _constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt))) // utility defines #define _2_SQRT3 1.15470053838 @@ -20,7 +21,6 @@ #define _2PI 6.28318530718 #define _3PI_2 4.71238898038 - #define NOT_SET -12345.0 /** diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/lowpass_filter.cpp b/minimal_project_examples/atmega328_driver_standalone/src/common/lowpass_filter.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_openloop/src/common/lowpass_filter.cpp rename to minimal_project_examples/atmega328_driver_standalone/src/common/lowpass_filter.cpp diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/lowpass_filter.h b/minimal_project_examples/atmega328_driver_standalone/src/common/lowpass_filter.h similarity index 94% rename from minimal_project_examples/arduino_foc_bldc_openloop/src/common/lowpass_filter.h rename to minimal_project_examples/atmega328_driver_standalone/src/common/lowpass_filter.h index 5a7619cf..7c51be54 100644 --- a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/lowpass_filter.h +++ b/minimal_project_examples/atmega328_driver_standalone/src/common/lowpass_filter.h @@ -2,7 +2,7 @@ #define LOWPASS_FILTER_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/pid.cpp b/minimal_project_examples/atmega328_driver_standalone/src/common/pid.cpp similarity index 92% rename from minimal_project_examples/arduino_foc_bldc_openloop/src/common/pid.cpp rename to minimal_project_examples/atmega328_driver_standalone/src/common/pid.cpp index 277e17ce..1a0a9828 100644 --- a/minimal_project_examples/arduino_foc_bldc_openloop/src/common/pid.cpp +++ b/minimal_project_examples/atmega328_driver_standalone/src/common/pid.cpp @@ -25,12 +25,12 @@ float PIDController::operator() (float error){ // Discrete implementations // proportional part // u_p = P *e(k) - float proportional = P * error_prev; + float proportional = P * error; // Tustin transform of the integral part // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) float integral = integral_prev + I*Ts*0.5*(error + error_prev); // antiwindup - limit the output voltage_q - integral = constrain(integral, -limit, limit); + integral = _constrain(integral, -limit, limit); // Discrete derivation // u_dk = D(ek - ek_1)/Ts float derivative = D*(error - error_prev)/Ts; @@ -38,7 +38,7 @@ float PIDController::operator() (float error){ // sum all the components float output = proportional + integral + derivative; // antiwindup - limit the output variable - output = constrain(output, -limit, limit); + output = _constrain(output, -limit, limit); // limit the acceleration by ramping the output float output_rate = (output - output_prev)/Ts; diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/pid.h b/minimal_project_examples/atmega328_driver_standalone/src/common/pid.h similarity index 97% rename from minimal_project_examples/arduino_foc_bldc_encoder/src/common/pid.h rename to minimal_project_examples/atmega328_driver_standalone/src/common/pid.h index 7ee337c4..0e9ddf54 100644 --- a/minimal_project_examples/arduino_foc_bldc_encoder/src/common/pid.h +++ b/minimal_project_examples/atmega328_driver_standalone/src/common/pid.h @@ -2,7 +2,7 @@ #define PID_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" /** diff --git a/minimal_project_examples/atmega328_driver_standalone/src/common/time_utils.cpp b/minimal_project_examples/atmega328_driver_standalone/src/common/time_utils.cpp new file mode 100644 index 00000000..181d03cf --- /dev/null +++ b/minimal_project_examples/atmega328_driver_standalone/src/common/time_utils.cpp @@ -0,0 +1,31 @@ +#include "time_utils.h" + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/atmega328_driver_standalone/src/common/time_utils.h b/minimal_project_examples/atmega328_driver_standalone/src/common/time_utils.h new file mode 100644 index 00000000..143d4853 --- /dev/null +++ b/minimal_project_examples/atmega328_driver_standalone/src/common/time_utils.h @@ -0,0 +1,22 @@ +#ifndef TIME_UTILS_H +#define TIME_UTILS_H + +#include "foc_utils.h" + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_driver_standalone/src/drivers/BLDCDriver3PWM.cpp b/minimal_project_examples/atmega328_driver_standalone/src/drivers/BLDCDriver3PWM.cpp new file mode 100644 index 00000000..bacb4ec5 --- /dev/null +++ b/minimal_project_examples/atmega328_driver_standalone/src/drivers/BLDCDriver3PWM.cpp @@ -0,0 +1,70 @@ +#include "BLDCDriver3PWM.h" + +BLDCDriver3PWM::BLDCDriver3PWM(int phA, int phB, int phC, int en){ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + + // enable_pin pin + enable_pin = en; + + // default power-supply value + voltage_power_supply = DEF_POWER_SUPPLY; + voltage_limit = NOT_SET; + +} + +// enable motor driver +void BLDCDriver3PWM::enable(){ + // enable_pin the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, HIGH); + // set zero to PWM + setPwm(0,0,0); +} + +// disable motor driver +void BLDCDriver3PWM::disable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // disable the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, LOW); + +} + +// init hardware pins +int BLDCDriver3PWM::init() { + + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); + + + // sanity check for the voltage limit configuration + if(voltage_limit == NOT_SET || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + + // Set the pwm frequency to the pins + // hardware specific function - depending on driver and mcu + _configure3PWM(pwm_frequency, pwmA, pwmB, pwmC); + return 0; +} + + +// Set voltage to the pwm pin +void BLDCDriver3PWM::setPwm(float Ua, float Ub, float Uc) { + // limit the voltage in driver + Ua = _constrain(Ua, -voltage_limit, voltage_limit); + Ub = _constrain(Ub, -voltage_limit, voltage_limit); + Uc = _constrain(Uc, -voltage_limit, voltage_limit); + // calculate duty cycle + // limited in [0,1] + float dc_a = _constrain(Ua / voltage_power_supply, 0 , 1 ); + float dc_b = _constrain(Ub / voltage_power_supply, 0 , 1 ); + float dc_c = _constrain(Uc / voltage_power_supply, 0 , 1 ); + // hardware specific writing + // hardware specific function - depending on driver and mcu + _writeDutyCycle3PWM(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC); +} \ No newline at end of file diff --git a/minimal_project_examples/atmega328_driver_standalone/src/drivers/BLDCDriver3PWM.h b/minimal_project_examples/atmega328_driver_standalone/src/drivers/BLDCDriver3PWM.h new file mode 100644 index 00000000..b6f7d7f8 --- /dev/null +++ b/minimal_project_examples/atmega328_driver_standalone/src/drivers/BLDCDriver3PWM.h @@ -0,0 +1,52 @@ +#ifndef BLDCDriver3PWM_h +#define BLDCDriver3PWM_h + +#include "../common/base_classes/BLDCDriver.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#include "../common/defaults.h" +#include "hardware_api.h" + +/** + 3 pwm bldc driver class +*/ +class BLDCDriver3PWM: public BLDCDriver +{ + public: + /** + BLDCDriver class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param en enable pin (optional input) + */ + BLDCDriver3PWM(int phA,int phB,int phC, int en = NOT_SET); + + /** Motor hardware init function */ + int init() override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc) override; + + private: + +}; + + +#endif diff --git a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_api.h b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_api.h new file mode 100644 index 00000000..da5ddf51 --- /dev/null +++ b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_api.h @@ -0,0 +1,100 @@ +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H + +#include "../common/foc_utils.h" +#include "../common/time_utils.h" + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + * @param pinC pinC bldc driver + */ +void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC); + +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pin1A pin1A stepper driver + * @param pin1B pin1B stepper driver + * @param pin2A pin2A stepper driver + * @param pin2B pin2B stepper driver + */ +void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B); + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low - if applicable + * @param pinA_h pinA high-side bldc driver + * @param pinA_l pinA low-side bldc driver + * @param pinB_h pinA high-side bldc driver + * @param pinB_l pinA low-side bldc driver + * @param pinC_h pinA high-side bldc driver + * @param pinC_l pinA low-side bldc driver + * + * @return 0 if config good, -1 if failed + */ +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low + * @param pinA_h phase A high-side hardware pin number + * @param pinA_l phase A low-side hardware pin number + * @param pinB_h phase B high-side hardware pin number + * @param pinB_l phase B low-side hardware pin number + * @param pinC_h phase C high-side hardware pin number + * @param pinC_l phase C low-side hardware pin number + * + */ +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l); + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/atmega328_mcu.cpp b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/atmega328_mcu.cpp new file mode 100644 index 00000000..58b368f7 --- /dev/null +++ b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/atmega328_mcu.cpp @@ -0,0 +1,133 @@ +#include "../hardware_api.h" + +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + +// set pwm frequency to 32KHz +void _pinHighFrequency(const int pin){ + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + if (pin == 5 || pin == 6 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + if (pin == 9 || pin == 10 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + if (pin == 3 || pin == 11) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 + +} + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +// supports Arudino/ATmega328 +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); + _pinHighFrequency(pinC); +} + + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); + analogWrite(pinC, 255.0*dc_c); +} + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +// supports Arudino/ATmega328 +void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pin1A); + _pinHighFrequency(pin1B); + _pinHighFrequency(pin2A); + _pinHighFrequency(pin2B); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255.0*dc_1a); + analogWrite(pin1B, 255.0*dc_1b); + analogWrite(pin2A, 255.0*dc_2a); + analogWrite(pin2B, 255.0*dc_2b); +} + + +// function configuring pair of high-low side pwm channels, 32khz frequency and center aligned pwm +int _configureComplementaryPair(int pinH, int pinL) { + if( (pinH == 5 && pinL == 6 ) || (pinH == 6 && pinL == 5 ) ){ + // configure the pwm phase-corrected mode + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); + // configure complementary pwm on low side + if(pinH == 6 ) TCCR0A = 0b10110000 | (TCCR0A & 0b00001111) ; + else TCCR0A = 0b11100000 | (TCCR0A & 0b00001111) ; + // set prescaler to 1 - 32kHz freq + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); + }else if( (pinH == 9 && pinL == 10 ) || (pinH == 10 && pinL == 9 ) ){ + // set prescaler to 1 - 32kHz freq + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); + // configure complementary pwm on low side + if(pinH == 9 ) TCCR1A = 0b10110000 | (TCCR1A & 0b00001111) ; + else TCCR1A = 0b11100000 | (TCCR1A & 0b00001111) ; + }else if((pinH == 3 && pinL == 11 ) || (pinH == 11 && pinL == 3 ) ){ + // set prescaler to 1 - 32kHz freq + TCCR2B = ((TCCR2B & 0b11111000) | 0x01); + // configure complementary pwm on low side + if(pinH == 11 ) TCCR2A = 0b10110000 | (TCCR2A & 0b00001111) ; + else TCCR2A = 0b11100000 | (TCCR2A & 0b00001111) ; + }else{ + return -1; + } + return 0; +} + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +// supports Arudino/ATmega328 +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) { + // High PWM frequency + // - always max 32kHz + int ret_flag = 0; + ret_flag += _configureComplementaryPair(pinA_h, pinA_l); + ret_flag += _configureComplementaryPair(pinB_h, pinB_l); + ret_flag += _configureComplementaryPair(pinC_h, pinC_l); + return ret_flag; // returns -1 if not well configured +} + +// function setting the +void _setPwmPair(int pinH, int pinL, float val, int dead_time) +{ + int pwm_h = _constrain(val-dead_time/2,0,255); + int pwm_l = _constrain(val+dead_time/2,0,255); + + analogWrite(pinH, pwm_h); + if(pwm_l == 255 || pwm_l == 0) + digitalWrite(pinL, pwm_l ? LOW : HIGH); + else + analogWrite(pinL, pwm_l); +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +// supports Arudino/ATmega328 +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + _setPwmPair(pinA_h, pinA_l, dc_a*255.0, dead_zone*255.0); + _setPwmPair(pinB_h, pinB_l, dc_b*255.0, dead_zone*255.0); + _setPwmPair(pinC_h, pinC_l, dc_c*255.0, dead_zone*255.0); +} + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/esp32_mcu.cpp b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/esp32_mcu.cpp new file mode 100644 index 00000000..3c07a445 --- /dev/null +++ b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/esp32_mcu.cpp @@ -0,0 +1,296 @@ +#include "../hardware_api.h" + +#if defined(ESP_H) + +#include "driver/mcpwm.h" +#include "soc/mcpwm_reg.h" +#include "soc/mcpwm_struct.h" + +// empty motor slot +#define _EMPTY_SLOT -20 +#define _TAKEN_SLOT -21 + +// structure containing motor slot configuration +// this library supports up to 4 motors +typedef struct { + int pinA; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; + mcpwm_io_signals_t mcpwm_c; +} bldc_3pwm_motor_slots_t; +typedef struct { + int pin1A; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_1a; + mcpwm_io_signals_t mcpwm_1b; + mcpwm_io_signals_t mcpwm_2a; + mcpwm_io_signals_t mcpwm_2b; +} stepper_motor_slots_t; + +typedef struct { + int pinAH; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator1; + mcpwm_operator_t mcpwm_operator2; + mcpwm_io_signals_t mcpwm_ah; + mcpwm_io_signals_t mcpwm_bh; + mcpwm_io_signals_t mcpwm_ch; + mcpwm_io_signals_t mcpwm_al; + mcpwm_io_signals_t mcpwm_bl; + mcpwm_io_signals_t mcpwm_cl; +} bldc_6pwm_motor_slots_t; + +// define bldc motor slots array +bldc_3pwm_motor_slots_t esp32_bldc_3pwm_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B + }; + +// define stepper motor slots array +stepper_motor_slots_t esp32_stepper_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + }; + +// define stepper motor slots array +bldc_6pwm_motor_slots_t esp32_bldc_6pwm_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0 + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0 + }; + +// configuring high frequency pwm timer +// a lot of help from this post from Paul Gauld +// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller +void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit, float dead_zone = NOT_SET){ + + mcpwm_config_t pwm_config; + pwm_config.frequency = pwm_frequency; //frequency + pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) + pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH + mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings + mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings + + if (dead_zone != NOT_SET){ + // dead zone is configured in dead_time x 100 nanoseconds + float dead_time = (float)(1e7 / pwm_frequency) * dead_zone; + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); + } + + _delay(100); + + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 1; + _delay(1); + mcpwm_num->timer[0].sync.out_sel = 0; +} + + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(2*pwm_frequency, 0, 100000); // constrain to 50kHz max - centered pwm has twice lower frequency + + bldc_3pwm_motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + int slot_num; + for(slot_num = 0; slot_num < 4; slot_num++){ + if(esp32_bldc_3pwm_motor_slots[slot_num].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_3pwm_motor_slots[slot_num].pinA = pinA; + m_slot = esp32_bldc_3pwm_motor_slots[slot_num]; + break; + } + } + // disable all the slots with the same MCPWM + if( slot_num < 2 ){ + // slot 0 of the stepper + esp32_stepper_motor_slots[0].pin1A = _TAKEN_SLOT; + // slot 0 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; + }else{ + // slot 1 of the stepper + esp32_stepper_motor_slots[1].pin1A = _TAKEN_SLOT; + // slot 1 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; + } + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + +} + + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(2*pwm_frequency, 0, 100000); // constrain to 50kHz max - centered pwm has twice lower frequency + stepper_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + int slot_num; + for(slot_num = 0; slot_num < 2; slot_num++){ + if(esp32_stepper_motor_slots[slot_num].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_motor_slots[slot_num].pin1A = pinA; + m_slot = esp32_stepper_motor_slots[slot_num]; + break; + } + } + // disable all the slots with the same MCPWM + if( slot_num == 0 ){ + // slots 0 and 1 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT; + // slot 0 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; + }else{ + // slots 2 and 3 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT; + // slot 1 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); +} + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +// ESP32 uses MCPWM +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_bldc_3pwm_motor_slots[i].pinA == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,100] + mcpwm_set_duty(esp32_bldc_3pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_bldc_3pwm_motor_slots[i].mcpwm_operator, dc_a*100.0); + mcpwm_set_duty(esp32_bldc_3pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_bldc_3pwm_motor_slots[i].mcpwm_operator, dc_b*100.0); + mcpwm_set_duty(esp32_bldc_3pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, esp32_bldc_3pwm_motor_slots[i].mcpwm_operator, dc_c*100.0); + break; + } + } +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +// ESP32 uses MCPWM +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,100] + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_motor_slots[i].mcpwm_operator1, dc_1a*100.0); + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_motor_slots[i].mcpwm_operator1, dc_1b*100.0); + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_motor_slots[i].mcpwm_operator2, dc_2a*100.0); + mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_motor_slots[i].mcpwm_operator2, dc_2b*100.0); + break; + } + } +} + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency + bldc_6pwm_motor_slots_t m_slot = {}; + // determine which motor are we connecting + // and set the appropriate configuration parameters + int slot_num; + for(slot_num = 0; slot_num < 2; slot_num++){ + if(esp32_bldc_6pwm_motor_slots[slot_num].pinAH == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_bldc_6pwm_motor_slots[slot_num].pinAH = pinA_h; + m_slot = esp32_bldc_6pwm_motor_slots[slot_num]; + break; + } + } + // if no slots available + if(slot_num >= 2) return -1; + + // disable all the slots with the same MCPWM + if( slot_num == 0 ){ + // slots 0 and 1 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT; + // slot 0 of the 6pwm bldc + esp32_stepper_motor_slots[0].pin1A = _TAKEN_SLOT; + }else{ + // slots 2 and 3 of the 3pwm bldc + esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT; + esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT; + // slot 1 of the 6pwm bldc + esp32_stepper_motor_slots[1].pin1A = _TAKEN_SLOT; + } + + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_ah, pinA_h); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_al, pinA_l); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_bh, pinB_h); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_bl, pinB_l); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_ch, pinC_h); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_cl, pinC_l); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit, dead_zone); + // return + return 0; +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + // determine which motor slot is the motor connected to + for(int i = 0; i < 2; i++){ + if(esp32_bldc_6pwm_motor_slots[i].pinAH == pinA_h){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,100.0] + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_A, dc_a*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_B, dc_a*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_A, dc_b*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_B, dc_b*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_A, dc_c*100.0); + mcpwm_set_duty(esp32_bldc_6pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_B, dc_c*100.0); + break; + } + } +} +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/generic_mcu.cpp b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/generic_mcu.cpp new file mode 100644 index 00000000..dc322746 --- /dev/null +++ b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/generic_mcu.cpp @@ -0,0 +1,68 @@ +#include "../hardware_api.h" + +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if mcu is not atmega328 + +#elif defined(__arm__) && defined(CORE_TEENSY) // or teensy + +#elif defined(ESP_H) // or esp32 + +#elif defined(_STM32_DEF_) // or stm32 + +#else + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +// in generic case dont do anything +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + return; +} + + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +// in generic case dont do anything +void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) { + return; +} + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + return -1; +} + + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); + analogWrite(pinC, 255.0*dc_c); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255.0*dc_1a); + analogWrite(pin1B, 255.0*dc_1b); + analogWrite(pin2A, 255.0*dc_2a); + analogWrite(pin2B, 255.0*dc_2b); +} + + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + return; +} + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/stm32_mcu.cpp b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/stm32_mcu.cpp new file mode 100644 index 00000000..85d0bd65 --- /dev/null +++ b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/stm32_mcu.cpp @@ -0,0 +1,291 @@ + +#include "../hardware_api.h" + +#if defined(_STM32_DEF_) + +#define _PWM_RESOLUTION 12 // 12bit +#define _PWM_RANGE 4095.0// 2^12 -1 = 4095 +#define _PWM_FREQUENCY 50000 // 50khz + + +#define _HARDWARE_6PWM 1 +#define _SOFTWARE_6PWM 0 +#define _ERROR_6PWM -1 + + +// setting pwm to hardware pin - instead analogWrite() +void _setPwm(int ulPin, uint32_t value, int resolution) +{ + PinName pin = digitalPinToPinName(ulPin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); + uint32_t index = get_timer_index(Instance); + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HT->setCaptureCompare(channel, value, (TimerCompareFormat_t)resolution); +} + + +// init pin pwm +HardwareTimer* _initPinPWM(uint32_t PWM_freq, int ulPin) +{ + PinName pin = digitalPinToPinName(ulPin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); + + uint32_t index = get_timer_index(Instance); + if (HardwareTimer_Handle[index] == NULL) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM)); + HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); + } + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, pin); + HT->setOverflow(PWM_freq, HERTZ_FORMAT); + HT->pause(); + HT->refresh(); + return HT; +} + + +// init high side pin +HardwareTimer* _initPinPWMHigh(uint32_t PWM_freq, int ulPin) +{ + return _initPinPWM(PWM_freq, ulPin); +} + +// init low side pin +HardwareTimer* _initPinPWMLow(uint32_t PWM_freq, int ulPin) +{ + PinName pin = digitalPinToPinName(ulPin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); + uint32_t index = get_timer_index(Instance); + + if (HardwareTimer_Handle[index] == NULL) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM)); + HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); + TIM_OC_InitTypeDef sConfigOC = TIM_OC_InitTypeDef(); + sConfigOC.OCMode = TIM_OCMODE_PWM2; + sConfigOC.Pulse = 100; + sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW; + sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH; + sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; + sConfigOC.OCIdleState = TIM_OCIDLESTATE_SET; + sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET; + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HAL_TIM_PWM_ConfigChannel(&(HardwareTimer_Handle[index]->handle), &sConfigOC, channel); + } + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM2, pin); + HT->setOverflow(PWM_freq, HERTZ_FORMAT); + HT->pause(); + HT->refresh(); + return HT; +} + + +// align the timers to end the init +void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3) +{ + HT1->pause(); + HT1->refresh(); + HT2->pause(); + HT2->refresh(); + HT3->pause(); + HT3->refresh(); + HT1->resume(); + HT2->resume(); + HT3->resume(); +} + +// align the timers to end the init +void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3,HardwareTimer *HT4) +{ + HT1->pause(); + HT1->refresh(); + HT2->pause(); + HT2->refresh(); + HT3->pause(); + HT3->refresh(); + HT4->pause(); + HT4->refresh(); + HT1->resume(); + HT2->resume(); + HT3->resume(); + HT4->resume(); +} + +HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l) +{ + PinName uhPinName = digitalPinToPinName(pinA_h); + PinName ulPinName = digitalPinToPinName(pinA_l); + PinName vhPinName = digitalPinToPinName(pinB_h); + PinName vlPinName = digitalPinToPinName(pinB_l); + PinName whPinName = digitalPinToPinName(pinC_h); + PinName wlPinName = digitalPinToPinName(pinC_l); + + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM); + + uint32_t index = get_timer_index(Instance); + + if (HardwareTimer_Handle[index] == NULL) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM)); + HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); + ((HardwareTimer *)HardwareTimer_Handle[index]->__this)->setOverflow(PWM_freq, HERTZ_FORMAT); + } + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + + HT->setMode(STM_PIN_CHANNEL(pinmap_function(uhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, uhPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(ulPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, ulPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(vhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vhPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(vlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vlPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(whPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, whPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(wlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, wlPinName); + + // dead time is set in nanoseconds + uint32_t dead_time_ns = (float)(1e9/PWM_freq)*dead_zone; + uint32_t dead_time = __LL_TIM_CALC_DEADTIME(SystemCoreClock, LL_TIM_GetClockDivision(HT->getHandle()->Instance), dead_time_ns); + LL_TIM_OC_SetDeadTime(HT->getHandle()->Instance, dead_time); // deadtime is non linear! + LL_TIM_CC_EnableChannel(HT->getHandle()->Instance, LL_TIM_CHANNEL_CH1 | LL_TIM_CHANNEL_CH1N | LL_TIM_CHANNEL_CH2 | LL_TIM_CHANNEL_CH2N | LL_TIM_CHANNEL_CH3 | LL_TIM_CHANNEL_CH3N); + + HT->pause(); + HT->refresh(); + HT->resume(); + return HT; +} + + +// returns 0 if each pair of pwm channels has same channel +// returns 1 all the channels belong to the same timer - hardware inverted channels +// returns -1 if neither - avoid configuring - error!!! +int _interfaceType(const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + PinName nameAH = digitalPinToPinName(pinA_h); + PinName nameAL = digitalPinToPinName(pinA_l); + PinName nameBH = digitalPinToPinName(pinB_h); + PinName nameBL = digitalPinToPinName(pinB_l); + PinName nameCH = digitalPinToPinName(pinC_h); + PinName nameCL = digitalPinToPinName(pinC_l); + int tim1 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAH, PinMap_PWM)); + int tim2 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAL, PinMap_PWM)); + int tim3 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBH, PinMap_PWM)); + int tim4 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBL, PinMap_PWM)); + int tim5 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCH, PinMap_PWM)); + int tim6 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCL, PinMap_PWM)); + if(tim1 == tim2 && tim2==tim3 && tim3==tim4 && tim4==tim5 && tim5==tim6) + return _HARDWARE_6PWM; // hardware 6pwm interface - only on timer + else if(tim1 == tim2 && tim3==tim4 && tim5==tim6) + return _SOFTWARE_6PWM; // software 6pwm interface - each pair of high-low side same timer + else + return _ERROR_6PWM; // might be error avoid configuration +} + + + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); + HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); + HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); + // allign the timers + _alignPWMTimers(HT1, HT2, HT3); +} + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); + HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); + HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); + HardwareTimer* HT4 = _initPinPWM(pwm_frequency, pinD); + // allign the timers + _alignPWMTimers(HT1, HT2, HT3, HT4); +} + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +//- hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,4095] + _setPwm(pinA, _PWM_RANGE*dc_a, _PWM_RESOLUTION); + _setPwm(pinB, _PWM_RANGE*dc_b, _PWM_RESOLUTION); + _setPwm(pinC, _PWM_RANGE*dc_c, _PWM_RESOLUTION); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +//- hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,4095] + _setPwm(pin1A, _PWM_RANGE*dc_1a, _PWM_RESOLUTION); + _setPwm(pin1B, _PWM_RANGE*dc_1b, _PWM_RESOLUTION); + _setPwm(pin2A, _PWM_RANGE*dc_2a, _PWM_RESOLUTION); + _setPwm(pin2B, _PWM_RANGE*dc_2b, _PWM_RESOLUTION); +} + + + + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, 100000); // constrain to 100kHz max + + // find configuration + int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); + // configure accordingly + switch(config){ + case _ERROR_6PWM: + return -1; // fail + break; + case _HARDWARE_6PWM: + _initHardware6PWMInterface(pwm_frequency, dead_zone, pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); + break; + case _SOFTWARE_6PWM: + HardwareTimer* HT1 = _initPinPWMHigh(pwm_frequency, pinA_h); + _initPinPWMLow(pwm_frequency, pinA_l); + HardwareTimer* HT2 = _initPinPWMHigh(pwm_frequency,pinB_h); + _initPinPWMLow(pwm_frequency, pinB_l); + HardwareTimer* HT3 = _initPinPWMHigh(pwm_frequency,pinC_h); + _initPinPWMLow(pwm_frequency, pinC_l); + _alignPWMTimers(HT1, HT2, HT3); + break; + } + return 0; // success +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + // find configuration + int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); + // set pwm accordingly + switch(config){ + case _HARDWARE_6PWM: + _setPwm(pinA_h, _PWM_RANGE*dc_a, _PWM_RESOLUTION); + _setPwm(pinB_h, _PWM_RANGE*dc_b, _PWM_RESOLUTION); + _setPwm(pinC_h, _PWM_RANGE*dc_c, _PWM_RESOLUTION); + break; + case _SOFTWARE_6PWM: + _setPwm(pinA_l, _constrain(dc_a + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinA_h, _constrain(dc_a - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinB_l, _constrain(dc_b + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinB_h, _constrain(dc_b - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinC_l, _constrain(dc_c + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinC_h, _constrain(dc_c - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + break; + } +} +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/teensy_mcu.cpp b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/teensy_mcu.cpp new file mode 100644 index 00000000..10bd24c5 --- /dev/null +++ b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/teensy_mcu.cpp @@ -0,0 +1,71 @@ +#include "../hardware_api.h" + +#if defined(__arm__) && defined(CORE_TEENSY) + +// configure High PWM frequency +void _setHighFrequency(const long freq, const int pin){ + analogWrite(pin, 0); + analogWriteFrequency(pin, freq); +} + + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor +} + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max + _setHighFrequency(pwm_frequency, pinA); + _setHighFrequency(pwm_frequency, pinB); + _setHighFrequency(pwm_frequency, pinC); + _setHighFrequency(pwm_frequency, pinD); +} + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); + analogWrite(pinC, 255.0*dc_c); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255.0*dc_1a); + analogWrite(pin1B, 255.0*dc_1b); + analogWrite(pin2A, 255.0*dc_2a); + analogWrite(pin2B, 255.0*dc_2b); +} + + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + return -1; +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + return; +} +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_encoder/src/BLDCMotor.cpp b/minimal_project_examples/stm32_bldc_hall/src/BLDCMotor.cpp similarity index 68% rename from minimal_project_examples/arduino_foc_bldc_encoder/src/BLDCMotor.cpp rename to minimal_project_examples/stm32_bldc_hall/src/BLDCMotor.cpp index 989b74a9..bed4cd6a 100644 --- a/minimal_project_examples/arduino_foc_bldc_encoder/src/BLDCMotor.cpp +++ b/minimal_project_examples/stm32_bldc_hall/src/BLDCMotor.cpp @@ -1,41 +1,39 @@ #include "BLDCMotor.h" -// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// // BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// // - phA, phB, phC - motor A,B,C phase pwm pins +// // - pp - pole pair number +// // - cpr - counts per rotation number (cpm=ppm*4) +// // - enable pin - (optional input) +// BLDCMotor::BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en){ +// noop; +// } + +// BLDCMotor( int pp) // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - cpr - counts per rotation number (cpm=ppm*4) // - enable pin - (optional input) -BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +BLDCMotor::BLDCMotor(int pp) : FOCMotor() { - // Pin initialization - pwmA = phA; - pwmB = phB; - pwmC = phC; + // save pole pairs number pole_pairs = pp; +} - // enable_pin pin - enable_pin = en; +/** + Link the driver which controls the motor +*/ +void BLDCMotor::linkDriver(BLDCDriver* _driver) { + driver = _driver; } - // init hardware pins -void BLDCMotor::init(long pwm_frequency) { - if(monitor_port) monitor_port->println("MOT: Init pins."); - // PWM pins - pinMode(pwmA, OUTPUT); - pinMode(pwmB, OUTPUT); - pinMode(pwmC, OUTPUT); - if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); - - if(monitor_port) monitor_port->println("MOT: PWM config."); - // Increase PWM frequency to 32 kHz - // make silent - _setPwmFrequency(pwm_frequency, pwmA, pwmB, pwmC); - +void BLDCMotor::init() { + if(monitor_port) monitor_port->println("MOT: Initialise variables."); // sanity check for the voltage limit configuration - if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + if(voltage_limit > driver->voltage_limit) voltage_limit = driver->voltage_limit; // constrain voltage for sensor alignment if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; // update the controller limits @@ -44,7 +42,7 @@ void BLDCMotor::init(long pwm_frequency) { _delay(500); // enable motor - if(monitor_port) monitor_port->println("MOT: Enable."); + if(monitor_port) monitor_port->println("MOT: Enable driver."); enable(); _delay(500); } @@ -53,18 +51,18 @@ void BLDCMotor::init(long pwm_frequency) { // disable motor driver void BLDCMotor::disable() { - // disable the driver - if enable_pin pin available - if (enable_pin != NOT_SET) digitalWrite(enable_pin, LOW); // set zero to PWM - setPwm(0, 0, 0); + driver->setPwm(0, 0, 0); + // disable the driver + driver->disable(); } // enable motor driver void BLDCMotor::enable() { + // enable the driver + driver->enable(); // set zero to PWM - setPwm(0, 0, 0); - // enable_pin the driver - if enable_pin pin available - if (enable_pin != NOT_SET) digitalWrite(enable_pin, HIGH); + driver->setPwm(0, 0, 0); } @@ -100,13 +98,13 @@ int BLDCMotor::alignSensor() { float start_angle = shaftAngle(); for (int i = 0; i <=5; i++ ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } float mid_angle = shaftAngle(); for (int i = 5; i >=0; i-- ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } if (mid_angle < start_angle) { @@ -121,7 +119,7 @@ int BLDCMotor::alignSensor() { // set sensor to zero sensor->initRelativeZero(); _delay(500); - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); _delay(200); // find the index if available @@ -153,7 +151,7 @@ int BLDCMotor::absoluteZeroAlign() { } voltage_q = 0; // disable motor - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); // align absolute zero if it has been found if(!sensor->needsAbsoluteZeroSearch()){ @@ -172,7 +170,7 @@ void BLDCMotor::loopFOC() { // shaft angle shaft_angle = shaftAngle(); // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); + setPhaseVoltage(voltage_q, voltage_d, _electricalAngle(shaft_angle,pole_pairs)); } // Iterative function running outer loop of the FOC algorithm @@ -219,15 +217,60 @@ void BLDCMotor::move(float new_target) { } -// Method using FOC to set Uq to the motor at the optimal angle +// Method using FOC to set Uq and Ud to the motor at the optimal angle // Function implementing Space Vector PWM and Sine PWM algorithms // // Function using sine approximation // regular sin + cos ~300us (no memory usaage) // approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { +void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { + + const bool centered = true; + int sector; + float _ca,_sa; + switch (foc_modulation) { + case FOCModulationType::Trapezoid_120 : + // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 5 + static int trap_120_map[6][3] = { + {0,1,-1},{-1,1,0},{-1,0,1},{0,-1,1},{1,-1,0},{1,0,-1} // each is 60 degrees with values for 3 phases of 1=positive -1=negative 0=high-z + }; + // static int trap_120_state = 0; + sector = 6 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes + + Ua = Uq + trap_120_map[sector][0] * Uq; + Ub = Uq + trap_120_map[sector][1] * Uq; + Uc = Uq + trap_120_map[sector][2] * Uq; + + if (centered) { + Ua += (driver->voltage_limit)/2 -Uq; + Ub += (driver->voltage_limit)/2 -Uq; + Uc += (driver->voltage_limit)/2 -Uq; + } + break; + + case FOCModulationType::Trapezoid_150 : + // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 8 + static int trap_150_map[12][3] = { + {0,1,-1},{-1,1,-1},{-1,1,0},{-1,1,1},{-1,0,1},{-1,-1,1},{0,-1,1},{1,-1,1},{1,-1,0},{1,-1,-1},{1,0,-1},{1,1,-1} // each is 30 degrees with values for 3 phases of 1=positive -1=negative 0=high-z + }; + // static int trap_150_state = 0; + sector = 12 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes + + Ua = Uq + trap_150_map[sector][0] * Uq; + Ub = Uq + trap_150_map[sector][1] * Uq; + Uc = Uq + trap_150_map[sector][2] * Uq; + + //center + if (centered) { + Ua += (driver->voltage_limit)/2 -Uq; + Ub += (driver->voltage_limit)/2 -Uq; + Uc += (driver->voltage_limit)/2 -Uq; + } + + break; + case FOCModulationType::SinePWM : // Sinusoidal PWM modulation // Inverse Park + Clarke transformation @@ -235,14 +278,24 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { // angle normalization in between 0 and 2pi // only necessary if using _sin and _cos - approximation functions angle_el = _normalizeAngle(angle_el + zero_electric_angle); + _ca = _cos(angle_el); + _sa = _sin(angle_el); // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + Ualpha = _ca * Ud - _sa * Uq; // -sin(angle) * Uq; + Ubeta = _sa * Ud + _ca * Uq; // cos(angle) * Uq; // Clarke transform - Ua = Ualpha + voltage_power_supply/2; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + Ua = Ualpha + driver->voltage_limit/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + driver->voltage_limit/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + driver->voltage_limit/2; + + if (!centered) { + float Umin = min(Ua, min(Ub, Uc)); + Ua -= Umin; + Ub -= Umin; + Uc -= Umin; + } + break; case FOCModulationType::SpaceVectorPWM : @@ -259,15 +312,15 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { angle_el = _normalizeAngle(angle_el + zero_electric_angle + _PI_2); // find the sector we are in currently - int sector = floor(angle_el / _PI_3) + 1; + sector = floor(angle_el / _PI_3) + 1; // calculate the duty cycles - float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; - float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/driver->voltage_limit; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/driver->voltage_limit; // two versions possible - // centered around voltage_power_supply/2 - float T0 = 1 - T1 - T2; - // pulled to 0 - better for low power supply voltage - //float T0 = 0; + float T0 = 0; // pulled to 0 - better for low power supply voltage + if (centered) { + T0 = 1 - T1 - T2; //centered around driver->voltage_limit/2 + } // calculate the duty cycles(times) float Ta,Tb,Tc; @@ -310,27 +363,15 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { } // calculate the phase voltages and center - Ua = Ta*voltage_power_supply; - Ub = Tb*voltage_power_supply; - Uc = Tc*voltage_power_supply; + Ua = Ta*driver->voltage_limit; + Ub = Tb*driver->voltage_limit; + Uc = Tc*driver->voltage_limit; break; + } - // set the voltages in hardware - setPwm(Ua, Ub, Uc); -} - - - -// Set voltage to the pwm pin -void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { - // calculate duty cycle - // limited in [0,1] - float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); - float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); - float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); - // hardware specific writing - _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); + // set the voltages in driver + driver->setPwm(Ua, Ub, Uc); } @@ -348,7 +389,7 @@ void BLDCMotor::velocityOpenloop(float target_velocity){ shaft_angle += target_velocity*Ts; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; @@ -371,7 +412,7 @@ void BLDCMotor::angleOpenloop(float target_angle){ shaft_angle = target_angle; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; diff --git a/minimal_project_examples/arduino_foc_bldc_openloop/src/BLDCMotor.h b/minimal_project_examples/stm32_bldc_hall/src/BLDCMotor.h similarity index 71% rename from minimal_project_examples/arduino_foc_bldc_openloop/src/BLDCMotor.h rename to minimal_project_examples/stm32_bldc_hall/src/BLDCMotor.h index a4fbb678..164cc108 100644 --- a/minimal_project_examples/arduino_foc_bldc_openloop/src/BLDCMotor.h +++ b/minimal_project_examples/stm32_bldc_hall/src/BLDCMotor.h @@ -1,16 +1,12 @@ -/** - * @file BLDCMotor.h - * - */ - #ifndef BLDCMotor_h #define BLDCMotor_h #include "Arduino.h" -#include "common/FOCMotor.h" +#include "common/base_classes/FOCMotor.h" +#include "common/base_classes/Sensor.h" +#include "common/base_classes/BLDCDriver.h" #include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "common/time_utils.h" #include "common/defaults.h" /** @@ -20,18 +16,27 @@ class BLDCMotor: public FOCMotor { public: /** - BLDCMotor class constructor - @param phA A phase pwm pin - @param phB B phase pwm pin - @param phC C phase pwm pin - @param pp pole pair number - @param cpr counts per rotation number (cpm=ppm*4) - @param en enable pin (optional input) + BLDCMotor class constructor + @param pp pole pairs number + */ + BLDCMotor(int pp); + + /** + * Function linking a motor and a foc driver + * + * @param driver BLDCDriver class implementing all the hardware specific functions necessary PWM setting + */ + void linkDriver(BLDCDriver* driver); + + /** + * BLDCDriver link: + * - 3PWM + * - 6PWM */ - BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + BLDCDriver* driver; /** Motor hardware init function */ - void init(long pwm_frequency = NOT_SET) override; + void init() override; /** Motor disable function */ void disable() override; /** Motor enable function */ @@ -59,12 +64,9 @@ class BLDCMotor: public FOCMotor * This function doesn't need to be run upon each loop execution - depends of the use case */ void move(float target = NOT_SET) override; - - // hardware variables - int pwmA; //!< phase A pwm pin number - int pwmB; //!< phase B pwm pin number - int pwmC; //!< phase C pwm pin number - int enable_pin; //!< enable pin number + + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform private: @@ -74,21 +76,15 @@ class BLDCMotor: public FOCMotor * Heart of the FOC algorithm * * @param Uq Current voltage in q axis to set to the motor + * @param Ud Current voltage in d axis to set to the motor * @param angle_el current electrical angle of the motor */ - void setPhaseVoltage(float Uq, float angle_el); + void setPhaseVoltage(float Uq, float Ud, float angle_el); /** Sensor alignment to electrical 0 angle of the motor */ int alignSensor(); /** Motor and sensor alignment to the sensors absolute 0 angle */ int absoluteZeroAlign(); - /** - * Set phase voltages to the harware - * - * @param Ua phase A voltage - * @param Ub phase B voltage - * @param Uc phase C voltage - */ - void setPwm(float Ua, float Ub, float Uc); + // Open loop motion control /** diff --git a/minimal_project_examples/stm32_bldc_hall/src/common/base_classes/BLDCDriver.h b/minimal_project_examples/stm32_bldc_hall/src/common/base_classes/BLDCDriver.h new file mode 100644 index 00000000..708323fb --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/common/base_classes/BLDCDriver.h @@ -0,0 +1,28 @@ +#ifndef BLDCDRIVER_H +#define BLDCDRIVER_H + +class BLDCDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + virtual void setPwm(float Ua, float Ub, float Uc); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/stm32_bldc_hall/src/common/base_classes/FOCMotor.cpp b/minimal_project_examples/stm32_bldc_hall/src/common/base_classes/FOCMotor.cpp new file mode 100644 index 00000000..1d1a0f43 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/common/base_classes/FOCMotor.cpp @@ -0,0 +1,241 @@ +#include "FOCMotor.h" + +/** + * Default constructor - setting all variabels to default values + */ +FOCMotor::FOCMotor() +{ + // maximum angular velocity to be used for positioning + velocity_limit = DEF_VEL_LIM; + // maximum voltage to be set to the motor + voltage_limit = DEF_POWER_SUPPLY; + + // index search velocity + velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; + // sensor and motor align voltage + voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN; + + // electric angle of comthe zero angle + zero_electric_angle = 0; + + // default modulation is SinePWM + foc_modulation = FOCModulationType::SinePWM; + + // default target value + target = 0; + voltage_d = 0; + voltage_q = 0; + + //monitor_port + monitor_port = nullptr; + //sensor + sensor = nullptr; +} + + +/** + Sensor communication methods +*/ +void FOCMotor::linkSensor(Sensor* _sensor) { + sensor = _sensor; +} +// shaft angle calculation +float FOCMotor::shaftAngle() { + // if no sensor linked return 0 + if(!sensor) return shaft_angle; + return sensor->getAngle(); +} +// shaft velocity calculation +float FOCMotor::shaftVelocity() { + // if no sensor linked return 0 + if(!sensor) return 0; + return LPF_velocity(sensor->getVelocity()); +} + +/** + * Monitoring functions + */ +// function implementing the monitor_port setter +void FOCMotor::useMonitoring(Print &print){ + monitor_port = &print; //operate on the address of print + if(monitor_port ) monitor_port->println("MOT: Monitor enabled!"); +} +// utility function intended to be used with serial plotter to monitor motor variables +// significantly slowing the execution down!!!! +void FOCMotor::monitor() { + if(!monitor_port) return; + switch (controller) { + case ControlType::velocity_openloop: + case ControlType::velocity: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_velocity_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + case ControlType::angle_openloop: + case ControlType::angle: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle_sp); + monitor_port->print("\t"); + monitor_port->println(shaft_angle); + break; + case ControlType::voltage: + monitor_port->print(voltage_q); + monitor_port->print("\t"); + monitor_port->print(shaft_angle); + monitor_port->print("\t"); + monitor_port->println(shaft_velocity); + break; + } +} + +int FOCMotor::command(String user_command) { + // error flag + int errorFlag = 1; + // if empty string + if(user_command.length() < 1) return errorFlag; + + // parse command letter + char cmd = user_command.charAt(0); + // check if get command + char GET = user_command.charAt(1) == '\n'; + // parse command values + float value = user_command.substring(1).toFloat(); + + // a bit of optimisation of variable memory for Arduino UNO (atmega328) + switch(cmd){ + case 'P': // velocity P gain change + case 'I': // velocity I gain change + case 'D': // velocity D gain change + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print(" PID velocity| "); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print(" LPF velocity| "); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P angle| "); + break; + case 'L': // velocity voltage limit change + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print(" Limits| "); + break; + } + + // apply the the command + switch(cmd){ + case 'P': // velocity P gain change + if(monitor_port) monitor_port->print("P: "); + if(!GET) PID_velocity.P = value; + if(monitor_port) monitor_port->println(PID_velocity.P); + break; + case 'I': // velocity I gain change + if(monitor_port) monitor_port->print("I: "); + if(!GET) PID_velocity.I = value; + if(monitor_port) monitor_port->println(PID_velocity.I); + break; + case 'D': // velocity D gain change + if(monitor_port) monitor_port->print("D: "); + if(!GET) PID_velocity.D = value; + if(monitor_port) monitor_port->println(PID_velocity.D); + break; + case 'R': // velocity voltage ramp change + if(monitor_port) monitor_port->print("volt_ramp: "); + if(!GET) PID_velocity.output_ramp = value; + if(monitor_port) monitor_port->println(PID_velocity.output_ramp); + break; + case 'L': // velocity voltage limit change + if(monitor_port) monitor_port->print("volt_limit: "); + if(!GET) { + voltage_limit = value; + PID_velocity.limit = value; + } + if(monitor_port) monitor_port->println(voltage_limit); + break; + case 'F': // velocity Tf low pass filter change + if(monitor_port) monitor_port->print("Tf: "); + if(!GET) LPF_velocity.Tf = value; + if(monitor_port) monitor_port->println(LPF_velocity.Tf); + break; + case 'K': // angle loop gain P change + if(monitor_port) monitor_port->print(" P: "); + if(!GET) P_angle.P = value; + if(monitor_port) monitor_port->println(P_angle.P); + break; + case 'N': // angle loop gain velocity_limit change + if(monitor_port) monitor_port->print("vel_limit: "); + if(!GET){ + velocity_limit = value; + P_angle.limit = value; + } + if(monitor_port) monitor_port->println(velocity_limit); + break; + case 'C': + // change control type + if(monitor_port) monitor_port->print("Control: "); + + if(GET){ // if get command + switch(controller){ + case ControlType::voltage: + if(monitor_port) monitor_port->println("voltage"); + break; + case ControlType::velocity: + if(monitor_port) monitor_port->println("velocity"); + break; + case ControlType::angle: + if(monitor_port) monitor_port->println("angle"); + break; + default: + if(monitor_port) monitor_port->println("open loop"); + } + }else{ // if set command + switch((int)value){ + case 0: + if(monitor_port) monitor_port->println("voltage"); + controller = ControlType::voltage; + break; + case 1: + if(monitor_port) monitor_port->println("velocity"); + controller = ControlType::velocity; + break; + case 2: + if(monitor_port) monitor_port->println("angle"); + controller = ControlType::angle; + break; + default: // not valid command + errorFlag = 0; + } + } + break; + case 'V': // get current values of the state variables + switch((int)value){ + case 0: // get voltage + if(monitor_port) monitor_port->print("Uq: "); + if(monitor_port) monitor_port->println(voltage_q); + break; + case 1: // get velocity + if(monitor_port) monitor_port->print("Velocity: "); + if(monitor_port) monitor_port->println(shaft_velocity); + break; + case 2: // get angle + if(monitor_port) monitor_port->print("Angle: "); + if(monitor_port) monitor_port->println(shaft_angle); + break; + case 3: // get angle + if(monitor_port) monitor_port->print("Target: "); + if(monitor_port) monitor_port->println(target); + break; + default: // not valid command + errorFlag = 0; + } + break; + default: // target change + if(monitor_port) monitor_port->print("Target : "); + target = user_command.toFloat(); + if(monitor_port) monitor_port->println(target); + } + // return 0 if error and 1 if ok + return errorFlag; +} \ No newline at end of file diff --git a/minimal_project_examples/stm32_bldc_hall/src/common/base_classes/FOCMotor.h b/minimal_project_examples/stm32_bldc_hall/src/common/base_classes/FOCMotor.h new file mode 100644 index 00000000..986e1ab2 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/common/base_classes/FOCMotor.h @@ -0,0 +1,197 @@ +#ifndef FOCMOTOR_H +#define FOCMOTOR_H + +#include "Arduino.h" +#include "Sensor.h" +#include "BLDCDriver.h" + +#include "../time_utils.h" +#include "../foc_utils.h" +#include "../defaults.h" +#include "../pid.h" +#include "../lowpass_filter.h" + + +/** + * Motiron control type + */ +enum ControlType{ + voltage,//!< Torque control using voltage + velocity,//!< Velocity motion control + angle,//!< Position/angle motion control + velocity_openloop, + angle_openloop +}; + +/** + * FOC modulation type + */ +enum FOCModulationType{ + SinePWM, //!< Sinusoidal PWM modulation + SpaceVectorPWM, //!< Space vector modulation method + Trapezoid_120, + Trapezoid_150 +}; + +/** + Generic motor class +*/ +class FOCMotor +{ + public: + /** + * Default constructor - setting all variabels to default values + */ + FOCMotor(); + + /** Motor hardware init function */ + virtual void init()=0; + /** Motor disable function */ + virtual void disable()=0; + /** Motor enable function */ + virtual void enable()=0; + + /** + * Function linking a motor and a sensor + * + * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity + */ + void linkSensor(Sensor* sensor); + + + /** + * Function initializing FOC algorithm + * and aligning sensor's and motors' zero position + * + * - If zero_electric_offset parameter is set the alignment procedure is skipped + * + * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. + * @param sensor_direction sensor natural direction - default is CW + * + */ + virtual int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW)=0; + /** + * Function running FOC algorithm in real-time + * it calculates the gets motor angle and sets the appropriate voltages + * to the phase pwm signals + * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us + */ + virtual void loopFOC()=0; + /** + * Function executing the control loops set by the controller parameter of the BLDCMotor. + * + * @param target Either voltage, angle or velocity based on the motor.controller + * If it is not set the motor will use the target set in its variable motor.target + * + * This function doesn't need to be run upon each loop execution - depends of the use case + */ + virtual void move(float target = NOT_SET)=0; + + // State calculation methods + /** Shaft angle calculation in radians [rad] */ + float shaftAngle(); + /** + * Shaft angle calculation function in radian per second [rad/s] + * It implements low pass filtering + */ + float shaftVelocity(); + + // state variables + float target; //!< current target value - depends of the controller + float shaft_angle;//!< current motor angle + float shaft_velocity;//!< current motor velocity + float shaft_velocity_sp;//!< current target velocity + float shaft_angle_sp;//!< current target angle + float voltage_q;//!< current voltage u_q set + float voltage_d;//!< current voltage u_d set + + // motor configuration parameters + float voltage_sensor_align;//!< sensor and motor align voltage parameter + float velocity_index_search;//!< target velocity for index search + int pole_pairs;//!< Motor pole pairs number + + // limiting variables + float voltage_limit; //!< Voltage limitting variable - global limit + float velocity_limit; //!< Velocity limitting variable - global limit + + float zero_electric_angle;//! _2PI ? a_sin - _2PI : a_sin; + return _sin(a_sin); +} + + +// normalizing radian angle to [0,2PI] +float _normalizeAngle(float angle){ + float a = fmod(angle, _2PI); + return a >= 0 ? a : (a + _2PI); +} + +// Electrical angle calculation +float _electricalAngle(float shaft_angle, int pole_pairs) { + return (shaft_angle * pole_pairs); +} \ No newline at end of file diff --git a/minimal_project_examples/stm32_bldc_hall/src/common/foc_utils.h b/minimal_project_examples/stm32_bldc_hall/src/common/foc_utils.h new file mode 100644 index 00000000..7da3f7bc --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/common/foc_utils.h @@ -0,0 +1,55 @@ +#ifndef FOCUTILS_LIB_H +#define FOCUTILS_LIB_H + +#include "Arduino.h" + +// sign function +#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) +#define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) +#define _constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt))) + +// utility defines +#define _2_SQRT3 1.15470053838 +#define _SQRT3 1.73205080757 +#define _1_SQRT3 0.57735026919 +#define _SQRT3_2 0.86602540378 +#define _SQRT2 1.41421356237 +#define _120_D2R 2.09439510239 +#define _PI 3.14159265359 +#define _PI_2 1.57079632679 +#define _PI_3 1.0471975512 +#define _2PI 6.28318530718 +#define _3PI_2 4.71238898038 + +#define NOT_SET -12345.0 + +/** + * Function approximating the sine calculation by using fixed size array + * - execution time ~40us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _sin(float a); +/** + * Function approximating cosine calculation by using fixed size array + * - execution time ~50us (Arduino UNO) + * + * @param a angle in between 0 and 2PI + */ +float _cos(float a); + +/** + * normalizing radian angle to [0,2PI] + * @param angle - angle to be normalized + */ +float _normalizeAngle(float angle); + + +/** + * Electrical angle calculation + * + * @param shaft_angle - shaft angle of the motor + * @param pole_pairs - number of pole pairs + */ +float _electricalAngle(float shaft_angle, int pole_pairs); +#endif \ No newline at end of file diff --git a/minimal_project_examples/stm32_bldc_hall/src/common/lowpass_filter.cpp b/minimal_project_examples/stm32_bldc_hall/src/common/lowpass_filter.cpp new file mode 100644 index 00000000..9bf4ab7a --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/common/lowpass_filter.cpp @@ -0,0 +1,25 @@ +#include "lowpass_filter.h" + +LowPassFilter::LowPassFilter(float time_constant) + : Tf(time_constant) + , y_prev(0.0f) +{ + timestamp_prev = _micros(); +} + + +float LowPassFilter::operator() (float x) +{ + unsigned long timestamp = _micros(); + float dt = (timestamp - timestamp_prev)*1e-6f; + + if (dt < 0.0f || dt > 0.5f) + dt = 1e-3f; + + float alpha = Tf/(Tf + dt); + float y = alpha*y_prev + (1.0f - alpha)*x; + + y_prev = y; + timestamp_prev = timestamp; + return y; +} \ No newline at end of file diff --git a/minimal_project_examples/stm32_bldc_hall/src/common/lowpass_filter.h b/minimal_project_examples/stm32_bldc_hall/src/common/lowpass_filter.h new file mode 100644 index 00000000..7c51be54 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/common/lowpass_filter.h @@ -0,0 +1,29 @@ +#ifndef LOWPASS_FILTER_H +#define LOWPASS_FILTER_H + + +#include "time_utils.h" +#include "foc_utils.h" + + +/** + * Low pass filter class + */ +class LowPassFilter +{ +public: + /** + * @param Tf - Low pass filter time constant + */ + LowPassFilter(float Tf); + ~LowPassFilter() = default; + + float operator() (float x); + float Tf; //!< Low pass filter time constant + +protected: + unsigned long timestamp_prev; //!< Last execution timestamp + float y_prev; //!< filtered value in previous execution step +}; + +#endif // LOWPASS_FILTER_H \ No newline at end of file diff --git a/minimal_project_examples/stm32_bldc_hall/src/common/pid.cpp b/minimal_project_examples/stm32_bldc_hall/src/common/pid.cpp new file mode 100644 index 00000000..1a0a9828 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/common/pid.cpp @@ -0,0 +1,56 @@ +#include "pid.h" + +PIDController::PIDController(float P, float I, float D, float ramp, float limit) + : P(P) + , I(I) + , D(D) + , output_ramp(ramp) // output derivative limit [volts/second] + , limit(limit) // output supply limit [volts] + , integral_prev(0.0) + , error_prev(0.0) + , output_prev(0.0) +{ + timestamp_prev = _micros()*1e-6; +} + +// PID controller function +float PIDController::operator() (float error){ + // calculate the time from the last call + unsigned long timestamp_now = _micros(); + float Ts = (timestamp_now - timestamp_prev) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // u(s) = (P + I/s + Ds)e(s) + // Discrete implementations + // proportional part + // u_p = P *e(k) + float proportional = P * error; + // Tustin transform of the integral part + // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) + float integral = integral_prev + I*Ts*0.5*(error + error_prev); + // antiwindup - limit the output voltage_q + integral = _constrain(integral, -limit, limit); + // Discrete derivation + // u_dk = D(ek - ek_1)/Ts + float derivative = D*(error - error_prev)/Ts; + + // sum all the components + float output = proportional + integral + derivative; + // antiwindup - limit the output variable + output = _constrain(output, -limit, limit); + + // limit the acceleration by ramping the output + float output_rate = (output - output_prev)/Ts; + if (output_rate > output_ramp) + output = output_prev + output_ramp*Ts; + else if (output_rate < -output_ramp) + output = output_prev - output_ramp*Ts; + + // saving for the next pass + integral_prev = integral; + output_prev = output; + error_prev = error; + timestamp_prev = timestamp_now; + return output; +} \ No newline at end of file diff --git a/minimal_project_examples/stm32_bldc_hall/src/common/pid.h b/minimal_project_examples/stm32_bldc_hall/src/common/pid.h new file mode 100644 index 00000000..0e9ddf54 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/common/pid.h @@ -0,0 +1,40 @@ +#ifndef PID_H +#define PID_H + + +#include "time_utils.h" +#include "foc_utils.h" + +/** + * PID controller class + */ +class PIDController +{ +public: + /** + * + * @param P - Proportional gain + * @param I - Integral gain + * @param D - Derivative gain + * @param ramp - Maximum speed of change of the output value + * @param limit - Maximum output value + */ + PIDController(float P, float I, float D, float ramp, float limit); + ~PIDController() = default; + + float operator() (float error); + + float P; //!< Proportional gain + float I; //!< Integral gain + float D; //!< Derivative gain + float output_ramp; //!< Maximum speed of change of the output value + float limit; //!< Maximum output value + +protected: + float integral_prev; //!< last integral component value + float error_prev; //!< last tracking error value + float timestamp_prev; //!< Last execution timestamp + float output_prev; //!< last pid output value +}; + +#endif // PID_H \ No newline at end of file diff --git a/minimal_project_examples/stm32_bldc_hall/src/common/time_utils.cpp b/minimal_project_examples/stm32_bldc_hall/src/common/time_utils.cpp new file mode 100644 index 00000000..181d03cf --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/common/time_utils.cpp @@ -0,0 +1,31 @@ +#include "time_utils.h" + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/stm32_bldc_hall/src/common/time_utils.h b/minimal_project_examples/stm32_bldc_hall/src/common/time_utils.h new file mode 100644 index 00000000..143d4853 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/common/time_utils.h @@ -0,0 +1,22 @@ +#ifndef TIME_UTILS_H +#define TIME_UTILS_H + +#include "foc_utils.h" + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver6PWM.cpp b/minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver6PWM.cpp new file mode 100644 index 00000000..b1f2e884 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver6PWM.cpp @@ -0,0 +1,78 @@ +#include "BLDCDriver6PWM.h" + +BLDCDriver6PWM::BLDCDriver6PWM(int phA_h,int phA_l,int phB_h,int phB_l,int phC_h,int phC_l, int en){ + // Pin initialization + pwmA_h = phA_h; + pwmB_h = phB_h; + pwmC_h = phC_h; + pwmA_l = phA_l; + pwmB_l = phB_l; + pwmC_l = phC_l; + + // enable_pin pin + enable_pin = en; + + // default power-supply value + voltage_power_supply = DEF_POWER_SUPPLY; + voltage_limit = NOT_SET; + + // dead zone initial - 2% + dead_zone = 0.02; + +} + +// enable motor driver +void BLDCDriver6PWM::enable(){ + // enable_pin the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, HIGH); + // set zero to PWM + setPwm(0, 0, 0); +} + +// disable motor driver +void BLDCDriver6PWM::disable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // disable the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, LOW); + +} + +// init hardware pins +int BLDCDriver6PWM::init() { + + // PWM pins + pinMode(pwmA_l, OUTPUT); + pinMode(pwmB_h, OUTPUT); + pinMode(pwmC_h, OUTPUT); + pinMode(pwmA_l, OUTPUT); + pinMode(pwmB_l, OUTPUT); + pinMode(pwmC_l, OUTPUT); + if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); + + + // sanity check for the voltage limit configuration + if(voltage_limit == NOT_SET || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + + // configure 6pwm + // hardware specific function - depending on driver and mcu + return _configure6PWM(pwm_frequency, dead_zone, pwmA_h,pwmA_l, pwmB_h,pwmB_l, pwmC_h,pwmC_l); +} + + +// Set voltage to the pwm pin +void BLDCDriver6PWM::setPwm(float Ua, float Ub, float Uc) { + // limit the voltage in driver + Ua = _constrain(Ua, -voltage_limit, voltage_limit); + Ub = _constrain(Ub, -voltage_limit, voltage_limit); + Uc = _constrain(Uc, -voltage_limit, voltage_limit); + // calculate duty cycle + // limited in [0,1] + float dc_a = _constrain(Ua / voltage_power_supply, 0.0 , 1.0 ); + float dc_b = _constrain(Ub / voltage_power_supply, 0.0 , 1.0 ); + float dc_c = _constrain(Uc / voltage_power_supply, 0.0 , 1.0 ); + // hardware specific writing + // hardware specific function - depending on driver and mcu + _writeDutyCycle6PWM(dc_a, dc_b, dc_c, dead_zone, pwmA_h,pwmA_l, pwmB_h,pwmB_l, pwmC_h,pwmC_l); +} \ No newline at end of file diff --git a/minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver6PWM.h b/minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver6PWM.h new file mode 100644 index 00000000..d13b69fd --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver6PWM.h @@ -0,0 +1,57 @@ +#ifndef BLDCDriver6PWM_h +#define BLDCDriver6PWM_h + +#include "../common/base_classes/BLDCDriver.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#include "../common/defaults.h" +#include "hardware_api.h" + +/** + 6 pwm bldc driver class +*/ +class BLDCDriver6PWM: public BLDCDriver +{ + public: + /** + BLDCDriver class constructor + @param phA_h A phase pwm pin + @param phA_l A phase pwm pin + @param phB_h B phase pwm pin + @param phB_l A phase pwm pin + @param phC_h C phase pwm pin + @param phC_l A phase pwm pin + @param en enable pin (optional input) + */ + BLDCDriver6PWM(int phA_h,int phA_l,int phB_h,int phB_l,int phC_h,int phC_l, int en = NOT_SET); + + /** Motor hardware init function */ + int init() override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + // hardware variables + int pwmA_h,pwmA_l; //!< phase A pwm pin number + int pwmB_h,pwmB_l; //!< phase B pwm pin number + int pwmC_h,pwmC_l; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + float dead_zone; //!< a percentage of dead-time(zone) (both high and low side in low) for each pwm cycle [0,1] + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc) override; + + private: + +}; + + +#endif diff --git a/minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_api.h b/minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_api.h new file mode 100644 index 00000000..da5ddf51 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_api.h @@ -0,0 +1,100 @@ +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H + +#include "../common/foc_utils.h" +#include "../common/time_utils.h" + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + * @param pinC pinC bldc driver + */ +void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC); + +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pin1A pin1A stepper driver + * @param pin1B pin1B stepper driver + * @param pin2A pin2A stepper driver + * @param pin2B pin2B stepper driver + */ +void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B); + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low - if applicable + * @param pinA_h pinA high-side bldc driver + * @param pinA_l pinA low-side bldc driver + * @param pinB_h pinA high-side bldc driver + * @param pinB_l pinA low-side bldc driver + * @param pinC_h pinA high-side bldc driver + * @param pinC_l pinA low-side bldc driver + * + * @return 0 if config good, -1 if failed + */ +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low + * @param pinA_h phase A high-side hardware pin number + * @param pinA_l phase A low-side hardware pin number + * @param pinB_h phase B high-side hardware pin number + * @param pinB_l phase B low-side hardware pin number + * @param pinC_h phase C high-side hardware pin number + * @param pinC_l phase C low-side hardware pin number + * + */ +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l); + +#endif \ No newline at end of file diff --git a/minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_specific/stm32_mcu.cpp b/minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_specific/stm32_mcu.cpp new file mode 100644 index 00000000..85d0bd65 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_specific/stm32_mcu.cpp @@ -0,0 +1,291 @@ + +#include "../hardware_api.h" + +#if defined(_STM32_DEF_) + +#define _PWM_RESOLUTION 12 // 12bit +#define _PWM_RANGE 4095.0// 2^12 -1 = 4095 +#define _PWM_FREQUENCY 50000 // 50khz + + +#define _HARDWARE_6PWM 1 +#define _SOFTWARE_6PWM 0 +#define _ERROR_6PWM -1 + + +// setting pwm to hardware pin - instead analogWrite() +void _setPwm(int ulPin, uint32_t value, int resolution) +{ + PinName pin = digitalPinToPinName(ulPin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); + uint32_t index = get_timer_index(Instance); + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HT->setCaptureCompare(channel, value, (TimerCompareFormat_t)resolution); +} + + +// init pin pwm +HardwareTimer* _initPinPWM(uint32_t PWM_freq, int ulPin) +{ + PinName pin = digitalPinToPinName(ulPin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); + + uint32_t index = get_timer_index(Instance); + if (HardwareTimer_Handle[index] == NULL) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM)); + HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); + } + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, pin); + HT->setOverflow(PWM_freq, HERTZ_FORMAT); + HT->pause(); + HT->refresh(); + return HT; +} + + +// init high side pin +HardwareTimer* _initPinPWMHigh(uint32_t PWM_freq, int ulPin) +{ + return _initPinPWM(PWM_freq, ulPin); +} + +// init low side pin +HardwareTimer* _initPinPWMLow(uint32_t PWM_freq, int ulPin) +{ + PinName pin = digitalPinToPinName(ulPin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); + uint32_t index = get_timer_index(Instance); + + if (HardwareTimer_Handle[index] == NULL) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM)); + HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); + TIM_OC_InitTypeDef sConfigOC = TIM_OC_InitTypeDef(); + sConfigOC.OCMode = TIM_OCMODE_PWM2; + sConfigOC.Pulse = 100; + sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW; + sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH; + sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; + sConfigOC.OCIdleState = TIM_OCIDLESTATE_SET; + sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET; + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HAL_TIM_PWM_ConfigChannel(&(HardwareTimer_Handle[index]->handle), &sConfigOC, channel); + } + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); + HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM2, pin); + HT->setOverflow(PWM_freq, HERTZ_FORMAT); + HT->pause(); + HT->refresh(); + return HT; +} + + +// align the timers to end the init +void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3) +{ + HT1->pause(); + HT1->refresh(); + HT2->pause(); + HT2->refresh(); + HT3->pause(); + HT3->refresh(); + HT1->resume(); + HT2->resume(); + HT3->resume(); +} + +// align the timers to end the init +void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3,HardwareTimer *HT4) +{ + HT1->pause(); + HT1->refresh(); + HT2->pause(); + HT2->refresh(); + HT3->pause(); + HT3->refresh(); + HT4->pause(); + HT4->refresh(); + HT1->resume(); + HT2->resume(); + HT3->resume(); + HT4->resume(); +} + +HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l) +{ + PinName uhPinName = digitalPinToPinName(pinA_h); + PinName ulPinName = digitalPinToPinName(pinA_l); + PinName vhPinName = digitalPinToPinName(pinB_h); + PinName vlPinName = digitalPinToPinName(pinB_l); + PinName whPinName = digitalPinToPinName(pinC_h); + PinName wlPinName = digitalPinToPinName(pinC_l); + + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM); + + uint32_t index = get_timer_index(Instance); + + if (HardwareTimer_Handle[index] == NULL) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM)); + HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); + ((HardwareTimer *)HardwareTimer_Handle[index]->__this)->setOverflow(PWM_freq, HERTZ_FORMAT); + } + HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + + HT->setMode(STM_PIN_CHANNEL(pinmap_function(uhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, uhPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(ulPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, ulPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(vhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vhPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(vlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vlPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(whPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, whPinName); + HT->setMode(STM_PIN_CHANNEL(pinmap_function(wlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, wlPinName); + + // dead time is set in nanoseconds + uint32_t dead_time_ns = (float)(1e9/PWM_freq)*dead_zone; + uint32_t dead_time = __LL_TIM_CALC_DEADTIME(SystemCoreClock, LL_TIM_GetClockDivision(HT->getHandle()->Instance), dead_time_ns); + LL_TIM_OC_SetDeadTime(HT->getHandle()->Instance, dead_time); // deadtime is non linear! + LL_TIM_CC_EnableChannel(HT->getHandle()->Instance, LL_TIM_CHANNEL_CH1 | LL_TIM_CHANNEL_CH1N | LL_TIM_CHANNEL_CH2 | LL_TIM_CHANNEL_CH2N | LL_TIM_CHANNEL_CH3 | LL_TIM_CHANNEL_CH3N); + + HT->pause(); + HT->refresh(); + HT->resume(); + return HT; +} + + +// returns 0 if each pair of pwm channels has same channel +// returns 1 all the channels belong to the same timer - hardware inverted channels +// returns -1 if neither - avoid configuring - error!!! +int _interfaceType(const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + PinName nameAH = digitalPinToPinName(pinA_h); + PinName nameAL = digitalPinToPinName(pinA_l); + PinName nameBH = digitalPinToPinName(pinB_h); + PinName nameBL = digitalPinToPinName(pinB_l); + PinName nameCH = digitalPinToPinName(pinC_h); + PinName nameCL = digitalPinToPinName(pinC_l); + int tim1 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAH, PinMap_PWM)); + int tim2 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAL, PinMap_PWM)); + int tim3 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBH, PinMap_PWM)); + int tim4 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBL, PinMap_PWM)); + int tim5 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCH, PinMap_PWM)); + int tim6 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCL, PinMap_PWM)); + if(tim1 == tim2 && tim2==tim3 && tim3==tim4 && tim4==tim5 && tim5==tim6) + return _HARDWARE_6PWM; // hardware 6pwm interface - only on timer + else if(tim1 == tim2 && tim3==tim4 && tim5==tim6) + return _SOFTWARE_6PWM; // software 6pwm interface - each pair of high-low side same timer + else + return _ERROR_6PWM; // might be error avoid configuration +} + + + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); + HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); + HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); + // allign the timers + _alignPWMTimers(HT1, HT2, HT3); +} + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); + HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); + HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); + HardwareTimer* HT4 = _initPinPWM(pwm_frequency, pinD); + // allign the timers + _alignPWMTimers(HT1, HT2, HT3, HT4); +} + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +//- hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,4095] + _setPwm(pinA, _PWM_RANGE*dc_a, _PWM_RESOLUTION); + _setPwm(pinB, _PWM_RANGE*dc_b, _PWM_RESOLUTION); + _setPwm(pinC, _PWM_RANGE*dc_c, _PWM_RESOLUTION); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +//- hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,4095] + _setPwm(pin1A, _PWM_RANGE*dc_1a, _PWM_RESOLUTION); + _setPwm(pin1B, _PWM_RANGE*dc_1b, _PWM_RESOLUTION); + _setPwm(pin2A, _PWM_RANGE*dc_2a, _PWM_RESOLUTION); + _setPwm(pin2B, _PWM_RANGE*dc_2b, _PWM_RESOLUTION); +} + + + + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz + else pwm_frequency = _constrain(pwm_frequency, 0, 100000); // constrain to 100kHz max + + // find configuration + int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); + // configure accordingly + switch(config){ + case _ERROR_6PWM: + return -1; // fail + break; + case _HARDWARE_6PWM: + _initHardware6PWMInterface(pwm_frequency, dead_zone, pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); + break; + case _SOFTWARE_6PWM: + HardwareTimer* HT1 = _initPinPWMHigh(pwm_frequency, pinA_h); + _initPinPWMLow(pwm_frequency, pinA_l); + HardwareTimer* HT2 = _initPinPWMHigh(pwm_frequency,pinB_h); + _initPinPWMLow(pwm_frequency, pinB_l); + HardwareTimer* HT3 = _initPinPWMHigh(pwm_frequency,pinC_h); + _initPinPWMLow(pwm_frequency, pinC_l); + _alignPWMTimers(HT1, HT2, HT3); + break; + } + return 0; // success +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + // find configuration + int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); + // set pwm accordingly + switch(config){ + case _HARDWARE_6PWM: + _setPwm(pinA_h, _PWM_RANGE*dc_a, _PWM_RESOLUTION); + _setPwm(pinB_h, _PWM_RANGE*dc_b, _PWM_RESOLUTION); + _setPwm(pinC_h, _PWM_RANGE*dc_c, _PWM_RESOLUTION); + break; + case _SOFTWARE_6PWM: + _setPwm(pinA_l, _constrain(dc_a + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinA_h, _constrain(dc_a - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinB_l, _constrain(dc_b + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinB_h, _constrain(dc_b - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinC_l, _constrain(dc_c + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + _setPwm(pinC_h, _constrain(dc_c - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); + break; + } +} +#endif \ No newline at end of file diff --git a/minimal_project_examples/stm32_bldc_hall/src/sensors/HallSensor.cpp b/minimal_project_examples/stm32_bldc_hall/src/sensors/HallSensor.cpp new file mode 100644 index 00000000..47dc53d0 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/sensors/HallSensor.cpp @@ -0,0 +1,161 @@ +#include "HallSensor.h" + + +/* + HallSensor(int hallA, int hallB , int cpr, int index) + - hallA, hallB, hallC - HallSensor A, B and C pins + - pp - pole pairs +*/ +HallSensor::HallSensor(int _hallA, int _hallB, int _hallC, int _pp){ + + // hardware pins + pinA = _hallA; + pinB = _hallB; + pinC = _hallC; + + // hall has 6 segments per electrical revolution + cpr = _pp * 6; + + // extern pullup as default + pullup = Pullup::EXTERN; +} + +// HallSensor interrupt callback functions +// A channel +void HallSensor::handleA() { + A_active= digitalRead(pinA); + updateState(); +} +// B channel +void HallSensor::handleB() { + B_active = digitalRead(pinB); + updateState(); +} + +// C channel +void HallSensor::handleC() { + C_active = digitalRead(pinC); + updateState(); +} + +/** + * Updates the state and sector following an interrupt + */ +void HallSensor::updateState() { + long new_pulse_timestamp = _micros(); + hall_state = C_active + (B_active << 1) + (A_active << 2); + int8_t new_electric_sector = ELECTRIC_SECTORS[hall_state]; + if (new_electric_sector - electric_sector > 3) { + //underflow + direction = static_cast(natural_direction * -1); + electric_rotations += direction; + } else if (new_electric_sector - electric_sector < (-3)) { + //overflow + direction = static_cast(natural_direction); + electric_rotations += direction; + } else { + direction = (new_electric_sector > electric_sector)? static_cast(natural_direction) : static_cast(natural_direction * (-1)); + } + electric_sector = new_electric_sector; + pulse_diff = new_pulse_timestamp - pulse_timestamp; + pulse_timestamp = new_pulse_timestamp; + total_interrupts++; + if (onSectorChange != nullptr) onSectorChange(electric_sector); +} + +/** + * Optionally set a function callback to be fired when sector changes + * void onSectorChange(int sector) { + * ... // for debug or call driver directly? + * } + * sensor.attachSectorCallback(onSectorChange); + */ +void HallSensor::attachSectorCallback(void (*_onSectorChange)(int sector)) { + onSectorChange = _onSectorChange; +} + +/* + Shaft angle calculation +*/ +float HallSensor::getAngle() { + return natural_direction * ((electric_rotations * 6 + electric_sector) / cpr) * _2PI; +} + +/* + Shaft velocity calculation + function using mixed time and frequency measurement technique +*/ +float HallSensor::getVelocity(){ + + if (pulse_diff == 0 || ((_micros() - pulse_timestamp) > STALE_HALL_DATA_MICROS) ) { // last velocity isn't accurate if too old + return 0; + } else { + return direction * (_2PI / cpr) / (pulse_diff / 1000000.0); + } + +} + +// getter for index pin +// return -1 if no index +int HallSensor::needsAbsoluteZeroSearch(){ + return 0; +} + +int HallSensor::hasAbsoluteZero(){ + return 1; +} + +// set current angle as zero angle +// return the angle [rad] difference +float HallSensor::initRelativeZero(){ + + // nothing to do. The interrupts should have changed sector. + electric_rotations = 0; + return 0; + +} + +// set absolute zero angle as zero angle +// return the angle [rad] difference +float HallSensor::initAbsoluteZero(){ + + return -getAngle(); + +} + +// HallSensor initialisation of the hardware pins +// and calculation variables +void HallSensor::init(){ + + // HallSensor - check if pullup needed for your HallSensor + if(pullup == Pullup::INTERN){ + pinMode(pinA, INPUT_PULLUP); + pinMode(pinB, INPUT_PULLUP); + pinMode(pinC, INPUT_PULLUP); + }else{ + pinMode(pinA, INPUT); + pinMode(pinB, INPUT); + pinMode(pinC, INPUT); + } + + // init hall_state + A_active= digitalRead(pinA); + B_active = digitalRead(pinB); + C_active = digitalRead(pinC); + updateState(); + + pulse_timestamp = _micros(); + +} + +// function enabling hardware interrupts for the callback provided +// if callback is not provided then the interrupt is not enabled +void HallSensor::enableInterrupts(void (*doA)(), void(*doB)(), void(*doC)()){ + // attach interrupt if functions provided + + // A, B and C callback + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); + if(doC != nullptr) attachInterrupt(digitalPinToInterrupt(pinC), doC, CHANGE); +} + diff --git a/minimal_project_examples/arduino_foc_bldc_hall/src/HallSensor.h b/minimal_project_examples/stm32_bldc_hall/src/sensors/HallSensor.h similarity index 75% rename from minimal_project_examples/arduino_foc_bldc_hall/src/HallSensor.h rename to minimal_project_examples/stm32_bldc_hall/src/sensors/HallSensor.h index 9b467b0a..0eb42286 100644 --- a/minimal_project_examples/arduino_foc_bldc_hall/src/HallSensor.h +++ b/minimal_project_examples/stm32_bldc_hall/src/sensors/HallSensor.h @@ -2,10 +2,16 @@ #define HALL_SENSOR_LIB_H #include "Arduino.h" -#include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "../common/base_classes/Sensor.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#ifndef STALE_HALL_DATA_MICROS + #define STALE_HALL_DATA_MICROS 500000 +#endif + +// seq 1 > 5 > 4 > 6 > 2 > 3 > 1 000 001 010 011 100 101 110 111 +const int8_t ELECTRIC_SECTORS[8] = { -1, 0, 4, 5, 2, 1, 3 , -1 }; class HallSensor: public Sensor{ public: @@ -81,26 +87,32 @@ class HallSensor: public Sensor{ // whether last step was CW (+1) or CCW (-1) direction Direction direction; - // the current 3bit state of the hall sensors - int state; + void attachSectorCallback(void (*onSectorChange)(int a) = nullptr); - volatile float angle; // rad/s - volatile float velocity; // rad/s + // the current 3bit state of the hall sensors + volatile int8_t hall_state; + // the current sector of the sensor. Each sector is 60deg electrical + volatile int8_t electric_sector; + // the number of electric rotations + volatile long electric_rotations; + // this is sometimes useful to identify interrupt issues (e.g. weak or no pullup resulting in 1000s of interrupts) + volatile long total_interrupts; private: Direction decodeDirection(int oldState, int newState); void updateState(); - volatile long pulse_counter;//!< current pulse counter + int zero_offset; volatile long pulse_timestamp;//!< last impulse timestamp in us volatile int A_active; //!< current active states of A channel volatile int B_active; //!< current active states of B channel volatile int C_active; //!< current active states of C channel - // velocity calculation variables - // float prev_Th, pulse_per_second; - volatile long prev_pulse_counter, prev_timestamp_us; + // function pointer for on sector change call back + void (*onSectorChange)(int sector) = nullptr; + + volatile long pulse_diff; }; diff --git a/minimal_project_examples/arduino_foc_bldc_hall/arduino_foc_bldc_hall.ino b/minimal_project_examples/stm32_bldc_hall/stm32_bldc_hall.ino similarity index 87% rename from minimal_project_examples/arduino_foc_bldc_hall/arduino_foc_bldc_hall.ino rename to minimal_project_examples/stm32_bldc_hall/stm32_bldc_hall.ino index 796ea01e..bd105e0a 100644 --- a/minimal_project_examples/arduino_foc_bldc_hall/arduino_foc_bldc_hall.ino +++ b/minimal_project_examples/stm32_bldc_hall/stm32_bldc_hall.ino @@ -37,14 +37,12 @@ * */ #include "src/BLDCMotor.h" -#include "src/HallSensor.h" +#include "src/sensors/HallSensor.h" +#include "src/drivers/BLDCDriver3PWM.h" -// software interrupt library -#include -#include - -// motor instance -BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 7); +// BLDC motor & driver instance +BLDCMotor motor = BLDCMotor(11); +BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8); // hall sensor instance HallSensor sensor = HallSensor(2, 3, 4, 11); @@ -54,29 +52,24 @@ HallSensor sensor = HallSensor(2, 3, 4, 11); void doA(){sensor.handleA();} void doB(){sensor.handleB();} void doC(){sensor.handleC();} -// If no available hadware interrupt pins use the software interrupt -PciListenerImp listenC(sensor.pinC, doC); - void setup() { // initialize encoder sensor hardware sensor.init(); - sensor.enableInterrupts(doA, doB); //, doC); - // software interrupts - PciManager.registerListener(&listenC); - + sensor.enableInterrupts(doA, doB, doC); // link the motor to the sensor motor.linkSensor(&sensor); - // choose FOC modulation - motor.foc_modulation = FOCModulationType::SpaceVectorPWM; - + // driver config // power supply voltage [V] - motor.voltage_power_supply = 12; + driver.voltage_power_supply = 12; + driver.init(); + // link driver + motor.linkDriver(&driver); + // set control loop type to be used motor.controller = ControlType::voltage; - // contoller configuration based on the controll type motor.PID_velocity.P = 0.2; motor.PID_velocity.I = 20; From c6f91cbd0087797493e7d1a09de5beebc06e2355 Mon Sep 17 00:00:00 2001 From: askuric Date: Thu, 17 Dec 2020 14:55:36 +0100 Subject: [PATCH 64/65] v2.0.1 verison added --- README.md | 212 ++++++--- library_source/BLDCMotor.cpp | 50 ++- library_source/SimpleFOC.h | 1 + library_source/StepperMotor.cpp | 4 +- library_source/common/time_utils.cpp | 4 +- library_source/drivers/BLDCDriver3PWM.cpp | 14 +- library_source/drivers/BLDCDriver6PWM.cpp | 8 +- library_source/drivers/StepperDriver2PWM.cpp | 98 ++++ library_source/drivers/StepperDriver2PWM.h | 59 +++ library_source/drivers/StepperDriver4PWM.cpp | 14 +- library_source/drivers/hardware_api.h | 23 + .../hardware_specific/atmega2560_mcu.cpp | 158 +++++++ .../hardware_specific/atmega328_mcu.cpp | 20 + .../drivers/hardware_specific/esp32_mcu.cpp | 205 +++++++-- .../drivers/hardware_specific/generic_mcu.cpp | 19 + .../drivers/hardware_specific/stm32_mcu.cpp | 49 +- library_source/sensors/HallSensor.cpp | 13 +- library_source/sensors/HallSensor.h | 4 - .../src/common/hardware_utils.cpp | 284 ------------ .../src/common/hardware_utils.h | 72 --- .../src/MagneticSensorI2C.cpp | 207 --------- .../src/MagneticSensorI2C.h | 104 ----- .../src/StepperMotor.cpp | 309 ------------- .../src/common/hardware_utils.cpp | 284 ------------ .../src/common/hardware_utils.h | 72 --- .../src/common/hardware_utils.cpp | 284 ------------ .../src/common/hardware_utils.h | 72 --- .../atmega2560_stepper_encoder.ino} | 0 .../src/Encoder.cpp | 0 .../src/Encoder.h | 0 .../src/StepperMotor.cpp | 0 .../src/StepperMotor.h | 0 .../src/common/FOCMotor.cpp | 0 .../src/common/FOCMotor.h | 0 .../src/common/Sensor.h | 0 .../src/common/defaults.h | 0 .../src/common/foc_utils.cpp | 0 .../src/common/foc_utils.h | 0 .../src/common/hardware_utils.cpp | 0 .../src/common/hardware_utils.h | 0 .../src/common/lowpass_filter.cpp | 0 .../src/common/lowpass_filter.h | 0 .../src/common/pid.cpp | 0 .../src/common/pid.h | 0 .../src/drivers/BLDCDriver3PWM.cpp | 14 +- .../src/drivers/hardware_api.h | 23 + .../hardware_specific/atmega328_mcu.cpp | 20 + .../drivers/hardware_specific/generic_mcu.cpp | 68 --- .../src/drivers/BLDCDriver3PWM.cpp | 14 +- .../src/drivers/hardware_api.h | 23 + .../hardware_specific/atmega328_mcu.cpp | 20 + .../drivers/hardware_specific/generic_mcu.cpp | 68 --- .../drivers/hardware_specific/teensy_mcu.cpp | 71 --- .../src/drivers/BLDCDriver3PWM.cpp | 14 +- .../src/drivers/hardware_api.h | 23 + .../hardware_specific/atmega328_mcu.cpp | 20 + .../drivers/hardware_specific/generic_mcu.cpp | 68 --- .../drivers/hardware_specific/stm32_mcu.cpp | 291 ------------ .../drivers/hardware_specific/teensy_mcu.cpp | 71 --- .../esp32_bldc_magnetic_spi.ino} | 24 +- .../src/BLDCMotor.cpp | 217 +++++---- .../src/BLDCMotor.h | 60 ++- .../src/common/base_classes/BLDCDriver.h | 28 ++ .../src/common/base_classes}/FOCMotor.cpp | 10 +- .../src/common/base_classes}/FOCMotor.h | 24 +- .../src/common/base_classes}/Sensor.h | 0 .../src/common/base_classes/StepperDriver.h | 27 ++ .../src/common/defaults.h | 0 .../src/common/foc_utils.cpp | 0 .../src/common/foc_utils.h | 2 +- .../src/common/lowpass_filter.cpp | 0 .../src/common/lowpass_filter.h | 2 +- .../src/common/pid.cpp | 6 +- .../src/common/pid.h | 2 +- .../src/common/time_utils.cpp | 31 ++ .../src/common/time_utils.h | 22 + .../src/drivers/BLDCDriver3PWM.cpp | 72 +++ .../src/drivers/BLDCDriver3PWM.h | 52 +++ .../src/drivers/hardware_api.h | 123 +++++ .../drivers/hardware_specific/esp32_mcu.cpp | 205 +++++++-- .../src/sensors}/MagneticSensorSPI.cpp | 31 +- .../src/sensors}/MagneticSensorSPI.h | 11 +- .../esp32_stepper_openloop.ino} | 47 +- .../src/StepperMotor.cpp | 105 ++--- .../src/StepperMotor.h | 53 +-- .../src/common/base_classes/BLDCDriver.h | 28 ++ .../src/common/base_classes}/FOCMotor.cpp | 10 +- .../src/common/base_classes}/FOCMotor.h | 24 +- .../src/common/base_classes}/Sensor.h | 0 .../src/common/base_classes/StepperDriver.h | 27 ++ .../src/common/defaults.h | 0 .../src/common/foc_utils.cpp | 0 .../src/common/foc_utils.h | 2 +- .../src/common/lowpass_filter.cpp | 0 .../src/common/lowpass_filter.h | 2 +- .../src/common/pid.cpp | 6 +- .../src/common/pid.h | 2 +- .../src/common/time_utils.cpp | 31 ++ .../src/common/time_utils.h | 22 + .../src/drivers/StepperDriver4PWM.cpp | 81 ++++ .../src/drivers/StepperDriver4PWM.h | 55 +++ .../src/drivers/hardware_api.h | 123 +++++ .../drivers/hardware_specific/esp32_mcu.cpp | 205 +++++++-- .../stm32_bldc_encoder/src/BLDCMotor.cpp | 421 ++++++++++++++++++ .../src/BLDCMotor.h} | 79 ++-- .../src/common/base_classes/BLDCDriver.h | 28 ++ .../src/common/base_classes}/FOCMotor.cpp | 10 +- .../src/common/base_classes}/FOCMotor.h | 24 +- .../src/common/base_classes}/Sensor.h | 0 .../src/common/base_classes/StepperDriver.h | 27 ++ .../src/common/defaults.h | 0 .../src/common/foc_utils.cpp | 0 .../src/common/foc_utils.h | 2 +- .../src/common/lowpass_filter.cpp | 0 .../src/common/lowpass_filter.h | 2 +- .../src/common/pid.cpp | 6 +- .../src/common/pid.h | 2 +- .../src/common/time_utils.cpp | 31 ++ .../src/common/time_utils.h | 22 + .../src/drivers/BLDCDriver6PWM.cpp | 8 +- .../src/drivers/BLDCDriver6PWM.h | 0 .../src/drivers/hardware_api.h | 123 +++++ .../drivers/hardware_specific/stm32_mcu.cpp | 49 +- .../src/sensors/Encoder.cpp | 228 ++++++++++ .../stm32_bldc_encoder/src/sensors/Encoder.h | 105 +++++ .../stm32_bldc_encoder.ino} | 51 ++- .../stm32_bldc_hall/src/BLDCMotor.cpp | 50 ++- .../src/drivers/BLDCDriver3PWM.cpp | 72 +++ .../src/drivers/BLDCDriver3PWM.h | 52 +++ .../src/drivers/hardware_api.h | 23 + .../drivers/hardware_specific/stm32_mcu.cpp | 49 +- .../src/sensors/HallSensor.cpp | 13 +- .../stm32_bldc_hall/src/sensors/HallSensor.h | 4 - 133 files changed, 3687 insertions(+), 3017 deletions(-) create mode 100644 library_source/drivers/StepperDriver2PWM.cpp create mode 100644 library_source/drivers/StepperDriver2PWM.h create mode 100644 library_source/drivers/hardware_specific/atmega2560_mcu.cpp delete mode 100644 minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.cpp delete mode 100644 minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.h delete mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/MagneticSensorI2C.cpp delete mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/MagneticSensorI2C.h delete mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/StepperMotor.cpp delete mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.cpp delete mode 100644 minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.h delete mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.cpp delete mode 100644 minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.h rename minimal_project_examples/{arduino_foc_stepper_encoder/arduino_foc_stepper_encoder.ino => atmega2560_stepper_encoder/atmega2560_stepper_encoder.ino} (100%) rename minimal_project_examples/{arduino_foc_stepper_encoder => atmega2560_stepper_encoder}/src/Encoder.cpp (100%) rename minimal_project_examples/{arduino_foc_stepper_encoder => atmega2560_stepper_encoder}/src/Encoder.h (100%) rename minimal_project_examples/{arduino_foc_stepper_encoder => atmega2560_stepper_encoder}/src/StepperMotor.cpp (100%) rename minimal_project_examples/{arduino_foc_stepper_encoder => atmega2560_stepper_encoder}/src/StepperMotor.h (100%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi => atmega2560_stepper_encoder}/src/common/FOCMotor.cpp (100%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi => atmega2560_stepper_encoder}/src/common/FOCMotor.h (100%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi => atmega2560_stepper_encoder}/src/common/Sensor.h (100%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi => atmega2560_stepper_encoder}/src/common/defaults.h (100%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi => atmega2560_stepper_encoder}/src/common/foc_utils.cpp (100%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi => atmega2560_stepper_encoder}/src/common/foc_utils.h (100%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi => atmega2560_stepper_encoder}/src/common/hardware_utils.cpp (100%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi => atmega2560_stepper_encoder}/src/common/hardware_utils.h (100%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi => atmega2560_stepper_encoder}/src/common/lowpass_filter.cpp (100%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi => atmega2560_stepper_encoder}/src/common/lowpass_filter.h (100%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi => atmega2560_stepper_encoder}/src/common/pid.cpp (100%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi => atmega2560_stepper_encoder}/src/common/pid.h (100%) delete mode 100644 minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/generic_mcu.cpp delete mode 100644 minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/generic_mcu.cpp delete mode 100644 minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/teensy_mcu.cpp delete mode 100644 minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/generic_mcu.cpp delete mode 100644 minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/stm32_mcu.cpp delete mode 100644 minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/teensy_mcu.cpp rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi/arduino_foc_bldc_magnetic_spi.ino => esp32_bldc_magnetic_spi/esp32_bldc_magnetic_spi.ino} (91%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi => esp32_bldc_magnetic_spi}/src/BLDCMotor.cpp (65%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi => esp32_bldc_magnetic_spi}/src/BLDCMotor.h (71%) create mode 100644 minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/BLDCDriver.h rename minimal_project_examples/{arduino_foc_stepper_openloop/src/common => esp32_bldc_magnetic_spi/src/common/base_classes}/FOCMotor.cpp (98%) rename minimal_project_examples/{arduino_foc_stepper_encoder/src/common => esp32_bldc_magnetic_spi/src/common/base_classes}/FOCMotor.h (93%) rename minimal_project_examples/{arduino_foc_stepper_encoder/src/common => esp32_bldc_magnetic_spi/src/common/base_classes}/Sensor.h (100%) create mode 100644 minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/StepperDriver.h rename minimal_project_examples/{arduino_foc_stepper_encoder => esp32_bldc_magnetic_spi}/src/common/defaults.h (100%) rename minimal_project_examples/{arduino_foc_stepper_encoder => esp32_bldc_magnetic_spi}/src/common/foc_utils.cpp (100%) rename minimal_project_examples/{arduino_foc_stepper_encoder => esp32_bldc_magnetic_spi}/src/common/foc_utils.h (94%) rename minimal_project_examples/{arduino_foc_stepper_encoder => esp32_bldc_magnetic_spi}/src/common/lowpass_filter.cpp (100%) rename minimal_project_examples/{arduino_foc_stepper_encoder => esp32_bldc_magnetic_spi}/src/common/lowpass_filter.h (94%) rename minimal_project_examples/{arduino_foc_stepper_magnetic_i2c => esp32_bldc_magnetic_spi}/src/common/pid.cpp (92%) rename minimal_project_examples/{arduino_foc_stepper_openloop => esp32_bldc_magnetic_spi}/src/common/pid.h (97%) create mode 100644 minimal_project_examples/esp32_bldc_magnetic_spi/src/common/time_utils.cpp create mode 100644 minimal_project_examples/esp32_bldc_magnetic_spi/src/common/time_utils.h create mode 100644 minimal_project_examples/esp32_bldc_magnetic_spi/src/drivers/BLDCDriver3PWM.cpp create mode 100644 minimal_project_examples/esp32_bldc_magnetic_spi/src/drivers/BLDCDriver3PWM.h create mode 100644 minimal_project_examples/esp32_bldc_magnetic_spi/src/drivers/hardware_api.h rename minimal_project_examples/{atmega328_driver_standalone => esp32_bldc_magnetic_spi}/src/drivers/hardware_specific/esp32_mcu.cpp (57%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi/src => esp32_bldc_magnetic_spi/src/sensors}/MagneticSensorSPI.cpp (93%) rename minimal_project_examples/{arduino_foc_bldc_magnetic_spi/src => esp32_bldc_magnetic_spi/src/sensors}/MagneticSensorSPI.h (94%) rename minimal_project_examples/{arduino_foc_stepper_openloop/arduino_foc_stepper_openloop.ino => esp32_stepper_openloop/esp32_stepper_openloop.ino} (58%) rename minimal_project_examples/{arduino_foc_stepper_openloop => esp32_stepper_openloop}/src/StepperMotor.cpp (73%) rename minimal_project_examples/{arduino_foc_stepper_openloop => esp32_stepper_openloop}/src/StepperMotor.h (73%) create mode 100644 minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/BLDCDriver.h rename minimal_project_examples/{arduino_foc_stepper_magnetic_i2c/src/common => esp32_stepper_openloop/src/common/base_classes}/FOCMotor.cpp (98%) rename minimal_project_examples/{arduino_foc_stepper_openloop/src/common => esp32_stepper_openloop/src/common/base_classes}/FOCMotor.h (93%) rename minimal_project_examples/{arduino_foc_stepper_magnetic_i2c/src/common => esp32_stepper_openloop/src/common/base_classes}/Sensor.h (100%) create mode 100644 minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/StepperDriver.h rename minimal_project_examples/{arduino_foc_stepper_magnetic_i2c => esp32_stepper_openloop}/src/common/defaults.h (100%) rename minimal_project_examples/{arduino_foc_stepper_magnetic_i2c => esp32_stepper_openloop}/src/common/foc_utils.cpp (100%) rename minimal_project_examples/{arduino_foc_stepper_openloop => esp32_stepper_openloop}/src/common/foc_utils.h (94%) rename minimal_project_examples/{arduino_foc_stepper_magnetic_i2c => esp32_stepper_openloop}/src/common/lowpass_filter.cpp (100%) rename minimal_project_examples/{arduino_foc_stepper_openloop => esp32_stepper_openloop}/src/common/lowpass_filter.h (94%) rename minimal_project_examples/{arduino_foc_stepper_openloop => esp32_stepper_openloop}/src/common/pid.cpp (92%) rename minimal_project_examples/{arduino_foc_stepper_magnetic_i2c => esp32_stepper_openloop}/src/common/pid.h (97%) create mode 100644 minimal_project_examples/esp32_stepper_openloop/src/common/time_utils.cpp create mode 100644 minimal_project_examples/esp32_stepper_openloop/src/common/time_utils.h create mode 100644 minimal_project_examples/esp32_stepper_openloop/src/drivers/StepperDriver4PWM.cpp create mode 100644 minimal_project_examples/esp32_stepper_openloop/src/drivers/StepperDriver4PWM.h create mode 100644 minimal_project_examples/esp32_stepper_openloop/src/drivers/hardware_api.h rename minimal_project_examples/{atmega328_bldc_openloop => esp32_stepper_openloop}/src/drivers/hardware_specific/esp32_mcu.cpp (57%) create mode 100644 minimal_project_examples/stm32_bldc_encoder/src/BLDCMotor.cpp rename minimal_project_examples/{arduino_foc_stepper_magnetic_i2c/src/StepperMotor.h => stm32_bldc_encoder/src/BLDCMotor.h} (59%) create mode 100644 minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/BLDCDriver.h rename minimal_project_examples/{arduino_foc_stepper_encoder/src/common => stm32_bldc_encoder/src/common/base_classes}/FOCMotor.cpp (98%) rename minimal_project_examples/{arduino_foc_stepper_magnetic_i2c/src/common => stm32_bldc_encoder/src/common/base_classes}/FOCMotor.h (93%) rename minimal_project_examples/{arduino_foc_stepper_openloop/src/common => stm32_bldc_encoder/src/common/base_classes}/Sensor.h (100%) create mode 100644 minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/StepperDriver.h rename minimal_project_examples/{arduino_foc_stepper_openloop => stm32_bldc_encoder}/src/common/defaults.h (100%) rename minimal_project_examples/{arduino_foc_stepper_openloop => stm32_bldc_encoder}/src/common/foc_utils.cpp (100%) rename minimal_project_examples/{arduino_foc_stepper_magnetic_i2c => stm32_bldc_encoder}/src/common/foc_utils.h (94%) rename minimal_project_examples/{arduino_foc_stepper_openloop => stm32_bldc_encoder}/src/common/lowpass_filter.cpp (100%) rename minimal_project_examples/{arduino_foc_stepper_magnetic_i2c => stm32_bldc_encoder}/src/common/lowpass_filter.h (94%) rename minimal_project_examples/{arduino_foc_stepper_encoder => stm32_bldc_encoder}/src/common/pid.cpp (92%) rename minimal_project_examples/{arduino_foc_stepper_encoder => stm32_bldc_encoder}/src/common/pid.h (97%) create mode 100644 minimal_project_examples/stm32_bldc_encoder/src/common/time_utils.cpp create mode 100644 minimal_project_examples/stm32_bldc_encoder/src/common/time_utils.h rename minimal_project_examples/{stm32_bldc_hall => stm32_bldc_encoder}/src/drivers/BLDCDriver6PWM.cpp (92%) rename minimal_project_examples/{stm32_bldc_hall => stm32_bldc_encoder}/src/drivers/BLDCDriver6PWM.h (100%) create mode 100644 minimal_project_examples/stm32_bldc_encoder/src/drivers/hardware_api.h rename minimal_project_examples/{atmega328_bldc_openloop => stm32_bldc_encoder}/src/drivers/hardware_specific/stm32_mcu.cpp (88%) create mode 100644 minimal_project_examples/stm32_bldc_encoder/src/sensors/Encoder.cpp create mode 100644 minimal_project_examples/stm32_bldc_encoder/src/sensors/Encoder.h rename minimal_project_examples/{arduino_foc_stepper_magnetic_i2c/arduino_foc_stepper_magnetic_i2c.ino => stm32_bldc_encoder/stm32_bldc_encoder.ino} (79%) create mode 100644 minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver3PWM.cpp create mode 100644 minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver3PWM.h diff --git a/README.md b/README.md index 16f86cd9..a46577e6 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ -# Arduino *SimpleFOClibrary* v1.6.0 - minimal project builder +# Arduino *SimpleFOClibrary* v2.0.1 - minimal project builder ![MinimalBuild](https://github.com/askuric/Arduino-FOC/workflows/MinimalBuild/badge.svg?branch=minimal) [![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT) @@ -11,40 +11,62 @@ Library source code structure ```shell ├─── library_source | | -| ├─── common # Contains all the common utility classes and functions +| ├─ BLDCMotor.cpp/h # BLDC motor handling class +| ├─ StepperMotor.cpp/h # Stepper motor handling class +| | +│ ├─── common # Contains all the common utility classes and functions | | | | | ├─ defaults.h # default motion control parameters -| | | | | ├─ foc_utils.cpp./h # utility functions of the FOC algorithm -| | ├─ hardware_utils.cpp./h # all the hardware specific implementations are in these files +| | ├─ time_utils.cpp/h # utility functions for dealing with time measurements and delays | | ├─ pid.cpp./h # class implementing PID controller | | ├─ lowpass_filter.cpp./h # class implementing Low pass filter | | | -| | ├─ FOCMotor.cpp./h # common class for all implemented motors -| | └─ Sensor./h # common class for all implemented sensors +| | ├─── base_classes +| | | ├─ FOCMotor.cpp./h # common class for all implemented motors +| | | ├─ BLDCDriver.h # common class for all BLDC drivers +| | | ├─ StepperDriver.h # common class for all Stepper drivers +| | | └─ Sensor./h # common class for all implemented sensors | | -| ├─ BLDCMotor.cpp/h # BLDC motor handling class -| ├─ StepperMotor.cpp/h # Stepper motor handling class -│ │ -│ ├─ Encoder.cpp/h # Encoder class implementing the Quadrature encoder operations -│ ├─ MagneticSensorSPI.cpp/h # class implementing SPI communication for Magnetic sensors -│ ├─ MagneticSensorI2C.cpp/h # class implementing I2C communication for Magnetic sensors -│ ├─ MagneticSensorAnalog.cpp/h # class implementing Analog output for Magnetic sensors - └─ HallSensor.cpp/h # class implementing Hall sensor +| ├─── drivers +| | ├─ BLDCDriver3PWM.cpp/h # Implementation of generic 3PWM bldc driver +| | ├─ BLDCDriver6PWM.cpp/h # Implementation of generic 6PWM bldc driver +| | ├─ StepperDriver2PWM.cpp/h # Implementation of generic 2PWM stepper driver +| | ├─ StepperDriver4PWM.cpp/h # Implementation of generic 4PWM stepper driver +| | | +| | ├─ hardware_api.h # common mcu specific api handling pwm setting and configuration +| | | +| | ├─── hardware_specific # mcu specific hadrware_api.h implementations +| | | ├─ atmega2560_mcu.cpp # ATMega 2560 implementation +| | | ├─ atmega328_mcu.cpp # ATMega 328 (Arduino UNO) implementation +| | | ├─ esp32_mcu.cpp # esp32 implementation +| | | ├─ stm32_mcu.cpp # stm32 implementation +| | | ├─ teensy_mcu.cpp # teensy implementation +| | | └─ generic_mcu./h # generic implementation - if not nay of above (not complete) +| | +| ├─── sensors +| │ ├─ Encoder.cpp/h # Encoder class implementing the Quadrature encoder operations +| │ ├─ MagneticSensorSPI.cpp/h # class implementing SPI communication for Magnetic sensors +| │ ├─ MagneticSensorI2C.cpp/h # class implementing I2C communication for Magnetic sensors +| │ ├─ MagneticSensorAnalog.cpp/h # class implementing Analog output for Magnetic sensors + └─ HallSensor.cpp/h # class implementing Hall sensor ``` Minimal project examples provided for quick start: ```shell ├─── minimal_project_examples # Project examples -│ ├─ arduino_foc_bldc_openloop # BLDC motor + Open loop control -│ ├─ arduino_foc_bldc_encoder # BLDC motor + Encoder -│ ├─ arduino_foc_bldc_hall # BLDC motor + Hall sensors -│ ├─ arduino_foc_bldc_magnetic_i2c # BLDC motor + I2C magnetic sensor -│ ├─ arduino_foc_bldc_magnetic_spi # BLDC motor + SPI magnetic sensor +│ ├─ atmega2560_stepper_encoder # ATMega2560 + BLDC motor + 3PWM driver + encoder +| | +│ ├─ atmega328_bldc_encoder # ATMega328 + BLDC motor + 3PWM driver + Encoder +│ ├─ atmega328_bldc_magnetic_i2c # ATMega328 + BLDC motor + 3PWM driver + I2C magnetic sensor +│ ├─ atmega328_bldc_openloop # ATMega328 + BLDC motor + 3PWM driver +│ ├─ atmega328_driver_standalone # ATMega328 + 3PWM driver │ | -│ ├─ arduino_foc_stepper_openloop # Stepper motor + Open loop control -│ ├─ arduino_foc_stepper_encoder # Stepper motor + Encoder - └─ arduino_foc_stepper_magnetic_i2c # Stepper motor + I2C magnetic sensor +│ ├─ esp32_bldc_magnetic_spi # ESP32 + BLDC motor + 3PWM driver + SPI magnetic sensor +│ ├─ esp32_stepper_openloop # ESP32 + Stepper motor + 4PWM driver +| | +│ ├─ stm32_bldc_encoder # stm32 + BLDC motor + 6PWM driver + encoder + └─ stm32_bldc_hall # stm32 + BLDC motor + 3PWM driver + hall sensors ``` @@ -54,8 +76,9 @@ Minimal project examples provided for quick start: Creating your own minimal project version is very simple and is done in four steps: - Step 0: Download minimal branch contents to your PC - Step 1: Create your the arduino project -- Step 2: Add motor specific code -- Step 3: Add sensor specific code +- Step 2: Add **driver** specific code +- Step 3: Add **motor** specific code +- Step 4: Add **sensor** specific code ## Step 0. Download the code #### Github website download @@ -78,25 +101,72 @@ Open a directory you want to use as your arduino project directory `my_arduino_p ├─── my_arduino_project | ├─ my_arduino_project.ino | └─── src -| | ├─── common # Contains all the common utility classes and functions -| | ├─ defaults.h # default motion control parameters -| | ├─ foc_utils.cpp./h # utility functions of the FOC algorithm -| | ├─ hardware_utils.cpp./h # all the hardware specific implementations are in these files -| | ├─ pid.cpp./h # class implementing PID controller -| | ├─ lowpass_filter.cpp./h # class implementing Low pass filter -| | ├─ FOCMotor.cpp./h # common class for all implemented motors -| | └─ Sensor./h # common class for all implemented sensors +│ | ├─── common +| | | ├─ defaults.h # default motion control parameters +| | | ├─ foc_utils.cpp./h # utility functions of the FOC algorithm +| | | ├─ time_utils.cpp/h # utility functions for dealing with time measurements and delays +| | | ├─ pid.cpp./h # class implementing PID controller +| | | ├─ lowpass_filter.cpp./h # class implementing Low pass filter +| | | └─── base_classes # common class for all implemented sensors +``` +## Step 2. Add driver specific code +First create a `drivers` folder in `src` folder. If you wish to use the 3PWM or 6PWM BLDC driver in your project with your setup you will have to copy the `BLDCDriver3PWM.cpp/h` files or `BLDCDriver3PWM.cpp/h` files from the `library_source/drivers` folder in your drivers folder. If you wish to use the 4PWM or 2PWM stepper motor make sure to copy the `StepperDriver4PWM.cpp/h` or `StepperDriver2PWM.cpp/h` files and place them to the `src/drivers` folder. +```shell +├─── my_arduino_project +| ├─ my_arduino_project.ino +| └─── src +| | ├─── common # Common utility classes and functions +| | | +│ └─── drivers +| └─ BLDCDriver3PWM.cpp/h # BLDC motor handling class +``` +Next from the `library_source/drivers` directory copy the `hardware_api.h` file to the `src/drivers` folder as well as the `hardware_specific` folder. Finally in the `hardware_specific` folder leave only the `x_mcu.cpp` file which corresponds to your mcu architecture. For example, for esp32 boards +```shell +├─── my_arduino_project +| ├─ my_arduino_project.ino +| └─── src +| | ├─── common # Common utility classes and functions +| | | +│ └─── drivers +| ├─ BLDCDriver3PWM.cpp/h # BLDC driver handling class +| ├─ hardware_api.h # common mcu specific api handling pwm setting and configuration +| └─── hardware_specific # mcu specific hadrware_api.h implementations +| └─ esp32_mcu.cpp # esp32 implementation ``` -## Step 2. Add motor specific code +And in your Arduino code in the `my_arduino_project.ino` file make sure to add the the include: +```cpp +#include "src/drivers/BLDCDriver3PWM.h" +``` +For the combination of stepper driver 4pwm and stm32 board the structure will be: +```shell +├─── my_arduino_project +| ├─ my_arduino_project.ino +| └─── src +| | ├─── common # Common utility classes and functions +| | | +│ └─── drivers +| ├─ StepperDriver4PWM.cpp/h # Stepper driver handling class +| ├─ hardware_api.h # common mcu specific api handling pwm setting and configuration +| └─── hardware_specific # mcu specific hadrware_api.h implementations +| └─ stm32_mcu.cpp # stm32 implementation +``` +And the include: +```cpp +#include "src/drivers/StepperDriver4PWM.h" +``` +If you wish to run your drivers in the standalone mode these are all the files that you will need. See the `atmega328_driver_standalone` project example. + +## Step 3. Add motor specific code If you wish to use the BLDC motor with your setup you will have to copy the `BLDCMotor.cpp/h` from the `library_source` folder, and if you wish to use the stepper motor make sure to copy the `StepperMotor.cpp/h` files and place them to the `src` folder ```shell ├─── my_arduino_project | ├─ my_arduino_project.ino | └─── src | | ├─── common # Common utility classes and functions +| | ├─── drivers # Driver handling software | | | -| | └─ BLDCMotor.cpp/h # BLDC motor handling class +| └─ BLDCMotor.cpp/h # BLDC motor handling class ``` And in your Arduino code in the `my_arduino_project.ino` file make sure to add the the include: ```cpp @@ -109,17 +179,18 @@ For stepper motors the procedure is equivalent: | ├─ my_arduino_project.ino | └─── src | | ├─── common # Common utility classes and functions +| | ├─── drivers # Driver handling software | | | -| | └─ StepperMotor.cpp/h # Stepper motor handling class +| └─ StepperMotor.cpp/h # Stepper motor handling class ``` And the include: ```cpp #include "src/StepperMotor.h" ``` -If you wish to run your motor in the open loop mode these are all the files that you will need. See the `arduino_foc_bldc_openloop` and `arduino_foc_stepper_openloop` project example. +If you wish to run your motor in the open loop mode these are all the files that you will need. See the `esp32_stepper_openloop` and `atmega328_bldc_openloop` project examples. -## Step 3. Add sensor specific code -In order to support the different position sensors you will have to copy their `*.cpp` and `*.h` into your `src` directory. All you need to do is copy the header files from the `library_source` directory. +## Step 4. Add sensor specific code +In order to support the different position sensors you will first have to create the `sensors` folder in your `src` folder. And then copy their `*.cpp` and `*.h` files which correspond to the sensor into your `src/sensors` directory. You can find the sensor implementations in the `library_source/sensors` directory. ### Example: Encoder sensor @@ -129,16 +200,17 @@ For example if you wish to use BLDC motor and encoder as a sensor, your arduino | ├─ my_arduino_project.ino | └─── src | | ├─── common # Common utility classes and functions -| | | -| | ├─ BLDCMotor.cpp/h # BLDC motor handling class -| | └─ Encoder.cpp/h # Encoder class implementing the Quadrature encoder operations +| | ├─── drivers # Driver handling software +│ ├─── sensors +| | └─ Encoder.cpp/h # Encoder class implementing the Quadrature encoder operations +| | +| └─ BLDCMotor.cpp/h # BLDC motor handling class ``` -And your includes will be: +And in your in your arduino project `my_arduino_project.ino` add the line: ```cpp -#include "src/BLDCMotor.h" -#include "src/Encoder.h" +#include "src/sensors/Encoder.h" ``` -See `arduino_foc_bldc_encoder` project example or `arduino_foc_stepper_encoder` for stepper equivalent. +See `atmega328_bldc_encoder` and `stm32_bldc_encoder` project example for BLDC motors or `atmega2560_stepper_encoder` for stepper equivalent. ### Example: SPI Magnetic sensor If you wish to use Stepper motor and SPI magnetic sensor in your project, your folder structure will be: @@ -147,17 +219,18 @@ If you wish to use Stepper motor and SPI magnetic sensor in your project, your f ├─── my_arduino_project | ├─ my_arduino_project.ino | └─── src -| | ├─── common # Common utility classes and functions -| | | -| | ├─ StepperMotor.cpp/h # Stepper motor handling class -| | └─ MagneticSensorSPI.cpp/h # class implementing SPI communication for Magnetic sensors +| | ├─── common # Common utility classes and functions +| | ├─── drivers # Driver handling software +│ ├─── sensors +| | └─ MagneticSensorSPI.cpp/h # class implementing SPI communication for Magnetic sensors +| | +| └─ StepperMotor.cpp/h # Stepper motor handling class ``` -And your includes will be: +And in your in your arduino project `my_arduino_project.ino` add the line: ```cpp -#include "src/StepperMotor.h" -#include "src/MagneticSensorSPI.h" +#include "src/sensors/MagneticSensorSPI.h" ``` -See `arduino_foc_stepper_magnetic_spi` project example or `arduino_foc_bldc_magnetic_spi` for BLDC motor equivalent. +See `esp32_bldc_magnetic_spi` project example or `atmega328_bldc_magnetic_i2c` for I2C magnetic sensors equivalent. ### Example: Multiple sensors: analog magnetic sensor and encoder @@ -167,19 +240,34 @@ For example if you wish to use magnetic sensor with SPI communication, your ardu ├─── my_arduino_project | ├─ my_arduino_project.ino | └─── src -| | ├─── common # Common utility classes and functions -| | | -| | ├─ BLDCMotor.cpp/h # BLDC motor handling class -| | ├─ Encoder.cpp/h # Encoder class implementing the Quadrature encoder operations -| | └─ MagneticSensorAnalog.cpp/h # class implementing Analog output for Magnetic sensors +| | ├─── common # Common utility classes and functions +| | ├─── drivers # Driver handling software +│ ├─── sensors +| | ├─ Encoder.cpp/h # Encoder class implementing the Quadrature encoder operations +| | └─ MagneticSensorAnalog.cpp/h # class implementing Analog output for Magnetic sensors +| | +| └─ StepperMotor.cpp/h # Stepper motor handling class ``` -And your includes will be: +And added includes should be: ```cpp -#include "src/BLDCMotor.h" -#include "src/MagneticSensorAnalog.h" -#include "src/Encoder.h" +#include "src/sensors/MagneticSensorAnalog.h" +#include "src/sensors/Encoder.h" +``` +### Example: Sensors standalone - *without motor/driver* +It is possible to use the sensors developed in this library as standalone sensors. For that you can need to do steps 0. and 1. and then just add the sensor specific code. This is one possible project structure if you wish to use an encoder as a standalone sensor: +```shell +├─── my_arduino_project +| ├─ my_arduino_project.ino +| └─── src +| | ├─── common # Common utility classes and functions +│ └─── sensors +| └─ Encoder.cpp/h # Encoder class implementing the Quadrature encoder operations ``` +And you can include it directly to the arduino project: +```cpp +#include "src/sensors/Encoder.h" +``` ## Documentation Find out more information about the Arduino *Simple**FOC**library* and *Simple**FOC**project* in [docs website](https://docs.simplefoc.com/) diff --git a/library_source/BLDCMotor.cpp b/library_source/BLDCMotor.cpp index bed4cd6a..5d36ce35 100644 --- a/library_source/BLDCMotor.cpp +++ b/library_source/BLDCMotor.cpp @@ -29,7 +29,7 @@ void BLDCMotor::linkDriver(BLDCDriver* _driver) { driver = _driver; } -// init hardware pins +// init hardware pins void BLDCMotor::init() { if(monitor_port) monitor_port->println("MOT: Initialise variables."); // sanity check for the voltage limit configuration @@ -53,13 +53,13 @@ void BLDCMotor::disable() { // set zero to PWM driver->setPwm(0, 0, 0); - // disable the driver + // disable the driver driver->disable(); } // enable motor driver void BLDCMotor::enable() { - // enable the driver + // enable the driver driver->enable(); // set zero to PWM driver->setPwm(0, 0, 0); @@ -93,7 +93,7 @@ int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction int BLDCMotor::alignSensor() { if(monitor_port) monitor_port->println("MOT: Align sensor."); // align the electrical phases of the motor and sensor - // set angle -90 degrees + // set angle -90 degrees float start_angle = shaftAngle(); for (int i = 0; i <=5; i++ ) { @@ -112,6 +112,8 @@ int BLDCMotor::alignSensor() { sensor->natural_direction = Direction::CCW; } else if (mid_angle == start_angle) { if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } else{ + if(monitor_port) monitor_port->println("MOT: natural_direction==CW"); } // let the motor stabilize for 2 sec @@ -134,19 +136,19 @@ int BLDCMotor::alignSensor() { } -// Encoder alignment the absolute zero angle +// Encoder alignment the absolute zero angle // - to the index int BLDCMotor::absoluteZeroAlign() { if(monitor_port) monitor_port->println("MOT: Absolute zero align."); // if no absolute zero return if(!sensor->hasAbsoluteZero()) return 0; - + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); // search the absolute zero with small velocity while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ - loopFOC(); + loopFOC(); voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); } voltage_q = 0; @@ -167,9 +169,9 @@ int BLDCMotor::absoluteZeroAlign() { // Iterative function looping FOC algorithm, setting Uq on the Motor // The faster it can be run the better void BLDCMotor::loopFOC() { - // shaft angle + // shaft angle shaft_angle = shaftAngle(); - // set the phase voltage - FOC heart function :) + // set the phase voltage - FOC heart function :) setPhaseVoltage(voltage_q, voltage_d, _electricalAngle(shaft_angle,pole_pairs)); } @@ -219,7 +221,7 @@ void BLDCMotor::move(float new_target) { // Method using FOC to set Uq and Ud to the motor at the optimal angle // Function implementing Space Vector PWM and Sine PWM algorithms -// +// // Function using sine approximation // regular sin + cos ~300us (no memory usaage) // approx _sin + _cos ~110us (400Byte ~ 20% of memory) @@ -257,7 +259,7 @@ void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { }; // static int trap_150_state = 0; sector = 12 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes - + Ua = Uq + trap_150_map[sector][0] * Uq; Ub = Uq + trap_150_map[sector][1] * Uq; Uc = Uq + trap_150_map[sector][2] * Uq; @@ -272,7 +274,7 @@ void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { break; case FOCModulationType::SinePWM : - // Sinusoidal PWM modulation + // Sinusoidal PWM modulation // Inverse Park + Clarke transformation // angle normalization in between 0 and 2pi @@ -299,10 +301,10 @@ void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { break; case FOCModulationType::SpaceVectorPWM : - // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm // https://www.youtube.com/watch?v=QMSWUMEAejg - // if negative voltages change inverse the phase + // if negative voltages change inverse the phase // angle + 180degrees if(Uq < 0) angle_el += _PI; Uq = abs(Uq); @@ -316,14 +318,14 @@ void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { // calculate the duty cycles float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/driver->voltage_limit; float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/driver->voltage_limit; - // two versions possible + // two versions possible float T0 = 0; // pulled to 0 - better for low power supply voltage - if (centered) { + if (centered) { T0 = 1 - T1 - T2; //centered around driver->voltage_limit/2 - } + } // calculate the duty cycles(times) - float Ta,Tb,Tc; + float Ta,Tb,Tc; switch(sector){ case 1: Ta = T1 + T2 + T0/2; @@ -369,7 +371,7 @@ void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { break; } - + // set the voltages in driver driver->setPwm(Ua, Ub, Uc); } @@ -386,7 +388,7 @@ void BLDCMotor::velocityOpenloop(float target_velocity){ float Ts = (now_us - open_loop_timestamp) * 1e-6; // calculate the necessary angle to achieve target velocity - shaft_angle += target_velocity*Ts; + shaft_angle += target_velocity*Ts; // set the maximal allowed voltage (voltage_limit) with the necessary angle setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); @@ -403,17 +405,17 @@ void BLDCMotor::angleOpenloop(float target_angle){ unsigned long now_us = _micros(); // calculate the sample time from last call float Ts = (now_us - open_loop_timestamp) * 1e-6; - + // calculate the necessary angle to move from current position towards target angle // with maximal velocity (velocity_limit) if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) - shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; else shaft_angle = target_angle; - + // set the maximal allowed voltage (voltage_limit) with the necessary angle setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; -} \ No newline at end of file +} diff --git a/library_source/SimpleFOC.h b/library_source/SimpleFOC.h index 41188c20..bb963ef1 100644 --- a/library_source/SimpleFOC.h +++ b/library_source/SimpleFOC.h @@ -106,5 +106,6 @@ void loop() { #include "drivers/BLDCDriver3PWM.h" #include "drivers/BLDCDriver6PWM.h" #include "drivers/StepperDriver4PWM.h" +#include "drivers/StepperDriver2PWM.h" #endif diff --git a/library_source/StepperMotor.cpp b/library_source/StepperMotor.cpp index e8e991cf..31c81eeb 100644 --- a/library_source/StepperMotor.cpp +++ b/library_source/StepperMotor.cpp @@ -105,6 +105,8 @@ int StepperMotor::alignSensor() { sensor->natural_direction = Direction::CCW; } else if (mid_angle == start_angle) { if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } else{ + if(monitor_port) monitor_port->println("MOT: natural_direction==CW"); } // let the motor stabilize for 2 sec @@ -246,7 +248,7 @@ void StepperMotor::velocityOpenloop(float target_velocity){ // calculate the necessary angle to achieve target velocity shaft_angle += target_velocity*Ts; - + // set the maximal allowed voltage (voltage_limit) with the necessary angle setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle,pole_pairs)); diff --git a/library_source/common/time_utils.cpp b/library_source/common/time_utils.cpp index 181d03cf..b00a8c78 100644 --- a/library_source/common/time_utils.cpp +++ b/library_source/common/time_utils.cpp @@ -3,7 +3,7 @@ // function buffering delay() // arduino uno function doesn't work well with interrupts void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega2560__) // if arduino uno and other atmega328p chips // use while instad of delay, // due to wrong measurement based on changed timer0 @@ -19,7 +19,7 @@ void _delay(unsigned long ms){ // function buffering _micros() // arduino function doesn't work well with interrupts unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega2560__) // if arduino uno and other atmega328p chips //return the value based on the prescaler if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); diff --git a/library_source/drivers/BLDCDriver3PWM.cpp b/library_source/drivers/BLDCDriver3PWM.cpp index bacb4ec5..a3fc052d 100644 --- a/library_source/drivers/BLDCDriver3PWM.cpp +++ b/library_source/drivers/BLDCDriver3PWM.cpp @@ -35,6 +35,8 @@ void BLDCDriver3PWM::disable() // init hardware pins int BLDCDriver3PWM::init() { + // a bit of separation + _delay(1000); // PWM pins pinMode(pwmA, OUTPUT); @@ -56,14 +58,14 @@ int BLDCDriver3PWM::init() { // Set voltage to the pwm pin void BLDCDriver3PWM::setPwm(float Ua, float Ub, float Uc) { // limit the voltage in driver - Ua = _constrain(Ua, -voltage_limit, voltage_limit); - Ub = _constrain(Ub, -voltage_limit, voltage_limit); - Uc = _constrain(Uc, -voltage_limit, voltage_limit); + Ua = _constrain(Ua, 0.0, voltage_limit); + Ub = _constrain(Ub, 0.0, voltage_limit); + Uc = _constrain(Uc, 0.0, voltage_limit); // calculate duty cycle // limited in [0,1] - float dc_a = _constrain(Ua / voltage_power_supply, 0 , 1 ); - float dc_b = _constrain(Ub / voltage_power_supply, 0 , 1 ); - float dc_c = _constrain(Uc / voltage_power_supply, 0 , 1 ); + float dc_a = _constrain(Ua / voltage_power_supply, 0.0 , 1.0 ); + float dc_b = _constrain(Ub / voltage_power_supply, 0.0 , 1.0 ); + float dc_c = _constrain(Uc / voltage_power_supply, 0.0 , 1.0 ); // hardware specific writing // hardware specific function - depending on driver and mcu _writeDutyCycle3PWM(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC); diff --git a/library_source/drivers/BLDCDriver6PWM.cpp b/library_source/drivers/BLDCDriver6PWM.cpp index b1f2e884..266a5412 100644 --- a/library_source/drivers/BLDCDriver6PWM.cpp +++ b/library_source/drivers/BLDCDriver6PWM.cpp @@ -41,6 +41,8 @@ void BLDCDriver6PWM::disable() // init hardware pins int BLDCDriver6PWM::init() { + // a bit of separation + _delay(1000); // PWM pins pinMode(pwmA_l, OUTPUT); @@ -64,9 +66,9 @@ int BLDCDriver6PWM::init() { // Set voltage to the pwm pin void BLDCDriver6PWM::setPwm(float Ua, float Ub, float Uc) { // limit the voltage in driver - Ua = _constrain(Ua, -voltage_limit, voltage_limit); - Ub = _constrain(Ub, -voltage_limit, voltage_limit); - Uc = _constrain(Uc, -voltage_limit, voltage_limit); + Ua = _constrain(Ua, 0, voltage_limit); + Ub = _constrain(Ub, 0, voltage_limit); + Uc = _constrain(Uc, 0, voltage_limit); // calculate duty cycle // limited in [0,1] float dc_a = _constrain(Ua / voltage_power_supply, 0.0 , 1.0 ); diff --git a/library_source/drivers/StepperDriver2PWM.cpp b/library_source/drivers/StepperDriver2PWM.cpp new file mode 100644 index 00000000..72182648 --- /dev/null +++ b/library_source/drivers/StepperDriver2PWM.cpp @@ -0,0 +1,98 @@ +#include "StepperDriver2PWM.h" + +StepperDriver2PWM::StepperDriver2PWM(int ph1PWM, int ph1INA, int ph1INB, int ph2PWM, int ph2INA, int ph2INB, int en1, int en2){ + // Pin initialization + pwm1 = ph1PWM; //!< phase 1 pwm pin number + ina1 = ph1INA; //!< phase 1 INA pin number + inb1 = ph1INB; //!< phase 1 INB pin number + pwm2 = ph2PWM; //!< phase 2 pwm pin number + ina2 = ph2INA; //!< phase 2 INA pin number + inb2 = ph2INB; //!< phase 2 INB pin number + + // enable_pin pin + enable_pin1 = en1; + enable_pin2 = en2; + + // default power-supply value + voltage_power_supply = DEF_POWER_SUPPLY; + voltage_limit = NOT_SET; + +} + +// enable motor driver +void StepperDriver2PWM::enable(){ + // enable_pin the driver - if enable_pin pin available + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, HIGH); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, HIGH); + // set zero to PWM + setPwm(0,0); +} + +// disable motor driver +void StepperDriver2PWM::disable() +{ + // set zero to PWM + setPwm(0, 0); + // disable the driver - if enable_pin pin available + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, LOW); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, LOW); + +} + +// init hardware pins +int StepperDriver2PWM::init() { + // a bit of separation + _delay(1000); + + // PWM pins + pinMode(pwm1, OUTPUT); + pinMode(pwm2, OUTPUT); + pinMode(ina1, OUTPUT); + pinMode(ina2, OUTPUT); + pinMode(inb1, OUTPUT); + pinMode(inb2, OUTPUT); + + if(enable_pin1 != NOT_SET) pinMode(enable_pin1, OUTPUT); + if(enable_pin2 != NOT_SET) pinMode(enable_pin2, OUTPUT); + + // sanity check for the voltage limit configuration + if(voltage_limit == NOT_SET || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + + // Set the pwm frequency to the pins + // hardware specific function - depending on driver and mcu + _configure2PWM(pwm_frequency, pwm1, pwm2); + return 0; +} + + +// Set voltage to the pwm pin +void StepperDriver2PWM::setPwm(float Ualpha, float Ubeta) { + float duty_cycle1(0.0),duty_cycle2(0.0); + // limit the voltage in driver + Ualpha = _constrain(Ualpha, -voltage_limit, voltage_limit); + Ubeta = _constrain(Ubeta, -voltage_limit, voltage_limit); + // hardware specific writing + duty_cycle1 = _constrain(abs(Ualpha)/voltage_power_supply,0.0,1.0); + duty_cycle2 = _constrain(abs(Ubeta)/voltage_power_supply,0.0,1.0); + // set direction + if( Ualpha > 0 ){ + digitalWrite(inb1, LOW); + digitalWrite(ina1, HIGH); + } + else{ + digitalWrite(ina1, LOW); + digitalWrite(inb1, HIGH); + } + + if( Ubeta > 0 ){ + digitalWrite(ina2, LOW); + digitalWrite(inb2, HIGH); + } + else{ + digitalWrite(inb2, LOW); + digitalWrite(ina2, HIGH); + } + + // write to hardware + _writeDutyCycle2PWM(duty_cycle1, duty_cycle2, pwm1, pwm2); +} \ No newline at end of file diff --git a/library_source/drivers/StepperDriver2PWM.h b/library_source/drivers/StepperDriver2PWM.h new file mode 100644 index 00000000..ef8797ee --- /dev/null +++ b/library_source/drivers/StepperDriver2PWM.h @@ -0,0 +1,59 @@ +#ifndef STEPPER_DRIVER_2PWM_h +#define STEPPER_DRIVER_2PWM_h + +#include "../common/base_classes/StepperDriver.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#include "../common/defaults.h" +#include "hardware_api.h" + +/** + 2 pwm stepper driver class +*/ +class StepperDriver2PWM: public StepperDriver +{ + public: + /** + StepperMotor class constructor + @param ph1PWM PWM1 phase pwm pin + @param ph1INA IN1A phase dir pin + @param ph1INB IN1B phase dir pin + @param ph2PWM PWM2 phase pwm pin + @param ph2INA IN2A phase dir pin + @param ph2INB IN2B phase dir pin + @param en1 enable pin phase 1 (optional input) + @param en2 enable pin phase 2 (optional input) + */ + StepperDriver2PWM(int ph1PWM,int ph1INA,int ph1INB,int ph2PWM,int ph2INA,int ph2INB, int en1 = NOT_SET, int en2 = NOT_SET); + + /** Motor hardware init function */ + int init() override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + // hardware variables + int pwm1; //!< phase 1 pwm pin number + int ina1; //!< phase 1 INA pin number + int inb1; //!< phase 1 INB pin number + int pwm2; //!< phase 2 pwm pin number + int ina2; //!< phase 2 INA pin number + int inb2; //!< phase 2 INB pin number + int enable_pin1; //!< enable pin number phase 1 + int enable_pin2; //!< enable pin number phase 2 + + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + */ + void setPwm(float Ua, float Ub) override; + + private: + +}; + + +#endif diff --git a/library_source/drivers/StepperDriver4PWM.cpp b/library_source/drivers/StepperDriver4PWM.cpp index e7eec6ff..28e2dcae 100644 --- a/library_source/drivers/StepperDriver4PWM.cpp +++ b/library_source/drivers/StepperDriver4PWM.cpp @@ -39,6 +39,8 @@ void StepperDriver4PWM::disable() // init hardware pins int StepperDriver4PWM::init() { + // a bit of separation + _delay(1000); // PWM pins pinMode(pwm1A, OUTPUT); @@ -62,18 +64,18 @@ int StepperDriver4PWM::init() { void StepperDriver4PWM::setPwm(float Ualpha, float Ubeta) { float duty_cycle1A(0.0),duty_cycle1B(0.0),duty_cycle2A(0.0),duty_cycle2B(0.0); // limit the voltage in driver - Ualpha = _constrain(Ualpha,-voltage_limit,voltage_limit); - Ubeta = _constrain(Ubeta,-voltage_limit,voltage_limit); + Ualpha = _constrain(Ualpha, -voltage_limit, voltage_limit); + Ubeta = _constrain(Ubeta, -voltage_limit, voltage_limit); // hardware specific writing if( Ualpha > 0 ) - duty_cycle1B = _constrain(abs(Ualpha)/voltage_power_supply,0,1); + duty_cycle1B = _constrain(abs(Ualpha)/voltage_power_supply,0.0,1.0); else - duty_cycle1A = _constrain(abs(Ualpha)/voltage_power_supply,0,1); + duty_cycle1A = _constrain(abs(Ualpha)/voltage_power_supply,0.0,1.0); if( Ubeta > 0 ) - duty_cycle2B = _constrain(abs(Ubeta)/voltage_power_supply,0,1); + duty_cycle2B = _constrain(abs(Ubeta)/voltage_power_supply,0.0,1.0); else - duty_cycle2A = _constrain(abs(Ubeta)/voltage_power_supply,0,1); + duty_cycle2A = _constrain(abs(Ubeta)/voltage_power_supply,0.0,1.0); // write to hardware _writeDutyCycle4PWM(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, pwm1A, pwm1B, pwm2A, pwm2B); } \ No newline at end of file diff --git a/library_source/drivers/hardware_api.h b/library_source/drivers/hardware_api.h index da5ddf51..01c03867 100644 --- a/library_source/drivers/hardware_api.h +++ b/library_source/drivers/hardware_api.h @@ -4,6 +4,17 @@ #include "../common/foc_utils.h" #include "../common/time_utils.h" +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + */ +void _configure2PWM(long pwm_frequency, const int pinA, const int pinB); + /** * Configuring PWM frequency, resolution and alignment * - BLDC driver - 3PWM setting @@ -47,6 +58,18 @@ void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const */ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l); +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + */ +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB); + /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) * - BLDC driver - 3PWM setting diff --git a/library_source/drivers/hardware_specific/atmega2560_mcu.cpp b/library_source/drivers/hardware_specific/atmega2560_mcu.cpp new file mode 100644 index 00000000..5236fb03 --- /dev/null +++ b/library_source/drivers/hardware_specific/atmega2560_mcu.cpp @@ -0,0 +1,158 @@ +#include "../hardware_api.h" + +#if defined(__AVR_ATmega2560__) + +// set pwm frequency to 32KHz +void _pinHighFrequency(const int pin){ + // High PWM frequency + // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 + // https://forum.arduino.cc/index.php?topic=72092.0 + if (pin == 13 || pin == 4 ) { + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 + } + else if (pin == 12 || pin == 11 ) + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 + else if (pin == 10 || pin == 9 ) + TCCR2B = ((TCCR2B & 0b11111000) | 0x01); // set prescaler to 1 + else if (pin == 5 || pin == 3 || pin == 2) + TCCR3B = ((TCCR2B & 0b11111000) | 0x01); // set prescaler to 1 + else if (pin == 8 || pin == 7 || pin == 6) + TCCR4B = ((TCCR4B & 0b11111000) | 0x01); // set prescaler to 1 + else if (pin == 44 || pin == 45 || pin == 46) + TCCR5B = ((TCCR5B & 0b11111000) | 0x01); // set prescaler to 1 + +} + + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 2PWM setting +// - hardware speciffic +void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); +} + +// function setting the high pwm frequency to the supplied pins +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); + _pinHighFrequency(pinC); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 2PWM setting +// - hardware speciffic +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); +} + +// function setting the pwm duty cycle to the hardware +// - BLDC motor - 3PWM setting +// - hardware speciffic +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); + analogWrite(pinC, 255.0*dc_c); +} + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pin1A); + _pinHighFrequency(pin1B); + _pinHighFrequency(pin2A); + _pinHighFrequency(pin2B); +} + +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 4PWM setting +// - hardware speciffic +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pin1A, 255.0*dc_1a); + analogWrite(pin1B, 255.0*dc_1b); + analogWrite(pin2A, 255.0*dc_2a); + analogWrite(pin2B, 255.0*dc_2b); +} + + +// function configuring pair of high-low side pwm channels, 32khz frequency and center aligned pwm +// supports Arudino/ATmega2560 +int _configureComplementaryPair(int pinH, int pinL) { + if( (pinH == 4 && pinL == 13 ) || (pinH == 13 && pinL == 4 ) ){ + // configure the pwm phase-corrected mode + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); + // configure complementary pwm on low side + if(pinH == 13 ) TCCR0A = 0b10110000 | (TCCR0A & 0b00001111) ; + else TCCR0A = 0b11100000 | (TCCR0A & 0b00001111) ; + // set prescaler to 1 - 32kHz freq + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); + }else if( (pinH == 11 && pinL == 12 ) || (pinH == 12 && pinL == 11 ) ){ + // set prescaler to 1 - 32kHz freq + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); + // configure complementary pwm on low side + if(pinH == 11 ) TCCR1A = 0b10110000 | (TCCR1A & 0b00001111) ; + else TCCR1A = 0b11100000 | (TCCR1A & 0b00001111) ; + }else if((pinH == 10 && pinL == 9 ) || (pinH == 9 && pinL == 10 ) ){ + // set prescaler to 1 - 32kHz freq + TCCR2B = ((TCCR2B & 0b11111000) | 0x01); + // configure complementary pwm on low side + if(pinH == 10 ) TCCR2A = 0b10110000 | (TCCR2A & 0b00001111) ; + else TCCR2A = 0b11100000 | (TCCR2A & 0b00001111) ; + }else{ + return -1; + } + return 0; +} + +// Configuring PWM frequency, resolution and alignment +// - BLDC driver - 6PWM setting +// - hardware specific +// supports Arudino/ATmega328 +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) { + // High PWM frequency + // - always max 32kHz + int ret_flag = 0; + ret_flag += _configureComplementaryPair(pinA_h, pinA_l); + ret_flag += _configureComplementaryPair(pinB_h, pinB_l); + ret_flag += _configureComplementaryPair(pinC_h, pinC_l); + return ret_flag; // returns -1 if not well configured +} + +// function setting the +void _setPwmPair(int pinH, int pinL, float val, int dead_time) +{ + int pwm_h = _constrain(val-dead_time/2,0,255); + int pwm_l = _constrain(val+dead_time/2,0,255); + + analogWrite(pinH, pwm_h); + if(pwm_l == 255 || pwm_l == 0) + digitalWrite(pinL, pwm_l ? LOW : HIGH); + else + analogWrite(pinL, pwm_l); +} + +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) +// - BLDC driver - 6PWM setting +// - hardware specific +// supports Arudino/ATmega328 +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ + _setPwmPair(pinA_h, pinA_l, dc_a*255.0, dead_zone*255.0); + _setPwmPair(pinB_h, pinB_l, dc_b*255.0, dead_zone*255.0); + _setPwmPair(pinC_h, pinC_l, dc_c*255.0, dead_zone*255.0); +} + +#endif \ No newline at end of file diff --git a/library_source/drivers/hardware_specific/atmega328_mcu.cpp b/library_source/drivers/hardware_specific/atmega328_mcu.cpp index 58b368f7..24fe563e 100644 --- a/library_source/drivers/hardware_specific/atmega328_mcu.cpp +++ b/library_source/drivers/hardware_specific/atmega328_mcu.cpp @@ -17,6 +17,18 @@ void _pinHighFrequency(const int pin){ } + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 2PWM setting +// - hardware speciffic +// supports Arudino/ATmega328 +void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); +} + // function setting the high pwm frequency to the supplied pins // - BLDC motor - 3PWM setting // - hardware speciffic @@ -29,6 +41,14 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int _pinHighFrequency(pinC); } +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 2PWM setting +// - hardware speciffic +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); +} // function setting the pwm duty cycle to the hardware // - BLDC motor - 3PWM setting diff --git a/library_source/drivers/hardware_specific/esp32_mcu.cpp b/library_source/drivers/hardware_specific/esp32_mcu.cpp index 3c07a445..983d4d54 100644 --- a/library_source/drivers/hardware_specific/esp32_mcu.cpp +++ b/library_source/drivers/hardware_specific/esp32_mcu.cpp @@ -10,6 +10,17 @@ #define _EMPTY_SLOT -20 #define _TAKEN_SLOT -21 +// ABI bus frequency - would be better to take it from somewhere +// but I did nto find a good exposed variable +#define _MCPWM_FREQ 160e6 + +// preferred pwm resolution default +#define _PWM_RES_DEF 2048 +// min resolution +#define _PWM_RES_MIN 1500 +// max resolution +#define _PWM_RES_MAX 3000 + // structure containing motor slot configuration // this library supports up to 4 motors typedef struct { @@ -31,7 +42,15 @@ typedef struct { mcpwm_io_signals_t mcpwm_1b; mcpwm_io_signals_t mcpwm_2a; mcpwm_io_signals_t mcpwm_2b; -} stepper_motor_slots_t; +} stepper_4pwm_motor_slots_t; +typedef struct { + int pin1pwm; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; +} stepper_2pwm_motor_slots_t; typedef struct { int pinAH; @@ -55,41 +74,87 @@ bldc_3pwm_motor_slots_t esp32_bldc_3pwm_motor_slots[4] = { {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B }; -// define stepper motor slots array -stepper_motor_slots_t esp32_stepper_motor_slots[2] = { - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 - }; - // define stepper motor slots array bldc_6pwm_motor_slots_t esp32_bldc_6pwm_motor_slots[2] = { {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0 {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0 }; +// define 4pwm stepper motor slots array +stepper_4pwm_motor_slots_t esp32_stepper_4pwm_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + }; + +// define 2pwm stepper motor slots array +stepper_2pwm_motor_slots_t esp32_stepper_2pwm_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B} // 4th motor will be MCPWM1 channel B + }; + // configuring high frequency pwm timer // a lot of help from this post from Paul Gauld // https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit, float dead_zone = NOT_SET){ mcpwm_config_t pwm_config; - pwm_config.frequency = pwm_frequency; //frequency pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings - + if (dead_zone != NOT_SET){ - // dead zone is configured in dead_time x 100 nanoseconds - float dead_time = (float)(1e7 / pwm_frequency) * dead_zone; - mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); - mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); - mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); + // dead zone is configured + float dead_time = (float)(_MCPWM_FREQ / (pwm_frequency)) * dead_zone; + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time/2.0, dead_time/2.0); + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time/2.0, dead_time/2.0); + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time/2.0, dead_time/2.0); } - _delay(100); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); + + // manual configuration due to the lack of config flexibility in mcpwm_init() + mcpwm_num->clk_cfg.prescale = 0; + // calculate prescaler and period + // step 1: calculate the prescaler using the default pwm resolution + // prescaler = bus_freq / (pwm_freq * default_pwm_res) - 1 + int prescaler = ceil((double)_MCPWM_FREQ / (double)_PWM_RES_DEF / 2.0 / (double)pwm_frequency) - 1; + // constrain prescaler + prescaler = _constrain(prescaler, 0, 128); + // now calculate the real resolution timer period necessary (pwm resolution) + // pwm_res = bus_freq / (pwm_freq * (prescaler + 1)) + int resolution_corrected = (double)_MCPWM_FREQ / 2.0 / (double)pwm_frequency / (double)(prescaler + 1); + // if pwm resolution too low lower the prescaler + if(resolution_corrected < _PWM_RES_MIN && prescaler > 0 ) + resolution_corrected = (double)_MCPWM_FREQ / 2.0 / (double)pwm_frequency / (double)(--prescaler + 1); + resolution_corrected = _constrain(resolution_corrected, _PWM_RES_MIN, _PWM_RES_MAX); + + // set prescaler + mcpwm_num->timer[0].period.prescale = prescaler; + mcpwm_num->timer[1].period.prescale = prescaler; + mcpwm_num->timer[2].period.prescale = prescaler; + _delay(1); + //set period + mcpwm_num->timer[0].period.period = resolution_corrected; + mcpwm_num->timer[1].period.period = resolution_corrected; + mcpwm_num->timer[2].period.period = resolution_corrected; + _delay(1); + mcpwm_num->timer[0].period.upmethod = 0; + mcpwm_num->timer[1].period.upmethod = 0; + mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + //restart the timers + mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); + _delay(1); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); @@ -99,6 +164,51 @@ void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm mcpwm_num->timer[0].sync.out_sel = 0; } +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 2PWM setting +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) { + + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 40kHz max - centered pwm has twice lower frequency + + stepper_2pwm_motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + int slot_num; + for(slot_num = 0; slot_num < 4; slot_num++){ + if(esp32_stepper_2pwm_motor_slots[slot_num].pin1pwm == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_2pwm_motor_slots[slot_num].pin1pwm = pinA; + m_slot = esp32_stepper_2pwm_motor_slots[slot_num]; + break; + } + } + + // disable all the slots with the same MCPWM + // disable 3pwm bldc motor which would go in the same slot + esp32_bldc_3pwm_motor_slots[slot_num].pinA = _TAKEN_SLOT; + if( slot_num < 2 ){ + // slot 0 of the 4pwm stepper + esp32_stepper_4pwm_motor_slots[0].pin1A = _TAKEN_SLOT; + // slot 0 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; + }else{ + // slot 1 of the stepper + esp32_stepper_4pwm_motor_slots[1].pin1A = _TAKEN_SLOT; + // slot 1 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; + } + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + +} + // function setting the high pwm frequency to the supplied pins // - BLDC motor - 3PWM setting @@ -106,8 +216,8 @@ void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm // supports Arudino/ATmega328, STM32 and ESP32 void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { - if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = _constrain(2*pwm_frequency, 0, 100000); // constrain to 50kHz max - centered pwm has twice lower frequency + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 40kHz max - centered pwm has twice lower frequency bldc_3pwm_motor_slots_t m_slot = {}; @@ -122,14 +232,16 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int } } // disable all the slots with the same MCPWM + // disable 2pwm steppr motor which would go in the same slot + esp32_stepper_2pwm_motor_slots[slot_num].pin1pwm = _TAKEN_SLOT; if( slot_num < 2 ){ - // slot 0 of the stepper - esp32_stepper_motor_slots[0].pin1A = _TAKEN_SLOT; + // slot 0 of the 4pwm stepper + esp32_stepper_4pwm_motor_slots[0].pin1A = _TAKEN_SLOT; // slot 0 of the 6pwm bldc esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; }else{ // slot 1 of the stepper - esp32_stepper_motor_slots[1].pin1A = _TAKEN_SLOT; + esp32_stepper_4pwm_motor_slots[1].pin1A = _TAKEN_SLOT; // slot 1 of the 6pwm bldc esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; } @@ -149,16 +261,16 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int // - hardware speciffic void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { - if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = _constrain(2*pwm_frequency, 0, 100000); // constrain to 50kHz max - centered pwm has twice lower frequency - stepper_motor_slots_t m_slot = {}; + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 50kHz max - centered pwm has twice lower frequency + stepper_4pwm_motor_slots_t m_slot = {}; // determine which motor are we connecting // and set the appropriate configuration parameters int slot_num; for(slot_num = 0; slot_num < 2; slot_num++){ - if(esp32_stepper_motor_slots[slot_num].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_stepper_motor_slots[slot_num].pin1A = pinA; - m_slot = esp32_stepper_motor_slots[slot_num]; + if(esp32_stepper_4pwm_motor_slots[slot_num].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_4pwm_motor_slots[slot_num].pin1A = pinA; + m_slot = esp32_stepper_4pwm_motor_slots[slot_num]; break; } } @@ -167,12 +279,18 @@ void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int // slots 0 and 1 of the 3pwm bldc esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT; esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT; + // slots 0 and 1 of the 2pwm stepper taken + esp32_stepper_2pwm_motor_slots[0].pin1pwm = _TAKEN_SLOT; + esp32_stepper_2pwm_motor_slots[1].pin1pwm = _TAKEN_SLOT; // slot 0 of the 6pwm bldc esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; }else{ // slots 2 and 3 of the 3pwm bldc esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT; esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT; + // slots 2 and 3 of the 2pwm stepper taken + esp32_stepper_2pwm_motor_slots[2].pin1pwm = _TAKEN_SLOT; + esp32_stepper_2pwm_motor_slots[3].pin1pwm = _TAKEN_SLOT; // slot 1 of the 6pwm bldc esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; } @@ -187,6 +305,23 @@ void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); } +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 2PWM setting +// - hardware speciffic +// ESP32 uses MCPWM +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){ + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_stepper_2pwm_motor_slots[i].pin1pwm == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,100] + mcpwm_set_duty(esp32_stepper_2pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_2pwm_motor_slots[i].mcpwm_operator, dc_a*100.0); + mcpwm_set_duty(esp32_stepper_2pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_2pwm_motor_slots[i].mcpwm_operator, dc_b*100.0); + break; + } + } +} + // function setting the pwm duty cycle to the hardware // - BLDC motor - 3PWM setting // - hardware speciffic @@ -212,13 +347,13 @@ void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ // determine which motor slot is the motor connected to for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + if(esp32_stepper_4pwm_motor_slots[i].pin1A == pin1A){ // if motor slot found // se the PWM on the slot timers // transform duty cycle from [0,1] to [0,100] - mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_motor_slots[i].mcpwm_operator1, dc_1a*100.0); - mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_motor_slots[i].mcpwm_operator1, dc_1b*100.0); - mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_motor_slots[i].mcpwm_operator2, dc_2a*100.0); - mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_motor_slots[i].mcpwm_operator2, dc_2b*100.0); + mcpwm_set_duty(esp32_stepper_4pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator1, dc_1a*100.0); + mcpwm_set_duty(esp32_stepper_4pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator1, dc_1b*100.0); + mcpwm_set_duty(esp32_stepper_4pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator2, dc_2a*100.0); + mcpwm_set_duty(esp32_stepper_4pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator2, dc_2b*100.0); break; } } @@ -229,8 +364,8 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in // - hardware specific int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ - if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = _constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 40kHz max - centered pwm has twice lower frequency bldc_6pwm_motor_slots_t m_slot = {}; // determine which motor are we connecting // and set the appropriate configuration parameters @@ -251,13 +386,13 @@ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT; esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT; // slot 0 of the 6pwm bldc - esp32_stepper_motor_slots[0].pin1A = _TAKEN_SLOT; + esp32_stepper_4pwm_motor_slots[0].pin1A = _TAKEN_SLOT; }else{ // slots 2 and 3 of the 3pwm bldc esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT; esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT; // slot 1 of the 6pwm bldc - esp32_stepper_motor_slots[1].pin1A = _TAKEN_SLOT; + esp32_stepper_4pwm_motor_slots[1].pin1A = _TAKEN_SLOT; } // configure pins diff --git a/library_source/drivers/hardware_specific/generic_mcu.cpp b/library_source/drivers/hardware_specific/generic_mcu.cpp index dc322746..b3641114 100644 --- a/library_source/drivers/hardware_specific/generic_mcu.cpp +++ b/library_source/drivers/hardware_specific/generic_mcu.cpp @@ -2,6 +2,8 @@ #if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if mcu is not atmega328 +#elif defined(__AVR_ATmega2560__) // if mcu is not atmega2560 + #elif defined(__arm__) && defined(CORE_TEENSY) // or teensy #elif defined(ESP_H) // or esp32 @@ -10,6 +12,14 @@ #else +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 2PWM setting +// - hardware speciffic +// in generic case dont do anything +void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) { + return; +} + // function setting the high pwm frequency to the supplied pins // - BLDC motor - 3PWM setting // - hardware speciffic @@ -35,6 +45,15 @@ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const } +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 2PWM setting +// - hardware speciffic +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); +} + // function setting the pwm duty cycle to the hardware // - BLDC motor - 3PWM setting // - hardware speciffic diff --git a/library_source/drivers/hardware_specific/stm32_mcu.cpp b/library_source/drivers/hardware_specific/stm32_mcu.cpp index 85d0bd65..0dc83cf7 100644 --- a/library_source/drivers/hardware_specific/stm32_mcu.cpp +++ b/library_source/drivers/hardware_specific/stm32_mcu.cpp @@ -5,7 +5,8 @@ #define _PWM_RESOLUTION 12 // 12bit #define _PWM_RANGE 4095.0// 2^12 -1 = 4095 -#define _PWM_FREQUENCY 50000 // 50khz +#define _PWM_FREQUENCY 25000 // 25khz +#define _PWM_FREQUENCY_MAX 50000 // 50khz #define _HARDWARE_6PWM 1 @@ -184,12 +185,31 @@ int _interfaceType(const int pinA_h, const int pinA_l, const int pinB_h, const +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 2PWM setting +// - hardware speciffic +void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) { + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max + // center-aligned frequency is uses two periods + pwm_frequency *=2; + + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); + HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); + // allign the timers + _alignPWMTimers(HT1, HT2, HT2); +} + + // function setting the high pwm frequency to the supplied pins // - BLDC motor - 3PWM setting // - hardware speciffic void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { - if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max + // center-aligned frequency is uses two periods + pwm_frequency *=2; + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); @@ -201,8 +221,11 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int // - Stepper motor - 4PWM setting // - hardware speciffic void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { - if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max + // center-aligned frequency is uses two periods + pwm_frequency *=2; + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); @@ -211,6 +234,15 @@ void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int _alignPWMTimers(HT1, HT2, HT3, HT4); } +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 2PWM setting +//- hardware speciffic +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){ + // transform duty cycle from [0,1] to [0,4095] + _setPwm(pinA, _PWM_RANGE*dc_a, _PWM_RESOLUTION); + _setPwm(pinB, _PWM_RANGE*dc_b, _PWM_RESOLUTION); +} + // function setting the pwm duty cycle to the hardware // - BLDC motor - 3PWM setting //- hardware speciffic @@ -221,6 +253,7 @@ void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB _setPwm(pinC, _PWM_RANGE*dc_c, _PWM_RESOLUTION); } + // function setting the pwm duty cycle to the hardware // - Stepper motor - 4PWM setting //- hardware speciffic @@ -239,8 +272,10 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in // - BLDC driver - 6PWM setting // - hardware specific int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ - if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, 100000); // constrain to 100kHz max + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to |%0kHz max + // center-aligned frequency is uses two periods + pwm_frequency *=2; // find configuration int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); diff --git a/library_source/sensors/HallSensor.cpp b/library_source/sensors/HallSensor.cpp index 47dc53d0..2c33a41e 100644 --- a/library_source/sensors/HallSensor.cpp +++ b/library_source/sensors/HallSensor.cpp @@ -45,6 +45,7 @@ void HallSensor::updateState() { long new_pulse_timestamp = _micros(); hall_state = C_active + (B_active << 1) + (A_active << 2); int8_t new_electric_sector = ELECTRIC_SECTORS[hall_state]; + static Direction old_direction; if (new_electric_sector - electric_sector > 3) { //underflow direction = static_cast(natural_direction * -1); @@ -57,9 +58,16 @@ void HallSensor::updateState() { direction = (new_electric_sector > electric_sector)? static_cast(natural_direction) : static_cast(natural_direction * (-1)); } electric_sector = new_electric_sector; - pulse_diff = new_pulse_timestamp - pulse_timestamp; + if (direction == old_direction) { + // not oscilating or just changed direction + pulse_diff = new_pulse_timestamp - pulse_timestamp; + } else { + pulse_diff = 0; + } + pulse_timestamp = new_pulse_timestamp; total_interrupts++; + old_direction = direction; if (onSectorChange != nullptr) onSectorChange(electric_sector); } @@ -86,8 +94,7 @@ float HallSensor::getAngle() { function using mixed time and frequency measurement technique */ float HallSensor::getVelocity(){ - - if (pulse_diff == 0 || ((_micros() - pulse_timestamp) > STALE_HALL_DATA_MICROS) ) { // last velocity isn't accurate if too old + if (pulse_diff == 0 || ((_micros() - pulse_timestamp) > pulse_diff) ) { // last velocity isn't accurate if too old return 0; } else { return direction * (_2PI / cpr) / (pulse_diff / 1000000.0); diff --git a/library_source/sensors/HallSensor.h b/library_source/sensors/HallSensor.h index 0eb42286..ad5673e3 100644 --- a/library_source/sensors/HallSensor.h +++ b/library_source/sensors/HallSensor.h @@ -6,10 +6,6 @@ #include "../common/foc_utils.h" #include "../common/time_utils.h" -#ifndef STALE_HALL_DATA_MICROS - #define STALE_HALL_DATA_MICROS 500000 -#endif - // seq 1 > 5 > 4 > 6 > 2 > 3 > 1 000 001 010 011 100 101 110 111 const int8_t ELECTRIC_SECTORS[8] = { -1, 0, 4, 5, 2, 1, 3 , -1 }; diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.cpp deleted file mode 100644 index 0d080bab..00000000 --- a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.cpp +++ /dev/null @@ -1,284 +0,0 @@ -#include "hardware_utils.h" - -#if defined(ESP_H) // if ESP32 board -// empty motor slot -#define _EMPTY_SLOT -20 - -// structure containing motor slot configuration -// this library supports up to 4 motors -typedef struct { - int pinA; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator; - mcpwm_io_signals_t mcpwm_a; - mcpwm_io_signals_t mcpwm_b; - mcpwm_io_signals_t mcpwm_c; -} bldc_motor_slots_t; -typedef struct { - int pin1A; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator1; - mcpwm_operator_t mcpwm_operator2; - mcpwm_io_signals_t mcpwm_1a; - mcpwm_io_signals_t mcpwm_1b; - mcpwm_io_signals_t mcpwm_2a; - mcpwm_io_signals_t mcpwm_2b; -} stepper_motor_slots_t; - -// define bldc motor slots array -bldc_motor_slots_t esp32_bldc_motor_slots[4] = { - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B - }; - -// define stepper motor slots array -stepper_motor_slots_t esp32_stepper_motor_slots[2] = { - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 - }; - -// configuring high frequency pwm timer -// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller -void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ - - mcpwm_config_t pwm_config; - pwm_config.frequency = pwm_frequency; //frequency - pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% - pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% - pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) - pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH - mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings - - _delay(100); - - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); - mcpwm_num->clk_cfg.prescale = 0; - - mcpwm_num->timer[0].period.prescale = 4; - mcpwm_num->timer[1].period.prescale = 4; - mcpwm_num->timer[2].period.prescale = 4; - _delay(1); - mcpwm_num->timer[0].period.period = 2048; - mcpwm_num->timer[1].period.period = 2048; - mcpwm_num->timer[2].period.period = 2048; - _delay(1); - mcpwm_num->timer[0].period.upmethod = 0; - mcpwm_num->timer[1].period.upmethod = 0; - mcpwm_num->timer[2].period.upmethod = 0; - _delay(1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); - - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 1; - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 0; -} - -#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips -// set pwm frequency to 32KHz -void _pinHighFrequency(const int pin){ - // High PWM frequency - // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pin == 5 || pin == 6 ) { - TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode - TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - } - if (pin == 9 || pin == 10 ) - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pin == 3 || pin == 11) - TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 - -} -#elif defined(_STM32_DEF_) // if stm chips -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); - analogWriteResolution(12); // resolution 12 bit 0 - 4096 -} -#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); -} -#endif - - -// function setting the high pwm frequency to the supplied pins -// - hardware speciffic -// supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips - // High PWM frequency - // - always max 32kHz - _pinHighFrequency(pinA); - _pinHighFrequency(pinB); - _pinHighFrequency(pinC); - if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor - -#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards - if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz - else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max - _setHighFrequency(pwm_frequency, pinA); - _setHighFrequency(pwm_frequency, pinB); - _setHighFrequency(pwm_frequency, pinC); - if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor - -#elif defined(ESP_H) // if esp32 boards - if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency - - if(pinD == NOT_SET){ - bldc_motor_slots_t m_slot = {}; - - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_bldc_motor_slots[i].pinA = pinA; - m_slot = esp32_bldc_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - - }else{ - stepper_motor_slots_t m_slot = {}; - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_stepper_motor_slots[i].pin1A = pinA; - m_slot = esp32_stepper_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - } -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pinA, 4095.0*dc_a); - analogWrite(pinB, 4095.0*dc_b); - analogWrite(pinC, 4095.0*dc_c); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255*dc_a); - analogWrite(pinB, 255*dc_b); - analogWrite(pinC, 255*dc_c); -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pin1A, 4095.0*dc_1a); - analogWrite(pin1B, 4095.0*dc_1b); - analogWrite(pin2A, 4095.0*dc_2a); - analogWrite(pin2B, 4095.0*dc_2b); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255*dc_1a); - analogWrite(pin1B, 255*dc_1b); - analogWrite(pin2A, 255*dc_2a); - analogWrite(pin2B, 255*dc_2b); -#endif -} - - -// function buffering delay() -// arduino uno function doesn't work well with interrupts -void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) - // if arduino uno and other atmega328p chips - // use while instad of delay, - // due to wrong measurement based on changed timer0 - unsigned long t = _micros() + ms*1000; - while( _micros() < t ){}; -#else - // regular micros - delay(ms); -#endif -} - - -// function buffering _micros() -// arduino function doesn't work well with interrupts -unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) -// if arduino uno and other atmega328p chips - //return the value based on the prescaler - if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); - else return (micros()); -#else - // regular micros - return micros(); -#endif -} diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.h b/minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.h deleted file mode 100644 index f99c260a..00000000 --- a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/hardware_utils.h +++ /dev/null @@ -1,72 +0,0 @@ -#ifndef HARDWARE_UTILS_H -#define HARDWARE_UTILS_H - -#include "Arduino.h" -#include "foc_utils.h" - - -#if defined(ESP_H) // if esp32 boards - -#include "driver/mcpwm.h" -#include "soc/mcpwm_reg.h" -#include "soc/mcpwm_struct.h" - -#endif - -/** - * High PWM frequency setting function - * - hardware specific - * - * @param pwm_frequency - frequency in hertz - if applicable - * @param pinA pinA bldc motor or pin1A stepper motor - * @param pinB pinB bldc motor or pin1B stepper motor - * @param pinC pinC bldc motor or pin2A stepper motor - * @param pinD pin2B stepper motor - */ -void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_a duty cycle phase A [0, 1] - * @param dc_b duty cycle phase B [0, 1] - * @param dc_c duty cycle phase C [0, 1] - * @param pinA phase A hardware pin number - * @param pinB phase B hardware pin number - * @param pinC phase C hardware pin number - */ -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_1a duty cycle phase 1A [0, 1] - * @param dc_1b duty cycle phase 1B [0, 1] - * @param dc_2a duty cycle phase 2A [0, 1] - * @param dc_2b duty cycle phase 2B [0, 1] - * @param pin1A phase 1A hardware pin number - * @param pin1B phase 1B hardware pin number - * @param pin2A phase 2A hardware pin number - * @param pin2B phase 2B hardware pin number - */ -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); - -/** - * Function implementing delay() function in milliseconds - * - blocking function - * - hardware specific - - * @param ms number of milliseconds to wait - */ -void _delay(unsigned long ms); - -/** - * Function implementing timestamp getting function in microseconds - * hardware specific - */ -unsigned long _micros(); - - -#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/MagneticSensorI2C.cpp b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/MagneticSensorI2C.cpp deleted file mode 100644 index a02b762b..00000000 --- a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/MagneticSensorI2C.cpp +++ /dev/null @@ -1,207 +0,0 @@ -#include "MagneticSensorI2C.h" - -/** Typical configuration for the 12bit AMS AS5600 magnetic sensor over I2C interface */ -MagneticSensorI2CConfig_s AS5600_I2C = { - .chip_address = 0x36, - .clock_speed = 1000000, - .bit_resolution = 12, - .angle_register = 0x0E, - .data_start_bit = 11 -}; - -/** Typical configuration for the 12bit AMS AS5048 magnetic sensor over I2C interface */ -MagneticSensorI2CConfig_s AS5048_I2C = { - .chip_address = 0x40, // highly configurable. if A1 and A2 are held low, this is probable value - .clock_speed = 1000000, - .bit_resolution = 14, - .angle_register = 0xFE, - .data_start_bit = 15 -}; - - -// MagneticSensorI2C(uint8_t _chip_address, float _cpr, uint8_t _angle_register_msb) -// @param _chip_address I2C chip address -// @param _bit_resolution bit resolution of the sensor -// @param _angle_register_msb angle read register -// @param _bits_used_msb number of used bits in msb -MagneticSensorI2C::MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _bits_used_msb){ - // chip I2C address - chip_address = _chip_address; - // angle read register of the magnetic sensor - angle_register_msb = _angle_register_msb; - // register maximum value (counts per revolution) - cpr = pow(2, _bit_resolution); - - // depending on the sensor architecture there are different combinations of - // LSB and MSB register used bits - // AS5600 uses 0..7 LSB and 8..11 MSB - // AS5048 uses 0..5 LSB and 6..13 MSB - // used bits in LSB - lsb_used = _bit_resolution - _bits_used_msb; - // extraction masks - lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); - msb_mask = (uint8_t)( (2 << _bits_used_msb) - 1 ); - clock_speed = 400000; - sda_pin = SDA; - scl_pin = SCL; - -} - -MagneticSensorI2C::MagneticSensorI2C(MagneticSensorI2CConfig_s config){ - chip_address = config.chip_address; - - // angle read register of the magnetic sensor - angle_register_msb = config.angle_register; - // register maximum value (counts per revolution) - cpr = pow(2, config.bit_resolution); - - int bits_used_msb = config.data_start_bit - 7; - lsb_used = config.bit_resolution - bits_used_msb; - // extraction masks - lsb_mask = (uint8_t)( (2 << lsb_used) - 1 ); - msb_mask = (uint8_t)( (2 << bits_used_msb) - 1 ); - clock_speed = 400000; - sda_pin = SDA; - scl_pin = SCL; - -} - -void MagneticSensorI2C::init(){ - -#if defined(_STM32_DEF_) // if stm chips - // I2C communication begin - Wire.begin(); - Wire.setClock(clock_speed); - Wire.setSCL(scl_pin); - Wire.setSDA(sda_pin); -#elif defined(ESP_H) // if esp32 - //I2C communication begin - Wire.begin(sda_pin, scl_pin, clock_speed); -#else - // I2C communication begin - Wire.begin(); - Wire.setClock(clock_speed); -#endif - - // velocity calculation init - angle_prev = 0; - velocity_calc_timestamp = _micros(); - - // full rotations tracking number - full_rotation_offset = 0; - angle_data_prev = getRawCount(); - zero_offset = 0; -} - -// Shaft angle calculation -// angle is in radians [rad] -float MagneticSensorI2C::getAngle(){ - // raw data from the sensor - float angle_data = getRawCount(); - - // tracking the number of rotations - // in order to expand angle range form [0,2PI] - // to basically infinity - float d_angle = angle_data - angle_data_prev; - // if overflow happened track it as full rotation - if(abs(d_angle) > (0.8*cpr) ) full_rotation_offset += d_angle > 0 ? -_2PI : _2PI; - // save the current angle value for the next steps - // in order to know if overflow happened - angle_data_prev = angle_data; - - // zero offset adding - angle_data -= (int)zero_offset; - // return the full angle - // (number of full rotations)*2PI + current sensor angle - return natural_direction * (full_rotation_offset + ( angle_data / (float)cpr) * _2PI); -} - -// Shaft velocity calculation -float MagneticSensorI2C::getVelocity(){ - // calculate sample time - unsigned long now_us = _micros(); - float Ts = (now_us - velocity_calc_timestamp)*1e-6; - // quick fix for strange cases (micros overflow) - if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; - - // current angle - float angle_c = getAngle(); - // velocity calculation - float vel = (angle_c - angle_prev)/Ts; - - // save variables for future pass - angle_prev = angle_c; - velocity_calc_timestamp = now_us; - return vel; -} - -// set current angle as zero angle -// return the angle [rad] difference -float MagneticSensorI2C::initRelativeZero(){ - float angle_offset = -getAngle(); - zero_offset = natural_direction * getRawCount(); - - // angle tracking variables - full_rotation_offset = 0; - return angle_offset; -} -// set absolute zero angle as zero angle -// return the angle [rad] difference -float MagneticSensorI2C::initAbsoluteZero(){ - float rotation = -(int)zero_offset; - // init absolute zero - zero_offset = 0; - - // angle tracking variables - full_rotation_offset = 0; - // return offset in radians - return rotation / (float)cpr * _2PI; -} -// returns 0 if it has no absolute 0 measurement -// 0 - incremental encoder without index -// 1 - encoder with index & magnetic sensors -int MagneticSensorI2C::hasAbsoluteZero(){ - return 1; -} -// returns 0 if it does need search for absolute zero -// 0 - magnetic sensor -// 1 - ecoder with index -int MagneticSensorI2C::needsAbsoluteZeroSearch(){ - return 0; -} - - -// function reading the raw counter of the magnetic sensor -int MagneticSensorI2C::getRawCount(){ - return (int)MagneticSensorI2C::read(angle_register_msb); -} - -// I2C functions -/* -* Read a register from the sensor -* Takes the address of the register as a uint8_t -* Returns the value of the register -*/ -int MagneticSensorI2C::read(uint8_t angle_reg_msb) { - // read the angle register first MSB then LSB - byte readArray[2]; - uint16_t readValue = 0; - // notify the device that is aboout to be read - Wire.beginTransmission(chip_address); - Wire.write(angle_reg_msb); - Wire.endTransmission(false); - - // read the data msb and lsb - Wire.requestFrom(chip_address, (uint8_t)2); - for (byte i=0; i < 2; i++) { - readArray[i] = Wire.read(); - } - - // depending on the sensor architecture there are different combinations of - // LSB and MSB register used bits - // AS5600 uses 0..7 LSB and 8..11 MSB - // AS5048 uses 0..5 LSB and 6..13 MSB - readValue = ( readArray[1] & lsb_mask ); - readValue += ( ( readArray[0] & msb_mask ) << lsb_used ); - return readValue; -} diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/MagneticSensorI2C.h b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/MagneticSensorI2C.h deleted file mode 100644 index 88d74d35..00000000 --- a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/MagneticSensorI2C.h +++ /dev/null @@ -1,104 +0,0 @@ -#ifndef MAGNETICSENSORI2C_LIB_H -#define MAGNETICSENSORI2C_LIB_H - -#include "Arduino.h" -#include -#include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" - -struct MagneticSensorI2CConfig_s { - int chip_address; - long clock_speed; - int bit_resolution; - int angle_register; - int data_start_bit; -}; -// some predefined structures -extern MagneticSensorI2CConfig_s AS5600_I2C,AS5048_I2C; - -class MagneticSensorI2C: public Sensor{ - public: - /** - * MagneticSensorI2C class constructor - * @param chip_address I2C chip address - * @param bits number of bits of the sensor resolution - * @param angle_register_msb angle read register msb - * @param _bits_used_msb number of used bits in msb - */ - MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _msb_bits_used); - - /** - * MagneticSensorI2C class constructor - * @param config I2C config - */ - MagneticSensorI2C(MagneticSensorI2CConfig_s config); - - static MagneticSensorI2C AS5600(); - - /** sensor initialise pins */ - void init(); - - // implementation of abstract functions of the Sensor class - /** get current angle (rad) */ - float getAngle() override; - /** get current angular velocity (rad/s) **/ - float getVelocity() override; - /** - * set current angle as zero angle - * return the angle [rad] difference - */ - float initRelativeZero() override; - /** - * set absolute zero angle as zero angle - * return the angle [rad] difference - */ - float initAbsoluteZero() override; - /** returns 1 because it is the absolute sensor */ - int hasAbsoluteZero() override; - /** returns 0 maning it doesn't need search for absolute zero */ - - int needsAbsoluteZeroSearch() override; - - /* the speed of the i2c clock signal */ - long clock_speed; - - /* the pin used for i2c data */ - int sda_pin; - - /* the pin used for i2c clock */ - int scl_pin; - - private: - float cpr; //!< Maximum range of the magnetic sensor - uint16_t lsb_used; //!< Number of bits used in LSB register - uint8_t lsb_mask; - uint8_t msb_mask; - - // I2C variables - uint8_t angle_register_msb; //!< I2C angle register to read - uint8_t chip_address; //!< I2C chip select pins - - // I2C functions - /** Read one I2C register value */ - int read(uint8_t angle_register_msb); - - word zero_offset; //!< user defined zero offset - /** - * Function getting current angle register value - * it uses angle_register variable - */ - int getRawCount(); - - // total angle tracking variables - float full_rotation_offset; //!println("MOT: Init pins."); - // PWM pins - pinMode(pwm1A, OUTPUT); - pinMode(pwm1B, OUTPUT); - pinMode(pwm2A, OUTPUT); - pinMode(pwm2B, OUTPUT); - if ( enable_pin1 != NOT_SET ) pinMode(enable_pin1, OUTPUT); - if ( enable_pin2 != NOT_SET ) pinMode(enable_pin2, OUTPUT); - - if(monitor_port) monitor_port->println("MOT: PWM config."); - // Increase PWM frequency - // make silent - _setPwmFrequency(pwm_frequency, pwm1A, pwm1B, pwm2A, pwm2B); - - // sanity check for the voltage limit configuration - if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; - // constrain voltage for sensor alignment - if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; - - // update the controller limits - PID_velocity.limit = voltage_limit; - P_angle.limit = velocity_limit; - - _delay(500); - // enable motor - if(monitor_port) monitor_port->println("MOT: Enable."); - enable(); - _delay(500); - -} - - -// disable motor driver -void StepperMotor::disable() -{ - // disable the driver - if enable_pin pin available - if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, LOW); - if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, LOW); - // set zero to PWM - setPwm(0, 0); -} -// enable motor driver -void StepperMotor::enable() -{ - // set zero to PWM - setPwm(0, 0); - // enable_pin the driver - if enable_pin pin available - if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, HIGH); - if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, HIGH); - -} - - -/** - FOC functions -*/ -// FOC initialization function -int StepperMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { - int exit_flag = 1; - // align motor if necessary - // alignment necessary for encoders! - if(zero_electric_offset != NOT_SET){ - // abosolute zero offset provided - no need to align - zero_electric_angle = zero_electric_offset; - // set the sensor direction - default CW - sensor->natural_direction = sensor_direction; - }else{ - // sensor and motor alignment - _delay(500); - exit_flag = alignSensor(); - _delay(500); - } - if(monitor_port) monitor_port->println("MOT: Motor ready."); - - return exit_flag; -} -// Encoder alignment to electrical 0 angle -int StepperMotor::alignSensor() { - if(monitor_port) monitor_port->println("MOT: Align sensor."); - // align the electrical phases of the motor and sensor - // set angle -90 degrees - - float start_angle = shaftAngle(); - for (int i = 0; i <=5; i++ ) { - float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); - _delay(200); - } - float mid_angle = shaftAngle(); - for (int i = 5; i >=0; i-- ) { - float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); - _delay(200); - } - if (mid_angle < start_angle) { - if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); - sensor->natural_direction = Direction::CCW; - } else if (mid_angle == start_angle) { - if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); - } - - // let the motor stabilize for 2 sec - _delay(2000); - // set sensor to zero - sensor->initRelativeZero(); - _delay(500); - setPhaseVoltage(0,0); - _delay(200); - - // find the index if available - int exit_flag = absoluteZeroAlign(); - _delay(500); - if(monitor_port){ - if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); - if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); - else monitor_port->println("MOT: Not available!"); - } - return exit_flag; -} - - -// Encoder alignment the absolute zero angle -// - to the index -int StepperMotor::absoluteZeroAlign() { - - if(monitor_port) monitor_port->println("MOT: Absolute zero align."); - // if no absolute zero return - if(!sensor->hasAbsoluteZero()) return 0; - - - if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); - // search the absolute zero with small velocity - while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ - loopFOC(); - voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); - } - voltage_q = 0; - // disable motor - setPhaseVoltage(0,0); - - // align absolute zero if it has been found - if(!sensor->needsAbsoluteZeroSearch()){ - // align the sensor with the absolute zero - float zero_offset = sensor->initAbsoluteZero(); - // remember zero electric angle - zero_electric_angle = _normalizeAngle(_electricalAngle(zero_offset, pole_pairs)); - } - // return bool if zero found - return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; -} - -// Iterative function looping FOC algorithm, setting Uq on the Motor -// The faster it can be run the better -void StepperMotor::loopFOC() { - // shaft angle - shaft_angle = shaftAngle(); - // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); -} - -// Iterative function running outer loop of the FOC algorithm -// Behavior of this function is determined by the motor.controller variable -// It runs either angle, velocity or voltage loop -// - needs to be called iteratively it is asynchronous function -// - if target is not set it uses motor.target value -void StepperMotor::move(float new_target) { - // set internal target variable - if( new_target != NOT_SET ) target = new_target; - // get angular velocity - shaft_velocity = shaftVelocity(); - // choose control loop - switch (controller) { - case ControlType::voltage: - voltage_q = target; - break; - case ControlType::angle: - // angle set point - // include angle loop - shaft_angle_sp = target; - shaft_velocity_sp = P_angle( shaft_angle_sp - shaft_angle ); - voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); - break; - case ControlType::velocity: - // velocity set point - // include velocity loop - shaft_velocity_sp = target; - voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); - break; - case ControlType::velocity_openloop: - // velocity control in open loop - // loopFOC should not be called - shaft_velocity_sp = target; - velocityOpenloop(shaft_velocity_sp); - break; - case ControlType::angle_openloop: - // angle control in open loop - // loopFOC should not be called - shaft_angle_sp = target; - angleOpenloop(shaft_angle_sp); - break; - } -} - - -// Method using FOC to set Uq to the motor at the optimal angle -// Function implementingSine PWM algorithms -// - space vector not implemented yet -// -// Function using sine approximation -// regular sin + cos ~300us (no memory usaage) -// approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void StepperMotor::setPhaseVoltage(float Uq, float angle_el) { - // Sinusoidal PWM modulation - // Inverse Park transformation - - // angle normalization in between 0 and 2pi - // only necessary if using _sin and _cos - approximation functions - angle_el = _normalizeAngle(angle_el + zero_electric_angle); - // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; - // set the voltages in hardware - setPwm(Ualpha,Ubeta); -} - - - -// Set voltage to the pwm pin -void StepperMotor::setPwm(float Ualpha, float Ubeta) { - float duty_cycle1A(0.0),duty_cycle1B(0.0),duty_cycle2A(0.0),duty_cycle2B(0.0); - // hardware specific writing - if( Ualpha > 0 ) - duty_cycle1B = constrain(abs(Ualpha)/voltage_power_supply,0,1); - else - duty_cycle1A = constrain(abs(Ualpha)/voltage_power_supply,0,1); - - if( Ubeta > 0 ) - duty_cycle2B = constrain(abs(Ubeta)/voltage_power_supply,0,1); - else - duty_cycle2A = constrain(abs(Ubeta)/voltage_power_supply,0,1); - // write to hardware - _writeDutyCycle(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, pwm1A, pwm1B, pwm2A, pwm2B); -} - -// Function (iterative) generating open loop movement for target velocity -// - target_velocity - rad/s -// it uses voltage_limit variable -void StepperMotor::velocityOpenloop(float target_velocity){ - // get current timestamp - unsigned long now_us = _micros(); - // calculate the sample time from last call - float Ts = (now_us - open_loop_timestamp) * 1e-6; - - // calculate the necessary angle to achieve target velocity - shaft_angle += target_velocity*Ts; - - // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle,pole_pairs)); - - // save timestamp for next call - open_loop_timestamp = now_us; -} - -// Function (iterative) generating open loop movement towards the target angle -// - target_angle - rad -// it uses voltage_limit and velocity_limit variables -void StepperMotor::angleOpenloop(float target_angle){ - // get current timestamp - unsigned long now_us = _micros(); - // calculate the sample time from last call - float Ts = (now_us - open_loop_timestamp) * 1e-6; - - // calculate the necessary angle to move from current position towards target angle - // with maximal velocity (velocity_limit) - if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) - shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; - else - shaft_angle = target_angle; - - // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle,pole_pairs)); - - // save timestamp for next call - open_loop_timestamp = now_us; -} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.cpp deleted file mode 100644 index 0d080bab..00000000 --- a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.cpp +++ /dev/null @@ -1,284 +0,0 @@ -#include "hardware_utils.h" - -#if defined(ESP_H) // if ESP32 board -// empty motor slot -#define _EMPTY_SLOT -20 - -// structure containing motor slot configuration -// this library supports up to 4 motors -typedef struct { - int pinA; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator; - mcpwm_io_signals_t mcpwm_a; - mcpwm_io_signals_t mcpwm_b; - mcpwm_io_signals_t mcpwm_c; -} bldc_motor_slots_t; -typedef struct { - int pin1A; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator1; - mcpwm_operator_t mcpwm_operator2; - mcpwm_io_signals_t mcpwm_1a; - mcpwm_io_signals_t mcpwm_1b; - mcpwm_io_signals_t mcpwm_2a; - mcpwm_io_signals_t mcpwm_2b; -} stepper_motor_slots_t; - -// define bldc motor slots array -bldc_motor_slots_t esp32_bldc_motor_slots[4] = { - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B - }; - -// define stepper motor slots array -stepper_motor_slots_t esp32_stepper_motor_slots[2] = { - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 - }; - -// configuring high frequency pwm timer -// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller -void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ - - mcpwm_config_t pwm_config; - pwm_config.frequency = pwm_frequency; //frequency - pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% - pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% - pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) - pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH - mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings - - _delay(100); - - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); - mcpwm_num->clk_cfg.prescale = 0; - - mcpwm_num->timer[0].period.prescale = 4; - mcpwm_num->timer[1].period.prescale = 4; - mcpwm_num->timer[2].period.prescale = 4; - _delay(1); - mcpwm_num->timer[0].period.period = 2048; - mcpwm_num->timer[1].period.period = 2048; - mcpwm_num->timer[2].period.period = 2048; - _delay(1); - mcpwm_num->timer[0].period.upmethod = 0; - mcpwm_num->timer[1].period.upmethod = 0; - mcpwm_num->timer[2].period.upmethod = 0; - _delay(1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); - - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 1; - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 0; -} - -#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips -// set pwm frequency to 32KHz -void _pinHighFrequency(const int pin){ - // High PWM frequency - // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pin == 5 || pin == 6 ) { - TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode - TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - } - if (pin == 9 || pin == 10 ) - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pin == 3 || pin == 11) - TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 - -} -#elif defined(_STM32_DEF_) // if stm chips -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); - analogWriteResolution(12); // resolution 12 bit 0 - 4096 -} -#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); -} -#endif - - -// function setting the high pwm frequency to the supplied pins -// - hardware speciffic -// supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips - // High PWM frequency - // - always max 32kHz - _pinHighFrequency(pinA); - _pinHighFrequency(pinB); - _pinHighFrequency(pinC); - if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor - -#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards - if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz - else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max - _setHighFrequency(pwm_frequency, pinA); - _setHighFrequency(pwm_frequency, pinB); - _setHighFrequency(pwm_frequency, pinC); - if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor - -#elif defined(ESP_H) // if esp32 boards - if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency - - if(pinD == NOT_SET){ - bldc_motor_slots_t m_slot = {}; - - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_bldc_motor_slots[i].pinA = pinA; - m_slot = esp32_bldc_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - - }else{ - stepper_motor_slots_t m_slot = {}; - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_stepper_motor_slots[i].pin1A = pinA; - m_slot = esp32_stepper_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - } -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pinA, 4095.0*dc_a); - analogWrite(pinB, 4095.0*dc_b); - analogWrite(pinC, 4095.0*dc_c); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255*dc_a); - analogWrite(pinB, 255*dc_b); - analogWrite(pinC, 255*dc_c); -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pin1A, 4095.0*dc_1a); - analogWrite(pin1B, 4095.0*dc_1b); - analogWrite(pin2A, 4095.0*dc_2a); - analogWrite(pin2B, 4095.0*dc_2b); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255*dc_1a); - analogWrite(pin1B, 255*dc_1b); - analogWrite(pin2A, 255*dc_2a); - analogWrite(pin2B, 255*dc_2b); -#endif -} - - -// function buffering delay() -// arduino uno function doesn't work well with interrupts -void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) - // if arduino uno and other atmega328p chips - // use while instad of delay, - // due to wrong measurement based on changed timer0 - unsigned long t = _micros() + ms*1000; - while( _micros() < t ){}; -#else - // regular micros - delay(ms); -#endif -} - - -// function buffering _micros() -// arduino function doesn't work well with interrupts -unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) -// if arduino uno and other atmega328p chips - //return the value based on the prescaler - if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); - else return (micros()); -#else - // regular micros - return micros(); -#endif -} diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.h b/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.h deleted file mode 100644 index f99c260a..00000000 --- a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/hardware_utils.h +++ /dev/null @@ -1,72 +0,0 @@ -#ifndef HARDWARE_UTILS_H -#define HARDWARE_UTILS_H - -#include "Arduino.h" -#include "foc_utils.h" - - -#if defined(ESP_H) // if esp32 boards - -#include "driver/mcpwm.h" -#include "soc/mcpwm_reg.h" -#include "soc/mcpwm_struct.h" - -#endif - -/** - * High PWM frequency setting function - * - hardware specific - * - * @param pwm_frequency - frequency in hertz - if applicable - * @param pinA pinA bldc motor or pin1A stepper motor - * @param pinB pinB bldc motor or pin1B stepper motor - * @param pinC pinC bldc motor or pin2A stepper motor - * @param pinD pin2B stepper motor - */ -void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_a duty cycle phase A [0, 1] - * @param dc_b duty cycle phase B [0, 1] - * @param dc_c duty cycle phase C [0, 1] - * @param pinA phase A hardware pin number - * @param pinB phase B hardware pin number - * @param pinC phase C hardware pin number - */ -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_1a duty cycle phase 1A [0, 1] - * @param dc_1b duty cycle phase 1B [0, 1] - * @param dc_2a duty cycle phase 2A [0, 1] - * @param dc_2b duty cycle phase 2B [0, 1] - * @param pin1A phase 1A hardware pin number - * @param pin1B phase 1B hardware pin number - * @param pin2A phase 2A hardware pin number - * @param pin2B phase 2B hardware pin number - */ -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); - -/** - * Function implementing delay() function in milliseconds - * - blocking function - * - hardware specific - - * @param ms number of milliseconds to wait - */ -void _delay(unsigned long ms); - -/** - * Function implementing timestamp getting function in microseconds - * hardware specific - */ -unsigned long _micros(); - - -#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.cpp b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.cpp deleted file mode 100644 index 0d080bab..00000000 --- a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.cpp +++ /dev/null @@ -1,284 +0,0 @@ -#include "hardware_utils.h" - -#if defined(ESP_H) // if ESP32 board -// empty motor slot -#define _EMPTY_SLOT -20 - -// structure containing motor slot configuration -// this library supports up to 4 motors -typedef struct { - int pinA; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator; - mcpwm_io_signals_t mcpwm_a; - mcpwm_io_signals_t mcpwm_b; - mcpwm_io_signals_t mcpwm_c; -} bldc_motor_slots_t; -typedef struct { - int pin1A; - mcpwm_dev_t* mcpwm_num; - mcpwm_unit_t mcpwm_unit; - mcpwm_operator_t mcpwm_operator1; - mcpwm_operator_t mcpwm_operator2; - mcpwm_io_signals_t mcpwm_1a; - mcpwm_io_signals_t mcpwm_1b; - mcpwm_io_signals_t mcpwm_2a; - mcpwm_io_signals_t mcpwm_2b; -} stepper_motor_slots_t; - -// define bldc motor slots array -bldc_motor_slots_t esp32_bldc_motor_slots[4] = { - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B}, // 2nd motor will be MCPWM0 channel B - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 3rd motor will be MCPWM1 channel A - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B - }; - -// define stepper motor slots array -stepper_motor_slots_t esp32_stepper_motor_slots[2] = { - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 - }; - -// configuring high frequency pwm timer -// https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller -void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit){ - - mcpwm_config_t pwm_config; - pwm_config.frequency = pwm_frequency; //frequency - pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 50.0% - pwm_config.cmpr_b = 0; //duty cycle of PWMxB = 50.0% - pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) - pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH - mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings - mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings - - _delay(100); - - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); - mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); - mcpwm_num->clk_cfg.prescale = 0; - - mcpwm_num->timer[0].period.prescale = 4; - mcpwm_num->timer[1].period.prescale = 4; - mcpwm_num->timer[2].period.prescale = 4; - _delay(1); - mcpwm_num->timer[0].period.period = 2048; - mcpwm_num->timer[1].period.period = 2048; - mcpwm_num->timer[2].period.period = 2048; - _delay(1); - mcpwm_num->timer[0].period.upmethod = 0; - mcpwm_num->timer[1].period.upmethod = 0; - mcpwm_num->timer[2].period.upmethod = 0; - _delay(1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); - mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); - - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); - mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 1; - _delay(1); - mcpwm_num->timer[0].sync.out_sel = 0; -} - -#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips -// set pwm frequency to 32KHz -void _pinHighFrequency(const int pin){ - // High PWM frequency - // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328 - if (pin == 5 || pin == 6 ) { - TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode - TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - } - if (pin == 9 || pin == 10 ) - TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 - if (pin == 3 || pin == 11) - TCCR2B = ((TCCR2B & 0b11111000) | 0x01);// set prescaler to 1 - -} -#elif defined(_STM32_DEF_) // if stm chips -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); - analogWriteResolution(12); // resolution 12 bit 0 - 4096 -} -#elif defined(__arm__) && defined(CORE_TEENSY) //if teensy 3x / 4x / LC boards -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(freq); -} -#endif - - -// function setting the high pwm frequency to the supplied pins -// - hardware speciffic -// supports Arudino/ATmega328, STM32 and ESP32 -void _setPwmFrequency(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if arduino uno and other ATmega328p chips - // High PWM frequency - // - always max 32kHz - _pinHighFrequency(pinA); - _pinHighFrequency(pinB); - _pinHighFrequency(pinC); - if(pinD != NOT_SET) _pinHighFrequency(pinD); // stepper motor - -#elif defined(_STM32_DEF_) || (defined(__arm__) && defined(CORE_TEENSY)) //if stm32 or teensy 3x / 4x / LC boards - if(pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz - else pwm_frequency = constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max - _setHighFrequency(pwm_frequency, pinA); - _setHighFrequency(pwm_frequency, pinB); - _setHighFrequency(pwm_frequency, pinC); - if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor - -#elif defined(ESP_H) // if esp32 boards - if(pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency - - if(pinD == NOT_SET){ - bldc_motor_slots_t m_slot = {}; - - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_bldc_motor_slots[i].pinA = pinA; - m_slot = esp32_bldc_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_c, pinC); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - - }else{ - stepper_motor_slots_t m_slot = {}; - // determine which motor are we connecting - // and set the appropriate configuration parameters - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_stepper_motor_slots[i].pin1A = pinA; - m_slot = esp32_stepper_motor_slots[i]; - break; - } - } - - // configure pins - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1a, pinA); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_1b, pinB); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2a, pinC); - mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_2b, pinD); - - // configure the timer - _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); - } -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 4; i++){ - if(esp32_bldc_motor_slots[i].pinA == pinA){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_bldc_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_a*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_b*2047; - esp32_bldc_motor_slots[i].mcpwm_num->channel[2].cmpr_value[esp32_bldc_motor_slots[i].mcpwm_operator].cmpr_val = dc_c*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pinA, 4095.0*dc_a); - analogWrite(pinB, 4095.0*dc_b); - analogWrite(pinC, 4095.0*dc_c); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255*dc_a); - analogWrite(pinB, 255*dc_b); - analogWrite(pinC, 255*dc_c); -#endif -} - -// function setting the pwm duty cycle to the hardware -//- hardware speciffic -// -// Arduino and STM32 devices use analogWrite() -// ESP32 uses MCPWM -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ -#if defined(ESP_H) // if ESP32 boards - // determine which motor slot is the motor connected to - for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found - // se the PWM on the slot timers - // transform duty cycle from [0,1] to [0,2047] - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator1].cmpr_val = dc_1b*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[0].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2a*2047; - esp32_stepper_motor_slots[i].mcpwm_num->channel[1].cmpr_value[esp32_stepper_motor_slots[i].mcpwm_operator2].cmpr_val = dc_2b*2047; - break; - } - } -#elif defined(_STM32_DEF_) // STM32 devices - // transform duty cycle from [0,1] to [0,4095] - analogWrite(pin1A, 4095.0*dc_1a); - analogWrite(pin1B, 4095.0*dc_1b); - analogWrite(pin2A, 4095.0*dc_2a); - analogWrite(pin2B, 4095.0*dc_2b); -#else // Arduino & Teensy - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255*dc_1a); - analogWrite(pin1B, 255*dc_1b); - analogWrite(pin2A, 255*dc_2a); - analogWrite(pin2B, 255*dc_2b); -#endif -} - - -// function buffering delay() -// arduino uno function doesn't work well with interrupts -void _delay(unsigned long ms){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) - // if arduino uno and other atmega328p chips - // use while instad of delay, - // due to wrong measurement based on changed timer0 - unsigned long t = _micros() + ms*1000; - while( _micros() < t ){}; -#else - // regular micros - delay(ms); -#endif -} - - -// function buffering _micros() -// arduino function doesn't work well with interrupts -unsigned long _micros(){ -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) -// if arduino uno and other atmega328p chips - //return the value based on the prescaler - if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); - else return (micros()); -#else - // regular micros - return micros(); -#endif -} diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.h b/minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.h deleted file mode 100644 index f99c260a..00000000 --- a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/hardware_utils.h +++ /dev/null @@ -1,72 +0,0 @@ -#ifndef HARDWARE_UTILS_H -#define HARDWARE_UTILS_H - -#include "Arduino.h" -#include "foc_utils.h" - - -#if defined(ESP_H) // if esp32 boards - -#include "driver/mcpwm.h" -#include "soc/mcpwm_reg.h" -#include "soc/mcpwm_struct.h" - -#endif - -/** - * High PWM frequency setting function - * - hardware specific - * - * @param pwm_frequency - frequency in hertz - if applicable - * @param pinA pinA bldc motor or pin1A stepper motor - * @param pinB pinB bldc motor or pin1B stepper motor - * @param pinC pinC bldc motor or pin2A stepper motor - * @param pinD pin2B stepper motor - */ -void _setPwmFrequency(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD = NOT_SET); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_a duty cycle phase A [0, 1] - * @param dc_b duty cycle phase B [0, 1] - * @param dc_c duty cycle phase C [0, 1] - * @param pinA phase A hardware pin number - * @param pinB phase B hardware pin number - * @param pinC phase C hardware pin number - */ -void _writeDutyCycle(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); - -/** - * Function setting the duty cycle to the pwm pin (ex. analogWrite()) - * hardware specific - * - * @param dc_1a duty cycle phase 1A [0, 1] - * @param dc_1b duty cycle phase 1B [0, 1] - * @param dc_2a duty cycle phase 2A [0, 1] - * @param dc_2b duty cycle phase 2B [0, 1] - * @param pin1A phase 1A hardware pin number - * @param pin1B phase 1B hardware pin number - * @param pin2A phase 2A hardware pin number - * @param pin2B phase 2B hardware pin number - */ -void _writeDutyCycle(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); - -/** - * Function implementing delay() function in milliseconds - * - blocking function - * - hardware specific - - * @param ms number of milliseconds to wait - */ -void _delay(unsigned long ms); - -/** - * Function implementing timestamp getting function in microseconds - * hardware specific - */ -unsigned long _micros(); - - -#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/arduino_foc_stepper_encoder.ino b/minimal_project_examples/atmega2560_stepper_encoder/atmega2560_stepper_encoder.ino similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_encoder/arduino_foc_stepper_encoder.ino rename to minimal_project_examples/atmega2560_stepper_encoder/atmega2560_stepper_encoder.ino diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/Encoder.cpp b/minimal_project_examples/atmega2560_stepper_encoder/src/Encoder.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_encoder/src/Encoder.cpp rename to minimal_project_examples/atmega2560_stepper_encoder/src/Encoder.cpp diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/Encoder.h b/minimal_project_examples/atmega2560_stepper_encoder/src/Encoder.h similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_encoder/src/Encoder.h rename to minimal_project_examples/atmega2560_stepper_encoder/src/Encoder.h diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/StepperMotor.cpp b/minimal_project_examples/atmega2560_stepper_encoder/src/StepperMotor.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_encoder/src/StepperMotor.cpp rename to minimal_project_examples/atmega2560_stepper_encoder/src/StepperMotor.cpp diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/StepperMotor.h b/minimal_project_examples/atmega2560_stepper_encoder/src/StepperMotor.h similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_encoder/src/StepperMotor.h rename to minimal_project_examples/atmega2560_stepper_encoder/src/StepperMotor.h diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/FOCMotor.cpp b/minimal_project_examples/atmega2560_stepper_encoder/src/common/FOCMotor.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/FOCMotor.cpp rename to minimal_project_examples/atmega2560_stepper_encoder/src/common/FOCMotor.cpp diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/FOCMotor.h b/minimal_project_examples/atmega2560_stepper_encoder/src/common/FOCMotor.h similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/FOCMotor.h rename to minimal_project_examples/atmega2560_stepper_encoder/src/common/FOCMotor.h diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/Sensor.h b/minimal_project_examples/atmega2560_stepper_encoder/src/common/Sensor.h similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/Sensor.h rename to minimal_project_examples/atmega2560_stepper_encoder/src/common/Sensor.h diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/defaults.h b/minimal_project_examples/atmega2560_stepper_encoder/src/common/defaults.h similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/defaults.h rename to minimal_project_examples/atmega2560_stepper_encoder/src/common/defaults.h diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/foc_utils.cpp b/minimal_project_examples/atmega2560_stepper_encoder/src/common/foc_utils.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/foc_utils.cpp rename to minimal_project_examples/atmega2560_stepper_encoder/src/common/foc_utils.cpp diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/foc_utils.h b/minimal_project_examples/atmega2560_stepper_encoder/src/common/foc_utils.h similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/foc_utils.h rename to minimal_project_examples/atmega2560_stepper_encoder/src/common/foc_utils.h diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/hardware_utils.cpp b/minimal_project_examples/atmega2560_stepper_encoder/src/common/hardware_utils.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/hardware_utils.cpp rename to minimal_project_examples/atmega2560_stepper_encoder/src/common/hardware_utils.cpp diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/hardware_utils.h b/minimal_project_examples/atmega2560_stepper_encoder/src/common/hardware_utils.h similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/hardware_utils.h rename to minimal_project_examples/atmega2560_stepper_encoder/src/common/hardware_utils.h diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/lowpass_filter.cpp b/minimal_project_examples/atmega2560_stepper_encoder/src/common/lowpass_filter.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/lowpass_filter.cpp rename to minimal_project_examples/atmega2560_stepper_encoder/src/common/lowpass_filter.cpp diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/lowpass_filter.h b/minimal_project_examples/atmega2560_stepper_encoder/src/common/lowpass_filter.h similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/lowpass_filter.h rename to minimal_project_examples/atmega2560_stepper_encoder/src/common/lowpass_filter.h diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/pid.cpp b/minimal_project_examples/atmega2560_stepper_encoder/src/common/pid.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/pid.cpp rename to minimal_project_examples/atmega2560_stepper_encoder/src/common/pid.cpp diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/pid.h b/minimal_project_examples/atmega2560_stepper_encoder/src/common/pid.h similarity index 100% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/common/pid.h rename to minimal_project_examples/atmega2560_stepper_encoder/src/common/pid.h diff --git a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/BLDCDriver3PWM.cpp b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/BLDCDriver3PWM.cpp index bacb4ec5..a3fc052d 100644 --- a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/BLDCDriver3PWM.cpp +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/BLDCDriver3PWM.cpp @@ -35,6 +35,8 @@ void BLDCDriver3PWM::disable() // init hardware pins int BLDCDriver3PWM::init() { + // a bit of separation + _delay(1000); // PWM pins pinMode(pwmA, OUTPUT); @@ -56,14 +58,14 @@ int BLDCDriver3PWM::init() { // Set voltage to the pwm pin void BLDCDriver3PWM::setPwm(float Ua, float Ub, float Uc) { // limit the voltage in driver - Ua = _constrain(Ua, -voltage_limit, voltage_limit); - Ub = _constrain(Ub, -voltage_limit, voltage_limit); - Uc = _constrain(Uc, -voltage_limit, voltage_limit); + Ua = _constrain(Ua, 0.0, voltage_limit); + Ub = _constrain(Ub, 0.0, voltage_limit); + Uc = _constrain(Uc, 0.0, voltage_limit); // calculate duty cycle // limited in [0,1] - float dc_a = _constrain(Ua / voltage_power_supply, 0 , 1 ); - float dc_b = _constrain(Ub / voltage_power_supply, 0 , 1 ); - float dc_c = _constrain(Uc / voltage_power_supply, 0 , 1 ); + float dc_a = _constrain(Ua / voltage_power_supply, 0.0 , 1.0 ); + float dc_b = _constrain(Ub / voltage_power_supply, 0.0 , 1.0 ); + float dc_c = _constrain(Uc / voltage_power_supply, 0.0 , 1.0 ); // hardware specific writing // hardware specific function - depending on driver and mcu _writeDutyCycle3PWM(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC); diff --git a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_api.h b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_api.h index da5ddf51..01c03867 100644 --- a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_api.h +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_api.h @@ -4,6 +4,17 @@ #include "../common/foc_utils.h" #include "../common/time_utils.h" +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + */ +void _configure2PWM(long pwm_frequency, const int pinA, const int pinB); + /** * Configuring PWM frequency, resolution and alignment * - BLDC driver - 3PWM setting @@ -47,6 +58,18 @@ void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const */ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l); +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + */ +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB); + /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) * - BLDC driver - 3PWM setting diff --git a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/atmega328_mcu.cpp b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/atmega328_mcu.cpp index 58b368f7..24fe563e 100644 --- a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/atmega328_mcu.cpp +++ b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/atmega328_mcu.cpp @@ -17,6 +17,18 @@ void _pinHighFrequency(const int pin){ } + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 2PWM setting +// - hardware speciffic +// supports Arudino/ATmega328 +void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); +} + // function setting the high pwm frequency to the supplied pins // - BLDC motor - 3PWM setting // - hardware speciffic @@ -29,6 +41,14 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int _pinHighFrequency(pinC); } +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 2PWM setting +// - hardware speciffic +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); +} // function setting the pwm duty cycle to the hardware // - BLDC motor - 3PWM setting diff --git a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/generic_mcu.cpp b/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/generic_mcu.cpp deleted file mode 100644 index dc322746..00000000 --- a/minimal_project_examples/atmega328_bldc_magnetic_i2c/src/drivers/hardware_specific/generic_mcu.cpp +++ /dev/null @@ -1,68 +0,0 @@ -#include "../hardware_api.h" - -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if mcu is not atmega328 - -#elif defined(__arm__) && defined(CORE_TEENSY) // or teensy - -#elif defined(ESP_H) // or esp32 - -#elif defined(_STM32_DEF_) // or stm32 - -#else - -// function setting the high pwm frequency to the supplied pins -// - BLDC motor - 3PWM setting -// - hardware speciffic -// in generic case dont do anything -void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { - return; -} - - -// function setting the high pwm frequency to the supplied pins -// - Stepper motor - 4PWM setting -// - hardware speciffic -// in generic case dont do anything -void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) { - return; -} - -// Configuring PWM frequency, resolution and alignment -// - BLDC driver - 6PWM setting -// - hardware specific -int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ - return -1; -} - - -// function setting the pwm duty cycle to the hardware -// - BLDC motor - 3PWM setting -// - hardware speciffic -void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255.0*dc_a); - analogWrite(pinB, 255.0*dc_b); - analogWrite(pinC, 255.0*dc_c); -} - -// function setting the pwm duty cycle to the hardware -// - Stepper motor - 4PWM setting -// - hardware speciffic -void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255.0*dc_1a); - analogWrite(pin1B, 255.0*dc_1b); - analogWrite(pin2A, 255.0*dc_2a); - analogWrite(pin2B, 255.0*dc_2b); -} - - -// Function setting the duty cycle to the pwm pin (ex. analogWrite()) -// - BLDC driver - 6PWM setting -// - hardware specific -void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ - return; -} - - -#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/BLDCDriver3PWM.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/BLDCDriver3PWM.cpp index bacb4ec5..a3fc052d 100644 --- a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/BLDCDriver3PWM.cpp +++ b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/BLDCDriver3PWM.cpp @@ -35,6 +35,8 @@ void BLDCDriver3PWM::disable() // init hardware pins int BLDCDriver3PWM::init() { + // a bit of separation + _delay(1000); // PWM pins pinMode(pwmA, OUTPUT); @@ -56,14 +58,14 @@ int BLDCDriver3PWM::init() { // Set voltage to the pwm pin void BLDCDriver3PWM::setPwm(float Ua, float Ub, float Uc) { // limit the voltage in driver - Ua = _constrain(Ua, -voltage_limit, voltage_limit); - Ub = _constrain(Ub, -voltage_limit, voltage_limit); - Uc = _constrain(Uc, -voltage_limit, voltage_limit); + Ua = _constrain(Ua, 0.0, voltage_limit); + Ub = _constrain(Ub, 0.0, voltage_limit); + Uc = _constrain(Uc, 0.0, voltage_limit); // calculate duty cycle // limited in [0,1] - float dc_a = _constrain(Ua / voltage_power_supply, 0 , 1 ); - float dc_b = _constrain(Ub / voltage_power_supply, 0 , 1 ); - float dc_c = _constrain(Uc / voltage_power_supply, 0 , 1 ); + float dc_a = _constrain(Ua / voltage_power_supply, 0.0 , 1.0 ); + float dc_b = _constrain(Ub / voltage_power_supply, 0.0 , 1.0 ); + float dc_c = _constrain(Uc / voltage_power_supply, 0.0 , 1.0 ); // hardware specific writing // hardware specific function - depending on driver and mcu _writeDutyCycle3PWM(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC); diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_api.h b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_api.h index da5ddf51..01c03867 100644 --- a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_api.h +++ b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_api.h @@ -4,6 +4,17 @@ #include "../common/foc_utils.h" #include "../common/time_utils.h" +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + */ +void _configure2PWM(long pwm_frequency, const int pinA, const int pinB); + /** * Configuring PWM frequency, resolution and alignment * - BLDC driver - 3PWM setting @@ -47,6 +58,18 @@ void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const */ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l); +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + */ +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB); + /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) * - BLDC driver - 3PWM setting diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/atmega328_mcu.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/atmega328_mcu.cpp index 58b368f7..24fe563e 100644 --- a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/atmega328_mcu.cpp +++ b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/atmega328_mcu.cpp @@ -17,6 +17,18 @@ void _pinHighFrequency(const int pin){ } + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 2PWM setting +// - hardware speciffic +// supports Arudino/ATmega328 +void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); +} + // function setting the high pwm frequency to the supplied pins // - BLDC motor - 3PWM setting // - hardware speciffic @@ -29,6 +41,14 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int _pinHighFrequency(pinC); } +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 2PWM setting +// - hardware speciffic +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); +} // function setting the pwm duty cycle to the hardware // - BLDC motor - 3PWM setting diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/generic_mcu.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/generic_mcu.cpp deleted file mode 100644 index dc322746..00000000 --- a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/generic_mcu.cpp +++ /dev/null @@ -1,68 +0,0 @@ -#include "../hardware_api.h" - -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if mcu is not atmega328 - -#elif defined(__arm__) && defined(CORE_TEENSY) // or teensy - -#elif defined(ESP_H) // or esp32 - -#elif defined(_STM32_DEF_) // or stm32 - -#else - -// function setting the high pwm frequency to the supplied pins -// - BLDC motor - 3PWM setting -// - hardware speciffic -// in generic case dont do anything -void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { - return; -} - - -// function setting the high pwm frequency to the supplied pins -// - Stepper motor - 4PWM setting -// - hardware speciffic -// in generic case dont do anything -void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) { - return; -} - -// Configuring PWM frequency, resolution and alignment -// - BLDC driver - 6PWM setting -// - hardware specific -int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ - return -1; -} - - -// function setting the pwm duty cycle to the hardware -// - BLDC motor - 3PWM setting -// - hardware speciffic -void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255.0*dc_a); - analogWrite(pinB, 255.0*dc_b); - analogWrite(pinC, 255.0*dc_c); -} - -// function setting the pwm duty cycle to the hardware -// - Stepper motor - 4PWM setting -// - hardware speciffic -void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255.0*dc_1a); - analogWrite(pin1B, 255.0*dc_1b); - analogWrite(pin2A, 255.0*dc_2a); - analogWrite(pin2B, 255.0*dc_2b); -} - - -// Function setting the duty cycle to the pwm pin (ex. analogWrite()) -// - BLDC driver - 6PWM setting -// - hardware specific -void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ - return; -} - - -#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/teensy_mcu.cpp b/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/teensy_mcu.cpp deleted file mode 100644 index 10bd24c5..00000000 --- a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/teensy_mcu.cpp +++ /dev/null @@ -1,71 +0,0 @@ -#include "../hardware_api.h" - -#if defined(__arm__) && defined(CORE_TEENSY) - -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(pin, freq); -} - - -// function setting the high pwm frequency to the supplied pins -// - BLDC motor - 3PWM setting -// - hardware speciffic -void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { - if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max - _setHighFrequency(pwm_frequency, pinA); - _setHighFrequency(pwm_frequency, pinB); - _setHighFrequency(pwm_frequency, pinC); - if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor -} - -// function setting the high pwm frequency to the supplied pins -// - Stepper motor - 4PWM setting -// - hardware speciffic -void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { - if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max - _setHighFrequency(pwm_frequency, pinA); - _setHighFrequency(pwm_frequency, pinB); - _setHighFrequency(pwm_frequency, pinC); - _setHighFrequency(pwm_frequency, pinD); -} - -// function setting the pwm duty cycle to the hardware -// - BLDC motor - 3PWM setting -// - hardware speciffic -void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255.0*dc_a); - analogWrite(pinB, 255.0*dc_b); - analogWrite(pinC, 255.0*dc_c); -} - -// function setting the pwm duty cycle to the hardware -// - Stepper motor - 4PWM setting -// - hardware speciffic -void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255.0*dc_1a); - analogWrite(pin1B, 255.0*dc_1b); - analogWrite(pin2A, 255.0*dc_2a); - analogWrite(pin2B, 255.0*dc_2b); -} - - -// Configuring PWM frequency, resolution and alignment -// - BLDC driver - 6PWM setting -// - hardware specific -int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ - return -1; -} - -// Function setting the duty cycle to the pwm pin (ex. analogWrite()) -// - BLDC driver - 6PWM setting -// - hardware specific -void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ - return; -} -#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_driver_standalone/src/drivers/BLDCDriver3PWM.cpp b/minimal_project_examples/atmega328_driver_standalone/src/drivers/BLDCDriver3PWM.cpp index bacb4ec5..a3fc052d 100644 --- a/minimal_project_examples/atmega328_driver_standalone/src/drivers/BLDCDriver3PWM.cpp +++ b/minimal_project_examples/atmega328_driver_standalone/src/drivers/BLDCDriver3PWM.cpp @@ -35,6 +35,8 @@ void BLDCDriver3PWM::disable() // init hardware pins int BLDCDriver3PWM::init() { + // a bit of separation + _delay(1000); // PWM pins pinMode(pwmA, OUTPUT); @@ -56,14 +58,14 @@ int BLDCDriver3PWM::init() { // Set voltage to the pwm pin void BLDCDriver3PWM::setPwm(float Ua, float Ub, float Uc) { // limit the voltage in driver - Ua = _constrain(Ua, -voltage_limit, voltage_limit); - Ub = _constrain(Ub, -voltage_limit, voltage_limit); - Uc = _constrain(Uc, -voltage_limit, voltage_limit); + Ua = _constrain(Ua, 0.0, voltage_limit); + Ub = _constrain(Ub, 0.0, voltage_limit); + Uc = _constrain(Uc, 0.0, voltage_limit); // calculate duty cycle // limited in [0,1] - float dc_a = _constrain(Ua / voltage_power_supply, 0 , 1 ); - float dc_b = _constrain(Ub / voltage_power_supply, 0 , 1 ); - float dc_c = _constrain(Uc / voltage_power_supply, 0 , 1 ); + float dc_a = _constrain(Ua / voltage_power_supply, 0.0 , 1.0 ); + float dc_b = _constrain(Ub / voltage_power_supply, 0.0 , 1.0 ); + float dc_c = _constrain(Uc / voltage_power_supply, 0.0 , 1.0 ); // hardware specific writing // hardware specific function - depending on driver and mcu _writeDutyCycle3PWM(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC); diff --git a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_api.h b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_api.h index da5ddf51..01c03867 100644 --- a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_api.h +++ b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_api.h @@ -4,6 +4,17 @@ #include "../common/foc_utils.h" #include "../common/time_utils.h" +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + */ +void _configure2PWM(long pwm_frequency, const int pinA, const int pinB); + /** * Configuring PWM frequency, resolution and alignment * - BLDC driver - 3PWM setting @@ -47,6 +58,18 @@ void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const */ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l); +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + */ +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB); + /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) * - BLDC driver - 3PWM setting diff --git a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/atmega328_mcu.cpp b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/atmega328_mcu.cpp index 58b368f7..24fe563e 100644 --- a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/atmega328_mcu.cpp +++ b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/atmega328_mcu.cpp @@ -17,6 +17,18 @@ void _pinHighFrequency(const int pin){ } + +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 2PWM setting +// - hardware speciffic +// supports Arudino/ATmega328 +void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) { + // High PWM frequency + // - always max 32kHz + _pinHighFrequency(pinA); + _pinHighFrequency(pinB); +} + // function setting the high pwm frequency to the supplied pins // - BLDC motor - 3PWM setting // - hardware speciffic @@ -29,6 +41,14 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int _pinHighFrequency(pinC); } +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 2PWM setting +// - hardware speciffic +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(pinA, 255.0*dc_a); + analogWrite(pinB, 255.0*dc_b); +} // function setting the pwm duty cycle to the hardware // - BLDC motor - 3PWM setting diff --git a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/generic_mcu.cpp b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/generic_mcu.cpp deleted file mode 100644 index dc322746..00000000 --- a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/generic_mcu.cpp +++ /dev/null @@ -1,68 +0,0 @@ -#include "../hardware_api.h" - -#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) // if mcu is not atmega328 - -#elif defined(__arm__) && defined(CORE_TEENSY) // or teensy - -#elif defined(ESP_H) // or esp32 - -#elif defined(_STM32_DEF_) // or stm32 - -#else - -// function setting the high pwm frequency to the supplied pins -// - BLDC motor - 3PWM setting -// - hardware speciffic -// in generic case dont do anything -void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { - return; -} - - -// function setting the high pwm frequency to the supplied pins -// - Stepper motor - 4PWM setting -// - hardware speciffic -// in generic case dont do anything -void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) { - return; -} - -// Configuring PWM frequency, resolution and alignment -// - BLDC driver - 6PWM setting -// - hardware specific -int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ - return -1; -} - - -// function setting the pwm duty cycle to the hardware -// - BLDC motor - 3PWM setting -// - hardware speciffic -void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255.0*dc_a); - analogWrite(pinB, 255.0*dc_b); - analogWrite(pinC, 255.0*dc_c); -} - -// function setting the pwm duty cycle to the hardware -// - Stepper motor - 4PWM setting -// - hardware speciffic -void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255.0*dc_1a); - analogWrite(pin1B, 255.0*dc_1b); - analogWrite(pin2A, 255.0*dc_2a); - analogWrite(pin2B, 255.0*dc_2b); -} - - -// Function setting the duty cycle to the pwm pin (ex. analogWrite()) -// - BLDC driver - 6PWM setting -// - hardware specific -void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ - return; -} - - -#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/stm32_mcu.cpp b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/stm32_mcu.cpp deleted file mode 100644 index 85d0bd65..00000000 --- a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/stm32_mcu.cpp +++ /dev/null @@ -1,291 +0,0 @@ - -#include "../hardware_api.h" - -#if defined(_STM32_DEF_) - -#define _PWM_RESOLUTION 12 // 12bit -#define _PWM_RANGE 4095.0// 2^12 -1 = 4095 -#define _PWM_FREQUENCY 50000 // 50khz - - -#define _HARDWARE_6PWM 1 -#define _SOFTWARE_6PWM 0 -#define _ERROR_6PWM -1 - - -// setting pwm to hardware pin - instead analogWrite() -void _setPwm(int ulPin, uint32_t value, int resolution) -{ - PinName pin = digitalPinToPinName(ulPin); - TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); - uint32_t index = get_timer_index(Instance); - HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); - - uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); - HT->setCaptureCompare(channel, value, (TimerCompareFormat_t)resolution); -} - - -// init pin pwm -HardwareTimer* _initPinPWM(uint32_t PWM_freq, int ulPin) -{ - PinName pin = digitalPinToPinName(ulPin); - TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); - - uint32_t index = get_timer_index(Instance); - if (HardwareTimer_Handle[index] == NULL) { - HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM)); - HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; - HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); - } - HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); - uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); - HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, pin); - HT->setOverflow(PWM_freq, HERTZ_FORMAT); - HT->pause(); - HT->refresh(); - return HT; -} - - -// init high side pin -HardwareTimer* _initPinPWMHigh(uint32_t PWM_freq, int ulPin) -{ - return _initPinPWM(PWM_freq, ulPin); -} - -// init low side pin -HardwareTimer* _initPinPWMLow(uint32_t PWM_freq, int ulPin) -{ - PinName pin = digitalPinToPinName(ulPin); - TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM); - uint32_t index = get_timer_index(Instance); - - if (HardwareTimer_Handle[index] == NULL) { - HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM)); - HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; - HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); - TIM_OC_InitTypeDef sConfigOC = TIM_OC_InitTypeDef(); - sConfigOC.OCMode = TIM_OCMODE_PWM2; - sConfigOC.Pulse = 100; - sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW; - sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH; - sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; - sConfigOC.OCIdleState = TIM_OCIDLESTATE_SET; - sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET; - uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); - HAL_TIM_PWM_ConfigChannel(&(HardwareTimer_Handle[index]->handle), &sConfigOC, channel); - } - HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); - uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM)); - HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM2, pin); - HT->setOverflow(PWM_freq, HERTZ_FORMAT); - HT->pause(); - HT->refresh(); - return HT; -} - - -// align the timers to end the init -void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3) -{ - HT1->pause(); - HT1->refresh(); - HT2->pause(); - HT2->refresh(); - HT3->pause(); - HT3->refresh(); - HT1->resume(); - HT2->resume(); - HT3->resume(); -} - -// align the timers to end the init -void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3,HardwareTimer *HT4) -{ - HT1->pause(); - HT1->refresh(); - HT2->pause(); - HT2->refresh(); - HT3->pause(); - HT3->refresh(); - HT4->pause(); - HT4->refresh(); - HT1->resume(); - HT2->resume(); - HT3->resume(); - HT4->resume(); -} - -HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l) -{ - PinName uhPinName = digitalPinToPinName(pinA_h); - PinName ulPinName = digitalPinToPinName(pinA_l); - PinName vhPinName = digitalPinToPinName(pinB_h); - PinName vlPinName = digitalPinToPinName(pinB_l); - PinName whPinName = digitalPinToPinName(pinC_h); - PinName wlPinName = digitalPinToPinName(pinC_l); - - TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM); - - uint32_t index = get_timer_index(Instance); - - if (HardwareTimer_Handle[index] == NULL) { - HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM)); - HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; - HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); - ((HardwareTimer *)HardwareTimer_Handle[index]->__this)->setOverflow(PWM_freq, HERTZ_FORMAT); - } - HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); - - HT->setMode(STM_PIN_CHANNEL(pinmap_function(uhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, uhPinName); - HT->setMode(STM_PIN_CHANNEL(pinmap_function(ulPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, ulPinName); - HT->setMode(STM_PIN_CHANNEL(pinmap_function(vhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vhPinName); - HT->setMode(STM_PIN_CHANNEL(pinmap_function(vlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vlPinName); - HT->setMode(STM_PIN_CHANNEL(pinmap_function(whPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, whPinName); - HT->setMode(STM_PIN_CHANNEL(pinmap_function(wlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, wlPinName); - - // dead time is set in nanoseconds - uint32_t dead_time_ns = (float)(1e9/PWM_freq)*dead_zone; - uint32_t dead_time = __LL_TIM_CALC_DEADTIME(SystemCoreClock, LL_TIM_GetClockDivision(HT->getHandle()->Instance), dead_time_ns); - LL_TIM_OC_SetDeadTime(HT->getHandle()->Instance, dead_time); // deadtime is non linear! - LL_TIM_CC_EnableChannel(HT->getHandle()->Instance, LL_TIM_CHANNEL_CH1 | LL_TIM_CHANNEL_CH1N | LL_TIM_CHANNEL_CH2 | LL_TIM_CHANNEL_CH2N | LL_TIM_CHANNEL_CH3 | LL_TIM_CHANNEL_CH3N); - - HT->pause(); - HT->refresh(); - HT->resume(); - return HT; -} - - -// returns 0 if each pair of pwm channels has same channel -// returns 1 all the channels belong to the same timer - hardware inverted channels -// returns -1 if neither - avoid configuring - error!!! -int _interfaceType(const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ - PinName nameAH = digitalPinToPinName(pinA_h); - PinName nameAL = digitalPinToPinName(pinA_l); - PinName nameBH = digitalPinToPinName(pinB_h); - PinName nameBL = digitalPinToPinName(pinB_l); - PinName nameCH = digitalPinToPinName(pinC_h); - PinName nameCL = digitalPinToPinName(pinC_l); - int tim1 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAH, PinMap_PWM)); - int tim2 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAL, PinMap_PWM)); - int tim3 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBH, PinMap_PWM)); - int tim4 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBL, PinMap_PWM)); - int tim5 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCH, PinMap_PWM)); - int tim6 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCL, PinMap_PWM)); - if(tim1 == tim2 && tim2==tim3 && tim3==tim4 && tim4==tim5 && tim5==tim6) - return _HARDWARE_6PWM; // hardware 6pwm interface - only on timer - else if(tim1 == tim2 && tim3==tim4 && tim5==tim6) - return _SOFTWARE_6PWM; // software 6pwm interface - each pair of high-low side same timer - else - return _ERROR_6PWM; // might be error avoid configuration -} - - - -// function setting the high pwm frequency to the supplied pins -// - BLDC motor - 3PWM setting -// - hardware speciffic -void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { - if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max - HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); - HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); - HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); - // allign the timers - _alignPWMTimers(HT1, HT2, HT3); -} - -// function setting the high pwm frequency to the supplied pins -// - Stepper motor - 4PWM setting -// - hardware speciffic -void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { - if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max - HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); - HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); - HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); - HardwareTimer* HT4 = _initPinPWM(pwm_frequency, pinD); - // allign the timers - _alignPWMTimers(HT1, HT2, HT3, HT4); -} - -// function setting the pwm duty cycle to the hardware -// - BLDC motor - 3PWM setting -//- hardware speciffic -void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ - // transform duty cycle from [0,1] to [0,4095] - _setPwm(pinA, _PWM_RANGE*dc_a, _PWM_RESOLUTION); - _setPwm(pinB, _PWM_RANGE*dc_b, _PWM_RESOLUTION); - _setPwm(pinC, _PWM_RANGE*dc_c, _PWM_RESOLUTION); -} - -// function setting the pwm duty cycle to the hardware -// - Stepper motor - 4PWM setting -//- hardware speciffic -void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ - // transform duty cycle from [0,1] to [0,4095] - _setPwm(pin1A, _PWM_RANGE*dc_1a, _PWM_RESOLUTION); - _setPwm(pin1B, _PWM_RANGE*dc_1b, _PWM_RESOLUTION); - _setPwm(pin2A, _PWM_RANGE*dc_2a, _PWM_RESOLUTION); - _setPwm(pin2B, _PWM_RANGE*dc_2b, _PWM_RESOLUTION); -} - - - - -// Configuring PWM frequency, resolution and alignment -// - BLDC driver - 6PWM setting -// - hardware specific -int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ - if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, 100000); // constrain to 100kHz max - - // find configuration - int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); - // configure accordingly - switch(config){ - case _ERROR_6PWM: - return -1; // fail - break; - case _HARDWARE_6PWM: - _initHardware6PWMInterface(pwm_frequency, dead_zone, pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); - break; - case _SOFTWARE_6PWM: - HardwareTimer* HT1 = _initPinPWMHigh(pwm_frequency, pinA_h); - _initPinPWMLow(pwm_frequency, pinA_l); - HardwareTimer* HT2 = _initPinPWMHigh(pwm_frequency,pinB_h); - _initPinPWMLow(pwm_frequency, pinB_l); - HardwareTimer* HT3 = _initPinPWMHigh(pwm_frequency,pinC_h); - _initPinPWMLow(pwm_frequency, pinC_l); - _alignPWMTimers(HT1, HT2, HT3); - break; - } - return 0; // success -} - -// Function setting the duty cycle to the pwm pin (ex. analogWrite()) -// - BLDC driver - 6PWM setting -// - hardware specific -void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ - // find configuration - int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); - // set pwm accordingly - switch(config){ - case _HARDWARE_6PWM: - _setPwm(pinA_h, _PWM_RANGE*dc_a, _PWM_RESOLUTION); - _setPwm(pinB_h, _PWM_RANGE*dc_b, _PWM_RESOLUTION); - _setPwm(pinC_h, _PWM_RANGE*dc_c, _PWM_RESOLUTION); - break; - case _SOFTWARE_6PWM: - _setPwm(pinA_l, _constrain(dc_a + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); - _setPwm(pinA_h, _constrain(dc_a - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); - _setPwm(pinB_l, _constrain(dc_b + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); - _setPwm(pinB_h, _constrain(dc_b - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); - _setPwm(pinC_l, _constrain(dc_c + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); - _setPwm(pinC_h, _constrain(dc_c - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION); - break; - } -} -#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/teensy_mcu.cpp b/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/teensy_mcu.cpp deleted file mode 100644 index 10bd24c5..00000000 --- a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/teensy_mcu.cpp +++ /dev/null @@ -1,71 +0,0 @@ -#include "../hardware_api.h" - -#if defined(__arm__) && defined(CORE_TEENSY) - -// configure High PWM frequency -void _setHighFrequency(const long freq, const int pin){ - analogWrite(pin, 0); - analogWriteFrequency(pin, freq); -} - - -// function setting the high pwm frequency to the supplied pins -// - BLDC motor - 3PWM setting -// - hardware speciffic -void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { - if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max - _setHighFrequency(pwm_frequency, pinA); - _setHighFrequency(pwm_frequency, pinB); - _setHighFrequency(pwm_frequency, pinC); - if(pinD != NOT_SET) _setHighFrequency(pwm_frequency, pinD); // stepper motor -} - -// function setting the high pwm frequency to the supplied pins -// - Stepper motor - 4PWM setting -// - hardware speciffic -void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { - if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 50000; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max - _setHighFrequency(pwm_frequency, pinA); - _setHighFrequency(pwm_frequency, pinB); - _setHighFrequency(pwm_frequency, pinC); - _setHighFrequency(pwm_frequency, pinD); -} - -// function setting the pwm duty cycle to the hardware -// - BLDC motor - 3PWM setting -// - hardware speciffic -void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ - // transform duty cycle from [0,1] to [0,255] - analogWrite(pinA, 255.0*dc_a); - analogWrite(pinB, 255.0*dc_b); - analogWrite(pinC, 255.0*dc_c); -} - -// function setting the pwm duty cycle to the hardware -// - Stepper motor - 4PWM setting -// - hardware speciffic -void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ - // transform duty cycle from [0,1] to [0,255] - analogWrite(pin1A, 255.0*dc_1a); - analogWrite(pin1B, 255.0*dc_1b); - analogWrite(pin2A, 255.0*dc_2a); - analogWrite(pin2B, 255.0*dc_2b); -} - - -// Configuring PWM frequency, resolution and alignment -// - BLDC driver - 6PWM setting -// - hardware specific -int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ - return -1; -} - -// Function setting the duty cycle to the pwm pin (ex. analogWrite()) -// - BLDC driver - 6PWM setting -// - hardware specific -void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){ - return; -} -#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/arduino_foc_bldc_magnetic_spi.ino b/minimal_project_examples/esp32_bldc_magnetic_spi/esp32_bldc_magnetic_spi.ino similarity index 91% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/arduino_foc_bldc_magnetic_spi.ino rename to minimal_project_examples/esp32_bldc_magnetic_spi/esp32_bldc_magnetic_spi.ino index 3a36fc43..5e7d562c 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/arduino_foc_bldc_magnetic_spi.ino +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/esp32_bldc_magnetic_spi.ino @@ -37,13 +37,15 @@ * */ #include "src/BLDCMotor.h" -#include "src/MagneticSensorSPI.h" +#include "src/drivers/BLDCDriver3PWM.h" +#include "src/sensors/MagneticSensorSPI.h" // SPI magnetic sensor instance MagneticSensorSPI sensor = MagneticSensorSPI(10, 14, 0x3FFF); -// motor instance -BLDCMotor motor = BLDCMotor(9, 5, 6, 11, 7); +// BLDC motor & driver instance +BLDCMotor motor = BLDCMotor(11); +BLDCDriver3PWM driver = BLDCDriver3PWM(12, 13, 14, 27); void setup() { @@ -52,12 +54,16 @@ void setup() { // link the motor to the sensor motor.linkSensor(&sensor); + // driver config + // power supply voltage [V] + driver.voltage_power_supply = 12; + driver.init(); + // link driver + motor.linkDriver(&driver); + // choose FOC modulation motor.foc_modulation = FOCModulationType::SpaceVectorPWM; - // power supply voltage [V] - motor.voltage_power_supply = 12; - // set control loop type to be used motor.controller = ControlType::voltage; @@ -97,7 +103,6 @@ void setup() { _delay(1000); } -long t = 0; void loop() { // iterative setting FOC phase voltage @@ -107,8 +112,7 @@ void loop() { // velocity, position or voltage // if tatget not set in parameter uses motor.target variable motor.move(); - t>1000 ? t = 0 : t++; - if(!t) Serial.println(_micros()); + // user communication motor.command(serialReceiveUserCommand()); } @@ -138,4 +142,4 @@ String serialReceiveUserCommand() { } } return command; -} +} \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/BLDCMotor.cpp b/minimal_project_examples/esp32_bldc_magnetic_spi/src/BLDCMotor.cpp similarity index 65% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/BLDCMotor.cpp rename to minimal_project_examples/esp32_bldc_magnetic_spi/src/BLDCMotor.cpp index 989b74a9..5d36ce35 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/BLDCMotor.cpp +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/BLDCMotor.cpp @@ -1,41 +1,39 @@ #include "BLDCMotor.h" -// BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// // BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// // - phA, phB, phC - motor A,B,C phase pwm pins +// // - pp - pole pair number +// // - cpr - counts per rotation number (cpm=ppm*4) +// // - enable pin - (optional input) +// BLDCMotor::BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en){ +// noop; +// } + +// BLDCMotor( int pp) // - phA, phB, phC - motor A,B,C phase pwm pins // - pp - pole pair number // - cpr - counts per rotation number (cpm=ppm*4) // - enable pin - (optional input) -BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en) +BLDCMotor::BLDCMotor(int pp) : FOCMotor() { - // Pin initialization - pwmA = phA; - pwmB = phB; - pwmC = phC; + // save pole pairs number pole_pairs = pp; - - // enable_pin pin - enable_pin = en; - } -// init hardware pins -void BLDCMotor::init(long pwm_frequency) { - if(monitor_port) monitor_port->println("MOT: Init pins."); - // PWM pins - pinMode(pwmA, OUTPUT); - pinMode(pwmB, OUTPUT); - pinMode(pwmC, OUTPUT); - if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); - - if(monitor_port) monitor_port->println("MOT: PWM config."); - // Increase PWM frequency to 32 kHz - // make silent - _setPwmFrequency(pwm_frequency, pwmA, pwmB, pwmC); +/** + Link the driver which controls the motor +*/ +void BLDCMotor::linkDriver(BLDCDriver* _driver) { + driver = _driver; +} +// init hardware pins +void BLDCMotor::init() { + if(monitor_port) monitor_port->println("MOT: Initialise variables."); // sanity check for the voltage limit configuration - if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + if(voltage_limit > driver->voltage_limit) voltage_limit = driver->voltage_limit; // constrain voltage for sensor alignment if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; // update the controller limits @@ -44,7 +42,7 @@ void BLDCMotor::init(long pwm_frequency) { _delay(500); // enable motor - if(monitor_port) monitor_port->println("MOT: Enable."); + if(monitor_port) monitor_port->println("MOT: Enable driver."); enable(); _delay(500); } @@ -53,18 +51,18 @@ void BLDCMotor::init(long pwm_frequency) { // disable motor driver void BLDCMotor::disable() { - // disable the driver - if enable_pin pin available - if (enable_pin != NOT_SET) digitalWrite(enable_pin, LOW); // set zero to PWM - setPwm(0, 0, 0); + driver->setPwm(0, 0, 0); + // disable the driver + driver->disable(); } // enable motor driver void BLDCMotor::enable() { + // enable the driver + driver->enable(); // set zero to PWM - setPwm(0, 0, 0); - // enable_pin the driver - if enable_pin pin available - if (enable_pin != NOT_SET) digitalWrite(enable_pin, HIGH); + driver->setPwm(0, 0, 0); } @@ -95,18 +93,18 @@ int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction int BLDCMotor::alignSensor() { if(monitor_port) monitor_port->println("MOT: Align sensor."); // align the electrical phases of the motor and sensor - // set angle -90 degrees + // set angle -90 degrees float start_angle = shaftAngle(); for (int i = 0; i <=5; i++ ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } float mid_angle = shaftAngle(); for (int i = 5; i >=0; i-- ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } if (mid_angle < start_angle) { @@ -114,6 +112,8 @@ int BLDCMotor::alignSensor() { sensor->natural_direction = Direction::CCW; } else if (mid_angle == start_angle) { if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } else{ + if(monitor_port) monitor_port->println("MOT: natural_direction==CW"); } // let the motor stabilize for 2 sec @@ -121,7 +121,7 @@ int BLDCMotor::alignSensor() { // set sensor to zero sensor->initRelativeZero(); _delay(500); - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); _delay(200); // find the index if available @@ -136,24 +136,24 @@ int BLDCMotor::alignSensor() { } -// Encoder alignment the absolute zero angle +// Encoder alignment the absolute zero angle // - to the index int BLDCMotor::absoluteZeroAlign() { if(monitor_port) monitor_port->println("MOT: Absolute zero align."); // if no absolute zero return if(!sensor->hasAbsoluteZero()) return 0; - + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); // search the absolute zero with small velocity while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ - loopFOC(); + loopFOC(); voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); } voltage_q = 0; // disable motor - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); // align absolute zero if it has been found if(!sensor->needsAbsoluteZeroSearch()){ @@ -169,10 +169,10 @@ int BLDCMotor::absoluteZeroAlign() { // Iterative function looping FOC algorithm, setting Uq on the Motor // The faster it can be run the better void BLDCMotor::loopFOC() { - // shaft angle + // shaft angle shaft_angle = shaftAngle(); - // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, voltage_d, _electricalAngle(shaft_angle,pole_pairs)); } // Iterative function running outer loop of the FOC algorithm @@ -219,37 +219,92 @@ void BLDCMotor::move(float new_target) { } -// Method using FOC to set Uq to the motor at the optimal angle +// Method using FOC to set Uq and Ud to the motor at the optimal angle // Function implementing Space Vector PWM and Sine PWM algorithms -// +// // Function using sine approximation // regular sin + cos ~300us (no memory usaage) // approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { +void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { + + const bool centered = true; + int sector; + float _ca,_sa; + switch (foc_modulation) { + case FOCModulationType::Trapezoid_120 : + // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 5 + static int trap_120_map[6][3] = { + {0,1,-1},{-1,1,0},{-1,0,1},{0,-1,1},{1,-1,0},{1,0,-1} // each is 60 degrees with values for 3 phases of 1=positive -1=negative 0=high-z + }; + // static int trap_120_state = 0; + sector = 6 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes + + Ua = Uq + trap_120_map[sector][0] * Uq; + Ub = Uq + trap_120_map[sector][1] * Uq; + Uc = Uq + trap_120_map[sector][2] * Uq; + + if (centered) { + Ua += (driver->voltage_limit)/2 -Uq; + Ub += (driver->voltage_limit)/2 -Uq; + Uc += (driver->voltage_limit)/2 -Uq; + } + break; + + case FOCModulationType::Trapezoid_150 : + // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 8 + static int trap_150_map[12][3] = { + {0,1,-1},{-1,1,-1},{-1,1,0},{-1,1,1},{-1,0,1},{-1,-1,1},{0,-1,1},{1,-1,1},{1,-1,0},{1,-1,-1},{1,0,-1},{1,1,-1} // each is 30 degrees with values for 3 phases of 1=positive -1=negative 0=high-z + }; + // static int trap_150_state = 0; + sector = 12 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes + + Ua = Uq + trap_150_map[sector][0] * Uq; + Ub = Uq + trap_150_map[sector][1] * Uq; + Uc = Uq + trap_150_map[sector][2] * Uq; + + //center + if (centered) { + Ua += (driver->voltage_limit)/2 -Uq; + Ub += (driver->voltage_limit)/2 -Uq; + Uc += (driver->voltage_limit)/2 -Uq; + } + + break; + case FOCModulationType::SinePWM : - // Sinusoidal PWM modulation + // Sinusoidal PWM modulation // Inverse Park + Clarke transformation // angle normalization in between 0 and 2pi // only necessary if using _sin and _cos - approximation functions angle_el = _normalizeAngle(angle_el + zero_electric_angle); + _ca = _cos(angle_el); + _sa = _sin(angle_el); // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; + Ualpha = _ca * Ud - _sa * Uq; // -sin(angle) * Uq; + Ubeta = _sa * Ud + _ca * Uq; // cos(angle) * Uq; // Clarke transform - Ua = Ualpha + voltage_power_supply/2; - Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2; - Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2; + Ua = Ualpha + driver->voltage_limit/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + driver->voltage_limit/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + driver->voltage_limit/2; + + if (!centered) { + float Umin = min(Ua, min(Ub, Uc)); + Ua -= Umin; + Ub -= Umin; + Uc -= Umin; + } + break; case FOCModulationType::SpaceVectorPWM : - // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm // https://www.youtube.com/watch?v=QMSWUMEAejg - // if negative voltages change inverse the phase + // if negative voltages change inverse the phase // angle + 180degrees if(Uq < 0) angle_el += _PI; Uq = abs(Uq); @@ -259,18 +314,18 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { angle_el = _normalizeAngle(angle_el + zero_electric_angle + _PI_2); // find the sector we are in currently - int sector = floor(angle_el / _PI_3) + 1; + sector = floor(angle_el / _PI_3) + 1; // calculate the duty cycles - float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply; - float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply; - // two versions possible - // centered around voltage_power_supply/2 - float T0 = 1 - T1 - T2; - // pulled to 0 - better for low power supply voltage - //float T0 = 0; + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/driver->voltage_limit; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/driver->voltage_limit; + // two versions possible + float T0 = 0; // pulled to 0 - better for low power supply voltage + if (centered) { + T0 = 1 - T1 - T2; //centered around driver->voltage_limit/2 + } // calculate the duty cycles(times) - float Ta,Tb,Tc; + float Ta,Tb,Tc; switch(sector){ case 1: Ta = T1 + T2 + T0/2; @@ -310,27 +365,15 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) { } // calculate the phase voltages and center - Ua = Ta*voltage_power_supply; - Ub = Tb*voltage_power_supply; - Uc = Tc*voltage_power_supply; + Ua = Ta*driver->voltage_limit; + Ub = Tb*driver->voltage_limit; + Uc = Tc*driver->voltage_limit; break; - } - - // set the voltages in hardware - setPwm(Ua, Ub, Uc); -} - + } -// Set voltage to the pwm pin -void BLDCMotor::setPwm(float Ua, float Ub, float Uc) { - // calculate duty cycle - // limited in [0,1] - float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 ); - float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 ); - float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 ); - // hardware specific writing - _writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC ); + // set the voltages in driver + driver->setPwm(Ua, Ub, Uc); } @@ -345,10 +388,10 @@ void BLDCMotor::velocityOpenloop(float target_velocity){ float Ts = (now_us - open_loop_timestamp) * 1e-6; // calculate the necessary angle to achieve target velocity - shaft_angle += target_velocity*Ts; + shaft_angle += target_velocity*Ts; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; @@ -362,17 +405,17 @@ void BLDCMotor::angleOpenloop(float target_angle){ unsigned long now_us = _micros(); // calculate the sample time from last call float Ts = (now_us - open_loop_timestamp) * 1e-6; - + // calculate the necessary angle to move from current position towards target angle // with maximal velocity (velocity_limit) if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) - shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; else shaft_angle = target_angle; - + // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle, pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; -} \ No newline at end of file +} diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/BLDCMotor.h b/minimal_project_examples/esp32_bldc_magnetic_spi/src/BLDCMotor.h similarity index 71% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/BLDCMotor.h rename to minimal_project_examples/esp32_bldc_magnetic_spi/src/BLDCMotor.h index a4fbb678..164cc108 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/BLDCMotor.h +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/BLDCMotor.h @@ -1,16 +1,12 @@ -/** - * @file BLDCMotor.h - * - */ - #ifndef BLDCMotor_h #define BLDCMotor_h #include "Arduino.h" -#include "common/FOCMotor.h" +#include "common/base_classes/FOCMotor.h" +#include "common/base_classes/Sensor.h" +#include "common/base_classes/BLDCDriver.h" #include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "common/time_utils.h" #include "common/defaults.h" /** @@ -20,18 +16,27 @@ class BLDCMotor: public FOCMotor { public: /** - BLDCMotor class constructor - @param phA A phase pwm pin - @param phB B phase pwm pin - @param phC C phase pwm pin - @param pp pole pair number - @param cpr counts per rotation number (cpm=ppm*4) - @param en enable pin (optional input) + BLDCMotor class constructor + @param pp pole pairs number + */ + BLDCMotor(int pp); + + /** + * Function linking a motor and a foc driver + * + * @param driver BLDCDriver class implementing all the hardware specific functions necessary PWM setting + */ + void linkDriver(BLDCDriver* driver); + + /** + * BLDCDriver link: + * - 3PWM + * - 6PWM */ - BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET); + BLDCDriver* driver; /** Motor hardware init function */ - void init(long pwm_frequency = NOT_SET) override; + void init() override; /** Motor disable function */ void disable() override; /** Motor enable function */ @@ -59,12 +64,9 @@ class BLDCMotor: public FOCMotor * This function doesn't need to be run upon each loop execution - depends of the use case */ void move(float target = NOT_SET) override; - - // hardware variables - int pwmA; //!< phase A pwm pin number - int pwmB; //!< phase B pwm pin number - int pwmC; //!< phase C pwm pin number - int enable_pin; //!< enable pin number + + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform private: @@ -74,21 +76,15 @@ class BLDCMotor: public FOCMotor * Heart of the FOC algorithm * * @param Uq Current voltage in q axis to set to the motor + * @param Ud Current voltage in d axis to set to the motor * @param angle_el current electrical angle of the motor */ - void setPhaseVoltage(float Uq, float angle_el); + void setPhaseVoltage(float Uq, float Ud, float angle_el); /** Sensor alignment to electrical 0 angle of the motor */ int alignSensor(); /** Motor and sensor alignment to the sensors absolute 0 angle */ int absoluteZeroAlign(); - /** - * Set phase voltages to the harware - * - * @param Ua phase A voltage - * @param Ub phase B voltage - * @param Uc phase C voltage - */ - void setPwm(float Ua, float Ub, float Uc); + // Open loop motion control /** diff --git a/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/BLDCDriver.h b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/BLDCDriver.h new file mode 100644 index 00000000..708323fb --- /dev/null +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/BLDCDriver.h @@ -0,0 +1,28 @@ +#ifndef BLDCDRIVER_H +#define BLDCDRIVER_H + +class BLDCDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + virtual void setPwm(float Ua, float Ub, float Uc); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/FOCMotor.cpp b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/FOCMotor.cpp similarity index 98% rename from minimal_project_examples/arduino_foc_stepper_openloop/src/common/FOCMotor.cpp rename to minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/FOCMotor.cpp index adecbeec..1d1a0f43 100644 --- a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/FOCMotor.cpp +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/FOCMotor.cpp @@ -5,13 +5,10 @@ */ FOCMotor::FOCMotor() { - // Power supply voltage - voltage_power_supply = DEF_POWER_SUPPLY; - // maximum angular velocity to be used for positioning velocity_limit = DEF_VEL_LIM; // maximum voltage to be set to the motor - voltage_limit = voltage_power_supply; + voltage_limit = DEF_POWER_SUPPLY; // index search velocity velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; @@ -26,6 +23,8 @@ FOCMotor::FOCMotor() // default target value target = 0; + voltage_d = 0; + voltage_q = 0; //monitor_port monitor_port = nullptr; @@ -53,9 +52,6 @@ float FOCMotor::shaftVelocity() { return LPF_velocity(sensor->getVelocity()); } - - - /** * Monitoring functions */ diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/FOCMotor.h b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/FOCMotor.h similarity index 93% rename from minimal_project_examples/arduino_foc_stepper_encoder/src/common/FOCMotor.h rename to minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/FOCMotor.h index 40f7f6d4..986e1ab2 100644 --- a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/FOCMotor.h +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/FOCMotor.h @@ -2,13 +2,14 @@ #define FOCMOTOR_H #include "Arduino.h" -#include "hardware_utils.h" -#include "foc_utils.h" -#include "defaults.h" - #include "Sensor.h" -#include "pid.h" -#include "lowpass_filter.h" +#include "BLDCDriver.h" + +#include "../time_utils.h" +#include "../foc_utils.h" +#include "../defaults.h" +#include "../pid.h" +#include "../lowpass_filter.h" /** @@ -27,7 +28,9 @@ enum ControlType{ */ enum FOCModulationType{ SinePWM, //!< Sinusoidal PWM modulation - SpaceVectorPWM //!< Space vector modulation method + SpaceVectorPWM, //!< Space vector modulation method + Trapezoid_120, + Trapezoid_150 }; /** @@ -42,7 +45,7 @@ class FOCMotor FOCMotor(); /** Motor hardware init function */ - virtual void init(long pwm_frequency)=0; + virtual void init()=0; /** Motor disable function */ virtual void disable()=0; /** Motor enable function */ @@ -55,6 +58,7 @@ class FOCMotor */ void linkSensor(Sensor* sensor); + /** * Function initializing FOC algorithm * and aligning sensor's and motors' zero position @@ -99,11 +103,9 @@ class FOCMotor float shaft_velocity_sp;//!< current target velocity float shaft_angle_sp;//!< current target angle float voltage_q;//!< current voltage u_q set - float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor - float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform + float voltage_d;//!< current voltage u_d set // motor configuration parameters - float voltage_power_supply;//!< Power supply voltage float voltage_sensor_align;//!< sensor and motor align voltage parameter float velocity_index_search;//!< target velocity for index search int pole_pairs;//!< Motor pole pairs number diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/Sensor.h b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/Sensor.h similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_encoder/src/common/Sensor.h rename to minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/Sensor.h diff --git a/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/StepperDriver.h b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/StepperDriver.h new file mode 100644 index 00000000..7800a4e7 --- /dev/null +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/base_classes/StepperDriver.h @@ -0,0 +1,27 @@ +#ifndef STEPPERDRIVER_H +#define STEPPERDRIVER_H + +class StepperDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + */ + virtual void setPwm(float Ua, float Ub); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/defaults.h b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/defaults.h similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_encoder/src/common/defaults.h rename to minimal_project_examples/esp32_bldc_magnetic_spi/src/common/defaults.h diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/foc_utils.cpp b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/foc_utils.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_encoder/src/common/foc_utils.cpp rename to minimal_project_examples/esp32_bldc_magnetic_spi/src/common/foc_utils.cpp diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/foc_utils.h b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/foc_utils.h similarity index 94% rename from minimal_project_examples/arduino_foc_stepper_encoder/src/common/foc_utils.h rename to minimal_project_examples/esp32_bldc_magnetic_spi/src/common/foc_utils.h index 5ab34f42..7da3f7bc 100644 --- a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/foc_utils.h +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/foc_utils.h @@ -6,6 +6,7 @@ // sign function #define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) #define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) +#define _constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt))) // utility defines #define _2_SQRT3 1.15470053838 @@ -20,7 +21,6 @@ #define _2PI 6.28318530718 #define _3PI_2 4.71238898038 - #define NOT_SET -12345.0 /** diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/lowpass_filter.cpp b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/lowpass_filter.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_encoder/src/common/lowpass_filter.cpp rename to minimal_project_examples/esp32_bldc_magnetic_spi/src/common/lowpass_filter.cpp diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/lowpass_filter.h b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/lowpass_filter.h similarity index 94% rename from minimal_project_examples/arduino_foc_stepper_encoder/src/common/lowpass_filter.h rename to minimal_project_examples/esp32_bldc_magnetic_spi/src/common/lowpass_filter.h index 5a7619cf..7c51be54 100644 --- a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/lowpass_filter.h +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/lowpass_filter.h @@ -2,7 +2,7 @@ #define LOWPASS_FILTER_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/pid.cpp b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/pid.cpp similarity index 92% rename from minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/pid.cpp rename to minimal_project_examples/esp32_bldc_magnetic_spi/src/common/pid.cpp index 277e17ce..1a0a9828 100644 --- a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/pid.cpp +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/pid.cpp @@ -25,12 +25,12 @@ float PIDController::operator() (float error){ // Discrete implementations // proportional part // u_p = P *e(k) - float proportional = P * error_prev; + float proportional = P * error; // Tustin transform of the integral part // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) float integral = integral_prev + I*Ts*0.5*(error + error_prev); // antiwindup - limit the output voltage_q - integral = constrain(integral, -limit, limit); + integral = _constrain(integral, -limit, limit); // Discrete derivation // u_dk = D(ek - ek_1)/Ts float derivative = D*(error - error_prev)/Ts; @@ -38,7 +38,7 @@ float PIDController::operator() (float error){ // sum all the components float output = proportional + integral + derivative; // antiwindup - limit the output variable - output = constrain(output, -limit, limit); + output = _constrain(output, -limit, limit); // limit the acceleration by ramping the output float output_rate = (output - output_prev)/Ts; diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/pid.h b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/pid.h similarity index 97% rename from minimal_project_examples/arduino_foc_stepper_openloop/src/common/pid.h rename to minimal_project_examples/esp32_bldc_magnetic_spi/src/common/pid.h index 7ee337c4..0e9ddf54 100644 --- a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/pid.h +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/pid.h @@ -2,7 +2,7 @@ #define PID_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" /** diff --git a/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/time_utils.cpp b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/time_utils.cpp new file mode 100644 index 00000000..b00a8c78 --- /dev/null +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/time_utils.cpp @@ -0,0 +1,31 @@ +#include "time_utils.h" + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega2560__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega2560__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/time_utils.h b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/time_utils.h new file mode 100644 index 00000000..143d4853 --- /dev/null +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/common/time_utils.h @@ -0,0 +1,22 @@ +#ifndef TIME_UTILS_H +#define TIME_UTILS_H + +#include "foc_utils.h" + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/esp32_bldc_magnetic_spi/src/drivers/BLDCDriver3PWM.cpp b/minimal_project_examples/esp32_bldc_magnetic_spi/src/drivers/BLDCDriver3PWM.cpp new file mode 100644 index 00000000..a3fc052d --- /dev/null +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/drivers/BLDCDriver3PWM.cpp @@ -0,0 +1,72 @@ +#include "BLDCDriver3PWM.h" + +BLDCDriver3PWM::BLDCDriver3PWM(int phA, int phB, int phC, int en){ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + + // enable_pin pin + enable_pin = en; + + // default power-supply value + voltage_power_supply = DEF_POWER_SUPPLY; + voltage_limit = NOT_SET; + +} + +// enable motor driver +void BLDCDriver3PWM::enable(){ + // enable_pin the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, HIGH); + // set zero to PWM + setPwm(0,0,0); +} + +// disable motor driver +void BLDCDriver3PWM::disable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // disable the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, LOW); + +} + +// init hardware pins +int BLDCDriver3PWM::init() { + // a bit of separation + _delay(1000); + + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); + + + // sanity check for the voltage limit configuration + if(voltage_limit == NOT_SET || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + + // Set the pwm frequency to the pins + // hardware specific function - depending on driver and mcu + _configure3PWM(pwm_frequency, pwmA, pwmB, pwmC); + return 0; +} + + +// Set voltage to the pwm pin +void BLDCDriver3PWM::setPwm(float Ua, float Ub, float Uc) { + // limit the voltage in driver + Ua = _constrain(Ua, 0.0, voltage_limit); + Ub = _constrain(Ub, 0.0, voltage_limit); + Uc = _constrain(Uc, 0.0, voltage_limit); + // calculate duty cycle + // limited in [0,1] + float dc_a = _constrain(Ua / voltage_power_supply, 0.0 , 1.0 ); + float dc_b = _constrain(Ub / voltage_power_supply, 0.0 , 1.0 ); + float dc_c = _constrain(Uc / voltage_power_supply, 0.0 , 1.0 ); + // hardware specific writing + // hardware specific function - depending on driver and mcu + _writeDutyCycle3PWM(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC); +} \ No newline at end of file diff --git a/minimal_project_examples/esp32_bldc_magnetic_spi/src/drivers/BLDCDriver3PWM.h b/minimal_project_examples/esp32_bldc_magnetic_spi/src/drivers/BLDCDriver3PWM.h new file mode 100644 index 00000000..b6f7d7f8 --- /dev/null +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/drivers/BLDCDriver3PWM.h @@ -0,0 +1,52 @@ +#ifndef BLDCDriver3PWM_h +#define BLDCDriver3PWM_h + +#include "../common/base_classes/BLDCDriver.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#include "../common/defaults.h" +#include "hardware_api.h" + +/** + 3 pwm bldc driver class +*/ +class BLDCDriver3PWM: public BLDCDriver +{ + public: + /** + BLDCDriver class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param en enable pin (optional input) + */ + BLDCDriver3PWM(int phA,int phB,int phC, int en = NOT_SET); + + /** Motor hardware init function */ + int init() override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc) override; + + private: + +}; + + +#endif diff --git a/minimal_project_examples/esp32_bldc_magnetic_spi/src/drivers/hardware_api.h b/minimal_project_examples/esp32_bldc_magnetic_spi/src/drivers/hardware_api.h new file mode 100644 index 00000000..01c03867 --- /dev/null +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/drivers/hardware_api.h @@ -0,0 +1,123 @@ +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H + +#include "../common/foc_utils.h" +#include "../common/time_utils.h" + +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + */ +void _configure2PWM(long pwm_frequency, const int pinA, const int pinB); + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + * @param pinC pinC bldc driver + */ +void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC); + +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pin1A pin1A stepper driver + * @param pin1B pin1B stepper driver + * @param pin2A pin2A stepper driver + * @param pin2B pin2B stepper driver + */ +void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B); + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low - if applicable + * @param pinA_h pinA high-side bldc driver + * @param pinA_l pinA low-side bldc driver + * @param pinB_h pinA high-side bldc driver + * @param pinB_l pinA low-side bldc driver + * @param pinC_h pinA high-side bldc driver + * @param pinC_l pinA low-side bldc driver + * + * @return 0 if config good, -1 if failed + */ +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + */ +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low + * @param pinA_h phase A high-side hardware pin number + * @param pinA_l phase A low-side hardware pin number + * @param pinB_h phase B high-side hardware pin number + * @param pinB_l phase B low-side hardware pin number + * @param pinC_h phase C high-side hardware pin number + * @param pinC_l phase C low-side hardware pin number + * + */ +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l); + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/esp32_mcu.cpp b/minimal_project_examples/esp32_bldc_magnetic_spi/src/drivers/hardware_specific/esp32_mcu.cpp similarity index 57% rename from minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/esp32_mcu.cpp rename to minimal_project_examples/esp32_bldc_magnetic_spi/src/drivers/hardware_specific/esp32_mcu.cpp index 3c07a445..983d4d54 100644 --- a/minimal_project_examples/atmega328_driver_standalone/src/drivers/hardware_specific/esp32_mcu.cpp +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/drivers/hardware_specific/esp32_mcu.cpp @@ -10,6 +10,17 @@ #define _EMPTY_SLOT -20 #define _TAKEN_SLOT -21 +// ABI bus frequency - would be better to take it from somewhere +// but I did nto find a good exposed variable +#define _MCPWM_FREQ 160e6 + +// preferred pwm resolution default +#define _PWM_RES_DEF 2048 +// min resolution +#define _PWM_RES_MIN 1500 +// max resolution +#define _PWM_RES_MAX 3000 + // structure containing motor slot configuration // this library supports up to 4 motors typedef struct { @@ -31,7 +42,15 @@ typedef struct { mcpwm_io_signals_t mcpwm_1b; mcpwm_io_signals_t mcpwm_2a; mcpwm_io_signals_t mcpwm_2b; -} stepper_motor_slots_t; +} stepper_4pwm_motor_slots_t; +typedef struct { + int pin1pwm; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; +} stepper_2pwm_motor_slots_t; typedef struct { int pinAH; @@ -55,41 +74,87 @@ bldc_3pwm_motor_slots_t esp32_bldc_3pwm_motor_slots[4] = { {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B }; -// define stepper motor slots array -stepper_motor_slots_t esp32_stepper_motor_slots[2] = { - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 - }; - // define stepper motor slots array bldc_6pwm_motor_slots_t esp32_bldc_6pwm_motor_slots[2] = { {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0 {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0 }; +// define 4pwm stepper motor slots array +stepper_4pwm_motor_slots_t esp32_stepper_4pwm_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + }; + +// define 2pwm stepper motor slots array +stepper_2pwm_motor_slots_t esp32_stepper_2pwm_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B} // 4th motor will be MCPWM1 channel B + }; + // configuring high frequency pwm timer // a lot of help from this post from Paul Gauld // https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit, float dead_zone = NOT_SET){ mcpwm_config_t pwm_config; - pwm_config.frequency = pwm_frequency; //frequency pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings - + if (dead_zone != NOT_SET){ - // dead zone is configured in dead_time x 100 nanoseconds - float dead_time = (float)(1e7 / pwm_frequency) * dead_zone; - mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); - mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); - mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); + // dead zone is configured + float dead_time = (float)(_MCPWM_FREQ / (pwm_frequency)) * dead_zone; + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time/2.0, dead_time/2.0); + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time/2.0, dead_time/2.0); + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time/2.0, dead_time/2.0); } - _delay(100); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); + + // manual configuration due to the lack of config flexibility in mcpwm_init() + mcpwm_num->clk_cfg.prescale = 0; + // calculate prescaler and period + // step 1: calculate the prescaler using the default pwm resolution + // prescaler = bus_freq / (pwm_freq * default_pwm_res) - 1 + int prescaler = ceil((double)_MCPWM_FREQ / (double)_PWM_RES_DEF / 2.0 / (double)pwm_frequency) - 1; + // constrain prescaler + prescaler = _constrain(prescaler, 0, 128); + // now calculate the real resolution timer period necessary (pwm resolution) + // pwm_res = bus_freq / (pwm_freq * (prescaler + 1)) + int resolution_corrected = (double)_MCPWM_FREQ / 2.0 / (double)pwm_frequency / (double)(prescaler + 1); + // if pwm resolution too low lower the prescaler + if(resolution_corrected < _PWM_RES_MIN && prescaler > 0 ) + resolution_corrected = (double)_MCPWM_FREQ / 2.0 / (double)pwm_frequency / (double)(--prescaler + 1); + resolution_corrected = _constrain(resolution_corrected, _PWM_RES_MIN, _PWM_RES_MAX); + + // set prescaler + mcpwm_num->timer[0].period.prescale = prescaler; + mcpwm_num->timer[1].period.prescale = prescaler; + mcpwm_num->timer[2].period.prescale = prescaler; + _delay(1); + //set period + mcpwm_num->timer[0].period.period = resolution_corrected; + mcpwm_num->timer[1].period.period = resolution_corrected; + mcpwm_num->timer[2].period.period = resolution_corrected; + _delay(1); + mcpwm_num->timer[0].period.upmethod = 0; + mcpwm_num->timer[1].period.upmethod = 0; + mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + //restart the timers + mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); + _delay(1); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); @@ -99,6 +164,51 @@ void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm mcpwm_num->timer[0].sync.out_sel = 0; } +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 2PWM setting +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) { + + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 40kHz max - centered pwm has twice lower frequency + + stepper_2pwm_motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + int slot_num; + for(slot_num = 0; slot_num < 4; slot_num++){ + if(esp32_stepper_2pwm_motor_slots[slot_num].pin1pwm == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_2pwm_motor_slots[slot_num].pin1pwm = pinA; + m_slot = esp32_stepper_2pwm_motor_slots[slot_num]; + break; + } + } + + // disable all the slots with the same MCPWM + // disable 3pwm bldc motor which would go in the same slot + esp32_bldc_3pwm_motor_slots[slot_num].pinA = _TAKEN_SLOT; + if( slot_num < 2 ){ + // slot 0 of the 4pwm stepper + esp32_stepper_4pwm_motor_slots[0].pin1A = _TAKEN_SLOT; + // slot 0 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; + }else{ + // slot 1 of the stepper + esp32_stepper_4pwm_motor_slots[1].pin1A = _TAKEN_SLOT; + // slot 1 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; + } + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + +} + // function setting the high pwm frequency to the supplied pins // - BLDC motor - 3PWM setting @@ -106,8 +216,8 @@ void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm // supports Arudino/ATmega328, STM32 and ESP32 void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { - if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = _constrain(2*pwm_frequency, 0, 100000); // constrain to 50kHz max - centered pwm has twice lower frequency + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 40kHz max - centered pwm has twice lower frequency bldc_3pwm_motor_slots_t m_slot = {}; @@ -122,14 +232,16 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int } } // disable all the slots with the same MCPWM + // disable 2pwm steppr motor which would go in the same slot + esp32_stepper_2pwm_motor_slots[slot_num].pin1pwm = _TAKEN_SLOT; if( slot_num < 2 ){ - // slot 0 of the stepper - esp32_stepper_motor_slots[0].pin1A = _TAKEN_SLOT; + // slot 0 of the 4pwm stepper + esp32_stepper_4pwm_motor_slots[0].pin1A = _TAKEN_SLOT; // slot 0 of the 6pwm bldc esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; }else{ // slot 1 of the stepper - esp32_stepper_motor_slots[1].pin1A = _TAKEN_SLOT; + esp32_stepper_4pwm_motor_slots[1].pin1A = _TAKEN_SLOT; // slot 1 of the 6pwm bldc esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; } @@ -149,16 +261,16 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int // - hardware speciffic void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { - if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = _constrain(2*pwm_frequency, 0, 100000); // constrain to 50kHz max - centered pwm has twice lower frequency - stepper_motor_slots_t m_slot = {}; + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 50kHz max - centered pwm has twice lower frequency + stepper_4pwm_motor_slots_t m_slot = {}; // determine which motor are we connecting // and set the appropriate configuration parameters int slot_num; for(slot_num = 0; slot_num < 2; slot_num++){ - if(esp32_stepper_motor_slots[slot_num].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_stepper_motor_slots[slot_num].pin1A = pinA; - m_slot = esp32_stepper_motor_slots[slot_num]; + if(esp32_stepper_4pwm_motor_slots[slot_num].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_4pwm_motor_slots[slot_num].pin1A = pinA; + m_slot = esp32_stepper_4pwm_motor_slots[slot_num]; break; } } @@ -167,12 +279,18 @@ void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int // slots 0 and 1 of the 3pwm bldc esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT; esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT; + // slots 0 and 1 of the 2pwm stepper taken + esp32_stepper_2pwm_motor_slots[0].pin1pwm = _TAKEN_SLOT; + esp32_stepper_2pwm_motor_slots[1].pin1pwm = _TAKEN_SLOT; // slot 0 of the 6pwm bldc esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; }else{ // slots 2 and 3 of the 3pwm bldc esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT; esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT; + // slots 2 and 3 of the 2pwm stepper taken + esp32_stepper_2pwm_motor_slots[2].pin1pwm = _TAKEN_SLOT; + esp32_stepper_2pwm_motor_slots[3].pin1pwm = _TAKEN_SLOT; // slot 1 of the 6pwm bldc esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; } @@ -187,6 +305,23 @@ void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); } +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 2PWM setting +// - hardware speciffic +// ESP32 uses MCPWM +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){ + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_stepper_2pwm_motor_slots[i].pin1pwm == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,100] + mcpwm_set_duty(esp32_stepper_2pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_2pwm_motor_slots[i].mcpwm_operator, dc_a*100.0); + mcpwm_set_duty(esp32_stepper_2pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_2pwm_motor_slots[i].mcpwm_operator, dc_b*100.0); + break; + } + } +} + // function setting the pwm duty cycle to the hardware // - BLDC motor - 3PWM setting // - hardware speciffic @@ -212,13 +347,13 @@ void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ // determine which motor slot is the motor connected to for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + if(esp32_stepper_4pwm_motor_slots[i].pin1A == pin1A){ // if motor slot found // se the PWM on the slot timers // transform duty cycle from [0,1] to [0,100] - mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_motor_slots[i].mcpwm_operator1, dc_1a*100.0); - mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_motor_slots[i].mcpwm_operator1, dc_1b*100.0); - mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_motor_slots[i].mcpwm_operator2, dc_2a*100.0); - mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_motor_slots[i].mcpwm_operator2, dc_2b*100.0); + mcpwm_set_duty(esp32_stepper_4pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator1, dc_1a*100.0); + mcpwm_set_duty(esp32_stepper_4pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator1, dc_1b*100.0); + mcpwm_set_duty(esp32_stepper_4pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator2, dc_2a*100.0); + mcpwm_set_duty(esp32_stepper_4pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator2, dc_2b*100.0); break; } } @@ -229,8 +364,8 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in // - hardware specific int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ - if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = _constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 40kHz max - centered pwm has twice lower frequency bldc_6pwm_motor_slots_t m_slot = {}; // determine which motor are we connecting // and set the appropriate configuration parameters @@ -251,13 +386,13 @@ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT; esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT; // slot 0 of the 6pwm bldc - esp32_stepper_motor_slots[0].pin1A = _TAKEN_SLOT; + esp32_stepper_4pwm_motor_slots[0].pin1A = _TAKEN_SLOT; }else{ // slots 2 and 3 of the 3pwm bldc esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT; esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT; // slot 1 of the 6pwm bldc - esp32_stepper_motor_slots[1].pin1A = _TAKEN_SLOT; + esp32_stepper_4pwm_motor_slots[1].pin1A = _TAKEN_SLOT; } // configure pins diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/MagneticSensorSPI.cpp b/minimal_project_examples/esp32_bldc_magnetic_spi/src/sensors/MagneticSensorSPI.cpp similarity index 93% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/MagneticSensorSPI.cpp rename to minimal_project_examples/esp32_bldc_magnetic_spi/src/sensors/MagneticSensorSPI.cpp index 1f63bc11..58660e0b 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/MagneticSensorSPI.cpp +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/sensors/MagneticSensorSPI.cpp @@ -5,7 +5,7 @@ MagneticSensorSPIConfig_s AS5147_SPI = { .spi_mode = SPI_MODE1, .clock_speed = 1000000, .bit_resolution = 14, - .angle_register = 0xCFFF, + .angle_register = 0x3FFF, .data_start_bit = 13, .command_rw_bit = 14, .command_parity_bit = 15 @@ -31,7 +31,7 @@ MagneticSensorSPI::MagneticSensorSPI(int cs, float _bit_resolution, int _angle_r chip_select_pin = cs; // angle read register of the magnetic sensor - angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTAR; + angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTER; // register maximum value (counts per revolution) cpr = pow(2,_bit_resolution); spi_mode = SPI_MODE1; @@ -47,7 +47,7 @@ MagneticSensorSPI::MagneticSensorSPI(int cs, float _bit_resolution, int _angle_r MagneticSensorSPI::MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs){ chip_select_pin = cs; // angle read register of the magnetic sensor - angle_register = config.angle_register ? config.angle_register : DEF_ANGLE_REGISTAR; + angle_register = config.angle_register ? config.angle_register : DEF_ANGLE_REGISTER; // register maximum value (counts per revolution) cpr = pow(2, config.bit_resolution); spi_mode = config.spi_mode; @@ -59,7 +59,10 @@ MagneticSensorSPI::MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs){ data_start_bit = config.data_start_bit; // for backwards compatibilty } -void MagneticSensorSPI::init(){ +void MagneticSensorSPI::init(SPIClass* _spi){ + + spi = _spi; + // 1MHz clock (AMS should be able to accept up to 10MHz) settings = SPISettings(clock_speed, MSBFIRST, spi_mode); @@ -67,11 +70,11 @@ void MagneticSensorSPI::init(){ pinMode(chip_select_pin, OUTPUT); //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices - SPI.begin(); + spi->begin(); #ifndef ESP_H // if not ESP32 board - SPI.setBitOrder(MSBFIRST); // Set the SPI_1 bit order - SPI.setDataMode(spi_mode) ; - SPI.setClockDivider(SPI_CLOCK_DIV8); + spi->setBitOrder(MSBFIRST); // Set the SPI_1 bit order + spi->setDataMode(spi_mode) ; + spi->setClockDivider(SPI_CLOCK_DIV8); #endif digitalWrite(chip_select_pin, HIGH); @@ -203,13 +206,13 @@ word MagneticSensorSPI::read(word angle_register){ #if !defined(_STM32_DEF_) // if not stm chips //SPI - begin transaction - SPI.beginTransaction(settings); + spi->beginTransaction(settings); #endif //Send the command digitalWrite(chip_select_pin, LOW); digitalWrite(chip_select_pin, LOW); - SPI.transfer16(command); + spi->transfer16(command); digitalWrite(chip_select_pin,HIGH); digitalWrite(chip_select_pin,HIGH); @@ -222,18 +225,18 @@ word MagneticSensorSPI::read(word angle_register){ //Now read the response digitalWrite(chip_select_pin, LOW); digitalWrite(chip_select_pin, LOW); - word register_value = SPI.transfer16(0x00); + word register_value = spi->transfer16(0x00); digitalWrite(chip_select_pin, HIGH); digitalWrite(chip_select_pin,HIGH); #if !defined(_STM32_DEF_) // if not stm chips //SPI - end transaction - SPI.endTransaction(); + spi->endTransaction(); #endif register_value = register_value >> (1 + data_start_bit - bit_resolution); //this should shift data to the rightmost bits of the word - const static word data_mask = ~(0 >> (16 - bit_resolution)); + const static word data_mask = 0xFFFF >> (16 - bit_resolution); return register_value & data_mask; // Return the data, stripping the non data (e.g parity) bits } @@ -243,5 +246,5 @@ word MagneticSensorSPI::read(word angle_register){ * SPI has an internal SPI-device counter, for each init()-call the close() function must be called exactly 1 time */ void MagneticSensorSPI::close(){ - SPI.end(); + spi->end(); } diff --git a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/MagneticSensorSPI.h b/minimal_project_examples/esp32_bldc_magnetic_spi/src/sensors/MagneticSensorSPI.h similarity index 94% rename from minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/MagneticSensorSPI.h rename to minimal_project_examples/esp32_bldc_magnetic_spi/src/sensors/MagneticSensorSPI.h index 8e884cf4..05fb9091 100644 --- a/minimal_project_examples/arduino_foc_bldc_magnetic_spi/src/MagneticSensorSPI.h +++ b/minimal_project_examples/esp32_bldc_magnetic_spi/src/sensors/MagneticSensorSPI.h @@ -3,11 +3,11 @@ #include "Arduino.h" #include -#include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "../common/base_classes/Sensor.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" -#define DEF_ANGLE_REGISTAR 0x3FFF +#define DEF_ANGLE_REGISTER 0x3FFF struct MagneticSensorSPIConfig_s { int spi_mode; @@ -38,7 +38,7 @@ class MagneticSensorSPI: public Sensor{ MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs); /** sensor initialise pins */ - void init(); + void init(SPIClass* _spi = &SPI); // implementation of abstract functions of the Sensor class /** get current angle (rad) */ @@ -103,6 +103,7 @@ class MagneticSensorSPI: public Sensor{ int command_rw_bit; //!< the bit where read/write flag is stored in command int data_start_bit; //!< the the position of first bit + SPIClass* spi; }; diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/arduino_foc_stepper_openloop.ino b/minimal_project_examples/esp32_stepper_openloop/esp32_stepper_openloop.ino similarity index 58% rename from minimal_project_examples/arduino_foc_stepper_openloop/arduino_foc_stepper_openloop.ino rename to minimal_project_examples/esp32_stepper_openloop/esp32_stepper_openloop.ino index 080f5469..ef61823d 100644 --- a/minimal_project_examples/arduino_foc_stepper_openloop/arduino_foc_stepper_openloop.ino +++ b/minimal_project_examples/esp32_stepper_openloop/esp32_stepper_openloop.ino @@ -1,49 +1,52 @@ #include "src/StepperMotor.h" +#include "src/drivers/StepperDriver4PWM.h" -// motor instance -StepperMotor motor = StepperMotor(10, 6, 5, 9, 50, 8); +// Stepper motor & driver instance +StepperMotor motor = StepperMotor(50); +StepperDriver4PWM driver = StepperDriver4PWM(27,26,25,33,32); void setup() { - - // power supply voltage - // default 12V - motor.voltage_power_supply = 12; + + // driver config + // power supply voltage [V] + driver.voltage_power_supply = 12; + driver.init(); + // link the motor and the driver + motor.linkDriver(&driver); // limiting motor movements - motor.voltage_limit = 3; // rad/s - motor.velocity_limit = 20; // rad/s + motor.voltage_limit = 3; // [V] + motor.velocity_limit = 20; // [rad/s] + // open loop control config motor.controller = ControlType::velocity_openloop; // init motor hardware motor.init(); - Serial.begin(115200); Serial.println("Motor ready!"); _delay(1000); } -float target_position = 0; // rad/s - +float target_velocity = 0; // [rad/s] void loop() { - // open loop angle movements + // open loop velocity movement // using motor.voltage_limit and motor.velocity_limit - motor.move(2); + motor.move(target_velocity); // receive the used commands from serial serialReceiveUserCommand(); - Serial.println(micros()); } // utility function enabling serial communication with the user to set the target values // this function can be implemented in serialEvent function as well void serialReceiveUserCommand() { - + // a string to hold incoming data static String received_chars; - + while (Serial.available()) { // get the new byte: char inChar = (char)Serial.read(); @@ -51,13 +54,13 @@ void serialReceiveUserCommand() { received_chars += inChar; // end of user input if (inChar == '\n') { - + // change the motor target - target_position = received_chars.toFloat(); - Serial.print("Target position: "); - Serial.println(target_position); - - // reset the command buffer + target_velocity = received_chars.toFloat(); + Serial.print("Target velocity "); + Serial.println(target_velocity); + + // reset the command buffer received_chars = ""; } } diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/StepperMotor.cpp b/minimal_project_examples/esp32_stepper_openloop/src/StepperMotor.cpp similarity index 73% rename from minimal_project_examples/arduino_foc_stepper_openloop/src/StepperMotor.cpp rename to minimal_project_examples/esp32_stepper_openloop/src/StepperMotor.cpp index 22ceb256..31c81eeb 100644 --- a/minimal_project_examples/arduino_foc_stepper_openloop/src/StepperMotor.cpp +++ b/minimal_project_examples/esp32_stepper_openloop/src/StepperMotor.cpp @@ -5,39 +5,26 @@ // - ph2A, ph2B - motor phase 2 pwm pins // - pp - pole pair number // - enable pin - (optional input) -StepperMotor::StepperMotor(int ph1A, int ph1B, int ph2A, int ph2B, int pp, int en1, int en2) +StepperMotor::StepperMotor(int pp) : FOCMotor() { - // Pin initialization - pwm1A = ph1A; - pwm1B = ph1B; - pwm2A = ph2A; - pwm2B = ph2B; + // number od pole pairs pole_pairs = pp; +} - // enable_pin pin - enable_pin1 = en1; - enable_pin2 = en2; +/** + Link the driver which controls the motor +*/ +void StepperMotor::linkDriver(StepperDriver* _driver) { + driver = _driver; } // init hardware pins -void StepperMotor::init(long pwm_frequency) { - if(monitor_port) monitor_port->println("MOT: Init pins."); - // PWM pins - pinMode(pwm1A, OUTPUT); - pinMode(pwm1B, OUTPUT); - pinMode(pwm2A, OUTPUT); - pinMode(pwm2B, OUTPUT); - if ( enable_pin1 != NOT_SET ) pinMode(enable_pin1, OUTPUT); - if ( enable_pin2 != NOT_SET ) pinMode(enable_pin2, OUTPUT); - - if(monitor_port) monitor_port->println("MOT: PWM config."); - // Increase PWM frequency - // make silent - _setPwmFrequency(pwm_frequency, pwm1A, pwm1B, pwm2A, pwm2B); +void StepperMotor::init() { + if(monitor_port) monitor_port->println("MOT: Init variables."); // sanity check for the voltage limit configuration - if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + if(voltage_limit > driver->voltage_limit) voltage_limit = driver->voltage_limit; // constrain voltage for sensor alignment if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; @@ -57,21 +44,18 @@ void StepperMotor::init(long pwm_frequency) { // disable motor driver void StepperMotor::disable() { - // disable the driver - if enable_pin pin available - if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, LOW); - if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, LOW); // set zero to PWM - setPwm(0, 0); + driver->setPwm(0, 0); + // disable driver + driver->disable(); } // enable motor driver void StepperMotor::enable() { + // disable enable + driver->enable(); // set zero to PWM - setPwm(0, 0); - // enable_pin the driver - if enable_pin pin available - if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, HIGH); - if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, HIGH); - + driver->setPwm(0, 0); } @@ -107,13 +91,13 @@ int StepperMotor::alignSensor() { float start_angle = shaftAngle(); for (int i = 0; i <=5; i++ ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } float mid_angle = shaftAngle(); for (int i = 5; i >=0; i-- ) { float angle = _3PI_2 + _2PI * i / 6.0; - setPhaseVoltage(voltage_sensor_align, angle); + setPhaseVoltage(voltage_sensor_align, 0, angle); _delay(200); } if (mid_angle < start_angle) { @@ -121,6 +105,8 @@ int StepperMotor::alignSensor() { sensor->natural_direction = Direction::CCW; } else if (mid_angle == start_angle) { if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } else{ + if(monitor_port) monitor_port->println("MOT: natural_direction==CW"); } // let the motor stabilize for 2 sec @@ -128,7 +114,7 @@ int StepperMotor::alignSensor() { // set sensor to zero sensor->initRelativeZero(); _delay(500); - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); _delay(200); // find the index if available @@ -159,8 +145,9 @@ int StepperMotor::absoluteZeroAlign() { voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); } voltage_q = 0; + voltage_d = 0; // disable motor - setPhaseVoltage(0,0); + setPhaseVoltage(0, 0, 0); // align absolute zero if it has been found if(!sensor->needsAbsoluteZeroSearch()){ @@ -179,7 +166,7 @@ void StepperMotor::loopFOC() { // shaft angle shaft_angle = shaftAngle(); // set the phase voltage - FOC heart function :) - setPhaseVoltage(voltage_q, _electricalAngle(shaft_angle,pole_pairs)); + setPhaseVoltage(voltage_q, voltage_d, _electricalAngle(shaft_angle, pole_pairs)); } // Iterative function running outer loop of the FOC algorithm @@ -226,44 +213,28 @@ void StepperMotor::move(float new_target) { } -// Method using FOC to set Uq to the motor at the optimal angle -// Function implementingSine PWM algorithms +// Method using FOC to set Uq and Ud to the motor at the optimal angle +// Function implementing Sine PWM algorithms // - space vector not implemented yet // // Function using sine approximation // regular sin + cos ~300us (no memory usaage) // approx _sin + _cos ~110us (400Byte ~ 20% of memory) -void StepperMotor::setPhaseVoltage(float Uq, float angle_el) { +void StepperMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { // Sinusoidal PWM modulation // Inverse Park transformation // angle normalization in between 0 and 2pi // only necessary if using _sin and _cos - approximation functions - angle_el = _normalizeAngle(angle_el + zero_electric_angle); + angle_el = _normalizeAngle(angle_el + zero_electric_angle); + float _ca = _cos(angle_el); + float _sa = _sin(angle_el); // Inverse park transform - Ualpha = -_sin(angle_el) * Uq; // -sin(angle) * Uq; - Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq; - // set the voltages in hardware - setPwm(Ualpha,Ubeta); -} + Ualpha = _ca * Ud - _sa * Uq; // -sin(angle) * Uq; + Ubeta = _sa * Ud + _ca * Uq; // cos(angle) * Uq; - - -// Set voltage to the pwm pin -void StepperMotor::setPwm(float Ualpha, float Ubeta) { - float duty_cycle1A(0.0),duty_cycle1B(0.0),duty_cycle2A(0.0),duty_cycle2B(0.0); - // hardware specific writing - if( Ualpha > 0 ) - duty_cycle1B = constrain(abs(Ualpha)/voltage_power_supply,0,1); - else - duty_cycle1A = constrain(abs(Ualpha)/voltage_power_supply,0,1); - - if( Ubeta > 0 ) - duty_cycle2B = constrain(abs(Ubeta)/voltage_power_supply,0,1); - else - duty_cycle2A = constrain(abs(Ubeta)/voltage_power_supply,0,1); - // write to hardware - _writeDutyCycle(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, pwm1A, pwm1B, pwm2A, pwm2B); + // set the voltages in hardware + driver->setPwm(Ualpha, Ubeta); } // Function (iterative) generating open loop movement for target velocity @@ -277,9 +248,9 @@ void StepperMotor::velocityOpenloop(float target_velocity){ // calculate the necessary angle to achieve target velocity shaft_angle += target_velocity*Ts; - + // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle,pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle,pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; @@ -302,7 +273,7 @@ void StepperMotor::angleOpenloop(float target_angle){ shaft_angle = target_angle; // set the maximal allowed voltage (voltage_limit) with the necessary angle - setPhaseVoltage(voltage_limit, _electricalAngle(shaft_angle,pole_pairs)); + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle,pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/StepperMotor.h b/minimal_project_examples/esp32_stepper_openloop/src/StepperMotor.h similarity index 73% rename from minimal_project_examples/arduino_foc_stepper_openloop/src/StepperMotor.h rename to minimal_project_examples/esp32_stepper_openloop/src/StepperMotor.h index bf14e096..af4783bf 100644 --- a/minimal_project_examples/arduino_foc_stepper_openloop/src/StepperMotor.h +++ b/minimal_project_examples/esp32_stepper_openloop/src/StepperMotor.h @@ -7,10 +7,11 @@ #define StepperMotor_h #include "Arduino.h" -#include "common/FOCMotor.h" +#include "common/base_classes/FOCMotor.h" +#include "common/base_classes/StepperDriver.h" +#include "common/base_classes/Sensor.h" #include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "common/time_utils.h" #include "common/defaults.h" /** @@ -21,18 +22,25 @@ class StepperMotor: public FOCMotor public: /** StepperMotor class constructor - @param ph1A 1A phase pwm pin - @param ph1B 1B phase pwm pin - @param ph2A 2A phase pwm pin - @param ph2B 2B phase pwm pin @param pp pole pair number - cpr counts per rotation number (cpm=ppm*4) - @param en1 enable pin phase 1 (optional input) - @param en2 enable pin phase 2 (optional input) */ - StepperMotor(int ph1A,int ph1B,int ph2A,int ph2B,int pp, int en1 = NOT_SET, int en2 = NOT_SET); - + StepperMotor(int pp); + + /** + * Function linking a motor and a foc driver + * + * @param driver StepperDriver class implementing all the hardware specific functions necessary PWM setting + */ + void linkDriver(StepperDriver* driver); + + /** + * StepperDriver link: + * - 4PWM - L298N for example + */ + StepperDriver* driver; + /** Motor hardware init function */ - void init(long pwm_frequency = NOT_SET) override; + void init() override; /** Motor disable function */ void disable() override; /** Motor enable function */ @@ -65,14 +73,8 @@ class StepperMotor: public FOCMotor * This function doesn't need to be run upon each loop execution - depends of the use case */ void move(float target = NOT_SET) override; - - // hardware variables - int pwm1A; //!< phase 1A pwm pin number - int pwm1B; //!< phase 1B pwm pin number - int pwm2A; //!< phase 2A pwm pin number - int pwm2B; //!< phase 2B pwm pin number - int enable_pin1; //!< enable pin number phase 1 - int enable_pin2; //!< enable pin number phase 2 + + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform private: @@ -82,22 +84,15 @@ class StepperMotor: public FOCMotor * Heart of the FOC algorithm * * @param Uq Current voltage in q axis to set to the motor + * @param Ud Current voltage in d axis to set to the motor * @param angle_el current electrical angle of the motor */ - void setPhaseVoltage(float Uq, float angle_el); + void setPhaseVoltage(float Uq, float Ud , float angle_el); /** Sensor alignment to electrical 0 angle of the motor */ int alignSensor(); /** Motor and sensor alignment to the sensors absolute 0 angle */ int absoluteZeroAlign(); - /** - * Set phase voltages to the harware - * - * @param Ua phase A voltage - * @param Ub phase B voltage - * @param Uc phase C voltage - */ - void setPwm(float Ualpha, float Ubeta); // Open loop motion control /** diff --git a/minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/BLDCDriver.h b/minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/BLDCDriver.h new file mode 100644 index 00000000..708323fb --- /dev/null +++ b/minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/BLDCDriver.h @@ -0,0 +1,28 @@ +#ifndef BLDCDRIVER_H +#define BLDCDRIVER_H + +class BLDCDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + virtual void setPwm(float Ua, float Ub, float Uc); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/FOCMotor.cpp b/minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/FOCMotor.cpp similarity index 98% rename from minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/FOCMotor.cpp rename to minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/FOCMotor.cpp index adecbeec..1d1a0f43 100644 --- a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/FOCMotor.cpp +++ b/minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/FOCMotor.cpp @@ -5,13 +5,10 @@ */ FOCMotor::FOCMotor() { - // Power supply voltage - voltage_power_supply = DEF_POWER_SUPPLY; - // maximum angular velocity to be used for positioning velocity_limit = DEF_VEL_LIM; // maximum voltage to be set to the motor - voltage_limit = voltage_power_supply; + voltage_limit = DEF_POWER_SUPPLY; // index search velocity velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; @@ -26,6 +23,8 @@ FOCMotor::FOCMotor() // default target value target = 0; + voltage_d = 0; + voltage_q = 0; //monitor_port monitor_port = nullptr; @@ -53,9 +52,6 @@ float FOCMotor::shaftVelocity() { return LPF_velocity(sensor->getVelocity()); } - - - /** * Monitoring functions */ diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/FOCMotor.h b/minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/FOCMotor.h similarity index 93% rename from minimal_project_examples/arduino_foc_stepper_openloop/src/common/FOCMotor.h rename to minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/FOCMotor.h index 40f7f6d4..986e1ab2 100644 --- a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/FOCMotor.h +++ b/minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/FOCMotor.h @@ -2,13 +2,14 @@ #define FOCMOTOR_H #include "Arduino.h" -#include "hardware_utils.h" -#include "foc_utils.h" -#include "defaults.h" - #include "Sensor.h" -#include "pid.h" -#include "lowpass_filter.h" +#include "BLDCDriver.h" + +#include "../time_utils.h" +#include "../foc_utils.h" +#include "../defaults.h" +#include "../pid.h" +#include "../lowpass_filter.h" /** @@ -27,7 +28,9 @@ enum ControlType{ */ enum FOCModulationType{ SinePWM, //!< Sinusoidal PWM modulation - SpaceVectorPWM //!< Space vector modulation method + SpaceVectorPWM, //!< Space vector modulation method + Trapezoid_120, + Trapezoid_150 }; /** @@ -42,7 +45,7 @@ class FOCMotor FOCMotor(); /** Motor hardware init function */ - virtual void init(long pwm_frequency)=0; + virtual void init()=0; /** Motor disable function */ virtual void disable()=0; /** Motor enable function */ @@ -55,6 +58,7 @@ class FOCMotor */ void linkSensor(Sensor* sensor); + /** * Function initializing FOC algorithm * and aligning sensor's and motors' zero position @@ -99,11 +103,9 @@ class FOCMotor float shaft_velocity_sp;//!< current target velocity float shaft_angle_sp;//!< current target angle float voltage_q;//!< current voltage u_q set - float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor - float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform + float voltage_d;//!< current voltage u_d set // motor configuration parameters - float voltage_power_supply;//!< Power supply voltage float voltage_sensor_align;//!< sensor and motor align voltage parameter float velocity_index_search;//!< target velocity for index search int pole_pairs;//!< Motor pole pairs number diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/Sensor.h b/minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/Sensor.h similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/Sensor.h rename to minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/Sensor.h diff --git a/minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/StepperDriver.h b/minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/StepperDriver.h new file mode 100644 index 00000000..7800a4e7 --- /dev/null +++ b/minimal_project_examples/esp32_stepper_openloop/src/common/base_classes/StepperDriver.h @@ -0,0 +1,27 @@ +#ifndef STEPPERDRIVER_H +#define STEPPERDRIVER_H + +class StepperDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + */ + virtual void setPwm(float Ua, float Ub); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/defaults.h b/minimal_project_examples/esp32_stepper_openloop/src/common/defaults.h similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/defaults.h rename to minimal_project_examples/esp32_stepper_openloop/src/common/defaults.h diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/foc_utils.cpp b/minimal_project_examples/esp32_stepper_openloop/src/common/foc_utils.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/foc_utils.cpp rename to minimal_project_examples/esp32_stepper_openloop/src/common/foc_utils.cpp diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/foc_utils.h b/minimal_project_examples/esp32_stepper_openloop/src/common/foc_utils.h similarity index 94% rename from minimal_project_examples/arduino_foc_stepper_openloop/src/common/foc_utils.h rename to minimal_project_examples/esp32_stepper_openloop/src/common/foc_utils.h index 5ab34f42..7da3f7bc 100644 --- a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/foc_utils.h +++ b/minimal_project_examples/esp32_stepper_openloop/src/common/foc_utils.h @@ -6,6 +6,7 @@ // sign function #define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) #define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) +#define _constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt))) // utility defines #define _2_SQRT3 1.15470053838 @@ -20,7 +21,6 @@ #define _2PI 6.28318530718 #define _3PI_2 4.71238898038 - #define NOT_SET -12345.0 /** diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/lowpass_filter.cpp b/minimal_project_examples/esp32_stepper_openloop/src/common/lowpass_filter.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/lowpass_filter.cpp rename to minimal_project_examples/esp32_stepper_openloop/src/common/lowpass_filter.cpp diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/lowpass_filter.h b/minimal_project_examples/esp32_stepper_openloop/src/common/lowpass_filter.h similarity index 94% rename from minimal_project_examples/arduino_foc_stepper_openloop/src/common/lowpass_filter.h rename to minimal_project_examples/esp32_stepper_openloop/src/common/lowpass_filter.h index 5a7619cf..7c51be54 100644 --- a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/lowpass_filter.h +++ b/minimal_project_examples/esp32_stepper_openloop/src/common/lowpass_filter.h @@ -2,7 +2,7 @@ #define LOWPASS_FILTER_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/pid.cpp b/minimal_project_examples/esp32_stepper_openloop/src/common/pid.cpp similarity index 92% rename from minimal_project_examples/arduino_foc_stepper_openloop/src/common/pid.cpp rename to minimal_project_examples/esp32_stepper_openloop/src/common/pid.cpp index 277e17ce..1a0a9828 100644 --- a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/pid.cpp +++ b/minimal_project_examples/esp32_stepper_openloop/src/common/pid.cpp @@ -25,12 +25,12 @@ float PIDController::operator() (float error){ // Discrete implementations // proportional part // u_p = P *e(k) - float proportional = P * error_prev; + float proportional = P * error; // Tustin transform of the integral part // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) float integral = integral_prev + I*Ts*0.5*(error + error_prev); // antiwindup - limit the output voltage_q - integral = constrain(integral, -limit, limit); + integral = _constrain(integral, -limit, limit); // Discrete derivation // u_dk = D(ek - ek_1)/Ts float derivative = D*(error - error_prev)/Ts; @@ -38,7 +38,7 @@ float PIDController::operator() (float error){ // sum all the components float output = proportional + integral + derivative; // antiwindup - limit the output variable - output = constrain(output, -limit, limit); + output = _constrain(output, -limit, limit); // limit the acceleration by ramping the output float output_rate = (output - output_prev)/Ts; diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/pid.h b/minimal_project_examples/esp32_stepper_openloop/src/common/pid.h similarity index 97% rename from minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/pid.h rename to minimal_project_examples/esp32_stepper_openloop/src/common/pid.h index 7ee337c4..0e9ddf54 100644 --- a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/pid.h +++ b/minimal_project_examples/esp32_stepper_openloop/src/common/pid.h @@ -2,7 +2,7 @@ #define PID_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" /** diff --git a/minimal_project_examples/esp32_stepper_openloop/src/common/time_utils.cpp b/minimal_project_examples/esp32_stepper_openloop/src/common/time_utils.cpp new file mode 100644 index 00000000..b00a8c78 --- /dev/null +++ b/minimal_project_examples/esp32_stepper_openloop/src/common/time_utils.cpp @@ -0,0 +1,31 @@ +#include "time_utils.h" + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega2560__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega2560__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/esp32_stepper_openloop/src/common/time_utils.h b/minimal_project_examples/esp32_stepper_openloop/src/common/time_utils.h new file mode 100644 index 00000000..143d4853 --- /dev/null +++ b/minimal_project_examples/esp32_stepper_openloop/src/common/time_utils.h @@ -0,0 +1,22 @@ +#ifndef TIME_UTILS_H +#define TIME_UTILS_H + +#include "foc_utils.h" + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/esp32_stepper_openloop/src/drivers/StepperDriver4PWM.cpp b/minimal_project_examples/esp32_stepper_openloop/src/drivers/StepperDriver4PWM.cpp new file mode 100644 index 00000000..28e2dcae --- /dev/null +++ b/minimal_project_examples/esp32_stepper_openloop/src/drivers/StepperDriver4PWM.cpp @@ -0,0 +1,81 @@ +#include "StepperDriver4PWM.h" + +StepperDriver4PWM::StepperDriver4PWM(int ph1A,int ph1B,int ph2A,int ph2B,int en1, int en2){ + // Pin initialization + pwm1A = ph1A; + pwm1B = ph1B; + pwm2A = ph2A; + pwm2B = ph2B; + + // enable_pin pin + enable_pin1 = en1; + enable_pin2 = en2; + + // default power-supply value + voltage_power_supply = DEF_POWER_SUPPLY; + voltage_limit = NOT_SET; + +} + +// enable motor driver +void StepperDriver4PWM::enable(){ + // enable_pin the driver - if enable_pin pin available + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, HIGH); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, HIGH); + // set zero to PWM + setPwm(0,0); +} + +// disable motor driver +void StepperDriver4PWM::disable() +{ + // set zero to PWM + setPwm(0, 0); + // disable the driver - if enable_pin pin available + if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, LOW); + if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, LOW); + +} + +// init hardware pins +int StepperDriver4PWM::init() { + // a bit of separation + _delay(1000); + + // PWM pins + pinMode(pwm1A, OUTPUT); + pinMode(pwm1B, OUTPUT); + pinMode(pwm2A, OUTPUT); + pinMode(pwm2B, OUTPUT); + if(enable_pin1 != NOT_SET) pinMode(enable_pin1, OUTPUT); + if(enable_pin2 != NOT_SET) pinMode(enable_pin2, OUTPUT); + + // sanity check for the voltage limit configuration + if(voltage_limit == NOT_SET || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + + // Set the pwm frequency to the pins + // hardware specific function - depending on driver and mcu + _configure4PWM(pwm_frequency, pwm1A, pwm1B, pwm2A, pwm2B); + return 0; +} + + +// Set voltage to the pwm pin +void StepperDriver4PWM::setPwm(float Ualpha, float Ubeta) { + float duty_cycle1A(0.0),duty_cycle1B(0.0),duty_cycle2A(0.0),duty_cycle2B(0.0); + // limit the voltage in driver + Ualpha = _constrain(Ualpha, -voltage_limit, voltage_limit); + Ubeta = _constrain(Ubeta, -voltage_limit, voltage_limit); + // hardware specific writing + if( Ualpha > 0 ) + duty_cycle1B = _constrain(abs(Ualpha)/voltage_power_supply,0.0,1.0); + else + duty_cycle1A = _constrain(abs(Ualpha)/voltage_power_supply,0.0,1.0); + + if( Ubeta > 0 ) + duty_cycle2B = _constrain(abs(Ubeta)/voltage_power_supply,0.0,1.0); + else + duty_cycle2A = _constrain(abs(Ubeta)/voltage_power_supply,0.0,1.0); + // write to hardware + _writeDutyCycle4PWM(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, pwm1A, pwm1B, pwm2A, pwm2B); +} \ No newline at end of file diff --git a/minimal_project_examples/esp32_stepper_openloop/src/drivers/StepperDriver4PWM.h b/minimal_project_examples/esp32_stepper_openloop/src/drivers/StepperDriver4PWM.h new file mode 100644 index 00000000..e4b2ee42 --- /dev/null +++ b/minimal_project_examples/esp32_stepper_openloop/src/drivers/StepperDriver4PWM.h @@ -0,0 +1,55 @@ +#ifndef STEPPER_DRIVER_4PWM_h +#define STEPPER_DRIVER_4PWM_h + +#include "../common/base_classes/StepperDriver.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#include "../common/defaults.h" +#include "hardware_api.h" + +/** + 4 pwm stepper driver class +*/ +class StepperDriver4PWM: public StepperDriver +{ + public: + /** + StepperMotor class constructor + @param ph1A 1A phase pwm pin + @param ph1B 1B phase pwm pin + @param ph2A 2A phase pwm pin + @param ph2B 2B phase pwm pin + @param en1 enable pin phase 1 (optional input) + @param en2 enable pin phase 2 (optional input) + */ + StepperDriver4PWM(int ph1A,int ph1B,int ph2A,int ph2B, int en1 = NOT_SET, int en2 = NOT_SET); + + /** Motor hardware init function */ + int init() override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + // hardware variables + int pwm1A; //!< phase 1A pwm pin number + int pwm1B; //!< phase 1B pwm pin number + int pwm2A; //!< phase 2A pwm pin number + int pwm2B; //!< phase 2B pwm pin number + int enable_pin1; //!< enable pin number phase 1 + int enable_pin2; //!< enable pin number phase 2 + + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + */ + void setPwm(float Ua, float Ub) override; + + private: + +}; + + +#endif diff --git a/minimal_project_examples/esp32_stepper_openloop/src/drivers/hardware_api.h b/minimal_project_examples/esp32_stepper_openloop/src/drivers/hardware_api.h new file mode 100644 index 00000000..01c03867 --- /dev/null +++ b/minimal_project_examples/esp32_stepper_openloop/src/drivers/hardware_api.h @@ -0,0 +1,123 @@ +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H + +#include "../common/foc_utils.h" +#include "../common/time_utils.h" + +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + */ +void _configure2PWM(long pwm_frequency, const int pinA, const int pinB); + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + * @param pinC pinC bldc driver + */ +void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC); + +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pin1A pin1A stepper driver + * @param pin1B pin1B stepper driver + * @param pin2A pin2A stepper driver + * @param pin2B pin2B stepper driver + */ +void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B); + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low - if applicable + * @param pinA_h pinA high-side bldc driver + * @param pinA_l pinA low-side bldc driver + * @param pinB_h pinA high-side bldc driver + * @param pinB_l pinA low-side bldc driver + * @param pinC_h pinA high-side bldc driver + * @param pinC_l pinA low-side bldc driver + * + * @return 0 if config good, -1 if failed + */ +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + */ +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low + * @param pinA_h phase A high-side hardware pin number + * @param pinA_l phase A low-side hardware pin number + * @param pinB_h phase B high-side hardware pin number + * @param pinB_l phase B low-side hardware pin number + * @param pinC_h phase C high-side hardware pin number + * @param pinC_l phase C low-side hardware pin number + * + */ +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l); + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/esp32_mcu.cpp b/minimal_project_examples/esp32_stepper_openloop/src/drivers/hardware_specific/esp32_mcu.cpp similarity index 57% rename from minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/esp32_mcu.cpp rename to minimal_project_examples/esp32_stepper_openloop/src/drivers/hardware_specific/esp32_mcu.cpp index 3c07a445..983d4d54 100644 --- a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/esp32_mcu.cpp +++ b/minimal_project_examples/esp32_stepper_openloop/src/drivers/hardware_specific/esp32_mcu.cpp @@ -10,6 +10,17 @@ #define _EMPTY_SLOT -20 #define _TAKEN_SLOT -21 +// ABI bus frequency - would be better to take it from somewhere +// but I did nto find a good exposed variable +#define _MCPWM_FREQ 160e6 + +// preferred pwm resolution default +#define _PWM_RES_DEF 2048 +// min resolution +#define _PWM_RES_MIN 1500 +// max resolution +#define _PWM_RES_MAX 3000 + // structure containing motor slot configuration // this library supports up to 4 motors typedef struct { @@ -31,7 +42,15 @@ typedef struct { mcpwm_io_signals_t mcpwm_1b; mcpwm_io_signals_t mcpwm_2a; mcpwm_io_signals_t mcpwm_2b; -} stepper_motor_slots_t; +} stepper_4pwm_motor_slots_t; +typedef struct { + int pin1pwm; + mcpwm_dev_t* mcpwm_num; + mcpwm_unit_t mcpwm_unit; + mcpwm_operator_t mcpwm_operator; + mcpwm_io_signals_t mcpwm_a; + mcpwm_io_signals_t mcpwm_b; +} stepper_2pwm_motor_slots_t; typedef struct { int pinAH; @@ -55,41 +74,87 @@ bldc_3pwm_motor_slots_t esp32_bldc_3pwm_motor_slots[4] = { {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B, MCPWM2B} // 4th motor will be MCPWM1 channel B }; -// define stepper motor slots array -stepper_motor_slots_t esp32_stepper_motor_slots[2] = { - {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 - {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 - }; - // define stepper motor slots array bldc_6pwm_motor_slots_t esp32_bldc_6pwm_motor_slots[2] = { {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0 {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM2A, MCPWM0B, MCPWM1B, MCPWM2B}, // 1st motor will be on MCPWM0 }; +// define 4pwm stepper motor slots array +stepper_4pwm_motor_slots_t esp32_stepper_4pwm_motor_slots[2] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM0 + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM_OPR_B, MCPWM0A, MCPWM1A, MCPWM0B, MCPWM1B}, // 1st motor will be on MCPWM1 + }; + +// define 2pwm stepper motor slots array +stepper_2pwm_motor_slots_t esp32_stepper_2pwm_motor_slots[4] = { + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A}, // 1st motor will be MCPWM0 channel A + {_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_B, MCPWM0B, MCPWM1B}, // 2nd motor will be MCPWM0 channel B + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_A, MCPWM0A, MCPWM1A}, // 3rd motor will be MCPWM1 channel A + {_EMPTY_SLOT, &MCPWM1, MCPWM_UNIT_1, MCPWM_OPR_B, MCPWM0B, MCPWM1B} // 4th motor will be MCPWM1 channel B + }; + // configuring high frequency pwm timer // a lot of help from this post from Paul Gauld // https://hackaday.io/project/169905-esp-32-bldc-robot-actuator-controller void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm_unit_t mcpwm_unit, float dead_zone = NOT_SET){ mcpwm_config_t pwm_config; - pwm_config.frequency = pwm_frequency; //frequency pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave) pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings - + if (dead_zone != NOT_SET){ - // dead zone is configured in dead_time x 100 nanoseconds - float dead_time = (float)(1e7 / pwm_frequency) * dead_zone; - mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); - mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); - mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time, dead_time); + // dead zone is configured + float dead_time = (float)(_MCPWM_FREQ / (pwm_frequency)) * dead_zone; + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time/2.0, dead_time/2.0); + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time/2.0, dead_time/2.0); + mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time/2.0, dead_time/2.0); } - _delay(100); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_stop(mcpwm_unit, MCPWM_TIMER_2); + + // manual configuration due to the lack of config flexibility in mcpwm_init() + mcpwm_num->clk_cfg.prescale = 0; + // calculate prescaler and period + // step 1: calculate the prescaler using the default pwm resolution + // prescaler = bus_freq / (pwm_freq * default_pwm_res) - 1 + int prescaler = ceil((double)_MCPWM_FREQ / (double)_PWM_RES_DEF / 2.0 / (double)pwm_frequency) - 1; + // constrain prescaler + prescaler = _constrain(prescaler, 0, 128); + // now calculate the real resolution timer period necessary (pwm resolution) + // pwm_res = bus_freq / (pwm_freq * (prescaler + 1)) + int resolution_corrected = (double)_MCPWM_FREQ / 2.0 / (double)pwm_frequency / (double)(prescaler + 1); + // if pwm resolution too low lower the prescaler + if(resolution_corrected < _PWM_RES_MIN && prescaler > 0 ) + resolution_corrected = (double)_MCPWM_FREQ / 2.0 / (double)pwm_frequency / (double)(--prescaler + 1); + resolution_corrected = _constrain(resolution_corrected, _PWM_RES_MIN, _PWM_RES_MAX); + + // set prescaler + mcpwm_num->timer[0].period.prescale = prescaler; + mcpwm_num->timer[1].period.prescale = prescaler; + mcpwm_num->timer[2].period.prescale = prescaler; + _delay(1); + //set period + mcpwm_num->timer[0].period.period = resolution_corrected; + mcpwm_num->timer[1].period.period = resolution_corrected; + mcpwm_num->timer[2].period.period = resolution_corrected; + _delay(1); + mcpwm_num->timer[0].period.upmethod = 0; + mcpwm_num->timer[1].period.upmethod = 0; + mcpwm_num->timer[2].period.upmethod = 0; + _delay(1); + //restart the timers + mcpwm_start(mcpwm_unit, MCPWM_TIMER_0); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_1); + mcpwm_start(mcpwm_unit, MCPWM_TIMER_2); + _delay(1); + mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_SELECT_SYNC_INT0, 0); mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_SELECT_SYNC_INT0, 0); mcpwm_sync_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_SELECT_SYNC_INT0, 0); @@ -99,6 +164,51 @@ void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm mcpwm_num->timer[0].sync.out_sel = 0; } +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 2PWM setting +// - hardware speciffic +// supports Arudino/ATmega328, STM32 and ESP32 +void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) { + + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 40kHz max - centered pwm has twice lower frequency + + stepper_2pwm_motor_slots_t m_slot = {}; + + // determine which motor are we connecting + // and set the appropriate configuration parameters + int slot_num; + for(slot_num = 0; slot_num < 4; slot_num++){ + if(esp32_stepper_2pwm_motor_slots[slot_num].pin1pwm == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_2pwm_motor_slots[slot_num].pin1pwm = pinA; + m_slot = esp32_stepper_2pwm_motor_slots[slot_num]; + break; + } + } + + // disable all the slots with the same MCPWM + // disable 3pwm bldc motor which would go in the same slot + esp32_bldc_3pwm_motor_slots[slot_num].pinA = _TAKEN_SLOT; + if( slot_num < 2 ){ + // slot 0 of the 4pwm stepper + esp32_stepper_4pwm_motor_slots[0].pin1A = _TAKEN_SLOT; + // slot 0 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; + }else{ + // slot 1 of the stepper + esp32_stepper_4pwm_motor_slots[1].pin1A = _TAKEN_SLOT; + // slot 1 of the 6pwm bldc + esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; + } + // configure pins + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_a, pinA); + mcpwm_gpio_init(m_slot.mcpwm_unit, m_slot.mcpwm_b, pinB); + + // configure the timer + _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); + +} + // function setting the high pwm frequency to the supplied pins // - BLDC motor - 3PWM setting @@ -106,8 +216,8 @@ void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm // supports Arudino/ATmega328, STM32 and ESP32 void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { - if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = _constrain(2*pwm_frequency, 0, 100000); // constrain to 50kHz max - centered pwm has twice lower frequency + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 40kHz max - centered pwm has twice lower frequency bldc_3pwm_motor_slots_t m_slot = {}; @@ -122,14 +232,16 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int } } // disable all the slots with the same MCPWM + // disable 2pwm steppr motor which would go in the same slot + esp32_stepper_2pwm_motor_slots[slot_num].pin1pwm = _TAKEN_SLOT; if( slot_num < 2 ){ - // slot 0 of the stepper - esp32_stepper_motor_slots[0].pin1A = _TAKEN_SLOT; + // slot 0 of the 4pwm stepper + esp32_stepper_4pwm_motor_slots[0].pin1A = _TAKEN_SLOT; // slot 0 of the 6pwm bldc esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; }else{ // slot 1 of the stepper - esp32_stepper_motor_slots[1].pin1A = _TAKEN_SLOT; + esp32_stepper_4pwm_motor_slots[1].pin1A = _TAKEN_SLOT; // slot 1 of the 6pwm bldc esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; } @@ -149,16 +261,16 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int // - hardware speciffic void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { - if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = _constrain(2*pwm_frequency, 0, 100000); // constrain to 50kHz max - centered pwm has twice lower frequency - stepper_motor_slots_t m_slot = {}; + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 50kHz max - centered pwm has twice lower frequency + stepper_4pwm_motor_slots_t m_slot = {}; // determine which motor are we connecting // and set the appropriate configuration parameters int slot_num; for(slot_num = 0; slot_num < 2; slot_num++){ - if(esp32_stepper_motor_slots[slot_num].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot - esp32_stepper_motor_slots[slot_num].pin1A = pinA; - m_slot = esp32_stepper_motor_slots[slot_num]; + if(esp32_stepper_4pwm_motor_slots[slot_num].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot + esp32_stepper_4pwm_motor_slots[slot_num].pin1A = pinA; + m_slot = esp32_stepper_4pwm_motor_slots[slot_num]; break; } } @@ -167,12 +279,18 @@ void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int // slots 0 and 1 of the 3pwm bldc esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT; esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT; + // slots 0 and 1 of the 2pwm stepper taken + esp32_stepper_2pwm_motor_slots[0].pin1pwm = _TAKEN_SLOT; + esp32_stepper_2pwm_motor_slots[1].pin1pwm = _TAKEN_SLOT; // slot 0 of the 6pwm bldc esp32_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT; }else{ // slots 2 and 3 of the 3pwm bldc esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT; esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT; + // slots 2 and 3 of the 2pwm stepper taken + esp32_stepper_2pwm_motor_slots[2].pin1pwm = _TAKEN_SLOT; + esp32_stepper_2pwm_motor_slots[3].pin1pwm = _TAKEN_SLOT; // slot 1 of the 6pwm bldc esp32_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT; } @@ -187,6 +305,23 @@ void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int _configureTimerFrequency(pwm_frequency, m_slot.mcpwm_num, m_slot.mcpwm_unit); } +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 2PWM setting +// - hardware speciffic +// ESP32 uses MCPWM +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){ + // determine which motor slot is the motor connected to + for(int i = 0; i < 4; i++){ + if(esp32_stepper_2pwm_motor_slots[i].pin1pwm == pinA){ // if motor slot found + // se the PWM on the slot timers + // transform duty cycle from [0,1] to [0,100] + mcpwm_set_duty(esp32_stepper_2pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_2pwm_motor_slots[i].mcpwm_operator, dc_a*100.0); + mcpwm_set_duty(esp32_stepper_2pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_2pwm_motor_slots[i].mcpwm_operator, dc_b*100.0); + break; + } + } +} + // function setting the pwm duty cycle to the hardware // - BLDC motor - 3PWM setting // - hardware speciffic @@ -212,13 +347,13 @@ void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ // determine which motor slot is the motor connected to for(int i = 0; i < 2; i++){ - if(esp32_stepper_motor_slots[i].pin1A == pin1A){ // if motor slot found + if(esp32_stepper_4pwm_motor_slots[i].pin1A == pin1A){ // if motor slot found // se the PWM on the slot timers // transform duty cycle from [0,1] to [0,100] - mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_motor_slots[i].mcpwm_operator1, dc_1a*100.0); - mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_motor_slots[i].mcpwm_operator1, dc_1b*100.0); - mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_motor_slots[i].mcpwm_operator2, dc_2a*100.0); - mcpwm_set_duty(esp32_stepper_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_motor_slots[i].mcpwm_operator2, dc_2b*100.0); + mcpwm_set_duty(esp32_stepper_4pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator1, dc_1a*100.0); + mcpwm_set_duty(esp32_stepper_4pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator1, dc_1b*100.0); + mcpwm_set_duty(esp32_stepper_4pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_0, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator2, dc_2a*100.0); + mcpwm_set_duty(esp32_stepper_4pwm_motor_slots[i].mcpwm_unit, MCPWM_TIMER_1, esp32_stepper_4pwm_motor_slots[i].mcpwm_operator2, dc_2b*100.0); break; } } @@ -229,8 +364,8 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in // - hardware specific int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ - if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 40000; // default frequency 20khz - centered pwm has twice lower frequency - else pwm_frequency = _constrain(2*pwm_frequency, 0, 60000); // constrain to 30kHz max - centered pwm has twice lower frequency + if(!pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency + else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 40kHz max - centered pwm has twice lower frequency bldc_6pwm_motor_slots_t m_slot = {}; // determine which motor are we connecting // and set the appropriate configuration parameters @@ -251,13 +386,13 @@ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const esp32_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT; esp32_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT; // slot 0 of the 6pwm bldc - esp32_stepper_motor_slots[0].pin1A = _TAKEN_SLOT; + esp32_stepper_4pwm_motor_slots[0].pin1A = _TAKEN_SLOT; }else{ // slots 2 and 3 of the 3pwm bldc esp32_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT; esp32_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT; // slot 1 of the 6pwm bldc - esp32_stepper_motor_slots[1].pin1A = _TAKEN_SLOT; + esp32_stepper_4pwm_motor_slots[1].pin1A = _TAKEN_SLOT; } // configure pins diff --git a/minimal_project_examples/stm32_bldc_encoder/src/BLDCMotor.cpp b/minimal_project_examples/stm32_bldc_encoder/src/BLDCMotor.cpp new file mode 100644 index 00000000..5d36ce35 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_encoder/src/BLDCMotor.cpp @@ -0,0 +1,421 @@ +#include "BLDCMotor.h" + +// // BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en) +// // - phA, phB, phC - motor A,B,C phase pwm pins +// // - pp - pole pair number +// // - cpr - counts per rotation number (cpm=ppm*4) +// // - enable pin - (optional input) +// BLDCMotor::BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en){ +// noop; +// } + +// BLDCMotor( int pp) +// - phA, phB, phC - motor A,B,C phase pwm pins +// - pp - pole pair number +// - cpr - counts per rotation number (cpm=ppm*4) +// - enable pin - (optional input) +BLDCMotor::BLDCMotor(int pp) +: FOCMotor() +{ + // save pole pairs number + pole_pairs = pp; +} + + +/** + Link the driver which controls the motor +*/ +void BLDCMotor::linkDriver(BLDCDriver* _driver) { + driver = _driver; +} + +// init hardware pins +void BLDCMotor::init() { + if(monitor_port) monitor_port->println("MOT: Initialise variables."); + // sanity check for the voltage limit configuration + if(voltage_limit > driver->voltage_limit) voltage_limit = driver->voltage_limit; + // constrain voltage for sensor alignment + if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit; + // update the controller limits + PID_velocity.limit = voltage_limit; + P_angle.limit = velocity_limit; + + _delay(500); + // enable motor + if(monitor_port) monitor_port->println("MOT: Enable driver."); + enable(); + _delay(500); +} + + +// disable motor driver +void BLDCMotor::disable() +{ + // set zero to PWM + driver->setPwm(0, 0, 0); + // disable the driver + driver->disable(); +} +// enable motor driver +void BLDCMotor::enable() +{ + // enable the driver + driver->enable(); + // set zero to PWM + driver->setPwm(0, 0, 0); + +} + +/** + FOC functions +*/ +// FOC initialization function +int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction ) { + int exit_flag = 1; + // align motor if necessary + // alignment necessary for encoders! + if(zero_electric_offset != NOT_SET){ + // abosolute zero offset provided - no need to align + zero_electric_angle = zero_electric_offset; + // set the sensor direction - default CW + sensor->natural_direction = sensor_direction; + }else{ + // sensor and motor alignment + _delay(500); + exit_flag = alignSensor(); + _delay(500); + } + if(monitor_port) monitor_port->println("MOT: Motor ready."); + + return exit_flag; +} +// Encoder alignment to electrical 0 angle +int BLDCMotor::alignSensor() { + if(monitor_port) monitor_port->println("MOT: Align sensor."); + // align the electrical phases of the motor and sensor + // set angle -90 degrees + + float start_angle = shaftAngle(); + for (int i = 0; i <=5; i++ ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, 0, angle); + _delay(200); + } + float mid_angle = shaftAngle(); + for (int i = 5; i >=0; i-- ) { + float angle = _3PI_2 + _2PI * i / 6.0; + setPhaseVoltage(voltage_sensor_align, 0, angle); + _delay(200); + } + if (mid_angle < start_angle) { + if(monitor_port) monitor_port->println("MOT: natural_direction==CCW"); + sensor->natural_direction = Direction::CCW; + } else if (mid_angle == start_angle) { + if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } else{ + if(monitor_port) monitor_port->println("MOT: natural_direction==CW"); + } + + // let the motor stabilize for 2 sec + _delay(2000); + // set sensor to zero + sensor->initRelativeZero(); + _delay(500); + setPhaseVoltage(0, 0, 0); + _delay(200); + + // find the index if available + int exit_flag = absoluteZeroAlign(); + _delay(500); + if(monitor_port){ + if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!"); + if(exit_flag> 0 ) monitor_port->println("MOT: Success!"); + else monitor_port->println("MOT: Not available!"); + } + return exit_flag; +} + + +// Encoder alignment the absolute zero angle +// - to the index +int BLDCMotor::absoluteZeroAlign() { + + if(monitor_port) monitor_port->println("MOT: Absolute zero align."); + // if no absolute zero return + if(!sensor->hasAbsoluteZero()) return 0; + + + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); + // search the absolute zero with small velocity + while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ + loopFOC(); + voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); + } + voltage_q = 0; + // disable motor + setPhaseVoltage(0, 0, 0); + + // align absolute zero if it has been found + if(!sensor->needsAbsoluteZeroSearch()){ + // align the sensor with the absolute zero + float zero_offset = sensor->initAbsoluteZero(); + // remember zero electric angle + zero_electric_angle = _normalizeAngle(_electricalAngle(zero_offset, pole_pairs)); + } + // return bool if zero found + return !sensor->needsAbsoluteZeroSearch() ? 1 : -1; +} + +// Iterative function looping FOC algorithm, setting Uq on the Motor +// The faster it can be run the better +void BLDCMotor::loopFOC() { + // shaft angle + shaft_angle = shaftAngle(); + // set the phase voltage - FOC heart function :) + setPhaseVoltage(voltage_q, voltage_d, _electricalAngle(shaft_angle,pole_pairs)); +} + +// Iterative function running outer loop of the FOC algorithm +// Behavior of this function is determined by the motor.controller variable +// It runs either angle, velocity or voltage loop +// - needs to be called iteratively it is asynchronous function +// - if target is not set it uses motor.target value +void BLDCMotor::move(float new_target) { + // set internal target variable + if( new_target != NOT_SET ) target = new_target; + // get angular velocity + shaft_velocity = shaftVelocity(); + // choose control loop + switch (controller) { + case ControlType::voltage: + voltage_q = target; + break; + case ControlType::angle: + // angle set point + // include angle loop + shaft_angle_sp = target; + shaft_velocity_sp = P_angle( shaft_angle_sp - shaft_angle ); + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity: + // velocity set point + // include velocity loop + shaft_velocity_sp = target; + voltage_q = PID_velocity(shaft_velocity_sp - shaft_velocity); + break; + case ControlType::velocity_openloop: + // velocity control in open loop + // loopFOC should not be called + shaft_velocity_sp = target; + velocityOpenloop(shaft_velocity_sp); + break; + case ControlType::angle_openloop: + // angle control in open loop + // loopFOC should not be called + shaft_angle_sp = target; + angleOpenloop(shaft_angle_sp); + break; + } +} + + +// Method using FOC to set Uq and Ud to the motor at the optimal angle +// Function implementing Space Vector PWM and Sine PWM algorithms +// +// Function using sine approximation +// regular sin + cos ~300us (no memory usaage) +// approx _sin + _cos ~110us (400Byte ~ 20% of memory) +void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { + + const bool centered = true; + int sector; + float _ca,_sa; + + switch (foc_modulation) + { + case FOCModulationType::Trapezoid_120 : + // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 5 + static int trap_120_map[6][3] = { + {0,1,-1},{-1,1,0},{-1,0,1},{0,-1,1},{1,-1,0},{1,0,-1} // each is 60 degrees with values for 3 phases of 1=positive -1=negative 0=high-z + }; + // static int trap_120_state = 0; + sector = 6 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes + + Ua = Uq + trap_120_map[sector][0] * Uq; + Ub = Uq + trap_120_map[sector][1] * Uq; + Uc = Uq + trap_120_map[sector][2] * Uq; + + if (centered) { + Ua += (driver->voltage_limit)/2 -Uq; + Ub += (driver->voltage_limit)/2 -Uq; + Uc += (driver->voltage_limit)/2 -Uq; + } + break; + + case FOCModulationType::Trapezoid_150 : + // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 8 + static int trap_150_map[12][3] = { + {0,1,-1},{-1,1,-1},{-1,1,0},{-1,1,1},{-1,0,1},{-1,-1,1},{0,-1,1},{1,-1,1},{1,-1,0},{1,-1,-1},{1,0,-1},{1,1,-1} // each is 30 degrees with values for 3 phases of 1=positive -1=negative 0=high-z + }; + // static int trap_150_state = 0; + sector = 12 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes + + Ua = Uq + trap_150_map[sector][0] * Uq; + Ub = Uq + trap_150_map[sector][1] * Uq; + Uc = Uq + trap_150_map[sector][2] * Uq; + + //center + if (centered) { + Ua += (driver->voltage_limit)/2 -Uq; + Ub += (driver->voltage_limit)/2 -Uq; + Uc += (driver->voltage_limit)/2 -Uq; + } + + break; + + case FOCModulationType::SinePWM : + // Sinusoidal PWM modulation + // Inverse Park + Clarke transformation + + // angle normalization in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle); + _ca = _cos(angle_el); + _sa = _sin(angle_el); + // Inverse park transform + Ualpha = _ca * Ud - _sa * Uq; // -sin(angle) * Uq; + Ubeta = _sa * Ud + _ca * Uq; // cos(angle) * Uq; + + // Clarke transform + Ua = Ualpha + driver->voltage_limit/2; + Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + driver->voltage_limit/2; + Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + driver->voltage_limit/2; + + if (!centered) { + float Umin = min(Ua, min(Ub, Uc)); + Ua -= Umin; + Ub -= Umin; + Uc -= Umin; + } + + break; + + case FOCModulationType::SpaceVectorPWM : + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // https://www.youtube.com/watch?v=QMSWUMEAejg + + // if negative voltages change inverse the phase + // angle + 180degrees + if(Uq < 0) angle_el += _PI; + Uq = abs(Uq); + + // angle normalisation in between 0 and 2pi + // only necessary if using _sin and _cos - approximation functions + angle_el = _normalizeAngle(angle_el + zero_electric_angle + _PI_2); + + // find the sector we are in currently + sector = floor(angle_el / _PI_3) + 1; + // calculate the duty cycles + float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/driver->voltage_limit; + float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/driver->voltage_limit; + // two versions possible + float T0 = 0; // pulled to 0 - better for low power supply voltage + if (centered) { + T0 = 1 - T1 - T2; //centered around driver->voltage_limit/2 + } + + // calculate the duty cycles(times) + float Ta,Tb,Tc; + switch(sector){ + case 1: + Ta = T1 + T2 + T0/2; + Tb = T2 + T0/2; + Tc = T0/2; + break; + case 2: + Ta = T1 + T0/2; + Tb = T1 + T2 + T0/2; + Tc = T0/2; + break; + case 3: + Ta = T0/2; + Tb = T1 + T2 + T0/2; + Tc = T2 + T0/2; + break; + case 4: + Ta = T0/2; + Tb = T1+ T0/2; + Tc = T1 + T2 + T0/2; + break; + case 5: + Ta = T2 + T0/2; + Tb = T0/2; + Tc = T1 + T2 + T0/2; + break; + case 6: + Ta = T1 + T2 + T0/2; + Tb = T0/2; + Tc = T1 + T0/2; + break; + default: + // possible error state + Ta = 0; + Tb = 0; + Tc = 0; + } + + // calculate the phase voltages and center + Ua = Ta*driver->voltage_limit; + Ub = Tb*driver->voltage_limit; + Uc = Tc*driver->voltage_limit; + break; + + } + + // set the voltages in driver + driver->setPwm(Ua, Ub, Uc); +} + + + +// Function (iterative) generating open loop movement for target velocity +// - target_velocity - rad/s +// it uses voltage_limit variable +void BLDCMotor::velocityOpenloop(float target_velocity){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to achieve target velocity + shaft_angle += target_velocity*Ts; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} + +// Function (iterative) generating open loop movement towards the target angle +// - target_angle - rad +// it uses voltage_limit and velocity_limit variables +void BLDCMotor::angleOpenloop(float target_angle){ + // get current timestamp + unsigned long now_us = _micros(); + // calculate the sample time from last call + float Ts = (now_us - open_loop_timestamp) * 1e-6; + + // calculate the necessary angle to move from current position towards target angle + // with maximal velocity (velocity_limit) + if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + else + shaft_angle = target_angle; + + // set the maximal allowed voltage (voltage_limit) with the necessary angle + setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); + + // save timestamp for next call + open_loop_timestamp = now_us; +} diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/StepperMotor.h b/minimal_project_examples/stm32_bldc_encoder/src/BLDCMotor.h similarity index 59% rename from minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/StepperMotor.h rename to minimal_project_examples/stm32_bldc_encoder/src/BLDCMotor.h index bf14e096..164cc108 100644 --- a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/StepperMotor.h +++ b/minimal_project_examples/stm32_bldc_encoder/src/BLDCMotor.h @@ -1,38 +1,42 @@ -/** - * @file StepperMotor.h - * - */ - -#ifndef StepperMotor_h -#define StepperMotor_h +#ifndef BLDCMotor_h +#define BLDCMotor_h #include "Arduino.h" -#include "common/FOCMotor.h" +#include "common/base_classes/FOCMotor.h" +#include "common/base_classes/Sensor.h" +#include "common/base_classes/BLDCDriver.h" #include "common/foc_utils.h" -#include "common/hardware_utils.h" -#include "common/Sensor.h" +#include "common/time_utils.h" #include "common/defaults.h" /** - Stepper Motor class + BLDC motor class */ -class StepperMotor: public FOCMotor +class BLDCMotor: public FOCMotor { public: /** - StepperMotor class constructor - @param ph1A 1A phase pwm pin - @param ph1B 1B phase pwm pin - @param ph2A 2A phase pwm pin - @param ph2B 2B phase pwm pin - @param pp pole pair number - cpr counts per rotation number (cpm=ppm*4) - @param en1 enable pin phase 1 (optional input) - @param en2 enable pin phase 2 (optional input) + BLDCMotor class constructor + @param pp pole pairs number + */ + BLDCMotor(int pp); + + /** + * Function linking a motor and a foc driver + * + * @param driver BLDCDriver class implementing all the hardware specific functions necessary PWM setting + */ + void linkDriver(BLDCDriver* driver); + + /** + * BLDCDriver link: + * - 3PWM + * - 6PWM */ - StepperMotor(int ph1A,int ph1B,int ph2A,int ph2B,int pp, int en1 = NOT_SET, int en2 = NOT_SET); + BLDCDriver* driver; /** Motor hardware init function */ - void init(long pwm_frequency = NOT_SET) override; + void init() override; /** Motor disable function */ void disable() override; /** Motor enable function */ @@ -41,12 +45,6 @@ class StepperMotor: public FOCMotor /** * Function initializing FOC algorithm * and aligning sensor's and motors' zero position - * - * - If zero_electric_offset parameter is set the alignment procedure is skipped - * - * @param zero_electric_offset value of the sensors absolute position electrical offset in respect to motor's electrical 0 position. - * @param sensor_direction sensor natural direction - default is CW - * */ int initFOC( float zero_electric_offset = NOT_SET , Direction sensor_direction = Direction::CW) override; /** @@ -56,6 +54,7 @@ class StepperMotor: public FOCMotor * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us */ void loopFOC() override; + /** * Function executing the control loops set by the controller parameter of the BLDCMotor. * @@ -65,39 +64,27 @@ class StepperMotor: public FOCMotor * This function doesn't need to be run upon each loop execution - depends of the use case */ void move(float target = NOT_SET) override; + + float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor + float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform - // hardware variables - int pwm1A; //!< phase 1A pwm pin number - int pwm1B; //!< phase 1B pwm pin number - int pwm2A; //!< phase 2A pwm pin number - int pwm2B; //!< phase 2B pwm pin number - int enable_pin1; //!< enable pin number phase 1 - int enable_pin2; //!< enable pin number phase 2 private: - // FOC methods /** * Method using FOC to set Uq to the motor at the optimal angle * Heart of the FOC algorithm * * @param Uq Current voltage in q axis to set to the motor + * @param Ud Current voltage in d axis to set to the motor * @param angle_el current electrical angle of the motor */ - void setPhaseVoltage(float Uq, float angle_el); - + void setPhaseVoltage(float Uq, float Ud, float angle_el); /** Sensor alignment to electrical 0 angle of the motor */ int alignSensor(); /** Motor and sensor alignment to the sensors absolute 0 angle */ int absoluteZeroAlign(); - /** - * Set phase voltages to the harware - * - * @param Ua phase A voltage - * @param Ub phase B voltage - * @param Uc phase C voltage - */ - void setPwm(float Ualpha, float Ubeta); + // Open loop motion control /** diff --git a/minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/BLDCDriver.h b/minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/BLDCDriver.h new file mode 100644 index 00000000..708323fb --- /dev/null +++ b/minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/BLDCDriver.h @@ -0,0 +1,28 @@ +#ifndef BLDCDRIVER_H +#define BLDCDRIVER_H + +class BLDCDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + virtual void setPwm(float Ua, float Ub, float Uc); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/FOCMotor.cpp b/minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/FOCMotor.cpp similarity index 98% rename from minimal_project_examples/arduino_foc_stepper_encoder/src/common/FOCMotor.cpp rename to minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/FOCMotor.cpp index adecbeec..1d1a0f43 100644 --- a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/FOCMotor.cpp +++ b/minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/FOCMotor.cpp @@ -5,13 +5,10 @@ */ FOCMotor::FOCMotor() { - // Power supply voltage - voltage_power_supply = DEF_POWER_SUPPLY; - // maximum angular velocity to be used for positioning velocity_limit = DEF_VEL_LIM; // maximum voltage to be set to the motor - voltage_limit = voltage_power_supply; + voltage_limit = DEF_POWER_SUPPLY; // index search velocity velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY; @@ -26,6 +23,8 @@ FOCMotor::FOCMotor() // default target value target = 0; + voltage_d = 0; + voltage_q = 0; //monitor_port monitor_port = nullptr; @@ -53,9 +52,6 @@ float FOCMotor::shaftVelocity() { return LPF_velocity(sensor->getVelocity()); } - - - /** * Monitoring functions */ diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/FOCMotor.h b/minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/FOCMotor.h similarity index 93% rename from minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/FOCMotor.h rename to minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/FOCMotor.h index 40f7f6d4..986e1ab2 100644 --- a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/FOCMotor.h +++ b/minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/FOCMotor.h @@ -2,13 +2,14 @@ #define FOCMOTOR_H #include "Arduino.h" -#include "hardware_utils.h" -#include "foc_utils.h" -#include "defaults.h" - #include "Sensor.h" -#include "pid.h" -#include "lowpass_filter.h" +#include "BLDCDriver.h" + +#include "../time_utils.h" +#include "../foc_utils.h" +#include "../defaults.h" +#include "../pid.h" +#include "../lowpass_filter.h" /** @@ -27,7 +28,9 @@ enum ControlType{ */ enum FOCModulationType{ SinePWM, //!< Sinusoidal PWM modulation - SpaceVectorPWM //!< Space vector modulation method + SpaceVectorPWM, //!< Space vector modulation method + Trapezoid_120, + Trapezoid_150 }; /** @@ -42,7 +45,7 @@ class FOCMotor FOCMotor(); /** Motor hardware init function */ - virtual void init(long pwm_frequency)=0; + virtual void init()=0; /** Motor disable function */ virtual void disable()=0; /** Motor enable function */ @@ -55,6 +58,7 @@ class FOCMotor */ void linkSensor(Sensor* sensor); + /** * Function initializing FOC algorithm * and aligning sensor's and motors' zero position @@ -99,11 +103,9 @@ class FOCMotor float shaft_velocity_sp;//!< current target velocity float shaft_angle_sp;//!< current target angle float voltage_q;//!< current voltage u_q set - float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor - float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform + float voltage_d;//!< current voltage u_d set // motor configuration parameters - float voltage_power_supply;//!< Power supply voltage float voltage_sensor_align;//!< sensor and motor align voltage parameter float velocity_index_search;//!< target velocity for index search int pole_pairs;//!< Motor pole pairs number diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/Sensor.h b/minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/Sensor.h similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_openloop/src/common/Sensor.h rename to minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/Sensor.h diff --git a/minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/StepperDriver.h b/minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/StepperDriver.h new file mode 100644 index 00000000..7800a4e7 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_encoder/src/common/base_classes/StepperDriver.h @@ -0,0 +1,27 @@ +#ifndef STEPPERDRIVER_H +#define STEPPERDRIVER_H + +class StepperDriver{ + public: + + /** Initialise hardware */ + virtual int init(); + /** Enable hardware */ + virtual void enable(); + /** Disable hardware */ + virtual void disable(); + + long pwm_frequency; //!< pwm frequency value in hertz + float voltage_power_supply; //!< power supply voltage + float voltage_limit; //!< limiting voltage set to the motor + + /** + * Set phase voltages to the harware + * + * @param Ua phase A voltage + * @param Ub phase B voltage + */ + virtual void setPwm(float Ua, float Ub); +}; + +#endif \ No newline at end of file diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/defaults.h b/minimal_project_examples/stm32_bldc_encoder/src/common/defaults.h similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_openloop/src/common/defaults.h rename to minimal_project_examples/stm32_bldc_encoder/src/common/defaults.h diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/foc_utils.cpp b/minimal_project_examples/stm32_bldc_encoder/src/common/foc_utils.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_openloop/src/common/foc_utils.cpp rename to minimal_project_examples/stm32_bldc_encoder/src/common/foc_utils.cpp diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/foc_utils.h b/minimal_project_examples/stm32_bldc_encoder/src/common/foc_utils.h similarity index 94% rename from minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/foc_utils.h rename to minimal_project_examples/stm32_bldc_encoder/src/common/foc_utils.h index 5ab34f42..7da3f7bc 100644 --- a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/foc_utils.h +++ b/minimal_project_examples/stm32_bldc_encoder/src/common/foc_utils.h @@ -6,6 +6,7 @@ // sign function #define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) #define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) +#define _constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt))) // utility defines #define _2_SQRT3 1.15470053838 @@ -20,7 +21,6 @@ #define _2PI 6.28318530718 #define _3PI_2 4.71238898038 - #define NOT_SET -12345.0 /** diff --git a/minimal_project_examples/arduino_foc_stepper_openloop/src/common/lowpass_filter.cpp b/minimal_project_examples/stm32_bldc_encoder/src/common/lowpass_filter.cpp similarity index 100% rename from minimal_project_examples/arduino_foc_stepper_openloop/src/common/lowpass_filter.cpp rename to minimal_project_examples/stm32_bldc_encoder/src/common/lowpass_filter.cpp diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/lowpass_filter.h b/minimal_project_examples/stm32_bldc_encoder/src/common/lowpass_filter.h similarity index 94% rename from minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/lowpass_filter.h rename to minimal_project_examples/stm32_bldc_encoder/src/common/lowpass_filter.h index 5a7619cf..7c51be54 100644 --- a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/src/common/lowpass_filter.h +++ b/minimal_project_examples/stm32_bldc_encoder/src/common/lowpass_filter.h @@ -2,7 +2,7 @@ #define LOWPASS_FILTER_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/pid.cpp b/minimal_project_examples/stm32_bldc_encoder/src/common/pid.cpp similarity index 92% rename from minimal_project_examples/arduino_foc_stepper_encoder/src/common/pid.cpp rename to minimal_project_examples/stm32_bldc_encoder/src/common/pid.cpp index 277e17ce..1a0a9828 100644 --- a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/pid.cpp +++ b/minimal_project_examples/stm32_bldc_encoder/src/common/pid.cpp @@ -25,12 +25,12 @@ float PIDController::operator() (float error){ // Discrete implementations // proportional part // u_p = P *e(k) - float proportional = P * error_prev; + float proportional = P * error; // Tustin transform of the integral part // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) float integral = integral_prev + I*Ts*0.5*(error + error_prev); // antiwindup - limit the output voltage_q - integral = constrain(integral, -limit, limit); + integral = _constrain(integral, -limit, limit); // Discrete derivation // u_dk = D(ek - ek_1)/Ts float derivative = D*(error - error_prev)/Ts; @@ -38,7 +38,7 @@ float PIDController::operator() (float error){ // sum all the components float output = proportional + integral + derivative; // antiwindup - limit the output variable - output = constrain(output, -limit, limit); + output = _constrain(output, -limit, limit); // limit the acceleration by ramping the output float output_rate = (output - output_prev)/Ts; diff --git a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/pid.h b/minimal_project_examples/stm32_bldc_encoder/src/common/pid.h similarity index 97% rename from minimal_project_examples/arduino_foc_stepper_encoder/src/common/pid.h rename to minimal_project_examples/stm32_bldc_encoder/src/common/pid.h index 7ee337c4..0e9ddf54 100644 --- a/minimal_project_examples/arduino_foc_stepper_encoder/src/common/pid.h +++ b/minimal_project_examples/stm32_bldc_encoder/src/common/pid.h @@ -2,7 +2,7 @@ #define PID_H -#include "hardware_utils.h" +#include "time_utils.h" #include "foc_utils.h" /** diff --git a/minimal_project_examples/stm32_bldc_encoder/src/common/time_utils.cpp b/minimal_project_examples/stm32_bldc_encoder/src/common/time_utils.cpp new file mode 100644 index 00000000..181d03cf --- /dev/null +++ b/minimal_project_examples/stm32_bldc_encoder/src/common/time_utils.cpp @@ -0,0 +1,31 @@ +#include "time_utils.h" + +// function buffering delay() +// arduino uno function doesn't work well with interrupts +void _delay(unsigned long ms){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) + // if arduino uno and other atmega328p chips + // use while instad of delay, + // due to wrong measurement based on changed timer0 + unsigned long t = _micros() + ms*1000; + while( _micros() < t ){}; +#else + // regular micros + delay(ms); +#endif +} + + +// function buffering _micros() +// arduino function doesn't work well with interrupts +unsigned long _micros(){ +#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) +// if arduino uno and other atmega328p chips + //return the value based on the prescaler + if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); + else return (micros()); +#else + // regular micros + return micros(); +#endif +} diff --git a/minimal_project_examples/stm32_bldc_encoder/src/common/time_utils.h b/minimal_project_examples/stm32_bldc_encoder/src/common/time_utils.h new file mode 100644 index 00000000..143d4853 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_encoder/src/common/time_utils.h @@ -0,0 +1,22 @@ +#ifndef TIME_UTILS_H +#define TIME_UTILS_H + +#include "foc_utils.h" + +/** + * Function implementing delay() function in milliseconds + * - blocking function + * - hardware specific + + * @param ms number of milliseconds to wait + */ +void _delay(unsigned long ms); + +/** + * Function implementing timestamp getting function in microseconds + * hardware specific + */ +unsigned long _micros(); + + +#endif \ No newline at end of file diff --git a/minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver6PWM.cpp b/minimal_project_examples/stm32_bldc_encoder/src/drivers/BLDCDriver6PWM.cpp similarity index 92% rename from minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver6PWM.cpp rename to minimal_project_examples/stm32_bldc_encoder/src/drivers/BLDCDriver6PWM.cpp index b1f2e884..266a5412 100644 --- a/minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver6PWM.cpp +++ b/minimal_project_examples/stm32_bldc_encoder/src/drivers/BLDCDriver6PWM.cpp @@ -41,6 +41,8 @@ void BLDCDriver6PWM::disable() // init hardware pins int BLDCDriver6PWM::init() { + // a bit of separation + _delay(1000); // PWM pins pinMode(pwmA_l, OUTPUT); @@ -64,9 +66,9 @@ int BLDCDriver6PWM::init() { // Set voltage to the pwm pin void BLDCDriver6PWM::setPwm(float Ua, float Ub, float Uc) { // limit the voltage in driver - Ua = _constrain(Ua, -voltage_limit, voltage_limit); - Ub = _constrain(Ub, -voltage_limit, voltage_limit); - Uc = _constrain(Uc, -voltage_limit, voltage_limit); + Ua = _constrain(Ua, 0, voltage_limit); + Ub = _constrain(Ub, 0, voltage_limit); + Uc = _constrain(Uc, 0, voltage_limit); // calculate duty cycle // limited in [0,1] float dc_a = _constrain(Ua / voltage_power_supply, 0.0 , 1.0 ); diff --git a/minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver6PWM.h b/minimal_project_examples/stm32_bldc_encoder/src/drivers/BLDCDriver6PWM.h similarity index 100% rename from minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver6PWM.h rename to minimal_project_examples/stm32_bldc_encoder/src/drivers/BLDCDriver6PWM.h diff --git a/minimal_project_examples/stm32_bldc_encoder/src/drivers/hardware_api.h b/minimal_project_examples/stm32_bldc_encoder/src/drivers/hardware_api.h new file mode 100644 index 00000000..01c03867 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_encoder/src/drivers/hardware_api.h @@ -0,0 +1,123 @@ +#ifndef HARDWARE_UTILS_H +#define HARDWARE_UTILS_H + +#include "../common/foc_utils.h" +#include "../common/time_utils.h" + +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + */ +void _configure2PWM(long pwm_frequency, const int pinA, const int pinB); + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + * @param pinC pinC bldc driver + */ +void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC); + +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pin1A pin1A stepper driver + * @param pin1B pin1B stepper driver + * @param pin2A pin2A stepper driver + * @param pin2B pin2B stepper driver + */ +void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B); + +/** + * Configuring PWM frequency, resolution and alignment + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low - if applicable + * @param pinA_h pinA high-side bldc driver + * @param pinA_l pinA low-side bldc driver + * @param pinB_h pinA high-side bldc driver + * @param pinB_l pinA low-side bldc driver + * @param pinC_h pinA high-side bldc driver + * @param pinC_l pinA low-side bldc driver + * + * @return 0 if config good, -1 if failed + */ +int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + */ +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 3PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + * @param pinC phase C hardware pin number + */ +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC); + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 4PWM setting + * - hardware specific + * + * @param dc_1a duty cycle phase 1A [0, 1] + * @param dc_1b duty cycle phase 1B [0, 1] + * @param dc_2a duty cycle phase 2A [0, 1] + * @param dc_2b duty cycle phase 2B [0, 1] + * @param pin1A phase 1A hardware pin number + * @param pin1B phase 1B hardware pin number + * @param pin2A phase 2A hardware pin number + * @param pin2B phase 2B hardware pin number + */ +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B); + + +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - BLDC driver - 6PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param dc_c duty cycle phase C [0, 1] + * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low + * @param pinA_h phase A high-side hardware pin number + * @param pinA_l phase A low-side hardware pin number + * @param pinB_h phase B high-side hardware pin number + * @param pinB_l phase B low-side hardware pin number + * @param pinC_h phase C high-side hardware pin number + * @param pinC_l phase C low-side hardware pin number + * + */ +void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l); + +#endif \ No newline at end of file diff --git a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/stm32_mcu.cpp b/minimal_project_examples/stm32_bldc_encoder/src/drivers/hardware_specific/stm32_mcu.cpp similarity index 88% rename from minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/stm32_mcu.cpp rename to minimal_project_examples/stm32_bldc_encoder/src/drivers/hardware_specific/stm32_mcu.cpp index 85d0bd65..0dc83cf7 100644 --- a/minimal_project_examples/atmega328_bldc_openloop/src/drivers/hardware_specific/stm32_mcu.cpp +++ b/minimal_project_examples/stm32_bldc_encoder/src/drivers/hardware_specific/stm32_mcu.cpp @@ -5,7 +5,8 @@ #define _PWM_RESOLUTION 12 // 12bit #define _PWM_RANGE 4095.0// 2^12 -1 = 4095 -#define _PWM_FREQUENCY 50000 // 50khz +#define _PWM_FREQUENCY 25000 // 25khz +#define _PWM_FREQUENCY_MAX 50000 // 50khz #define _HARDWARE_6PWM 1 @@ -184,12 +185,31 @@ int _interfaceType(const int pinA_h, const int pinA_l, const int pinB_h, const +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 2PWM setting +// - hardware speciffic +void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) { + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max + // center-aligned frequency is uses two periods + pwm_frequency *=2; + + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); + HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); + // allign the timers + _alignPWMTimers(HT1, HT2, HT2); +} + + // function setting the high pwm frequency to the supplied pins // - BLDC motor - 3PWM setting // - hardware speciffic void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { - if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max + // center-aligned frequency is uses two periods + pwm_frequency *=2; + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); @@ -201,8 +221,11 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int // - Stepper motor - 4PWM setting // - hardware speciffic void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { - if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max + // center-aligned frequency is uses two periods + pwm_frequency *=2; + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); @@ -211,6 +234,15 @@ void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int _alignPWMTimers(HT1, HT2, HT3, HT4); } +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 2PWM setting +//- hardware speciffic +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){ + // transform duty cycle from [0,1] to [0,4095] + _setPwm(pinA, _PWM_RANGE*dc_a, _PWM_RESOLUTION); + _setPwm(pinB, _PWM_RANGE*dc_b, _PWM_RESOLUTION); +} + // function setting the pwm duty cycle to the hardware // - BLDC motor - 3PWM setting //- hardware speciffic @@ -221,6 +253,7 @@ void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB _setPwm(pinC, _PWM_RANGE*dc_c, _PWM_RESOLUTION); } + // function setting the pwm duty cycle to the hardware // - Stepper motor - 4PWM setting //- hardware speciffic @@ -239,8 +272,10 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in // - BLDC driver - 6PWM setting // - hardware specific int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ - if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, 100000); // constrain to 100kHz max + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to |%0kHz max + // center-aligned frequency is uses two periods + pwm_frequency *=2; // find configuration int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); diff --git a/minimal_project_examples/stm32_bldc_encoder/src/sensors/Encoder.cpp b/minimal_project_examples/stm32_bldc_encoder/src/sensors/Encoder.cpp new file mode 100644 index 00000000..1965c015 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_encoder/src/sensors/Encoder.cpp @@ -0,0 +1,228 @@ +#include "Encoder.h" + + +/* + Encoder(int encA, int encB , int cpr, int index) + - encA, encB - encoder A and B pins + - cpr - counts per rotation number (cpm=ppm*4) + - index pin - (optional input) +*/ + +Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){ + + // Encoder measurement structure init + // hardware pins + pinA = _encA; + pinB = _encB; + // counter setup + pulse_counter = 0; + pulse_timestamp = 0; + + cpr = _ppr; + A_active = 0; + B_active = 0; + I_active = 0; + // index pin + index_pin = _index; // its 0 if not used + index_pulse_counter = 0; + + // velocity calculation variables + prev_Th = 0; + pulse_per_second = 0; + prev_pulse_counter = 0; + prev_timestamp_us = _micros(); + + // extern pullup as default + pullup = Pullup::EXTERN; + // enable quadrature encoder by default + quadrature = Quadrature::ON; +} + +// Encoder interrupt callback functions +// A channel +void Encoder::handleA() { + int A = digitalRead(pinA); + switch (quadrature){ + case Quadrature::ON: + // CPR = 4xPPR + if ( A != A_active ) { + pulse_counter += (A_active == B_active) ? 1 : -1; + pulse_timestamp = _micros(); + A_active = A; + } + break; + case Quadrature::OFF: + // CPR = PPR + if(A && !digitalRead(pinB)){ + pulse_counter++; + pulse_timestamp = _micros(); + } + break; + } +} +// B channel +void Encoder::handleB() { + int B = digitalRead(pinB); + switch (quadrature){ + case Quadrature::ON: + // // CPR = 4xPPR + if ( B != B_active ) { + pulse_counter += (A_active != B_active) ? 1 : -1; + pulse_timestamp = _micros(); + B_active = B; + } + break; + case Quadrature::OFF: + // CPR = PPR + if(B && !digitalRead(pinA)){ + pulse_counter--; + pulse_timestamp = _micros(); + } + break; + } +} + +// Index channel +void Encoder::handleIndex() { + if(hasIndex()){ + int I = digitalRead(index_pin); + if(I && !I_active){ + // align encoder on each index + if(index_pulse_counter){ + long tmp = pulse_counter; + // corrent the counter value + pulse_counter = round((double)pulse_counter/(double)cpr)*cpr; + // preserve relative speed + prev_pulse_counter += pulse_counter - tmp; + } else { + // initial offset + index_pulse_counter = pulse_counter; + } + } + I_active = I; + } +} + +/* + Shaft angle calculation +*/ +float Encoder::getAngle(){ + return natural_direction * _2PI * (pulse_counter) / ((float)cpr); +} +/* + Shaft velocity calculation + function using mixed time and frequency measurement technique +*/ +float Encoder::getVelocity(){ + // timestamp + long timestamp_us = _micros(); + // sampling time calculation + float Ts = (timestamp_us - prev_timestamp_us) * 1e-6; + // quick fix for strange cases (micros overflow) + if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; + + // time from last impulse + float Th = (timestamp_us - pulse_timestamp) * 1e-6; + long dN = pulse_counter - prev_pulse_counter; + + // Pulse per second calculation (Eq.3.) + // dN - impulses received + // Ts - sampling time - time in between function calls + // Th - time from last impulse + // Th_1 - time form last impulse of the previous call + // only increment if some impulses received + float dt = Ts + prev_Th - Th; + pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second; + + // if more than 0.05 passed in between impulses + if ( Th > 0.1) pulse_per_second = 0; + + // velocity calculation + float velocity = pulse_per_second / ((float)cpr) * (_2PI); + + // save variables for next pass + prev_timestamp_us = timestamp_us; + // save velocity calculation variables + prev_Th = Th; + prev_pulse_counter = pulse_counter; + return natural_direction * (velocity); +} + +// getter for index pin +// return -1 if no index +int Encoder::needsAbsoluteZeroSearch(){ + return index_pulse_counter == 0; +} +// getter for index pin +int Encoder::hasAbsoluteZero(){ + return hasIndex(); +} +// initialize counter to zero +float Encoder::initRelativeZero(){ + long angle_offset = -pulse_counter; + pulse_counter = 0; + pulse_timestamp = _micros(); + return _2PI * (angle_offset) / ((float)cpr); +} +// initialize index to zero +float Encoder::initAbsoluteZero(){ + pulse_counter -= index_pulse_counter; + prev_pulse_counter = pulse_counter; + return (index_pulse_counter) / ((float)cpr) * (_2PI); +} +// private function used to determine if encoder has index +int Encoder::hasIndex(){ + return index_pin != 0; +} + + +// encoder initialisation of the hardware pins +// and calculation variables +void Encoder::init(){ + + // Encoder - check if pullup needed for your encoder + if(pullup == Pullup::INTERN){ + pinMode(pinA, INPUT_PULLUP); + pinMode(pinB, INPUT_PULLUP); + if(hasIndex()) pinMode(index_pin,INPUT_PULLUP); + }else{ + pinMode(pinA, INPUT); + pinMode(pinB, INPUT); + if(hasIndex()) pinMode(index_pin,INPUT); + } + + // counter setup + pulse_counter = 0; + pulse_timestamp = _micros(); + // velocity calculation variables + prev_Th = 0; + pulse_per_second = 0; + prev_pulse_counter = 0; + prev_timestamp_us = _micros(); + + // initial cpr = PPR + // change it if the mode is quadrature + if(quadrature == Quadrature::ON) cpr = 4*cpr; + +} + +// function enabling hardware interrupts of the for the callback provided +// if callback is not provided then the interrupt is not enabled +void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){ + // attach interrupt if functions provided + switch(quadrature){ + case Quadrature::ON: + // A callback and B callback + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE); + break; + case Quadrature::OFF: + // A callback and B callback + if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING); + if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING); + break; + } + + // if index used initialize the index interrupt + if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE); +} diff --git a/minimal_project_examples/stm32_bldc_encoder/src/sensors/Encoder.h b/minimal_project_examples/stm32_bldc_encoder/src/sensors/Encoder.h new file mode 100644 index 00000000..29122888 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_encoder/src/sensors/Encoder.h @@ -0,0 +1,105 @@ +#ifndef ENCODER_LIB_H +#define ENCODER_LIB_H + +#include "Arduino.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#include "../common/base_classes/Sensor.h" + + +/** + * Quadrature mode configuration structure + */ +enum Quadrature{ + ON, //!< Enable quadrature mode CPR = 4xPPR + OFF //!< Disable quadrature mode / CPR = PPR +}; + +class Encoder: public Sensor{ + public: + /** + Encoder class constructor + @param encA encoder B pin + @param encB encoder B pin + @param ppr impulses per rotation (cpr=ppr*4) + @param index index pin number (optional input) + */ + Encoder(int encA, int encB , float ppr, int index = 0); + + /** encoder initialise pins */ + void init(); + /** + * function enabling hardware interrupts for the encoder channels with provided callback functions + * if callback is not provided then the interrupt is not enabled + * + * @param doA pointer to the A channel interrupt handler function + * @param doB pointer to the B channel interrupt handler function + * @param doIndex pointer to the Index channel interrupt handler function + * + */ + void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr); + + // Encoder interrupt callback functions + /** A channel callback function */ + void handleA(); + /** B channel callback function */ + void handleB(); + /** Index channel callback function */ + void handleIndex(); + + + // pins A and B + int pinA; //!< encoder hardware pin A + int pinB; //!< encoder hardware pin B + int index_pin; //!< index pin + + // Encoder configuration + Pullup pullup; //!< Configuration parameter internal or external pullups + Quadrature quadrature;//!< Configuration parameter enable or disable quadrature mode + float cpr;//!< encoder cpr number + + // Abstract functions of the Sensor class implementation + /** get current angle (rad) */ + float getAngle() override; + /** get current angular velocity (rad/s) */ + float getVelocity() override; + /** + * set current angle as zero angle + * return the angle [rad] difference + */ + float initRelativeZero() override; + /** + * set index angle as zero angle + * return the angle [rad] difference + */ + float initAbsoluteZero() override; + /** + * returns 0 if it has no index + * 0 - encoder without index + * 1 - encoder with index + */ + int hasAbsoluteZero() override; + /** + * returns 0 if it does need search for absolute zero + * 0 - encoder without index + * 1 - ecoder with index + */ + int needsAbsoluteZeroSearch() override; + + private: + int hasIndex(); //!< function returning 1 if encoder has index pin and 0 if not. + + volatile long pulse_counter;//!< current pulse counter + volatile long pulse_timestamp;//!< last impulse timestamp in us + volatile int A_active; //!< current active states of A channel + volatile int B_active; //!< current active states of B channel + volatile int I_active; //!< current active states of Index channel + volatile long index_pulse_counter; //!< impulse counter number upon first index interrupt + + // velocity calculation variables + float prev_Th, pulse_per_second; + volatile long prev_pulse_counter, prev_timestamp_us; +}; + + +#endif diff --git a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/arduino_foc_stepper_magnetic_i2c.ino b/minimal_project_examples/stm32_bldc_encoder/stm32_bldc_encoder.ino similarity index 79% rename from minimal_project_examples/arduino_foc_stepper_magnetic_i2c/arduino_foc_stepper_magnetic_i2c.ino rename to minimal_project_examples/stm32_bldc_encoder/stm32_bldc_encoder.ino index adcba2c5..3ddabbab 100644 --- a/minimal_project_examples/arduino_foc_stepper_magnetic_i2c/arduino_foc_stepper_magnetic_i2c.ino +++ b/minimal_project_examples/stm32_bldc_encoder/stm32_bldc_encoder.ino @@ -1,5 +1,5 @@ /** - * Comprehensive BLDC motor control example using magnetic sensor + * Comprehensive BLDC motor control example using encoder * * Using serial terminal user can send motor commands and configure the motor and FOC in real-time: * - configure PID controller constants @@ -32,36 +32,49 @@ * - V: get motor variables * - 0: currently set voltage * - 1: current velocity - * - 2: current angle + * - 2: current anglex * - 3: current target value - * + * */ -#include "src/StepperMotor.h" -#include "src/MagneticSensorI2C.h" +#include "src/BLDCMotor.h" +#include "src/sensors/Encoder.h" +#include "src/drivers/BLDCDriver6PWM.h" + +// BLDC motor & driver instance +BLDCMotor motor = BLDCMotor(11); +BLDCDriver6PWM driver = BLDCDriver6PWM(7, 2, 6, 3, 5, 4, 8); -// motor instance -StepperMotor motor = StepperMotor(10, 6, 5, 9, 50, 8); +// encoder instance +Encoder encoder = Encoder(2, 3, 500); -// I2C magnetic sensor instance -MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0x0E, 4); +// Interrupt routine intialisation +// channel A and B callbacks +void doA(){encoder.handleA();} +void doB(){encoder.handleB();} void setup() { - // initialise magnetic sensor hardware - sensor.init(); + // initialize encoder sensor hardware + encoder.init(); + encoder.enableInterrupts(doA, doB); // link the motor to the sensor - motor.linkSensor(&sensor); - - // choose FOC modulation - motor.foc_modulation = FOCModulationType::SpaceVectorPWM; + motor.linkSensor(&encoder); + // driver config // power supply voltage [V] - motor.voltage_power_supply = 12; + driver.voltage_power_supply = 12; + driver.dead_zone = 0.05; // 5% + driver.init(); + // link driver + motor.linkDriver(&driver); + + // choose FOC modulation + motor.foc_modulation = FOCModulationType::SpaceVectorPWM; // set control loop type to be used motor.controller = ControlType::voltage; - // contoller configuration based on the control type + // contoller configuration based on the controll type motor.PID_velocity.P = 0.2; motor.PID_velocity.I = 20; motor.PID_velocity.D = 0; @@ -106,7 +119,7 @@ void loop() { // velocity, position or voltage // if tatget not set in parameter uses motor.target variable motor.move(); - + // user communication motor.command(serialReceiveUserCommand()); } @@ -136,4 +149,4 @@ String serialReceiveUserCommand() { } } return command; -} +} \ No newline at end of file diff --git a/minimal_project_examples/stm32_bldc_hall/src/BLDCMotor.cpp b/minimal_project_examples/stm32_bldc_hall/src/BLDCMotor.cpp index bed4cd6a..5d36ce35 100644 --- a/minimal_project_examples/stm32_bldc_hall/src/BLDCMotor.cpp +++ b/minimal_project_examples/stm32_bldc_hall/src/BLDCMotor.cpp @@ -29,7 +29,7 @@ void BLDCMotor::linkDriver(BLDCDriver* _driver) { driver = _driver; } -// init hardware pins +// init hardware pins void BLDCMotor::init() { if(monitor_port) monitor_port->println("MOT: Initialise variables."); // sanity check for the voltage limit configuration @@ -53,13 +53,13 @@ void BLDCMotor::disable() { // set zero to PWM driver->setPwm(0, 0, 0); - // disable the driver + // disable the driver driver->disable(); } // enable motor driver void BLDCMotor::enable() { - // enable the driver + // enable the driver driver->enable(); // set zero to PWM driver->setPwm(0, 0, 0); @@ -93,7 +93,7 @@ int BLDCMotor::initFOC( float zero_electric_offset, Direction sensor_direction int BLDCMotor::alignSensor() { if(monitor_port) monitor_port->println("MOT: Align sensor."); // align the electrical phases of the motor and sensor - // set angle -90 degrees + // set angle -90 degrees float start_angle = shaftAngle(); for (int i = 0; i <=5; i++ ) { @@ -112,6 +112,8 @@ int BLDCMotor::alignSensor() { sensor->natural_direction = Direction::CCW; } else if (mid_angle == start_angle) { if(monitor_port) monitor_port->println("MOT: Sensor failed to notice movement"); + } else{ + if(monitor_port) monitor_port->println("MOT: natural_direction==CW"); } // let the motor stabilize for 2 sec @@ -134,19 +136,19 @@ int BLDCMotor::alignSensor() { } -// Encoder alignment the absolute zero angle +// Encoder alignment the absolute zero angle // - to the index int BLDCMotor::absoluteZeroAlign() { if(monitor_port) monitor_port->println("MOT: Absolute zero align."); // if no absolute zero return if(!sensor->hasAbsoluteZero()) return 0; - + if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching..."); // search the absolute zero with small velocity while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){ - loopFOC(); + loopFOC(); voltage_q = PID_velocity(velocity_index_search - shaftVelocity()); } voltage_q = 0; @@ -167,9 +169,9 @@ int BLDCMotor::absoluteZeroAlign() { // Iterative function looping FOC algorithm, setting Uq on the Motor // The faster it can be run the better void BLDCMotor::loopFOC() { - // shaft angle + // shaft angle shaft_angle = shaftAngle(); - // set the phase voltage - FOC heart function :) + // set the phase voltage - FOC heart function :) setPhaseVoltage(voltage_q, voltage_d, _electricalAngle(shaft_angle,pole_pairs)); } @@ -219,7 +221,7 @@ void BLDCMotor::move(float new_target) { // Method using FOC to set Uq and Ud to the motor at the optimal angle // Function implementing Space Vector PWM and Sine PWM algorithms -// +// // Function using sine approximation // regular sin + cos ~300us (no memory usaage) // approx _sin + _cos ~110us (400Byte ~ 20% of memory) @@ -257,7 +259,7 @@ void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { }; // static int trap_150_state = 0; sector = 12 * (_normalizeAngle(angle_el + PI/6.0 + zero_electric_angle) / _2PI); // adding PI/6 to align with other modes - + Ua = Uq + trap_150_map[sector][0] * Uq; Ub = Uq + trap_150_map[sector][1] * Uq; Uc = Uq + trap_150_map[sector][2] * Uq; @@ -272,7 +274,7 @@ void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { break; case FOCModulationType::SinePWM : - // Sinusoidal PWM modulation + // Sinusoidal PWM modulation // Inverse Park + Clarke transformation // angle normalization in between 0 and 2pi @@ -299,10 +301,10 @@ void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { break; case FOCModulationType::SpaceVectorPWM : - // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm + // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm // https://www.youtube.com/watch?v=QMSWUMEAejg - // if negative voltages change inverse the phase + // if negative voltages change inverse the phase // angle + 180degrees if(Uq < 0) angle_el += _PI; Uq = abs(Uq); @@ -316,14 +318,14 @@ void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { // calculate the duty cycles float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/driver->voltage_limit; float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/driver->voltage_limit; - // two versions possible + // two versions possible float T0 = 0; // pulled to 0 - better for low power supply voltage - if (centered) { + if (centered) { T0 = 1 - T1 - T2; //centered around driver->voltage_limit/2 - } + } // calculate the duty cycles(times) - float Ta,Tb,Tc; + float Ta,Tb,Tc; switch(sector){ case 1: Ta = T1 + T2 + T0/2; @@ -369,7 +371,7 @@ void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) { break; } - + // set the voltages in driver driver->setPwm(Ua, Ub, Uc); } @@ -386,7 +388,7 @@ void BLDCMotor::velocityOpenloop(float target_velocity){ float Ts = (now_us - open_loop_timestamp) * 1e-6; // calculate the necessary angle to achieve target velocity - shaft_angle += target_velocity*Ts; + shaft_angle += target_velocity*Ts; // set the maximal allowed voltage (voltage_limit) with the necessary angle setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); @@ -403,17 +405,17 @@ void BLDCMotor::angleOpenloop(float target_angle){ unsigned long now_us = _micros(); // calculate the sample time from last call float Ts = (now_us - open_loop_timestamp) * 1e-6; - + // calculate the necessary angle to move from current position towards target angle // with maximal velocity (velocity_limit) if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)) - shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; + shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts; else shaft_angle = target_angle; - + // set the maximal allowed voltage (voltage_limit) with the necessary angle setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle, pole_pairs)); // save timestamp for next call open_loop_timestamp = now_us; -} \ No newline at end of file +} diff --git a/minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver3PWM.cpp b/minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver3PWM.cpp new file mode 100644 index 00000000..a3fc052d --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver3PWM.cpp @@ -0,0 +1,72 @@ +#include "BLDCDriver3PWM.h" + +BLDCDriver3PWM::BLDCDriver3PWM(int phA, int phB, int phC, int en){ + // Pin initialization + pwmA = phA; + pwmB = phB; + pwmC = phC; + + // enable_pin pin + enable_pin = en; + + // default power-supply value + voltage_power_supply = DEF_POWER_SUPPLY; + voltage_limit = NOT_SET; + +} + +// enable motor driver +void BLDCDriver3PWM::enable(){ + // enable_pin the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, HIGH); + // set zero to PWM + setPwm(0,0,0); +} + +// disable motor driver +void BLDCDriver3PWM::disable() +{ + // set zero to PWM + setPwm(0, 0, 0); + // disable the driver - if enable_pin pin available + if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, LOW); + +} + +// init hardware pins +int BLDCDriver3PWM::init() { + // a bit of separation + _delay(1000); + + // PWM pins + pinMode(pwmA, OUTPUT); + pinMode(pwmB, OUTPUT); + pinMode(pwmC, OUTPUT); + if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT); + + + // sanity check for the voltage limit configuration + if(voltage_limit == NOT_SET || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply; + + // Set the pwm frequency to the pins + // hardware specific function - depending on driver and mcu + _configure3PWM(pwm_frequency, pwmA, pwmB, pwmC); + return 0; +} + + +// Set voltage to the pwm pin +void BLDCDriver3PWM::setPwm(float Ua, float Ub, float Uc) { + // limit the voltage in driver + Ua = _constrain(Ua, 0.0, voltage_limit); + Ub = _constrain(Ub, 0.0, voltage_limit); + Uc = _constrain(Uc, 0.0, voltage_limit); + // calculate duty cycle + // limited in [0,1] + float dc_a = _constrain(Ua / voltage_power_supply, 0.0 , 1.0 ); + float dc_b = _constrain(Ub / voltage_power_supply, 0.0 , 1.0 ); + float dc_c = _constrain(Uc / voltage_power_supply, 0.0 , 1.0 ); + // hardware specific writing + // hardware specific function - depending on driver and mcu + _writeDutyCycle3PWM(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC); +} \ No newline at end of file diff --git a/minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver3PWM.h b/minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver3PWM.h new file mode 100644 index 00000000..b6f7d7f8 --- /dev/null +++ b/minimal_project_examples/stm32_bldc_hall/src/drivers/BLDCDriver3PWM.h @@ -0,0 +1,52 @@ +#ifndef BLDCDriver3PWM_h +#define BLDCDriver3PWM_h + +#include "../common/base_classes/BLDCDriver.h" +#include "../common/foc_utils.h" +#include "../common/time_utils.h" +#include "../common/defaults.h" +#include "hardware_api.h" + +/** + 3 pwm bldc driver class +*/ +class BLDCDriver3PWM: public BLDCDriver +{ + public: + /** + BLDCDriver class constructor + @param phA A phase pwm pin + @param phB B phase pwm pin + @param phC C phase pwm pin + @param en enable pin (optional input) + */ + BLDCDriver3PWM(int phA,int phB,int phC, int en = NOT_SET); + + /** Motor hardware init function */ + int init() override; + /** Motor disable function */ + void disable() override; + /** Motor enable function */ + void enable() override; + + // hardware variables + int pwmA; //!< phase A pwm pin number + int pwmB; //!< phase B pwm pin number + int pwmC; //!< phase C pwm pin number + int enable_pin; //!< enable pin number + + /** + * Set phase voltages to the harware + * + * @param Ua - phase A voltage + * @param Ub - phase B voltage + * @param Uc - phase C voltage + */ + void setPwm(float Ua, float Ub, float Uc) override; + + private: + +}; + + +#endif diff --git a/minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_api.h b/minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_api.h index da5ddf51..01c03867 100644 --- a/minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_api.h +++ b/minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_api.h @@ -4,6 +4,17 @@ #include "../common/foc_utils.h" #include "../common/time_utils.h" +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA bldc driver + * @param pinB pinB bldc driver + */ +void _configure2PWM(long pwm_frequency, const int pinA, const int pinB); + /** * Configuring PWM frequency, resolution and alignment * - BLDC driver - 3PWM setting @@ -47,6 +58,18 @@ void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const */ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l); +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param pinA phase A hardware pin number + * @param pinB phase B hardware pin number + */ +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB); + /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) * - BLDC driver - 3PWM setting diff --git a/minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_specific/stm32_mcu.cpp b/minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_specific/stm32_mcu.cpp index 85d0bd65..0dc83cf7 100644 --- a/minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_specific/stm32_mcu.cpp +++ b/minimal_project_examples/stm32_bldc_hall/src/drivers/hardware_specific/stm32_mcu.cpp @@ -5,7 +5,8 @@ #define _PWM_RESOLUTION 12 // 12bit #define _PWM_RANGE 4095.0// 2^12 -1 = 4095 -#define _PWM_FREQUENCY 50000 // 50khz +#define _PWM_FREQUENCY 25000 // 25khz +#define _PWM_FREQUENCY_MAX 50000 // 50khz #define _HARDWARE_6PWM 1 @@ -184,12 +185,31 @@ int _interfaceType(const int pinA_h, const int pinA_l, const int pinB_h, const +// function setting the high pwm frequency to the supplied pins +// - Stepper motor - 2PWM setting +// - hardware speciffic +void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) { + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max + // center-aligned frequency is uses two periods + pwm_frequency *=2; + + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); + HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); + // allign the timers + _alignPWMTimers(HT1, HT2, HT2); +} + + // function setting the high pwm frequency to the supplied pins // - BLDC motor - 3PWM setting // - hardware speciffic void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { - if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max + // center-aligned frequency is uses two periods + pwm_frequency *=2; + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); @@ -201,8 +221,11 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int // - Stepper motor - 4PWM setting // - hardware speciffic void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) { - if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY); // constrain to 50kHz max + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max + // center-aligned frequency is uses two periods + pwm_frequency *=2; + HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA); HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB); HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC); @@ -211,6 +234,15 @@ void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int _alignPWMTimers(HT1, HT2, HT3, HT4); } +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 2PWM setting +//- hardware speciffic +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){ + // transform duty cycle from [0,1] to [0,4095] + _setPwm(pinA, _PWM_RANGE*dc_a, _PWM_RESOLUTION); + _setPwm(pinB, _PWM_RANGE*dc_b, _PWM_RESOLUTION); +} + // function setting the pwm duty cycle to the hardware // - BLDC motor - 3PWM setting //- hardware speciffic @@ -221,6 +253,7 @@ void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB _setPwm(pinC, _PWM_RANGE*dc_c, _PWM_RESOLUTION); } + // function setting the pwm duty cycle to the hardware // - Stepper motor - 4PWM setting //- hardware speciffic @@ -239,8 +272,10 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in // - BLDC driver - 6PWM setting // - hardware specific int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){ - if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz - else pwm_frequency = _constrain(pwm_frequency, 0, 100000); // constrain to 100kHz max + if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz + else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to |%0kHz max + // center-aligned frequency is uses two periods + pwm_frequency *=2; // find configuration int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l); diff --git a/minimal_project_examples/stm32_bldc_hall/src/sensors/HallSensor.cpp b/minimal_project_examples/stm32_bldc_hall/src/sensors/HallSensor.cpp index 47dc53d0..2c33a41e 100644 --- a/minimal_project_examples/stm32_bldc_hall/src/sensors/HallSensor.cpp +++ b/minimal_project_examples/stm32_bldc_hall/src/sensors/HallSensor.cpp @@ -45,6 +45,7 @@ void HallSensor::updateState() { long new_pulse_timestamp = _micros(); hall_state = C_active + (B_active << 1) + (A_active << 2); int8_t new_electric_sector = ELECTRIC_SECTORS[hall_state]; + static Direction old_direction; if (new_electric_sector - electric_sector > 3) { //underflow direction = static_cast(natural_direction * -1); @@ -57,9 +58,16 @@ void HallSensor::updateState() { direction = (new_electric_sector > electric_sector)? static_cast(natural_direction) : static_cast(natural_direction * (-1)); } electric_sector = new_electric_sector; - pulse_diff = new_pulse_timestamp - pulse_timestamp; + if (direction == old_direction) { + // not oscilating or just changed direction + pulse_diff = new_pulse_timestamp - pulse_timestamp; + } else { + pulse_diff = 0; + } + pulse_timestamp = new_pulse_timestamp; total_interrupts++; + old_direction = direction; if (onSectorChange != nullptr) onSectorChange(electric_sector); } @@ -86,8 +94,7 @@ float HallSensor::getAngle() { function using mixed time and frequency measurement technique */ float HallSensor::getVelocity(){ - - if (pulse_diff == 0 || ((_micros() - pulse_timestamp) > STALE_HALL_DATA_MICROS) ) { // last velocity isn't accurate if too old + if (pulse_diff == 0 || ((_micros() - pulse_timestamp) > pulse_diff) ) { // last velocity isn't accurate if too old return 0; } else { return direction * (_2PI / cpr) / (pulse_diff / 1000000.0); diff --git a/minimal_project_examples/stm32_bldc_hall/src/sensors/HallSensor.h b/minimal_project_examples/stm32_bldc_hall/src/sensors/HallSensor.h index 0eb42286..ad5673e3 100644 --- a/minimal_project_examples/stm32_bldc_hall/src/sensors/HallSensor.h +++ b/minimal_project_examples/stm32_bldc_hall/src/sensors/HallSensor.h @@ -6,10 +6,6 @@ #include "../common/foc_utils.h" #include "../common/time_utils.h" -#ifndef STALE_HALL_DATA_MICROS - #define STALE_HALL_DATA_MICROS 500000 -#endif - // seq 1 > 5 > 4 > 6 > 2 > 3 > 1 000 001 010 011 100 101 110 111 const int8_t ELECTRIC_SECTORS[8] = { -1, 0, 4, 5, 2, 1, 3 , -1 }; From cf5ab7e91e16ebfc0eab1544d6adb480a4973b19 Mon Sep 17 00:00:00 2001 From: Antun Skuric <36178713+askuric@users.noreply.github.com> Date: Thu, 17 Dec 2020 14:58:52 +0100 Subject: [PATCH 65/65] Update ccpp.yml --- .github/workflows/ccpp.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/ccpp.yml b/.github/workflows/ccpp.yml index 0d9a5721..53421726 100644 --- a/.github/workflows/ccpp.yml +++ b/.github/workflows/ccpp.yml @@ -14,3 +14,4 @@ jobs: uses: ArminJo/arduino-test-compile@v1.0.0 with: libraries: PciManager + examples-exclude: esp32_bldc_magnetic_spi, esp32_stepper_openloop, stm32_bldc_encoder, stm32_bldc_hall

ZrrVuZbv6HAFOOq<|{tI047PHB&bnJvrALf>QUE{$8e9P$zt~oIgl)+w)b>@oSgMCIGvFlv5C5 zHSlZX4S9csY*4PXbg}0sr~e9DDz^f?S5In|^_NAUvM|0h-*KG1@tWU+Rc_PG5r*?g$4QeWC)qw1?$`W3_PTl zc~gKGdKpec=;?+~oW-{$y};I|{whpdG+RFkWM&TqVJu|!{sR;OnZfD=1K6O{phY#s z`h9*L+PqV~ea02lDR7`ia{YRYD?6^U@}i>3hQo=yq5Fykj(T8f_In=9z+(}=HzG%L zJ`@&N+VjJ8A^aZPzqXbCo~{U-`TzDj!G1+2xBIDsi;U$nZqPFfW@7TV=a}X zy`-<4!C&IgR9lF3?Hh#lH6OwWBsela9&{473r08{zeD~skO5i!IJksn;1rX_qS(-h zDb%n(9Aut`ufdb0C1I4G zSH&Ocm@UR0!`xc+D{)@qO}H;4VP(=QRK|$pIU!+<3q7I z_EVV~f0rbk;hKL@)(~8NCUwlg2xv1IiEh}=y1uL+x;RgXX*||_TQ9uRqEF_xv%R>0 zyfz9fPLW-^0K<*gvcrlzn8o;#C%lx@LQd3ZzGb%7s{+My4nd3L91e(9S;G^y#{)<~ z!Oc8`f71AA6~oHXz6}?Fx9e@F^=Amg$+dBRce0HHkBl7ff{_;Iq6;0b>3Tx^F^2n`O&pB{-< zgx$o4P9gQ4=jSfEGV!~fvf4| zk3~>J^HVBUnv`D6RhHEf@Mnc`srRjOn+&^ za>_YB$~>Ie91HwS*{e^{s56-NT&X!i!AtI}S6uXgTJ_(GZm0D`^>_VzeCXe>zm@K! zyQV8tbPN`=Tja$QQD5!njfp#ij;LM{V*tHTK15hkX+)1h0`&_lLq2MA0>;Rah^(4b zdh2UwhS$xm65rq6uXTL;cVsJeOSV%|OCnZ3%YNIZT`s}W-2X@Kj|QbcmMdMz-3mq5 z>})TdB$tFbaCih6=T!v}xCmZ8+|T|+G!=DI+-G=K7vFjo^d+v5BHcD4(w40{75;~A zfRc}CC5iX|h5>as$3AMu`Q}x6-nqkD{DrpsnRgzQnqpc9sBiiGW+MJryEMoxBtX%u zT5aqO^WWIyye76J-HV-oeM4Uua3;XK+n6=IJdifKXr^~#!D2A?PnFF5#0oNRJw=Zk z%8iJFEH`Aq;=t-QKZ&Avcisb7xz1TIAC3kquHf;)LHMXqpu#l1?Dx+f%ltigJmj!E zwzHb1aUw%VrO7V6y8MC@U9s6!s#csOR8GIHf2}WcSE~oXN8vX)l`F&dkyoGB+xzV6 zRUuf1;15=9_~*lBo~=hYqen_``DCkxG~MJ{{wCYWtRE(>Y4;D^s*2H@UhTBDskLjI z*odz~F%J&;t=R+po~cuC9M5O@_t3H6tc{r?aGXMf*q>XRNn|erH4Icm${QES{m3!6MtmR0y&mwVLB3nmN4ul(6pN$bSH1bLLYOo3s9cg?}bfo-r zUbbdhsLZP^MYOqag03dh$x%FO0QuBJ1>Ea&M^WAFhf97ho;-ahxoqP=)kg_=J1l0>Nu>ke^s!%~ zrsHD|eoyAwZ!X!isUh2XAuG8mU3t6>Q;LolB{LS~S@gT0PwBPV3RmgNu|@?68qYCm z9)Xng-nIFpelH86U}`T#uk?y$MM3LBn&Mh_VH=L6^s(5NpX;Bu)Gz;Wxpln>bOWq~ zZ6hVDxKegwoyVj|sbDPp6dw0c_GH`2;OM1){CBPp%=rs$S>?|d(Qutr1eK%cRkc57 zsjq9Xw(E^|yHW$QG>?ZzX8i4#?~AbBQ>@*f3S`M4;(aVu4jHIl*@(t$BW&Hn+Xc}i z8fSTUd$cklAK(3^W(=`n>L219=&s0=p?NRxQEi$H?Woo>6Yy`Z?x4y*x_#l_j^|7C zRg&dx6mLdPMQ@jFF$wr)im>WCHcRsPJnh8aXyA>7y}^4avzF}5<*VbUR-g$)sxsl; zmfm6qecC!KT?K9y54kCYoI8pB9|}r(I7|Zk2yZ6qfOU$^em_Hi z8NR`8%ktXdYvJ6tcux8^DR^kgAcZfvJ z)@@h4R__vBSvZog(kg2!(oiIz8qOe=`TYwhxczRoxk5D%|W z%M5^gxfUP(ca=jHCXCOPoXMW#%~3y_2?}5ZawBt=e9===)n5 zFC5iYeh6iM$F8COKsrMdDSrnXWBj{9B($96s(wwL{AD@dOPqSN`RYu7kp1hT;f+1Z zY<4U&?3`I#U!bDs&7sS@=)%XjFHPC@ z<^Q~k;CjfO$}E>k!9`t?C1K^Ra0=+K-qZ9bPl`!%D>b zB?$$#w_&>t@ScvCgdjW~WEO1}^2Tg>By~}RtF9?nj`Niu>yN>MfN8n@qzOjW4CAjW zUtM`WjgpP`qa}rzsjtSA``lVP8jrKRnYafZd52LoRH+wz$Jh(({4(S2AFejUMEex( zKMCgBTOx1F4*|xeg6VYe)$r-f+F6`sd8}ze>j93i;Wgx!by#@rT1ZDuY03$D z7g?|cdH_#w0x>un%lqY)B*^HDbF^j?2BUN7X0NM?B}&F}d})Dv`9&PN7eYb0v-uO$ zeK^av^0NIi2FSSNgqEhC*~;T?O<|K0ITdCy1=&+`rDF;k;?}dBkPm*zT8rL|sshhl zFEjqm1Eajii>9?t!-|zy)5x$C2g15wvFP+HE$2MO*2acZy+$U{4-c-)oh zpWCoC`Htwvh51ug23kPt>I(=@!O!rKm@Dzso>{(x*4J4UL28wE=2)qmOVUl_Tl#GS z@-#B<=3ERh-_xBTs?}N-*gEcJfA99~M`2yn zV%Ku6H*zKrbVEnXAPI_m8-Y^|S*~4m>BqAYT9+=36z+!)r3D8tagn~Au;@~7vs?VW zz}p3>U`PkZCy_yT6)X<3)duQVnyV^=mJBHikn6)p;yZj~{tl~595|%Z*-RJ4iiA8k z^PrQvpZ>f_m0H{3?H#W4I2XF>MYWJxJN(HHN;-x)k#S+s_p;2!K{z?8FMI8tmF(>_x zqO%Tb@_nQD6eJWyK{}=aqNH>)6=^By7Lbw{or5VzHwXv_Q|X+<=#=j69Nlc>fU)oI z{r$_uMZ8=*@BN(noX?ThY%z0PY9JJc=H5B8dy!uj!GQy(OvLzk=BhplwA&uvHq+<& z!m=nyjW`(@pUxG0fdO?1%(HO$SPokAJ_wHs;_Xf!9sk(*Z-RE}428~oncrf%{7QW9 ztRS|ehMTPblk#;-{8ImZa1ez5k!ix;cr%KxfVVEC*@i61ra#J&pc#b zN11Fc-`O?6ES8lt*(`S!t~lCQZNe1_`m`2ADzagY(Q2}QiCk0pbcpJr>^*Lt>WeQu zZwyzWtcx+mZ#E69R}S3oE(FITQ{XGe=BELW6=cw<`1*aIMnTB`8TADkRqeQixZH6C zZeoX}+sLMDx(%hpd;!NDTS7aQfe$O1cG79@D;;GG`xR$wR zFU3>Lx%X23UvuthMY#Jl8x_`hz2oQGjcf*5Re%#cfSaE{zTs6bc0l>d+UwGLXR>*F z8CXiYP|9GZn(h(qPX88Z>FCYqO{S@M^NC2@IeUI{SMrlhQQlv>Aq18(p1^8$lhn!R z(Wi1rHv%EeV+XI97cEoDe)<--Di6sGRPzZmuTrU$(YnH_Y;v0Jy2k|rt$Ed2azmor()lvwl|fuS=jqzdMVu zqlce)OLoUhSUPhp7k>Vv9&5^91;Dr8@GPS+>5?c{SGu`FEuYJuBwO@df_?y0@E9w@ zHG9UQB3`{QTk}Bj=V?(XdwgMc;VFFI9qn$7_CHXN@0h0e+Xd{3qfTnpPM+ZJ`zKcj zvgFn{t?ilQ|3gp!Z)T2_0DcYVS^WIV@3(3;;b~v5XuHv-v8hg}T@XqY+`gKkWSQcO zh5hjdElGZ|&g)K*NypFan8~cg+O@A^^^{MWG`5uA)hXS0@OGhrlHY&n+fQR(*V;Jc zCuHUaL2^0f52|g#>^+%u%I6~CbK)|%9i<2XRo~}ImI(=3i3}9siMLKH!awx?T!|Ny zXx%Y4fz@%sSef!=Ad6S0TYJi}E{!kQ;yNgIAw7S5X;(M2Wc6A(;uLzNJ&$_wsZm-P z*Ckuql#qg7YSBsr-7Pz zzt)t^esXImX9{%sXwZHL*gGpJK@a8bKIY6 z9jv7+%@C@fYHD9;oulYZb&TuRZ{bAKh0huh9kS%(j)#17dXrWy%~a*~ALB*WYSHBv z743=iXEJ+;1dj%*>mQ$zpjef*N}Yj{+3h*~11rz`ugrlAn5%zV{Q_@3KaHmNcnhTn zI_+888&tEvrnZ^AtX(d{IUgz4+8N3(ec!&O|N0+@XT6mzHuSZW-=hs7v&*nYUBy-F zPDH^6TFOqY?wPfEUB)h3tSx=9USWOyN1>KNSO2IzvdojWGnj| z$UMnL=x#~N8B!~;8ls{C^+v^OsC#YY33LW9tRO;`#BnV)yq@seyCZ!CUW=yhs{5bQ zgwGuQd-FvSED$hFFPf9JA8W|gQqEuC^wjR@!=4&izu{S#Kw z9+&H9x_t0vRkeyRfXhWoLBcivy@Fatcr4o7idCF@U8hb2k;EoQJ6&y*n|1r(I^ z^^)z%Dr7<0gORxv3}2ha9N+p3NyJdvkp}63=#SRFY(>;yV0O z`*TMvv4t-ALDtvf8NO<1I9j9K_=slr01CxSiKV}8G$m(U%kuVhUHu^5W$Ly5H6gMA zOV>_d#OaonM4cO}eUMP+bvh%hw_CnT|2<|F1lYQzK9-4QeP50QsE$#M?m6Arr5lJ~ zy!hZI+}a?)(b(lO>RU%5ZCh{rIze~iudzXYVEG(Rs(uoUs>ijE$->YK>D^$^&n*xM z{+=1|WN^3w^?W>x-Gq7fBco>_b!n z$>dYiNYy<3q3jb}8iij>ySnIh^*72>wY9^CB$qP}lpY1?J~%3o_AJJEpY!3IWaDxM z?{pzwQTlr}a;xJmD|;*$f4ca^cPEYKN3}~r_FrQ3l*;mI>ao?$!PhEi4yHBno)9KP zLo~B3CntSppmX39xGEDMtn?TBsr?URD4ya}=0)-84qozBYq#HSw64g&kVKtMazfa( z9AT7h2{OeOH@69R6r&QVlJ?qU^9yAhqHt0ecO4vR)!<3wy~0272~j?*hIv*A<&WL= z2V05qiMM`xw`l~=T^!uP-tAT$^|%zdFZTh_A4E(L^xKNRU2rFg>hT@+_*=+X%31F7 zH-Hqmk62Olmyu*L)#z}0Q>iuC*s`P?|0WcC_?DEOp6`v#&}*~1s0EbmZ-t;pS?dw_ zN|b2UD-20Gfg9^pj*j{8@K`b1{;#p=oBR!hWr?)c_VbDJ21SRu`cIst6+7X$r{>|p z4oro34lJkqRLT-<8n1|xtntg-IWebY*0cLaxm10+Kg%wE;Z|4N~3}x?Qx_!U)HRst+8GhBl0Oohl&At+sB=* zE}=d1jjlO8MsKCZ=zm{^bF!C_ifpc)lyFeI{WqDJ&*8agO2J|DebIoIb}M0z5gc}^ z!P-Qe6zhqPJ@O?DFimby<5J~-#=?8NPF}A+uATCNI45h}m)(){Xt_~$X zdmJmUNxUwWcKqeFrHiaHsS61rn&%KH%dvCCdl4xuZwoJMcc5uT*g9~|pd-fn!>Md2 z26VWU-q}(ZkL5MtT+vcM>8{%6Zj(tANpfsHG=G;?G@ku)h~?av3V6Vl?C3a}M*8II zEQ`^*+Japlv&@q>tmJdApXJq}sAt~SN_qX|%0{w~qO%Yx+nhLPp*?NFq6yqa@;&;U z-c@qr7(X#0nLa-IH#_J7x7EL85@e&AHG9h(;qjPGYMf+VMT&a9om5aVN2meF#qAAC zjHe={)_$~X`Ta6)0_!B+qHu8a#TkO$hu;X5q}U+lRS!GQbNGFe%GJFQ{`!nv;yaJUng!=GWE;HOw;wn;N ze<-`X+4**oQ4&+psQ-J5yMQiTG+x+i-BMTYdXL~f&2Zx|-b}vR{OT|2FXt*}@Tm;{ z^&@swE0Kg+f9g%zFGQ?pG0r0Z+XAGfw#RmH#wH=K@{*5O~2r zf5SZ`O9fLNb41-Uj?rHI5XMG2j6ZrYcXAVvziX5lU95F9;REo6BdG<5d95!zlJcHP~dKP)4?vLk?0@tA83{g&%Fp= zslOmKz%gNF6JVVg=3gH_DC?Tre?f#17YXcDuVHUM(6ypicx1UW{fZI+W9ZtR`P}t~ zaR5I0D?iLpZ)o~0mNJYcHk;i|l>}MX>+3d4rmFy}A|n2hMogWM4Y(%mfTqB!C}c!7 zX7ZaiEdcgwiL|UyQ}__Y_f5Lk-;+sp|F5OkN4fZ0>}xcubaMOpREk`EV~T7-lFT$V zyfv}vYY8FUGPpr`nm;}ILrEWPW`l6U>U0bLfv736T*Q$U)&`#0iZv8lbPWkjSg|#Z z3&2rkM=KU@XxzS{2GI>uvzzGw0AO$TG(Euo-u8O*-CbcR{5lPB4;(eesK*h*L~pWS z+DJQKF2`HjmfFcOPI@YdfDc~ekK5=Z+R`OvXZNr@?6rUVf>m$;$wu2RfUEfjuH1@j zeu-1nX~uMiq3)|MP1&7pHW-J0td3l@ekM+wB*^(=<2#6)i$VNy8e$hXZq7_#n#YB8 zEYVHyochPO8`RWSWawpdIgZXPE%@$PL`fMu?~NR3ElN~Pc#=^4D~8$Uvg-F+fqeP- z(X1hjm#fT0dNKI@KsO(V$q1f*EyFklE@oT}QcFhS9B*^CnleVxQvmc=AK%3292zW&Gp14utyqupNgSs35m3p?n zQxsl#4){CBLvzsx(q$aqaNCIe$o%4vW0k>@>Y$Olq51wsyCUmvikwD>a2UnE*QT%+ zLvDeD7NI4NH5SWKt8R{{P63$QMAhUNUcj})zJA@WX(KbU+>~0`moEkFB#rr@BdGdV z*-=hO*NWX+7yyJ*&UKx%H?xhN#jsu|PN5u3&+9uge~t}81%18Z>t)wT{iOvTl39i* zN=SXq@8F+rP{H2q&D)t~AsarlCbm6qRD(W3!=>RqYO3XLv5JR zHP1iUY~ub$x8@^2N?=qDGPjRY70D?_Qm@?k{V%K&B-!q zgQGEUDjwhr)L*FQ3G$qi0tp>DoJ5^(Os`|N@Q?3xjPM!B+?El08*R(JUlpq_-i<#? zF%vTV?rF=bY{VH&81eqouQy&w*h40dkN=Fk7CQHg&{j9 z0$?kUuyzPaG^ZF#*RNe=9G)5r>IQE$10A{X(jWlk&2bb0y`FKC&GfsP z{vDRu(R-nJSX|}=QKI? zwsnxkD_AR)(!q}DRN}nH@Sg(N|3F(rCrDvj(<(QF+#Z-)3o6y#5{oAl;+ zS9Hs47C6qOt*##deSLNId$f|#oVW*6Xvm{&!RWoTBePGaqJjM?y# z=J+=ZE18iBN^QfY*%;}&Yu&o2=R^DVnI@FZ3m^e5CGc=tl6p19evUw`OFh3DnA@*;++1Y=30wM4;j`ly$V!;Ca;jn2-9L`_= z*7f_q$z@9TC**ChaKaOx#O3yLs@v7B;d2g6Dw^cSzrManRFFOlfP)uAHk3Q-s-a2r=WU zj`3c`HuCsB&_ZLDI=qZ~R`x#dD@q2wg26^h&eZ7IE>h}g*7j>AMeINHb?Givx>e!_ z8p`{)DG-*5Kh58{whm8|RXenU4aSLN9cge^z7- zaGz&)m^~;TD|M`LU=kg7^vH0v&6`(9Ggf*k9`mOA_2cO1^>qNiWMau@bv)b($H+63 zY8iJDgcF}H(5lKj7*H0bf2(etvB4R5Yc9u)d%Tex`0gDziUSFD?sopd1!_Hw>q{OvN_Tnp%~&qgiZS@FQmL863N+3rziZz3Ko#wp z`UX>$Y@=@s^fiZPmrs=OD!h-eroC-n{jK;Fne?R+sOl3bR}3ewp)Qv^H=EV!xAc)w ztLiCU$7Y5d#*-h89*btJpO;=>Z*hNR$%`Y0DeW~xPy!h(`W{v}ECfv&N&pR7iFMrA zXn=YwsSR;{n^)ZbfgUe(S6OUEJ{Fz2)1Y`404=?0UF>ULqn!6w!z_1jFOw4b<^t=G zKEcLe`*ZmnO$uYCa-EXbus?6|=2x0fb^l()7uY^w2GI<0{u{=zL%aAR{Te|K=tS6~`RaLW$?a zwBVnyf)k`08b)5%*R@?=h$U7(a)ECYr&s{*%{FG-CoqLGnGubmy1Q3`q0E_22>Nb6kSc)pLn`ZMu|6sxLnJY4+(>xm#x zHE2yFy2yl0t#pXg2um8~v8a|^BWNmnE^8Wf5b@*IMHxLEY$dwroL)klHR)5D-fk+McnU zTjQ+q2?OR2^j8(bOL?{R>Z*wpt6a)~EZ_VZ*{;BGxh9Q&fyGR;uLho)|6KI%NR_d} zpu_<^0>cj-{KK%_PD!*1=_qOO$@Xu=~(2eG~8+<{+v+WpQCC5Y|c7MckbhAj@A? z#a|@dW`+TzZvl(271a0VBwEYf#X)7}!typQ3gUHM3nXi%_&C>7J6gh~e>4^y0mg{aW#GW~=m z4dmyW*TCVbMff*@7s6zwcEmk0{Ifevtc`Oawq-j#RfL7kX-Gpmq`X$FMX9U6TyEZtl-V;S<&R4wAo?s;_PL%}Dq338)0$Mt9f=G!VxFZPCFMZIPrLQ6R z?A~B)jLHZ8tkxwytkVWJh0^!Wiyf4s zS!uC6Wqz~g`s^5~6Zl28b ze%(-J3X-l^5JyY&ua{$l13ICxM3!N94ZR9PPFQKE2jkk}pl{}2qq9_z>sK0cR zl=xu$R1}e1i<5n^0<=!XhC=R(7tC_YruZX;9E&6V&b*jt*NJkzn6F!9%t8dvg;o``7s#*9~cf zH|!il&R|)8(?xhT464XS9Eqr=*425+#~2yXH_+&!6*TTjQrsGA4#sfqi&?C;+`}nq zwqP&5ohmhI3mPlllorhH{2}*JW+Pda`2PE@j(BuZ$XX)lw!wRzS6H(#ecQP3&Iu%j zZF3%cue5eSLsJaaf3?0fepakX?7-ib@0TcOj1gaJzGLg)CKB5eV9OA?Vt?UoO#UYW z=6>l`LH_tcp$k1vtgF}P`>6WM?E8XYbzob0)>7&>+N~X0aIz6xGI;bd`NF9>!?kC@ z+bUr?c<(ZJtklqqW8>fDvC+W(Ev2b9$Jg=hnc2CX%`6zm7ZHQsl}>)$S`%f$1)Imh zH+E|Lb7|GWoT7c?aTNPB6`C%uC0L`d!E4P)-k3=zM;>Q()Pxh~=o+uBa|-roJU?B6 zEduWIRjljXx97AEJBW<5hn@x+WM}1Re7H!GsW~^U!9iD{v-<7*Yy4kj1#xw*l#$=W z7!hG}@&Sya10_!HT@W(q=pU~P;#03*t~=5kgAdqp=e7}58qrV7F>5}m8a4F>r5^V0 z_pcmP@7{@+LsLN;QaZw;i9m`VL_XYN9{JEG?A*D&YBW&7q2uUwPI96u5OM}|ncoA2;D)PIQ#GGFFxB2Vz^O>&> zQ-Xy8!NKjKBn!ws9fTM|p!ah>anbL(!<>n?Y67QtEAN~igU*h+n>@i}Ri;MD7U|O~ z>Pf5p@N(f8Z@>LQcgDt$vU@79s-ZEG5z^kD4;R*P@PB@(5iqUCdXi4(rR;p{iBnVL z&%L7s57D=tu(Ud}MMoY6(gya|7%x!dchD55qRB5x$Gd1GKxn8^rb@2x5(eezO ze|wO8s8zqJ-M6X=0j|IBG9!V{41LtWk9S!gp~gMqXqR>_^!3m6Q)`4CV>xy%X}MqO zG6aV{I8pq{O;q*L3i}{}!tWEpI?j1s%&r&Q`S*Z;C=EcZN$>%0(t91Foh61h4PA3x z`3~rg@<+C6Df4=bOXHNnhXM&rc-X+xe|WV8XC0C6H-JQVc`0WTo0>`&g-tdY&foN@+?? z-ZbhJ7pp|^u6R;aWoi7#DQfxg$!DQLe*kECvc=7=QDfTABXA-4d!!wVV+*Px&DW~e z;&X@G*av@XDW)=XRL0)+1PN^XntLN5l4T#B!lfd-6jiz(P-gs=UIjL(M^KzWU^L9< zY+D&^gBs;?@cOkF_}9j#?u7pxH|95vkD!UFThiVQ^+^cISRqZ%4Ac@%Ris^T@IqCQ#~1S$TAw)$Mwxqch; zyoq}adT@lqBz!0Bb?Y}`ril8I>f^Qz*qo#EW5{%yXawHj5XnKDVKz69Sv@*AKVEcp~H zqfcC(q{DKta3#%Zhtc%R?yv4f`c$qqg>|*i;nXP~bo&?Z#aW@RMGRKrjr(PCJJV8L zYu%;Muld=q&b3}C*4Gw*JfFw1l+^(j27kV(F4{Z9xDw3OQ#8)fN zrY>gw*4vs~=8&=2xOcwr`S?;<+h&4d$F#zt{=jwrQx1Bd+U4jHjC&{}VBAdFoFO;G z<5}Ru&#A_>t`sz-7?N(zJ7CAoFgKuxCnI6GJlB|8TN&JHQ}b@u^B!E~6}{HM+%y*# z+c8!lnn#XUebILKl9v%IPHV}JCSJwrfM0z^FNR;Wh1P7OkIzF08!UhkWK& zu69Ig)O>i2SwEOaItf`Q^45G!d_6?MJw>?dGX{Q$b8<>lt29WC8DY&nVvB2y*Ij8CU$Hg{pK<2Zl+2l1B2V-L)@8|p&zyg8QnV2 ziRoc*-le}w@rVb_ddK-fUhSIZxM{2^gJZlkqw3niy%dx1KENKVruoIL zHmwzS?%vB`%`*K{mWJtV2%bu1>skYC8&mRqQ*?axUyTAg1p@DXiX4n%GGTzJ`3$Bk zvPldEM#9^e4`IcoA6RCncN{6NO(=oobGHV1Hq59pl?Lo7w8jOpQiY^zZIdoHp}@z7JN-0k z7|v6cVt{@5j{ua<26?nIfd$oM3>U+BqYEsqNUs8uC)^Hf0^cvkaT{8r-L~ithCkns z0iS8VyX=Ic8nOOifAziGO6KvmrvY_50hOo7VE}m6cCJA+Sm#=8Lw~wHJ%_-kLLNF} zY9dNh!3$>XE_GXW)>epNNTzQEE>172yzW9YhR@?{ot5%gvkdU1OJI6&{}6Y1U?TUV z%y7*oj(w1g%;Y-#c!W*DA9ELa{i!SAih#I{UaN0f)3QGFN>@mnYEwtrJfaiw!@s<2)|8UE5UjsR>6S|{tv^6>-xfyAAEFHQk#9suh) zG_Qh(JDuL=>TXXF5;ER#<&hVAc<(rPL0iv&L7&%Iq_*GiM`O z0R++6dHy$PPRdXZCKkTM>|;kZfejx)S$D+so-5vA3pvZ*T3qOpXKLjj>}Nz99Sy6b z4p}Q)DL+LAIPBiP+ml#Fl&_9jvC%b7W!L!Kw|(55rLY-d*FZ24JeP6fE*d*HUyJM< zIjH`-qOX=Gf1*$PXuD@@Y(H)N$O!ULxSpeWi>CZsWhYwQn>}vA7A$z9raLK8AT5() zYPKX^gBo|rX{!DH^DDDM(~sEPx6$zuY~lxL3zuI6Zzjvw&J#vGDX9a8&7{UXV0ncF zI0x;ZL2cZogK`jMu>c4tf>lpA#?OI=mk*+_+GaNu03qtWd&hLjMPfBdWN_s5l9jz5 zMn}=O)6zE`=eyocA%wf z+D*Cay&1eaCNn?65_5AD-6-U@Q)16}81ty!ojJoyUe?S|^9${}WG@o>p%r?4-hs=w zp^T%D)TuzG%E_ZY#>Q&OL58Wx(*0vz=)+QqmKqSRs|8 z!lsfoe7ob#w{shLZL!@+;fJU+#I@Aha?RaKhtxZ> z;lv?2Th2nE45N;6Bj>}97VQYsqn@V5hRv0ur%{gu7nc^4o>rsYGxv1Xd-NU#9N&R0 zUuzR)SZQ!#D>D3MShaKHpY1tRW95!47^Us7YEFH)K!bfUnEb;eNviCao(C>FcbR`4 z3H&6L_J2+nF4LhMa3;HfvF&qvt92Ztoyt1AIa!sqxj|E5a6W-d{G&G!w$X3%H#Wa> zuBMYelCi6NH8=6#X=7uf<&nSJyEsOP9-Zhr;t?*lLqIR)N+nI4W=*b6(0nnaflE`| zSjd`awmoL;9EyXBF0!eNKXC|jeRx(dN@Av!XQ zjh*-)AUqvLdgs%J9^sE2Ny3HHY*M^Kzn0mmS4UgD${BR-%bkC~(O^{xcO#(Io~xyn zd+6o;S+w$)gWYdWAOu^b_vCftWX`?Bc6;BG^{%&$l+Rw8mjwy{7XXzOo8=j9^l2dV z$XO}BsX1jkZ&m_YgGAadE@7kh_;Q@vSM!iR#om0ts_Ab>I)@bZv%+z6YMJqsmR6v9 zkOcD%Fks4lwf#LWcXA8*@LG4PkK{6!ZQy%SQi{w;D>4c0JdERs`wF-ITI6HfT57d6 z43=x2T?>gjR}T@Vw{jI+8%U;4Sbyhjt>pEd$efrk55^e80e=!yUGvEP;UAp$id3?I za<<(GO>J{@LI@yBd`gNf$YA@ZE~np9>V5w1*g_NX4J1yJBfe$2lf6PfsWiKno8nPi;tK_FdFG#q%IpYZWL zD8*mM6z}lQ0L+#+tkn5bOHD@mm5CoXI7_WYmUD_oF0V_6>K!|1TF}KMVV&8nkDl?} z?(iKP9CM+GosROj0gUg?XV8ZZ+PqDsW(;-Y%+FO-3KWw1Ej8}$5fl)X14bOmr07or@X;(8ECw2WC|Nj>^ zV6&KPG|ih`#zl4LRcp{JAp-;zJxdpQ&`(fbg({{bI6T#g+=w%N)M$lZDAk~|*J#pk z+2^>T9e%uFnMg;_O7#vulp|r|M;9|oLyl7<$=k9OSsj{EdUu)kd#WkVNe`y6Ny<0r zfsBSQu@PIKVr%{tbR*ajHSsID3?35o^0GpskM#AOKzY19E-hdUNwr{RqIS}=j_m&z zJgfK%bc?VJh@ zEq~ict*~xFM0u^IT7Jk(!IF*{BTjtU<;zy;5RRBtlx59GZ5+;NSxGkkdkU|j>=2zo z?HL;X%VP0J)dYK(^z?tPVL;bBN@=^)rOzs0Itwv{oy{}O&vzC45l^-3D!5&AYXl(Y zvAn9KQCxxVpX3G(A;^W7$#yb77e7dmIY5J+DN*hdiu`r zlH;m;LkL11KY9~lanFwy=^YYU*$XPBx_J&{xWg!Yl*9$XPpA~ z$N2|-t8yz=3(o9zA4ad7_4IVZta72VrhQT)taG zznLEzXP-zB?kQe>9K3!_81eJ|*Fteqv?hmh_2fm3z3yDrnp%82q%ihIRd*32ZP9o# zLS+8XC$C)>voUKNk}g$H+4Svt;v8gc9&u&{V-6ntWzu!P-Qj z13qw**`(g#Xi@RKo^F*Zwl>}s7E8#jg_d@uAXFdDwWqQE=U?H{a^~Eg7Ni zRX0F9C~A(p$ts1Z{oXaZUpr2CWw(6K>5!uWC=XuUkR8u{m{2oEZ2T=(CkO}+>q-!( zbUEBj9T8Ui@wt@!YAM%cs^(D|(gyxa|GCnw%)nG`H9*nb#9W}M_5_;plB^jnGMvRwcXLGL<_*JN{ON9+>kjYy zXS^NwWFq?$mwaA^tHhV>C1Uukll>tAlMQ@uUw)+leW1mif6ku6UAK_@=IoGpljhTy@z!dG6&jC~h1l9g|*loxo0 zH%e4ah?$b3Dw;t=Y->0C3Z^6svRa!ox3DK%L7*!?O82a@s{}x0FvFqIEtG^l*{8r2 z>pZmZK`CXpv&g+(e)eznUIa(i@DB?|ysXiuE@JVzib?du#RPK->>xFP;*YjOJ+0w*zMa1z69-4q8{{mqS z6lGiZA%EjLAVuJb{5;2K(vkazrdmUrv(7mf2F?-E~!f1Qsd(I9C-fFEKv93Zw* zs^|;7xPcq3m18cb=LG^{2f=9k2fB~Hh0{ViFf_BnK1ONi$_vey%+49kNGCOhzQ3nu z_sftuI!$TeP4|EfEa2K5#xMf6Qst-Eol`r{U9Cl9ze}dYnc1z=DKiTUJd6Jm)Tf}8 z)@;L`B@}tXJq~d?`i7tnq{bPmVQE_cptNoYEw7w>T*s7A>I^4wsv&#OheX9Xw=xAX z?(cdlJ{q0y$2FaZaPMhJ{wNqV8km2#ch9T6Dom9 zdKM5ytP#1pHX)?cC!oLSJQYxC)jL?Yp&q5bjc?OWJARq9V z-LuGc_#iJbzR+(+H8f{WZRtB!;__HmCxVEEJzB)?Xy5yq4A;NPlKb;2FTx&*)z+L8 zi712OozTV^^Zs?tRc#Jd9!X5b;g+#OP+9#*&sZ^8tzNPp*KFs0H=(jG2!LR~B+I^F zpT&xE$n}xyF#2Q^8&W*iZFQfJvFczdOT(CpYE;>y(5LGebF?IA9vglT+Pu4$!m1gp zlx3%G?{NYF2lD#Jo}eeQ!dxl5dmV_FxC{8yw@Xp-l$*Xkxi0gB8D6(E=rDyZHPkhc z45?WjFFRTZ5)UK_mV8zxs*?thkawGS@0jNT+`wf#Rl|A6O=+WQUcnUpmS^rxFYiFo z=Q&`9z%sGI62|R2z+{W+E)dx3CnDoigTsk7jv;B?= zd~Z-SBvvudwTrv*<;9cB3u*lPJ&8fd&wGU@(@_MX9Rhvr-*I6z(LJN|HMzf2X7^|M;S4HVaW0Lzpzsb1%1BvdMSAg4R34A-vvY4qT=jlNHNsoi)0hC$@#g++# zT7^Ss%C>W5P3FORGVQ!$=qnXE-A_xCS6Z0ha}YMaZ8(IH_h$lLWCHJ$*R&s3Y-+w- zB?!%ebBHP4P0B9KRgck=& ztht+weFNX$F8ZPQs*aP{7n^LWRVTyem+)^)C);iphPXD`F|rNugg?OPTA|Eod^Fm7 z?N>9xt1?P?MVQb$!_EgR6RzsVHyJ<)?GY7&xhqo`TMvQA$Cf~K6eWo&34JMIC(T>1 zu-*R@eMA@{7@GOUQw`K@_fcXZuZhkRZlarC;NMG9iQ%7NaqzZ!VOj7PFMx2L^kjqH zgN>P(FzK9Zc*DN@W_!oYZ1>x3nG0rglMXXp;nh9-1bD_pRTV=cJ>0HrgNdTF^}C|Vb?77%1YDwR`SV)Up9L0d@taX*m8j(|7vQmPa(t9wMv6VeKzBVk;<}!6eKwg6NEYmaB;Xlwr&*8J);>D!_wgCfvwuGNf zZ>Cv%dbQn7sXXKbWDYR9%C4?ylE+rb}PZy?lmVz-r(H=z3arWjT2K-TOd8-b(hLTP&o_>h6F^ z>X#jaGKHQkpr~PjN?=!NI$1r#FRN6g-zsDb_Od))sr2NF;*@(Kpx6h$c;~;wP$kuW#})JJyrWbt>zz4%>xe z_TR2?M4qJHR5CiTqWc&a^YyJ9(4#cXE71eBJ!k7*FXMI&v}bVs``0dF&QEo+njlD% zX%ov>`}czwJa7IW6Mx#K0&?Mtf((3E1z(4gK-=pZPV?dmX_eM%KL`YoCDbCPGNlye ztn?ju-jkEo5hcYoBa&gdnB^5eAc{f*Gkx6CFD#k6?+?1HON&fGoV)mYc6yB{3&l2; z#SJcp`)Q3!YkS{w`=_XlC`69%&kVv!MorQGi=RnQZq-o`4a%j)T9#|+a$9&Y{GlWpY=-!9L9^0Q6`FQ~zzS)a zA$A^+U)h3t2$oH31oGLEo4B=e1lgt0@sz>k%EMn`r;r~=$v>4cT!I&r4K4QkF)R4KY)bEz*Xj&xo`V^zFmX??HDrN4QSDKK(4Sf*i=C?JeDQ}g=0fG zBl2b)DCCOEt&UVzC@C~nhab+(&LPu;$A~p0o@7A~J31oQNKt~umCZce4Iv-5*B09)th!G1&j*tS8mS`IE_J!mdtDp7ji4+v>D(1e%%cY1w(;tuA$Fk=gRP z7Vj{6$}N+t_^Zo-Q!%{qC0HwVa>B0qS_K2)y0jI0X^Jqs`}v`kLRS(rNW3gcp=y!i z(@r&hTKCsX5@Stasin1;m4Ew{&t;(2_*nISpi2Gg;!CYxJ4@Ox*-(y`4mXqd;tGM0 z)$b^XTw41)7ZS|xjHf&q-dl(@d}8MUONlh{5YyT&TQ3xs>)5O>3m zOB)zuTejx$4%^z&_YCmBzA@+*<<^FHtU8jt7m`53%Y#HU3L`rcA(a?5}37}Z#*KPad> zT1%L7!3jAyFVP|gKFvvdQ`KpjIb`4>FWhH_@;3b?KPR$`ef~7`cKW?ZYfYQef2r{< zIUfWPhCS1U{pcAW<~{|`KTFj;vSV*nW}rO2eEUPr6_C=}X5%_4YmKM;^+Kf!%37^K zt=%iuvYH4=HMqiZUU{f;>VK%8X;(1RG=0KWgHzE2dK6!&PK7SCEPHsiuybk%(rf^=y3LS+D zzd5XfW%_*CR@)j5&vxHjzVyw%P^XxWEk*h(6tCUYW^j-V{*d+jY2pw_NlOfeO5X+@ zyhTM#i@u%H?skp1e>~V3)3bQDt@1<0X@f5HRVkqvPK`}Rw)-GiieP2G+&)E;;`UnC zXq(^1Qyp@&XM}UorM(u#Z&evAO{LUP4&6A?p%@pweET&@`ZQQU8elLB1yYtb2>J)X zxc1eR$e(|%`ZxcGh+^8Q`%RlwFj$Yb#vqci6%-4$V40c}t`D~vCAPAMeZ5F;Xl z^xGx7>7XKXUwnzKCaPjpoALU1&CK6eDM4ul5w_8p_$Ds3hwUz4TZ{8Y(;cAMDD?{Y zrw3?_hAHj`VHM?aj#AqTr}As1X6=*3(MQic5wMmN$36?$Ps!@Ke2H>nd+b(>K%S*Z^VyU#IJtJt19D#AwDSzGn!xk}FL z@PT?(+&$K9m@v#47HyCvdN|n|Jw_ORC8jA~F}dMp)C9Sl=|oMOZWq|x%8=m0%5goZ z*!J`-=(*KEfb(#cWg-*fQSRdvtrUbx8dG7cq$ne>QXa0{Nn|Ks{`&Yt`a_;y;i9WxOddVe31&xExQ3duC#tkK zJ_H>+q}8mdeg@!DC~5fd5>4y4me+Tuf3suRn#^%{d{W4JKtA95IA1M1p^jh=J8ZCK zsF0RF#{K=yVKW-R<84;F_~v=%Xuw^v0C>P=ed;+w+P5yCKEJ+mx{xf!`?S9bb0>F3S8-~&zVm^ssW zkjwe!)uOL0U*B}yCYkP`lNnq7!$$kNV9{p|J1<3q_#O6)&JOz+-YKIRm-XeFJ~qeH zmG4Skp@e4Xg_M>8U(heDocx@=)2?zjy~0nt!_%j^TqaQqzUCWZ!RY8&Eo-Kt5bgh# zqc6k~&5%ChT=4U|EMxZcA9D)%J;ZUz$guNtKtfQQi8qeoNpC8s97mJw+|8<^N`+xL z!r@Taksx9cMb16e+)$PWtP`w#cVca8R!`U3-Z4$mcig-))pn#liF zv#U*WAgDU8IC6%|%abcS3b|?CT&KJZ@||vB_h;Vy8FH16Ep} z?Z%z!ztM-Zt={-NqQP_;cYV3~>nAoO_mNs_5Q~rXUGE1i{iylDwQM$mn(1c{Vk*+> zB+6p;_$Uknk)Y! z-bxT{wP&$vn#Jl*8|#i%Y%JWU`wwTWKkqT`QSxOAm*D;fhnowcxLs6yyjCS|1)g>7 zkbIP~)R9H2W^EZI&TiGcE+2M;KU3!nU@#tsg=DeBi6nMG?>=Syc-PBBPr$QgIgJ!> zdH*;<{KO|?s7^|U*0DL4I(+mxO#8Ky_Yc)6r*7g^e7($oBKk+crLJr>>`ntF{1+#L znc`j_`26p2uc32I5Eo}}I?h z+RaL)&Q+@S9>N@wIF(7d;f*ueWTF`>`g!u3f)AR$5m4Kzm`&-ut!& zI?LAy!m)?hF%YUL6|;1jbECRMQZ@Nw0G^~3W8^Dq+rc_wkDrpe&q_buekMHeNec@oz@UHfJO)$17Oml;*etQ>3o*4>o6 zSY2W=H^QIcVlfDpX7gT=-p4bYL(2Shc`j3>{;a2;O&Ginp*Qj`;y=u{nB9-IwLc!H zNTy)IR1hoC5u_3kKuS>u}UVp?zjIM*?ivB3wjK8>ZNV~eWdx}JEj%Uzv|l$>WZ$ycKB-2B?Qht z2}etxAz{CK;kbd-m=8+lC71HukP-)P$+?swXzJ+{Wg{btoF;gRdG9IdDtj-~i3iVtVcdS!F+DDxqTy5RNkQ;51PZA>Vil80Pu+6C>W zs=b(Sq`S`;g$pPF0H?8Y$l103%++i`bD|_& zjgVzfYOorBTHl4Ja2G+>zL%o@3H0oRdqb9XIm3qu>|C>v)2SM56gn@aPkZ4(@Q0cp z|BdRsQnsX?p?Vns#5_MgQTnv}KD=>K+mT~ECFALy$sqmx2hD%qJj`%Ecc=K4m6-&I zN@MhC%4&T$qA#JD4kqgKeDeVziycr-S^fOf{F1ris;Ys85Cv8LAQ_SX#A^MgprL&; z2=dqz%5kAz_7#!jr$;#Nlf9oXhZ-i-VSGkHjU}gKVgfQLC-Pa@Ru49*^lqKzZQOn^ zLmQa%qSVB`OKom2NB6+p;6Ys{85S<_@gZ)@B$r1vNO06g;l&EH5xio44Wmg9z6PBz z(B%F5v>>7s)26z~Qe_qIw-Zu~iJA;U{9ixa zeti$D&=OlYfaU=XIURRp$uhM{*|Sbe+ChC_otka8%Mq)Q!aVRHeMoF`(lX>=2T@T= zQAdVIZo5KOZ$->{t~t146?ef|>cpMJc9;F@YKOpOQh8koyR1^>FgtHZ3nYgw`Q&)Z z0!+a|!VhE_dNPf#!=CD&@(D3eZvZa2LJaH1v8eW#bvur06t`?pg!XFc(mBCW?OT%Q&1;KJnSijqQ4FH!8s_ES%0N zC>aJJ3fmrLM6oeUhhOxaCjGImrHmO`fa- z{cLiocxY1*0+rvC{Y6}|`8_`8=VAz>wYvL>f13)^ex+&Y{IN@#5Lw*e(qP@ln#%o; zHN(0&d%nZdygBg!ya3jxq3^jPsw`JQNbxuO;nJ#P&Y|2YeM#{)RRaD)W5TI5zoLn{ zMP3q0%~$ym9oVG- ziy-^SPQA@~C! z!X;9{p^5RYfoiSui!(cY`$sN7(~N(Bn4m8QjvbK)mz^ozKMd#JL>6H7#b}+008p%B z56lJ?hB!#@&6nHBGZJ#T=eI;jKq3~yxL{PshiyNr*niC{_zs|U%(-lh_v5+92H}?; z;x*q)<7?eo!+&{Q=(3`ZOP#s647SYp;I63^0{mq>kQddqiF3^eI{WW}NEVc@r`97R zmLe<>-*v|PE}!$d$dJf$w!aH>AYF5S*)qH$7R|}uV7*e->*)7{)c5~w2K;&e!mUrT z4?V;vbM<1J%lVL+w34Aa5K1jb*TEG|B!OkWc04(!ti0Gn;^D=`bQPRW9nz*66oHzq zz^Ye^s>;aKbB4IM0zM+ns+5WTLC_@XiGpH5)iGjkW=KZ+0>|l|hAGG8)YHk5h$Tm< zg&TQwZou|w?pVTU8R^Bd)Q!Pv$zC^E%R{((-2aBnCG%as%_MQn-UQ@d_b*7-)h!%O ziDUHVH=h2o*3<{^@ivBX3Mb@#rL)MF&~yK2U4h1AsKwrfSjVjnV$Yyi_*_?>Fn`ngI)z7Tda2&?cf?$t)_@ll4cElH7vh2rjr{{-I7~DM$=zK3%P_=f zsF7Mx?p3IRs*DZ4;;tGH{QA%W-EM9MUiQl3v|4gFOkOjV&wfrQh3}VF`4Nnz)4>qw zlM1WamK)#o1-c~p<=3bZNdQi~g$#6ZF87==X@&m@lrED>&Dlbyx$;RgH2+{|R6F}v z8xcDCGKOLzI4q#?D+iy7J3M^I5Qexao(c4NC+=3)SX9&{V!L`{$W|c(*U@i71cL%C zN=8;ej0>ik{F$Ea5B#(|8zZqqlHeZfT#%uUwRR{h?B=X$jyHtecY*n1!ybT;X3aII zAh`03&K@y0chXt|6MVz1Gzi$aaGwVLE~yZ-iw%@_*@G6sI-3#I^8RO0fv*mE-qn5z z@0R@8)g5T@psA6*boqGjMPfjxEEHTkW<>bgRJHonQX1o;@*MP~hV9RfX40WUxPaTGV&bX09PymF4MdC zt!o~OD>|u<)SnFob`quMRkiDGlI$PU+Qx_Cn}^s=fIRlZe&kfS8Q{Sqe_}V!5&37L z1Cr0}rA?TguYfWy69IcD@zPT?Q8{^Dw@A4A55f8|8&OGy*fbe10=B25#2K~wH5al0 zn9hrM+WDtyGJexmJx2*Gd$8g-;Nu6qg39YvE2`_G1`|ZI@+kohws?KjTHC5a+`ic< zvLSJX3Prqy7|TIuXt-Lt@W9>QWm|t{rBs;}V|BevtalafxpE(0JtZCp@I{F@@{WB} zy{~$eSgbmAncFZh>UX^PnELyK_-U-2t}0)&3*A>9+9k=qyT9tNZDZH0wvDyp62u+J zr6KoXb+J$PqeD+9e~jUFlX-Q@_#Vy`qmjA4>INNugsT&mpfY#FE6a`7qWTJ&3L zSP9VWRAv<1y;wU^j&wRQbs5Ss+29QF?O@Tl=+FSquIUtah_x-XhDO6${6T$*mbD^1 zayDUFuUYtkm)Ra*Zf(Md>Qvcn0?ZGCzpkL9O2K45`~LxgbOR5rdl#b8cE8UBc{Rf1H#ma4# zI-8UIfK5WcIQjASottX&OJaPh8fz=DyRao+a59As+a>v~mED!|`rqlDXol>Q62W|% z6&s6_=t`VIaF^%F96fBVBxTO3thIimevKh)@5cW59i*iK-Z)?TiG_C6;tt}6yOIy> z9`#jQGJ*V=_xW2B=>daveXSHON(D06y;uFQER+czy^#L&Dk#jbZg)rWMz=!D1Oyx` zQz3EipUm_sd55D-F`V_{&>XS+^(fGOWeY(z+D_4tIld(eS`(b?4w&(K#uJ;L{6X=5 zI!gsjUJHsbkJr?2g5AZM{#w0EZ{GV1l6=n6c{|Mo^r$lHvTJX~x=h9@fsQ8HcDg-==|-F_Pa}vi$Mf^76$o&jDWxKbfZ1st@re2}U81ViYso$aUE~ zR(sICb+B~bDsT%4es6dtNj6D@i@CZfT4``FK)xLJdR-(JS(VP98xqtGAvrt}@t>_x zT$@95{b=nMo=fO`rv0e(c(1=9r9h6@MN_;@?0%-MLB zaJvq-^jHw-;;w(^)wNF=_nbVQT#b+B5`pKGy)pURm|!Gd1#>IvI#)kg>2au-dK&M~6M?K7YXPKrQ_*(&uMl%=Pv{x(zCz~d8pP|TGTU(*y#M44z z$}QC5!T=@2%VMl%o!0?f#hu9SGLHykB8d?u%y|zoE23)H%Y=`>k|^D;KeL$5vZSs` zZLq`1wGNc)-yZZV2c(TZ*Msw0e-qvycvsAG0HoPYap!t$<`kdLKq<-E^KGrrz`Xw(y zF`B|)%oA4&ooBsB{*yxG9aQfYdWkQ+7I+m~0~2@B2`KFYAt)WGaF3>>RH{G0mfKaQ zg`u1k3O2?S9AvQE(ac~V-Zgn^q8-UpRdh6U&FaQBO*Y#Z8)uMU31u6ISZF-^>b3cT zjU9JKNy*8_@;PkTqRa}`>4X?QB(;1yiu|dJtSYmEbuxdlO|wV7DgRScJNKTjlJ zei;TOcEFbNFMMVcVA zjq%7CzeUMW!xyDwz{tAQ0iRM6q2`IvFF2O-%kIgFB@h1 z$edpMahIpb1^ICJb^OXvoTe2pprL zY*xxAU?DhiE<_bz!%=_xW0hQ-31h=UmZ3SBYRuLziW+43ZV3g*Zd4yKBtP z41JdK_dy+B&q)^=;G%Tv*a*sN!9YCGj{5G!{AdZ!oufJ&vhm^{AW_$472??pR$||$ z4G9`$#Y_McYug`X+vU7JGwa}v4L)p$%_6X5K%Ui{S;-u)C=vU?XCu_ArhonHxpzwt z-O^y}#N>=w5~~qn__MU7A8!_-T%jnz#4i$Vu08hS)9c~RHrKQ)=ywnnjSikp8w*=6 z&#{hn_QsS0cw)g>j%(nEcE&6ua*46UhU>mvg^P398FuY%<*y`bmt&FZw>k(-2O1Y$ z;|B1zu`CmQbSpd2yYhr?|h_&+ae8;rE?!q6ka!d$3G-Gw2#sjHm!fYhRAOtLH)Gh% zSyolJ@)Tnh&j6_etmdSV5bKwV#x=1>cq+RF3Ul0{m^9P>CZFBoN~PdVFia#^7Um!E zXh~2|#8qU{5VL{ePEfd^aN+*pj)uYuyNoCAR0N8worMXe#j72bWqBhTgv z_Ert-1y|6P5A;-Gv((=okO#r@lH4`xlG9%;kSpWWQLp5&U~IuuZsJ)=zb-DBzJrRx zI{qSzWOqel?cNp5_5jwwBY%c%df3JBhI2w+Zi5V0fxPX~KR}t@kmW!I&iU_Wteo-y zv7abl@WRZjaa8$uAA!dyG5_fH_RivOomz>3v`yqj3a`bu)eB`=l}K~c{4nH^k(p%< zO43a&e67g=flk=cBITN?5oURwNRFt6M|W5fsT!}^j)%hWJMh;9;(d~O7T=9xS7kA* zWXN$gt>3cYrd984R3@xc;4d^9@gjJ?W~70yPsgiK#g?oR4!7}J^C z*z)%K*4d}dZA(2L*yD~;9;*@-KVoBPAN$VkqGoU_`pfYHw`!Rmq`2`@YGM&!4XvPgf;Td zp9vk08wi!B-s~1v-Gh~`9`0u$eDzySo%HQ<+3PBuD@K(8#mD`o-kk26bRQVQL~Du% zZmIG<-XW^kDoD>Mp`4!YPnwo6|7ZT0!mi?tl9HC@WylZ?y2%Zh(QCHTe_DTIsPT7c zUJxY=Y)Su7^|{`+fCrrDkA_3M)`Qu5mU@*Fr;jvVhK* zT-ur36gu_01%KviHA|?wR&Njs8td2#wmWp)-~<88TYXLi=Ij5+{S*93#io;{H(7 zmb1Lc6Z9;Ko0La}OP^e?E11mr_SXJBChc$d0zZ(mo%a5TTP@`N?ZzP;x)JffN(%m7 z5zL`zh>E=0d{hpvte*z(m6Rv}KzlzcFEEv;37;{+yH3yeWmxc_-5(r^>=aNFLY}Nt zH|TFVgyx6}L_5!xn&ROvT!5ISw#1Y@`H#sc?QQVs2h%j;c-`IEU%vH%2oYGPQT#e7 zwdJWNO)<>+ylZ6)J{T33FqP`(bEptu1<3t|re_(Mg za6RV^dEj+y(H)Idqbt?csp`iHFOGv1mb4=RFn>I8W99>XG{t>o*q5bR`^jHuV5ZYg zWde?ZM*AwX_?bK%I<1pa*E@LoU=hm+iUr_si0+>Fl!#i2exe_su)~`=R-xOPp`d^h zbn1c8+4$)P;{w!?+p=Fmp?`M&Qse7FQLg7mejnv+ylRB~m8 z4+xn)+Q^SZIS9m+-a4VqQ2?XLIDT&Mn27!Zw0t~Ebya9!5j7I2dlp^eWN-u`SB#bi z{TLq1_im(V#HIg!U^SksJ7=rdD(8(=5IHV+DZ~6KZb9(bK0BK!J|h|y^Zvf~D!Oeo z>FIv6_y5G>uw6y<+iFKRjxT6p2DGh~c`BM;?|pF3oy~$mVzqJ4ce(GsO+@4(2#JMA z%5vQ!*Z0Wh;z3k z#x}a`zumV+itS6&lS71=3GtNBy+eHdF}6B!#$cf7*M#g@Y#?=!a=7Ep6CQi!l!bNK zj~$re_N!hetL@7C!P?Z4_q;U(JVT)GLviD9hjY2Uc3Soo1nz_5N<#OpcR#MHQMS+6jYmd4xyO@N#Vethb}iVh`D&&tC3`lNr@+f6G@#(|{v3k^1N;Y+m`4#Is?|WQcLB0`b4MjnY5;^8-M%B)=Il-hL zN8f$Oy@MP(!! z%sTl6xi>^P_KHvADbcg`hAJbzJD#%{2BxtM7%~PKU zcUXd?n;?t|I~9@O7`f!R^Mz&)+(`#01>BYHnRUFJ7j;a4izUazd&_baE3us@);Rb1 za5l(CUwFu!jVKVlRui8REI(y>H#At^YPMU*TI0GwhQ0mpR_1l|bHzOd9g(H6bU(61 zIDxDu#^_J%Ib!uWBY$Sq&h%Xv05D)qkYj1-m29*c>ur$4eXVb!U;8EOF2)k|Ci2fNq{pA z#p${VM)E7ZGZ)xF|J_{SdoWNDc~r*in(8Y2>vXqIq*F+nYaS*WwjmV84)ghaAcG~s zr$QRve#=CUJCt)?32F8JOvDrP{O+BNxE1G$1he?NfX3S#jkjlt@b^_AwH_UbvCEW9 z>C<9^yGxBf>`8N#PwLM#_P|*|n_>YOl&GWbY$DxZ-a)nCs}+)}9YW?&Z%qR@l#xCN z{?>LGG1uJVSm5ihr2Xz=_?xi(niOZSErNx!uBxGl-1*t6^`g@mjOE~c#V8q9hhyY4OLC_=3s1&vOUJ~WV`m&=hlu2y)55_n(ib@ zEao49g@&P_S)p_7Zz&^oH0ov~S;Tip-v+{25uV51-ZW;0Mn<3Z&x>sa?cfDg;HN); za%rDYo)%^Q00+)f-x0S0wVS2qn?6Us$y%x4JP3;X3KPH_$Uisqz$-^V&SOzZY}|&Lt2>bfk?12*>@kPl88Ml03y=mFA0_@ zs>Ysg6Qg$PhV#s(Oy?+Wmc*fTx%o2(WkBS1hf-T6jg)?UwRy3OJyWs*!}@Es z-1=Si0jBF<-`@lBm&X@R0Y*_4!ZOq@gbv6=hSx_##|NzyNgo!wsz%OOwUKjx8up#K zK1>WEirHJk*v+Y*khy^`+_RpHH5kIBoK7{MM*K^U81#3o72h{N{#OTOTs48>xvn|Or0avp1p{z7Ea%*9*Q-iSB&G-b0A zjM)HCbttyt^=UOX63>j3IjHfR1@XtrwmVyTe`gE!H^fE#)P1`%o3$}`h7yL?fC`VW zZ9RQCh#tRyNP=4{7&Mmi{jPzlSiz5m46kcnu3mbcf8ClYH5J9h`-#*v1GZ{tGvF`0 z$^T87l|CdGRx3^=0{1^-#&h1ovy0;28^~O0-ZpVuP~Comd$Dx_B+cJe4-;ga;{CwP z{rG`Vx4O}{+v8kHR4-99W!+LQEq!^`t-RMV@QF3F?q>mbV}rXtCX)?;mS%8EHvs9m z!f%JxVHKSGUCa5R6IO+wLmm4;y*kqTKttePXOI+Rx_uf^reVu|Q_-}>iTMtqN!wh( zA2gcfEaEl9$HpuwMlU0X)N1Gl1!K~)=4OUV5Cr?XtFj&n;Om^Qt`M8sW1VYFH_%`) zT1;#0ely5J$i|{^YYablEuoh86Wo6&pZU~j zDIW{D0hf^n68d61>P9~a?F}Pv6$Jj`aw4(6lusXd0q!S|uPA*)Y3YV$EyzxcKO3F7 zEKp!@J+d#kmqLcPH!vllK_WzgB2hp7K?%Lx>0P>Hbdt+(-ri`y@z(jpeT#>pCc~=V zUq+4fNIz|G?%4GQy`{=($afY{Je}4PcpiWyJ~>d$4;sv2y+V@ac#OeIn3UYWSA3;V z%~LWD@E9q$yj@dPQL)3Kd{fHCp)E}b!w;`BkFR={=wGv83Rf(t1{7l&f7K=0J3Xh0 zyzGZsiR_QMDNsh~Jk~BYF`;+niFyA3m_|^HdJ%~T8`oB$G|cONX(rGaVV7#2?c%b@ z6NEbwMAWtOe1ozJTXN%bNxxroE?HhW13VqBO^c#6)=F!L_ z-Gxf$GB!PqI}LH#@1p@?@zXL2&&BjD``^{Qc_^vQVf|&E1Z*`=K6A%^-t*(1&YIMJ z`AkIUr&@g1GK}%6HG@`WP%j`kqTn5`Ww!@un5hp4MoBQoS;Ct2AE3i%RrYKwXK)ko z=M**qUqp$sg69qyHo!G0|BFQtbr}h64I%6)aWG)txH{d*W*uD>fm`grr^oU?KU@gj z2|<_*x2i!AuYbqK?9_9lA_Fb2P~6*MG4muhUcT~Iu2l3uen=QsBL`Ux{QB?sUrU>v z8jj^7c3#g!GM-C7P-)2)&!QBc@%4fs=?+0J!h{4GlD7_L+t!VSOjE~i=_=WuzU59( zwORO16NeCZ;yrU?Z!qm@R-WyZga9gsF=BS`i!U=YEmcgnRF{taaKLp8DP`{xFGKfY zQt##Y^!hflZGjefQsZVb^R@Ka?rRn;&1zf)gbD9=MW#4YK^J*1LL_Jy`l&)KxJsH} zBux_lz=G0&njQ`8e38 zrXpN?i(VIJHa>rP@tA*FrlP#SY)lRB?ByDl72X;cbZCAAx(!{*5{Of6(@M1eXsxf@ z?y?{&6M=NivI@|T)3+Y5g9cH+s(#DMK;=v2ZLkQ)Hij{F2q{mIBKx4Qd$5C-LlV^o zOX21B9vJW0eym^Dxos>t|*$scJ|mGj!NaDjDl9y9F1 zzGiXR%lFSMX{KyL5)_X@)VTK4plS|tV5aEYJp>=D^Zm0Fi`coUCu!1(+GWiDpLOINQvAuQa zK~)IRjd#B)lOwf-kh2EvL_q0NmxWpot2wAe-{P758sN)2hOxGC5*&J$fzDU2cBgPo zu2u8(+*;t!l}dI}eLUf@!Vdh7Ny0rfEv|1FyZ-s1+30i67q#QN6G%t<8(|WZN2MoY zi%xhazy4PfzOz_{BL607^4eR-d@vXel92Z3>ox|EZA{4xvP0`SEJIh4$O4N1HyW z)Ub&2!mEI3@40X<>$~>nX6;=-?E~>%v;Ts2`GGtMvJ}U22d~n=$<5O4MD$f>k_`B@ zhYD7m$$+L~&Aam|o(#K~P`(j;j5&~@w8Ck1s1p1sU%_9DAs-+%Msf3al*M!*HV1q7 ziw@s@ITTF-qX^6_Ou#|p4yv6Z@C)C0X;~~exiGpIM1v=y*56d~X?G*~ZBMpdGbHWi zf<>g+PLRy^`BdEQ&fL8mS{DjDf=yZ9*@^3MpUZqyAMd8uC?edQk#m=gp~fp{R;Q zlHgBxm)q1ieDuk6oCf?-tzxSEBL(2j=f6LoNIX4aN-oQUB-MER5<}saTbfXL#wDl3 zOEd~!F;#Ic1vJ03Y43>vc?GPEm6g}Y5F*~h<+iJAc=+Q@tDuJqbnx-t80fs@tj}$2 zy${Xc38>0gI<9`rwI%PK0-B!^mz|zqk{|1pI0W=8(iy5}`;ZZBc>??sJ)vk~GT)v2 zbUpd)myESLs0vsQruCguuQk3L;v(7C5<4Fa+npue$S?N0oNTjMI@;UT68l1II6M9Y z+(qH~q0%JQvCC{t?|Y)Cx8iu;xZ>+J^dBl= z3#_+A6eOP$m-U)KX{PZeCvo zDlyk@$N=!fLS9&!`8vbGd36; z3<@}pSmRnk@E;v-j?0#HxiuS7hxQrJ&_nYM5wCB?-$n7w2*fl9-2jrt{7yC%lL$A3 zM^Gxw^4Hg3h`uE0+vQMflEnu3bfM*P4JM#wDju4=kOh1n>1g z2TZ(i1&5;ozb2ezDc4m@`a_dF1tM< zuN+v@4Cbg+6rx;z3E|dzaE&Tzw{O33pQ)cfBvH+;>C~3^RVigWOZU#eUQKXEl)ri# z!~LS@^gGu*!S5MgonSXXBINe)i3yLsDpBId{ryhC0VfPKrz}^1SJ6XP8Qnga8yGCs zO&YUv6b;GlIQ?l=ZWPP*x^T#Aj=jE-+jdh>a^!~bg3ihWEzTpC^9$?F$pEsDMRboJ z{$m6H=2(uSqW)t^nMIeFJrC20?+tU0Rc2+oU}Rw3x#+L_{l&mNnl_>1cr8m?D-T1$ z>}XK&-ukUNbXI>CRRW|;+K~F?%AnD5QAmtZ{BQqzJQaTsmm9@j2_p5bgGvC1s|@CV z&fqBuNLTN3H5Nwev+aLeW;JXrV6tk}@==YN;{(szWKh@sS!q0=#6Ygk=80026`8}N}$_663?&BB1dRuI3L{`%ENphR> zjE=U8I*)|-cWqu*f{~swazPqtp(TA0FdkSo{kGAGqmdi(1w}m%!q4A(a=#9;K<;$P zN}~YBG99O*DJS0B<6CXNHQw2#I)JOjS{6{}8zI>x=zYv5(>Zoq|0j|+# z7pRP7{U(&Rd^Nhs9s7M}sg7E2qDs)M;4&LafDdtz9Hh(AgdDRxzw+0qfxizBgElv= zLU_#6yav&F}{QxzLM<(0^9zef)k>V+To=SFEYddboYvBj_FM-b?A?XD|;yRnL9)-<1ouT5iwZQ z_grJ%fF0_Dac$rsOh%;gW|lN_Ds)JLwA9w$4%ZF`sK83KZk{opQmoV{eR~ya(S>)uE(3ii_l)Xw;_*&qjwdpvJn>U=YQp)CK}`cj698( zPIL;hAWz25e~ z^{xs(PVUgt`0}M)NwI^-15*wmoo|65zWs)1#ObS`o0p#hwGR2a8A3EEX1aAM0g}IN zrtGmNx=bDP+`h%%%Ey6PPVfeWDzCG2%7G8=$>UwJ9w_sIISonLD1mIlVgmqtoKb z=UXX9nETM^_+V9*@82@G{E6Z7nCWz4`ys5uOlPP^QZ^}$kV5Cl+_(L=Wix`Iq2x5iQ?Z-JgIRF_^vlK1(t26 z*cmV}Fa;V+3d2V@>UExTefe<}hG{SJt&dteseL(jn&sSa~ zn!{GT65qAg)|xF^&**WLYW=TS9$Q+$QcM7mE@-35t3b|igBRPO> z^=9g^wK?Zi@&-8utp4{V_l+}z_2#McZL0ccXVy{+x_ng40BI(T!KIrpt)R8>TY`Ke zP_p5?=|zjPBDLf?3iPjgTlh$tm^#YeQVwd#kU2Rq^+= zN~hFc%y}-E&sn?}Xv`hQR5(1hx##BOxaZ?}KB>}8028TW|InODwV2f|LrTnML26%e z?TSSE6UC3A4oNy?MA!tc6TnStZ~7P>7ZTN%q14_yd2U!a0GJL@p?H} z@yDP@TV*7vbl1hG$G61%{TXpvPGSX`>^M{wy&$&Lb}_%5geO8?CU;yT}Ik16AwfjfLixomoo6LcgndhZ9dT+nSdy~;w!bk&1RtBhpZqF z#VGirfCuL)l7{OWL0-11Q~W}c)&duT7Umi6O=OAfkLA7^>c+e1+>lvj+E*`sH(RsP z;1Vs{0=Gh1YO;F(IXy(Jjt4oVOZ_KFn$MZ313lZjn%g|>Es$zOf9y5*uYhU0g z<~Qihw8RoTcd0NV_di4`em^PV)%?cB3AN#w@FDg+wi;`{>|y9h;W;KJRf5C?pDofQ$T?l5 zCbk=En!cZp`H{zenVY3>ZtN6;4P3Yd=mBZv!rvoz&KX~AAn&jLSi5oal%Vks z@J9{1^`gIw(AO?-ar2UA#$8HhKt@mVl>Py} zJb>LNI+C(oewa5M>hp-!mE_z^VjhLLRS?!d2N*b7(5P+HTJ)jtfQmZ%*N#q}V{q#4 zioT^eNGJFpEYNjY+-89san|(CtYN-VgZF*13|6E#gKBB}`mv1-B%HC703XJ_5WaB6 z#$6Y&$O9d?GDP!?!|ZSYZ_-r_Pv8s-b5#|KT~waPBD9P97UF|NX8PnewBsGsp-N10 zauQtwch=+y1M&8~)r3G0sVl^XQQNmOvGGm7v4tucz080k^D}P1%}Sw%v05fX za9_%MuNZ5X#y3XJ6z5r1N}E;Oa7>+}gidE+-~aver#xo(P{Ub#!0k%j*v}?W(q@KQ zBWv($X5K6AN(4=N%-l=Z0-DD*m>B>@5~DshKb`Q@ypiaFNw!&!s_SFr**lon`ZO}3;b9;J9*(&twp6f;(`J=8_x!&QG#&T9t%FeJNCvGMiZWz}Out_MxB9;I@&-v)~)-4-pr zF_{`@-yn6C#EImYu#NV?wh73X465lnk3Ac;;HXox=&^<}Z_-wq{vSo>9?$guNAZc8 z+!pdhE~_Yo2a=(Ny_iN@Zk^6mfH}}gn+xmTe zf9@Y1JU*ZIUhmg=o^wK!FIR?OSBz~IH8S1@w;)3C8dcbrULl-++j|9K#Qpml3zGZ% zO>aLt>GsT;!1lR@gU%RJs`=ewv~SyAYgW}#da5GTPzEKhh#mqjyHCV)@wnAOUFaNj z)L{rzwsXD$Un1QVU;%0IIXK+dEB)P& zWNFVDa8+9E@20U}B|oJ9+lu;D2&;eRnYcr3Jq~9&ag-$g0XMXIB0Nv{4zhwarKFWET4Jqd>5Q+h|JIeo6Ia~- zFhTv9fCE|1#EJq+NHjsKfZ+b%=HJ-f-6D*8)GKgLyQfH<&){&08}C_pU0m$r-Bt+? zTZl&&mgIWJIHQ8&jGium+nZES!pn$D1$AVJ9B&n?}tAfviW_^3W zT|Pm(526G89T_PE0h+VoY5(k*OBPMW7|#~2+AVd63JqMsHS6rmyZtCmQ@w4U>h(w} z>BG{efH2e=;ALL?!ZxAi0^K=e9&4r?<}*EAT+~+QzK0nXzJU1$@;?u)pHkuV5{5sc2MZ1>KCX{;O_P>lLwsVtovk}rn%>)pH?xe zwMl#_j0FhYEV1FWu{n@m7QrbIJu8_fp)3f_Yv%LS_5K6hPKZAP^s4V|;Pa{f2?Td* zQv5uOl@I25Y3tRea@Lk|qMCi)y&FGiX4Iw1-`_Ng=4@9ZxzAal_g4cPZn4StqQ6jq zLHPM2!**#$jOQ81!D<@{uN=d)= zjSE3^Q+J<+Huaz3v-H;Opb!1rC&MYmY2v*y%lqQCe7@0pC_~0Ap5P5Y?7v4IwBJcS z(jO`LVmVk${$qZt|IW;ScsP<)NsYl|39djcUmzPW{=1ECw}}`%PM!99;!^;*a-sD| zKVRQ_sHXd33$p+iTu{2tVAI>RVelW5Dxs0C_9xn*^QtC841*NpI3y*og?hGH>o9D# z=_b8KMgPr9n3$$Co(`NVM?50hcMuv196`Cn?ib^SQ!yxAa+sf2NKV(MTX1ruXc zV5c6f6Zd!9B2>a_ujaIssICSp)J{I=YT+e)R_`9rK+ya<&mf0F zqv3mSp~@u)_j9WUB?^km5(S5}^}Mi)FSHh`(MM(E;~H$gue&GzG6Q~Cvdz1`yRKyI zzNzRv4Nt|_MDq80L2kU`Qf0RC4*dEFZi%1V1A@$JecW1K{LmXj=@4F*+9~`w ze5alN#Fcm&T(E)esinYgNGTnEygd`lK0<1cTU7QaLz+tydA6Z)1FY7t2?tKHnY#0H zjw!B$q`be>)9*zEhHl&%S2%JJ2>%(dt~t+eOxSv29n^5Ba$8G#@6dnLDdo9Jwo#do zy*d1#D1ItHs$Rgl{ZEr=$yB{YJp}4=+3Ct4@Mge>CO9nLy^-azdoCG9I>v^+6O~c* z_A)ZYroj@>uP@3UH@yysQXM>VX8$vh5JrAe_G~9};rtPENr1sSM1_Wdm06L$dGN*o z@S^~UU5CAVd2HzGN~F$!RQXWUy9O?)_?-m`uSYe)1H8v~jr((m)PN3S$i(YL}noQV}udhzq2mY>mI$a86(Ro zcd-WhjF1AJ2T5)KgkZ`9vr5g6*}O_Zhqp_KLbA58uU$i{WkyxsXV|K2#LRUO_VO%> zf=?J`;}haMQ1Dz68^d@6yxB854j(QQqN@B>e6r@)RYiInll(my5rj8SfH!P zc*}$xo1E1}X|~o#l%$oHoroc#cUmxEhk|s(V~_YNjB||;t02PcyV?j9$5_J%j8eWb zOzOWCs5RtIvkb6KEw<(aYI$Hsg}9OCrD2`{w$6s=KWxnQd9^>+!dRfm3hp+zk$Tquatrc8i z?5DhY?${j(W&E}l1%8X!BBRRj*o<_>WUxoENyMPkGXM;Y(b`FPZUgaOF{s^tE-P*- z!!-&*#OZh|Fc2?lNcLGW*?!+QdWGa?wTQ6#Jc->_n_yeB_|=3>VEpSS={`CrUe|f{ zkf-4pEPp!;#WO~LwQRGJf5_`8eK^3m=OFgBa3=}ZL^OHDi&izkjm}mBmD6f29*CcJ zEYA&vHB=BTx>G&_sV0cgCKZ4SWMlls1Y6OQWP+gx#f@$7G&_#qcsgU$m#u|);6L+E zyy*@bQ|PMFFhTBt(Uee)7R=zXap*q~6HS){*L%J7G+wrbO)I$YdwaqdSU7`lgGztR zX$qCUu5^Z?J&W_u%$`%hH(Di$ROni6owLDA%eK(YXsZvF==ia#86m>0`daJK(;fGz zL=)bTy>0g3r&Z*b-8}2cp|M8|=oSRZZf?5!8|>>*a%f+irAe|}Y zwXbS8B~&rR?iD6I{)`;jx?QB)h~=b&c2BoWjv-ymieG$i>VY0|yC;(b9@!rRCZ+^U zF0Cb;yM|^TkvYN|wL5?B;P98CTsb48r>7tDI~{%~667Ni6ehj9R1@5gFiqSg6Ga25 zsWD6^ca(O0RaUaLf$)jRw;~tzdfJ!8-Zq?G)uXMauiMwyyXt*rHAXc1{%IGb1$j%- z+gWqW@zb8{93cw{*b%tsL}6f5dH8*l^d}q!o4f>wxfP6`O!p{{F?0C3prZT<4-Fp%k$__uV)i zB4_3|7jJ3;jv?Bvlv%~g%`uN=6-ZDLQA_bB(Y;Db zZ(mw|%pkNKyFYiH95Lk|B=0UAv=cxJ1mJa(RQQp98#HYI^Vw(aryXJ{iH&Ixl=1hL zQ5ehS_xCPW`~HDM^_1~>UfZFX7lc@x@=Yu~I5E@coud|l`fGnS;+A;WzRH#+Smbrp zPhioxLriKJR1r|4GDjc&GJkjX{Ofzs`K?B-h5B$b*sLNtAA2aSDP3@(+63CiVK8eg z3;BySc=$~_U&DRw@YB+rYObvyrny}IoLZ(P_d?lP{Kc?tn%^5Bw#C)b&R+LfY=<|P zj3z^Be}#}PNJ;c)PJ#%`wA2*P@2T(F49XR)3})V+j^hO8DL&3&l5xUGPLfzOk>~oL zWM?6EZ_r&~R-Tnvv_okxSKqe-{G@(=H9H!<1E!_MT}4zcBsP!Ae|>xCdJcCyfP%Ee zOH5s`4f*|D=k9=+I9*R!^z+mQz-ud~OUaq~FECxSfo=`~GKz$ne%CTCv#+cpXn<;V zH8dfY0~5Mm#2s1U>5?%bv0>=z&jE=O81M@4Q_E~YR$aJWd=mw(3Y1iUJ;O#ACMa9DVE=V@PP!z;D&0AHS6nT(^WIGr2Z!Q# z7Ut&~nWhm@t4LOwgvW;(w1;r~RI%r+?;S{6cpRuztQ?NFKQ6V>(wj(oN%@KnrYFz% z7({xLoFU2HTF?cXL`&v1x(n{F*p(oph$OlV7O_LSwj)ydiMe=8Ps|{|lmFDBGuMi; z+FNBq?1JICi-D1Ct+1z;jY3pqniG{KGGfwmjx#eva;Cv`rr-Dj@$ZJ&yct&P_YF%9 zMaiW~(%09;Vpod+3(X>Up4;BCTb7pOM*|T}0(3MIDy6u{3Kj*u9Wz%^(~ znW43xd73-_x8 z$qi)V_@&KKer!c0@O9CG$iOtjj-QW=3Ksif`XsPN*L7x(MM>|Y8+K_kp`90N|FYAi z#CX}G@drK>-4KIqfF((~@U!ph?bU$KcFGNIgi?krKX$G%{56#PWnRErsj(Tqt)9=U zKI`^P8Wh~WG;NR~I?FnVv^ob^!=6*TrxYt?JzS&c0LlBVBADwRDE#`#Q!5wKquur_ z^49cgf%t0^&wVK#PfumWUG2!r)ffp=e}J?HqLZ_B{64uCPr_~(e#*KiL+zLUsc!Mdt?LI80J)XChEkNH2i~OMV-Y}ECJUhd`LKs zXACVg*(bavJ?rtim;?r%g0|+wveW)a9_;=R15|#wUXP1*7qKagkn%N~AsZU6!4bBG z4rrM629Wh9Qjbdf-35NWFtIlJQ{C12&OzczLs#qRSnplE^z>1u?W!SCP1+Ji(eY;m z=7|V>$e4gg(1;o84*$h`xB3WFWC3`mh0pzg(fWjBkFPv>9xsNrLJElf<$YX9-%f-Z z5z8KccCp^9zbrmyzfvLBW3bDrtVBoy7nm@(DyedV)@9~AZhS__z)Du|_+TwHZFBjO zxEoqtp*MtmpAqybJ6?;ZQ?q?tJQ$DQP{FUDX@0wBFO)QI@*05<_IzdAb*=nH-RRMFDPZL(h5SBZV(T)?qm zI(1)@FaB!OX_HG!kAEedl(x+C4ySWJsf$ohZnwsl?PtJyS|Mac%@$?TnWP+NDJipg zXtKp$K3G6NquSE>drq2VycH;bEAU62qz7(hz;{7!9n^`~c&DR3{q%IeTwiF;i{2lc z&T?%7jr!s!md+bn^^y`Tqa=l>g!!)|VD<5PR4w1< z{=P~3B4LWlTLwnR=FztbrSP*tZ*&Qok-wFU@_ySUWHhR-@QIpQ)QHSU5&u*5RaOD7 zYS^@xY$Ta~E_;9r&KG~B@fKPjNQ<$XF6l^3Y>3)vb&sBX{qsSp<{4sp1e51#;Q^ycMM;YF*hz=e_&Wk2hHX2UlVJ!_Ju(8n33tBVKlcbJeQ}=k-aan`gQ# z_+o>&0Ef^56?uNbhNF0)=06Wvu0qW&sx38e^lBK~KIkJiqCAv&jO7|wMD+;I7C2H} z86Yp6h5!nFnACVsYW#ryVAA`uWS=yRk5`R{K%d|bX-RW$2q#m?s1u14e!)#0YZc-% zO(*Sd+CElpwwdQNUVIUv*S0`E6#Xu*Yn;w|-F?ZFWl#1F@AgQLX`rm!9^=Wy*`T300i8+s2x!^pz!-lH_I_0j|h{Dw+OCXw7=pTArf>>caSguo8Y_8 z_T7Z2LhpL~PG6^gkPxf9{Y$}jl}WhG;f;-q{@- z=3}#>rJ;AP8_@g!j#jVe?GHt`E3M&O5F$3R@jfOZO71w3v6q2Ou7R$cFGje@@1GQ~ zGiTIS?~-ll*V{iTU0$e;WlKl#FH9ZgpVFP!XBU0km)+-%sU3i5#89LEw546C!b>fM zvkyfb5dG8~YhK$X_W--}6ytn+0kgz@?^9FVBok8)IpdefMZ(0Vr$1O8k1}jtEI%pf z7LOpJ{#j-fiu_5K`xb&U6pShu88q%`?IO-WAv&y@RoxTOyh; z#M$I1=}4OrBU{DW)2Eu|(jt!L0XGCvY%+0SrrEEzo&^A*b%l<3|)1RgoA|9Jvo?mT62f4RV-m{ z|2B7YqHTaJNOZP=;mDW8eDxF2HQFs0VyoLPzdZe(V_)5+*v=o2z*=h$M`7nkDH=d}e(k62+f8}*1_T~&eKd3Ux;qbT|WUSgJ#UNyeEJr%U*y{>V|O=G&e zvRvc7T5#rDCYa`3n!s2uHD)`}Lk!wLW1coM+g0f3Ulj3PG>}U%C(pDvmv>p zS2oGct<0mf%Uk{5ilY>?@3Uvr*A52Kfv4czowds+ZK7(bW}L1m0vlB@x=l&&X|*eG zcAIa23+BEMA|%VdbL8jC(u=)33QL{miB!Az?6DHJ2=W&E!(XU4W9W{Hb2IntTdEbw z^4GWHg-;+GvyHq*Vrh=iH_ZxMv}#}`gL}988RHk8J*PeYD>hZtG<@k|V7xMoGT7*h z{H0W{7FblD6!ADj)_{zxYLAUt_p?Qchv>=Sk%!6oWi}-)R;8maSD)C=aU|HtS!!+M zH%57Jur<1C08`;L#xcQk{`RjMv88UVR_{%|aLMrhe>P(@8i)UQ{j2^TDCdTrj@SIW zozqlB>Y)L9^|6h9)e@2`8Gdc`|9K3hjaqFyb^yST6`7cb)~Ha2v=7IbWwbZ?K3Dm_ z7fq_Y9rGe0<|=F1!;Jj>t92q*Di`^ve@U}{Q`{uB%;@XQO?BDdRB{G$3Cfp~9?!=j z-822R0ZbtaxhUSAkX zacDC5Vg=SPwz(&fOXl1P+vXD5^(wfZ)Gd(v*tey0stJyXE<+9GZyQ9Y_tsXYod4n3 z?B`5DP!NZr2N$l}X!}dh&gUIDcubldJs&CAykTl^j;yaZ`twJ&f)(F~k0fm!T2=TI zC{C?wal__4Ry6n~y)j#8byTJF;IGjDr0+K-aeLoqZJO8SPlJ3{y^UBO`{!0MW)F!P z6|szo!!kU;x=VpKu>jlr548Jd>mNwJIwttaV!ox}Fu~@~x5q+b*qKD^IZ5>IFzQs1 z9M4}zjGF$1eo_4MzqmPz$~)ET>1NConz1vL3S&BW`xE7nn4)T|#DhiV@y+rQnQUaVexv|nKF zWG)cl9P+4OyK(KqU@WMlyUvMG3pqgdItJx&LF@$KEhp$9}& z1@0ve0$AB9VXRqz4`}+}E;?H9nDkq4Po594G_H&6nB_dBt3TrG^Frmay=fHNWNJ>~Tf_N@O!XD(x z?%g0@QW_FH;($=Zi_C|3SZqk4;Z-pXq-%8_{Gw;O@~XFT?o?T_lVIgu*%!G1%a_ay zmVm=~XlHcSpE!>j?jePqz3^pkK<%GCo z)&vsU*}R_P_BHu+cWvj6PS1Hzb9ZDOsswZkxoB?+7<&eSR)F`NQ&Xppc~8@-d|h`2 zi+5s2Yi%20FzLzmKAz^ZK6!oEIaZoeBJ-f&0I9h1ZcMi1G<*(P6!e=#t}N~ATxVW@ z@Vp&YQ|)VCNc#7t{e+n2H?{>Udy6@#H)r+2r@F1)5a-doZnwKJ=H9h&*DfCZUr18P zWGmryg&(IR`_4V71u@<;&bM=I%iioCXz^;Ld=NY$I_?xzkfL=1i(RI0646L$6bIGB zd2#={6JhfEBdJqfV<_0CYXYQHP>;l$qWa}oR-@_t-;iO7iQpnc&H32w1L%95@G(tR zJ0!-sK>!1uow~Y-d`}Nr%wLB|>8-e7;HGS<*Iso%`x3@(@d;X_m_2OQrwE4i3kZP2 zX9hJ|h>SP%CpB}uSDKTiN@Y%+=!Df!xD1}lBo9P-AIi!;!Ta6#8L{avCUE>qORS)I zU#y+9H>5lj&o2!b6Dz&5A8Ot;u5Hf)O*?)W$~l5gi@;~Kiiw6ry>a_V!!vnXp%(Qb|#eML1v88$iuGoGJGwB{<+}a*(I?xXm_wAxp4er`z zKkkDOOG$Gf>Joe?}B zI?^OB^NE@7C%T4Bztl#M_d<3;u8%2f#s>)cUG5UBobqFV6mg{csY~`nN@u*Zq80ZQ z>kkhEMh9`x9M#v)*vPZmnK0xPxdM8CO&qlI>t!LAl=Ib(c(Oi1+go8&{`29{Q5HyT z4~((smlfD?H}g&=(>LDYD9F}sy%>&74~o5|a|w4t!Z!vY;u#d=$O0*AyraU$I<;3i z6wTE@$XlD+>%WckH!)JjwM8r0z6VsrGJ_HaCvMs(sqGyf#`BK1tj-=jtKS@h3{Zq_ z6)FZyEfw)%k7E^nyKi8g7Rs~|p3q0(J=RqNx_WpsVIBXl4cxy<=f*j@U|eE1pz8Y5Ol zHHyw31VI<6zW6HLoGS!QoFFLdZ~!v0vR88Uf<^%Av~P_hkUhV0yF2(bxjP4_3N%}U z2)aBh$|EEDbGdmCL8^C(6<5J3@jAv`C)o(k^Qr5$i74+mzvW4Je}Q!`>Iw#%b(;c& z-JM3zGwsM(yJ1hr&oXDEt26jgZImDRWh81HsvRyt?Jo0<}rQgz}s zpEe%7I}hn&+Prg21s~P!ZbBi!B98M@VAH5ksQj{t$6-A6oI2QJIEs?6fCoH}3-Dmg z*y~}O8m&#ke%BSDByikmjs!9v4I zwgqp{R=dG^;n;9x*^S(NEKpk1&JgzCv3XGxTulwB>>;9fNo_Lf<6#G9(snG{=5`Xv zv#K^X5nAUH>IfG}paW{^@~8UpoS$ZLJ_5l%bi95cBT%hpzFW||O3ZPbN4jF)(iNi3-ZBPLF@KO3*JOUxTp0&v)RM4BsbmqM>9v;Lf+PCE|HIC% zAC{!J$>KK9ulq(wKN`$>Ml~v;e`-I(rqf@KK%ycYhK+8X!V!O}iZ%9f3)c|LZfIN1 zjcxogtZ_}PWwssJn@LmWs&6yeNk1+#+DXW_rwrbmZAfm5f0@*%+9q=rm}PtJ2;Z(& z*J}6P0}$S%_yC*lUe^4H!QpGe32QH6!@O`ZA*TaBAF0)PAactEf$6&BuW9RkRBioa zU91Z9sTgD?Nl=&&i@M+fx#RP4*r`jRrWQDa7VrDQm^JeLmlRHP4zRueaX7z+cd-R4x5mW4>&!uRJlFLt9XSLS}LRaN#)aI{-cn$8KNsZ5LC{$7$ z$6H68wP7^shGzM?P3(0&C1mKR;NerZX4)k7j>2`v#jYPr*V2^Lw5^J8=HXZz6{E@N(5^U_ zh-k^}QW8UNpJtwdGXApSk3$B<-`>GYQ5eX!*tpL2Wz`WRRPG-LGQ0zdSDf=SpdEmf zw-0EMOV%bQR>;01n<}%Gl1J^X)db`BRSdKzImWHbP~f!RvwL@GNLzztuDP~E{>{M)opZ97E7R)61n8Hw140Q)l@FZKNzY;MSgjsEkHrQ! z2e_3u`$2eHy*a$^cbPw8hl}-TQ@rBkao{se0Ty-@>DO)Q0>C3?TWA^|5PbZ9SYh}9 zj-0n}VrTgY5P$iEUw@Bwd>>1`ww@^)YxBT3foubdfeNT`OzM|;Avmtwjr&=6*5mpB z*YKvdZqDC6xP+j^SLkN_$paT?<>0S={$Hs#I!5bq6Ye}>&J|$B*~RJ3#IgMtu&{{m z^hA9#m_QvR0k$@h%Z|{a-H0&BpUK=M8F}z##M;;;vp%bxDXZXBT}oUW(%u&K#qEyo zJM+CBv-~bR0sWjh#W4ni0}-T6J}#uDwJ z#04Y-ftdcDN5v!GKhtGOF+rLJgFtx7+9AF~CFRBz{6&R!l)n`1NxG=IhBden^0@kz zkdm9=EVxWGdsvO}nMoLX%gCqwraSJU7i9>sFEX_7v73F$bDrU!#Vbef+u56Ie`kD3 zof@KYa4T=Cuc-XFw#^r8ZR-p<8gjD!mV0ba)r{C@A1ZR!iy?S^NMcekq3Thc9kedr zD}fw%NO?=rSL^)l|Du6I^eamA?VnqBXLY-;UAQ!b*(MFBhIQWg&7#SBp}DWH^%*7| zXuR2&+Py6t9~>D-`$1y6OAN;QjnSA63zje`CZ8p{x^bmQWBLL#|0ztgie-nA7T_9O zcy^shd2qyWuhT!1qeL4j2PB&ZNVX0-bh~nI1BnF1z4MlRjH{_n#=+v4IPjv-Zi&lr zhps1|R&Y;Pt$+<)B7M)FIjeX^-#*1*ruvqAQG|6NxCcyB)@Y!E)*Wi6Tq{cbbeLY0 z99zCFA5iZGt9OYhuj#M($^V$CJEwJXr|Dt18Z|>p~yrAFNrVeQWr%Bu3gBSX_nG$DduH$NNIaeCpyI z!){#Oe)vQ|VIpK0TOx1tLpsba^@ZVY(GTpxa@%7-r;#y6JNHQiAKHs!%b%^5$N*)0 z{cu1ObZ9lUQIo21HGHMGQ7@z9xa!|}Kr5ZpTPgHjui;sW2!JLV=?w%S)=X}M27M)) zBz`lS^dF$nnmYVw*N=3%KS;@SNY;ng5#rSu?&{5&PpojU_9>QIg%NAR$|B7&&O^N? zNjJXs`H?n$JNl}7&V*>*7LM%EjzN-d2wprqZ2+PYYPbKS$2%<9^@Pyu;A~i#GaB!T zzTlG$0SvvZnlw}nZo*>8eBMBjD3}TPC*tX8S~3`f8wngba?0d>f*U= zlU~OU<0=<|BY!6MtOr|sBcE1XE$-l zpMoPIg@c%kGR;lWy z;20-0=-K_4xXqd=`pis_SE#9=-(ynOBu;=JtmM&QeCgQUm-ffe3D%}ZI9yI25Lbo< zG~I{)1>F4)f1IWjWz6u2ibD7coPb9j(zZBRG)0D2vx#Np}b zjZ%a3V6VwXZrMp{f-^fIFhk4}-b>}3zjY+O;DrqO44PqMd(h|R?0Uk|NKTRU%yJ;8M~%5*(4avpbe& zkbGED#L5xo2a``BpjvgY>zkH-1u+m zzRS@lOa8i&Z~}Tz-Nlk|mb8f9DI=+8&J;Q=7eU{8YMOT%^Stm-YlxrYfeU@2%dJN zN!S%ECf(z$D52d>-)QEzWf|^nR~^l}@$)pS=lclBPm>fn$G2CNnEM%h0N{ z-ESPJKAZP>4|6BOQUUl@{h@~a2j1l(&vX-~PEPX(`6u@z9iJ?yfWK6&&2p;vH~tDR zh=kg=L0(#?%&+ZMW&k;5j}S?v`G*kB-Ve{_fP!PUZ`cf+4X1|hKTzX~(S&xhvPW4< zgIc-6*zeYJ43gon4*LOLQ14M`fkKj@#y719kFvY>BafjwVzh!vMT&{p(x#Wz%`3ox zK%E;g%MW<<`P32_`sOHC)q$D58SPk8>O29+MnR+v^6z!EP62}I2mDL?!xx(3(L8fA zuar<#=sFn0dPF-X+c94`+Y4M)?F2sc=`B-BZbI`i)W=@~xa>0T=iS5UDTRzK=>Z2z z*oqszr_vs`sk4JFvj%ehbs(yNaE*2vjLI1KQ~TacxXU+JkFc26 zzKov8j}`z^&};71oHBd!`Yt$A=nHy`=5%}cPkY}xy`$Z#P%4UlRT&np6&`o<3*?&a z%Q3-jns*C|T4*TRHO}>1v+I3qBw(6Nr%S4&z@u)T6!ymFef@uw!q__PjSU*THIraDhHd&xmLP;X{adq&03gW0c`l7z#X3`v&mWXGgJKx zYH&%DW$Av5gbzG)iWw}%{96=-Rd&%ex`NTXA>`-*j|DOy>G@7=DdNmaMw-+>q}IWy zxE=|#H?6SCQ%4wB@S1ICvdb3-eL+C`qC(md>i5}X{l!n7jRc4xJbRWZfLc4Rx!ps$ zn8&nE_|j)?w7vpuP1{b)Lr8xUvWSQEVSC<+*Vok4MJ$f`={yB>I`hiw?dzd;TvmM*GrA?+s|5JYqoK`;P5C$@o^$c15CFPsg76>5y*V z4HTh=9-=4kcwX~aw}#UR$3TeetTPoJR&O0d0=-J1ZUX zaiMj5T*w0Ep>~O&F0m*P_GXU9=}vfc*|+uIDbi&n=&h}|U>x4qXJE{9$v`xbR!Fkl*fWHIC+*47uvW2q|}{Lw5yxR6!cTi{%eh3@Sk=s}V*|Le0?q`B^# z>&ppbic{B|JbkOLi*;{tGW%O zDcg?|-QqYFK8Rme)$6*bxRz3^rD4{utu^@Ar*)m{_2}dG(oy_N1AidB@hTz}LSk!C zWwQI3Op$$f7QkXd*!ayj&!m5(RvhUr5Z}(sBFsqHU_7y#jn*5w_oZzKJUxTA@fsY7 zJuLB_b^Q~Ecfxov2Fq5$EC8srAv6VPRi7m3n|=)h3W8IaH3b7PD@&S%g*{<^wKdfn zb=18NwHF`g<+M)s;GONaGtQ`nu5GHjJTv-GGS!J+iqeql1WDvAX2O3nS=883b}K`c zOgOxLCyJvks#jX1;a`0YCt|YQDkKwU>E9(6I#Ju`7T(zmdnK;#XfD~iVuIq(VQdFx z{Aqm_C;Bi};{kk{dq0T2yEeS`1T#`DS9wiFmVELl&VW#*GrW6?5I{};T$MY1L$TdDBTi$)oz+gW{an$v9nouhide|n+m6BtSNCaaW1TGCMH0;3CR)(CIc3yD{Pg9&WVw$I6 z{-;7@8+@l8mMtZnWF>n@O^L`+v2EX+{aBNiTsJ{s_+3ZlraL3v1BHS$axF3%HjU`D zeMnD&t$A&N9j+5T`~B?(F6`NZo5`2UIF}M?eq;BTXq<-L48OkCPwpSPPKsN&vF(DQ zbI;=kh`K#G94)a}pHCb}+bFA+=X>!>9Mb)_8{XPm<}O_RF_?ea82vcJxr37XWDd5? zr?0;`&l`PA@ggr4n(JTa7DTQBmkw6|{Ceb0=rIwI3(fckx~6h`P*|(>edZ)LnAXRt zgPpLC~(GP-jnb@b_+M~wR4wf~~E2Q#->{e_o%G()*81#oxE}Z@R z=z*u=KM+s%*9rV^O_my${~)tqd`N*`ZIk(5y#cv|XaXQp9u{sW^{6T(ojq8a%Y)HT z4_yXvI^FHp1~sNpm!1nI>F&F;lbAg@(RTrO{#O3Uf9iAch3~+}Ul7=~qLP6LUB>z7 z_)G$uK8#!(=yD+Y zJjmB?lI{VxMRH483`_?%wKymcK(+p&#dPI+>8Y6)(cY{v9lAQIOVSz(Wjf>)U@h5h zQ#lw8|J$I493^>oaw{eJ)t_PQy1SMBYkyO6|8@qI0U=f zi1^n%5_+tY>s)xFm;k_B-Uh}LZjo%eA53-3>Kwuwsvi>l=-!m*$-QTop&wf-Z|YV7e!@0`m*a*wz;vxGuY}|98>(7JEX|WhjAP*ZBlyQoiYxmWqAQw!_t3RvsHkh{o=3Tc<5FL-3i-QVwPH zaCdPO_cjpCurt_3^7EW*m^n`|Z8;)v%zYr-o|$k)Da`eaB4mY_ILZ~5q(@-Yl1u7B693)FtT!{q2?%L)U16@;8sCH`zd3fbKj~S68z?xkffKcD+^M`~%t`y@mLxS)L7U}0eiabw^Y?r79|slC=*ZuEo#i5*pd{hT=Q5;(lhTj+G$9=n7Gk;`=@t$&ee|E7S@;9KP}XNA&CZ;#L5YxsV&S z{40R(zq~SoS3&T8%lE|8BDQ_A8>1D5(v!dO+vkr7sRte`u)b(*Z4ka0=uKJ)JVyx+ z1c%L?)^V5mma%NYhgo9?tHKSe#{9BG`lP~l3TFA$b|58w&v`k@4B8q4jehSHN>vsP zTVkGz+B>Xe-+0dV=TLD-yO_S9S{?w(!H&wdMH(@YPQ)mu+Kwmpt`=f9UX%>P+SO6Si5qcu5-W zsXXkNG0VAq{^Lqa!t4jaOV^T^y{^1Vb$oz(M@~OcW1#0w@O$`ls%5&aAnGm9m?~25 zHGG~^PU%KRy!^hfZMa0{v{}MhI<(}zO<#0Z{!G+MWIYNW$|GJ8g|T z37gP?CF`q)OMhzgzf@D&rn4J60?I&W2Isc6yCF56YX3n{pzY94_wSN|KNDO(y;EgQ z0!pcnpBI_!%W>E*vG3HsdfG_dzkOu1xXyGYX@s3yC3=rGT1a~P7R%n>L ze1?8y3B}OHpN@gwxGe`qN5Xx(RhXexNIqdiNX8Xrx?}SGf2()rvHi_9-`OFF9-^L8 zybcg;H70T}es1X(2mup9viif1V#z-F{_tN^zsa93?j{oAWi^KKx{6_cE(Qlze2Zvp zWjR$+YaT`p0_JEiFr5Yg)9K6I$no2{7u-~z^7Q7qoSR}L9kPa<15J908-|KM_-N`H zU0~`ln@QqB3#G*CGZC@`NOS7y3Rca(%HA>f$fWtSL3VPH&L@*U9t86}O}&zIRrx3E zp>-hnj{DJio4>m0x1(CO9Im=yu;e z`FJ9VoI-->)eS0qE0ONmRig_Z-ETI)#Pdjs8}S1>)qi<9m6ZBGcB|_-X8SrW`KOBJ zvNm2E|Bs^c@TdC!;`kL&5(#BrArhHc8JB!B$`;Db-g}RGjY{frLpR&4?1W_RnM=l% zYi};D%{A}ky8S-Cf578D-1mLI&v~8KdA>R@NoS`WVCI)wHauhE)ieDZ-Gr9>9fqIU z_0yYw+TWh?)+>JH>=Qz43^R!{1&^KEr}|3)gB+4m}D2_82Yfpzxf zyPkGnqaoRMCkxrDa&96BZ(SnmohG2?{e59aH|Uo1Qg=oD4l0w`VDENjtPohvXTk zH__ZjJps@6mj8jQDtC^o7(}U4u?Jsj*svsVQN?!k^vq?j34wAT89Z1%&(SPcAO49KIh# z&Rf^cI9l%u?GCBh=U?dSsAii*Ejl;6sV$jl+D&@XYEQRC%$0c$7>_yXL=QwocNSSa zy%@66nUgY9wCcaF$()2z*4fRj4S$)HraL?xw92_XNd4B#D{g@rjNgp9UksDQ-Mn=% zLk&L&z^KlVcAw~!C`*UwNgvh<%ZNDq`OF7AmU z0fNWCXsq7IuV1D8)wOEtA+dDBheTZJ`zm(<$Ln1`j8dd}7R{-TMX?nRsXY1*&Amqw zxuZRI>Dtzy%^`!#k}UUk=VCQjHn$&9_$XkDL|X;pfK}CsPFP-Nx_2w0FqoL#B3yF+1o;M-L zP04%)sDmoH%sgINZPoI@z;}ZnE5C_RRPS>+nxsw3{%I)%I@cY50%rZiVJiBlKN6$r ztow1~W>Z?_I@4;Z?yJ_#TeeLsq70|Pt43#()?;S>(lzntO5_FGrJW7bVP*oAvr@}n znO6>;o>u-W*Za_|5R1rw=t`}6Tqr}7`KlmP;}Bv|1Uj%WXf8@kKK)6*3pt&@>D6Yh zN<$rbc|vg1aXYCb@Ke_Js}H|5-)x@3i#~yK7u=rNS@BFci6?@5D{*87dl9xDXs-et=K-EC%s(1u9SZ zn|u8ttNGqEI#KpKiuWqNOHK8{n$4#EmCoPvIp|%Gb!`t5L;L&bHE9*9mwVlR(cB0r z-z?V84n5(F`EmcJ<{m8U^aGcI{yuEG!6)LI>jQ^n3{T{+j&~}ma>HQw$APf4wp{XR z5&iShUbq}83FZkQilN@OKD3w*jc9+2>!7eU{?QS<*&LpfUxZlDt*0-myU-QnqbcRk z;EqJNebXs+53co~Bu7Qvx17=FncEI0w3}`k%$d@pPFxDl=smf%kVugv9^zU|mT$vl zJ#tLUnzg0P4#zHgjZ{Ion|K9 z&|LV+*m_Y0RB1+(S@LH?y9^Uw0X2MV*+8&gb?D)$ZKDiUQ6=KDFb{eN_6ukkYYZD- zOI5ks2&KPxK|qNwz{C|Pa^MuI`4-H{0x^fKlPSK@ysL%RK6&Gd4%D1tq5C}Bg>BtZ_cAfK}}Mbi{x!s zjNucMDbum6D6k{{W2$)@rgLRLJ#9Y0~&3@;ncpM3L_+~=*|pJ*9F?U#K=~srcyp-mAB=FP06zgL79F>u$T`T< zrPPq&%_lq%{VsDQ!sEdovR+JvD-W8xU50lxF0O|pzt~X$mBW^MQpAtg^~Wy;zE;j4 z1xVxR!8jv1P5uX1mmjbW?W4FKky86_%W6JYO=+&i25G8w9V=igh+@57vQ1%JL@O2` z0_Aa=d+0>ZLM0@2&w&drx1_lGiS|B(mu|^67s_w-dFFuRm8;Oc+|sNYwUsN!YXSZV zEMo6|R|d8oX!e_GO&YfM*zZ#%wtr)wp4^W*Bu%Uq^;kl-|ADyXJDQLgt%j=Wvsxy7 zM`W4#HXYdFr_2em;6jzb`-h)ND^on}edk||;#WVL9Aj)e4$n`%jyb!M#7W~qPf9V~Fu_37+~??29lia{Qo33Qv05FxshpaTOk zi<0HJ{BO&Clcw9BC2mj)CnwM5h&RO)g4kjGmc) zC5rRRzZ`-Z4TcRR$q3gKkpO#2S-3=uW2YA8@ns4ObZrYATr^ehFM{eA%~j- zZpnq~$Ozm+kY?T=Z;|53nH>aPzh~p67PohyXds&Jz@Pv`O?i1d-F>u`>FHI66|_rU z0Nm_P&8(z4{{N3g6&HC?-HuVa$|r9tLoS3MVKaqK&)>3eIiBYqSp^k&3#~DadT$V6 z$Cy>^57j%=tFv_LFwBzL)f+}{l+t%^em$o72g=3> z;~}FaS)K+$3&^lO>I!Ap+4?0#orC+I<@{WY4hz6&v!n2+X+A2eKuzz+prlSx=d zCF?rwa(%fo2gDXIO@9L~ahl_H|3XF9wOWCyQEmK|;nl^54E*TA?}kzli1?!~G-(%N zl{WNm3=Qn5xX%H+Ps-9AjH=CJVjsi~jyq+gB-m>r4fTf(KA1 zXM?Oeh@W&vd@yAbhmQjPK!Hqi6}~8O$Q{gbfZBC}+=oJ9Ti59{Z%xsZ`?Po|I4!^_ z~GJ+KPX8+m@or9Yu zuD+4xdx7gxFoj6+v~SHoqGin%%YLQ7>Z$k|C^r~=BTjLXxh+u5i`=%w`Zik1gEAy4 zA@i_@P2%H6zny?i(akb>CtDBGpB+w1>8EY)vDm8HtoTZO7p9&~Q$ zHa|n+Y0@TjXc!Rb)R^HhtN2^-2H?+Sg7H3geZ#3R3TN4{_BW>Kq@V9Hpe}mt;owhr zEVUR@u&p$0C2Al)DB1d`&!1XtVI00-{VBL0WT zA`Jc2c6J9vsTlH=z`c*ql1*BLxJWB>O?DH1F8%HztWiS*tV>~ajB`tDYeBkQ=>gGk zqY5ERuPig)dAPi+Y-q%dO?*8aVh>noF>d}T*>&PN=6EpslkV#-gs@FPK6o)Aea~`D zF}C!fl7mnB^_dW6RCfxa%I5FyWmUSrX>aTr&9j|8`XfBs9+O|_eZZuf3Z(qiNeUN zu?yExgK#C72}NzXy~9jynTJh;`trFhdTOf8;5c9^Br4V)TXX?HCZKe?g7&4D{;}iWaJpZX&C=E28U8V!0!3yRu^-UBn9_~M zYu(jcY6=DGUWx}4l`U3RW(QL@wmiF+y^6-|JM60I4p@~zqllijdW3I@c@9*6dxqsu zo;Ra(`i{QWrA4b%ZqIPuztXOM<&HX-xW|6{CHP^P%c1z~l9!*dbNxOGAE^Q|OW7rT zfn;Pb(m3lB{3#{|v9*`H>mg%I5DWK$Prq3iKe?s7!H_zqTRV*YcvWos@%I&cStNl_ zN1-p<4_TZ$dLz4`>{4u5rCobQe|2ZBHkw+0pps3@oL}f;3_A{T@A3empj`Iu;mRz! z55D43B1|u{?hn9lJU$Wo38$U5RjqFu5%8cb6bF-zD;u!~fre)2_?k)!=2z_9vw?=jj<)yiEB7cwVHIEA}PB?Fp$p&;6qlA6#L872bNJ0s1!_q=PGFhcB(^_c;+vg)T< zfU6Cyu{TpR1F353N+-)MwMZBw3jlxjySJtCGa1T>nIbMNnEK))-P8I9x-OzDWLH8U zm>$aT#KnuhZ0H+PI*62>)A9DoMkti}cX9GebR)PeHs}XAaxyJTG%o$^&XWc} z#olU*26o~k%ua9AhKVuppmZSMJvdW;P^&1CCbQp}1a(aP z;d^2!4&9wq@y_N!Q)_*2id#WgKg($b#Tk+z3y{@z@C5ORc3zH=X6k}|{^|9(SHXii`>gT^znt}NE}xWXIP_G-Q=)%m^9UZ>C7UyPb_#?m1{Ly{1WIjja5>|6L^-#8lt}?S;{ymi9We zk4t-T2s6TSkH{sG>y9K8!wZ?dzJ{{iNJg^Fx{s?GU8|0qBV2@=Uv|qGwfBcirBj$m zCP}DjU(gx-bcAGnVjjXhX?f=ANTo^Tv#dnpu8v z=qF;smK3^ZzFyZs7;G8BLpn1^bxhq%{hJ<#3uv>o8H>imG!GwdNYh{x z4=hGz?cRnE^dpd3UNb)C8T3E`A~tPOe7)DJAjCx#2SF_Xjq}A4;cKMV7@OvpbS2#k z`7pQnobwb+ypvROhnVK$zNRIk72wTYvH!0BqYQBZuv2sx2Fhbq72UbgJc_l@Had!D zIN2-;Pybt_xUcO`@rsKN=j!X5&zL0p7#D)A>|4nM8g>(sbDKOMgSS`*wjp>qP((|k zxVCc*fMRg=a`{SR1CPNz-2BbE+0&m*yaCG*Fl1v0rEO6(%kf|^h;kPpb#!svKc$?f zwFWmvMA&~AW+kIyD5lc9FwPirS?3Xz!9fRyFQda>B!njrTQ-S{qlSOUd0%#{7~^j5 zh0aWjQo#MkYzv|4k|oE#J=jVxGFWBl$R3j^wO*jDz@LS1K5V!T<6MrER)fFa3JkvZ z6Xo%@sItSzI>#pM&I1d}i!GU_-db#V$nw0aU^5pnnW6dk5v0TH)P)l9R?-v& zXcV;95&gs(X%XKKN0$<3&x{=|MYEFQ{ZScjxh9RN4=#oqHZNbTiHIDWg;~fnka~1* zSe1XE0uaY?=8MGooouE(*jdTE-Lp6Cb6maw(+L7occzdBebbiN_%e_dt7ElS>H=+w zI1|nQEZ`6vob700<)ui5F@6GJ-(~reXY{qthMy(rcSEm4V5L+5RuoxHC( zT?}d@nsq5}y6ZDH$e*s_i2Ov(UfZy3!2z)(90%NjBqITKE!bSI#yxhNvYqiD$AE9e z;Gu7nR3G@=7h24%p5R64lrM~LG`SSc02<4S#rUD-NpJc54ambDm%Zx)cqS zgsI7haOPUe@@=`Lns+#1j!hM9j*~A}{&uz!=EY?uAiz+KP`rZhD)l-aXs24I<2Xx! z@VPrZPU1MYc*bOt&!iuXI_#3RPYvE#kmN&Pfd1@koywd3!N*RuP+>zZ!kbPdr zeUOo;4k}Bj0Wt@C!{QBO(QIPPerhL*hkREk4yVG1>E`6lTdQvP^Gi;SRH>b>!_O{XS>)Y}W_9{B zm%l#g;$_rQVg=mEY@N{xck^IbyA4~UuLSwUq=x4TY}=v`0H@If*6??Q8X(gfb{>55~LdWm~a_KAXJl=Zgo%Lgl&v^K$| zzUU2X19_{8=yLunv~6*|j<#s&!t7kX{>^Frcz|qkWiBM)in5*GM_Rgqu+<^d-4Y); zdE-aBieLbu?EX$iyTUc&6yH%nRG?dKi&f5w3O?xXxlwv~s&p!^zWu>KZ=a|ys4rlm zFvNTmb**i2v4U#rARj8YZ&Q^&$Z@~Q&AbxBp`s~JKdH$Wu05sD!(`jTtjII?qPp3Y zvL(G@w}|79PRzKt5ef$2vHM)hH@$0#Zydh$`LHMN9A|~pOiJ}igX|5mRBXW#wgxu) z6^YGCxT!8zUZMS=hU!v)1KIYxu0ARsPW#;7zYFfr8roa2CeGu$cJncY|3^;v4bbAr zo`r==ccQ}+-|@3J(R&ZF8D;u_Wsz-_jjswQY{7h--@_5lnjEKtcZLpvAg()&fkU{X zA6umyck1Z9@=YCDOw*8Nh6WR48QUS-w-C>^1YXW3*7Cn|`LJz`wHB{GZ)V%s-Jxd3 zC1*!@RAOO^MKGR+!|zcn&0*IZy!Bg@Jli|kd)tA4pWJGBKYvu4Jg3j}E1#B{kF>(E zRLbz9xm>AjmCfpLu)}A~)U^cDDH24|1j9SK!m9|HSlqVVH$zN=w1gHC=A{*TNyoH` zM?*}2o)8asNn?v5!^XdurY(mgF|JI~ZyvND(>G`xTX)Y}Ss^$`Ghp)DqG@bXIiKhS@P85x{m|J^5v8|g1gh8kfx6nAVfg>~mJ zvJFAdjrS{VkJCmydne001KEJ#Yg<&2vNEe7eCW=-t5kj*(ck0w3J+7s;$a%h4O5Bo zkSpg#9|_=W5p7J7ckmizq30cPp1*Du95;mtF4SoATF9tMn?m;t(Y&qd1SSf7%)b26 z@%Bu!wa`xjb9!LEh+yzEqh;VX!Cso;JNxpNB3$;zVa)ToT)@8B!f8FbPiINZJlY+=c%s{T{<}D^P4)W+%vOptxvK;8s9w)6D+66pr%Xh1uBL# z@@?QCe<*A~Xr$`w|9BwEKA~Ur(#fz3yj3{=r#%2EkUH_6SgiZA!K)O@qZDp(>p~-^ zo~Qok`$<%XKK={Y@Zy`Y4c7L4IG$>5XMRJUdZ?bi z;143rP|nJjK#?*8;omBb8?C$}HP-`-j9F(UJF$Hj>QzJSO+^K2f$`QK#0S8A=T2C7 zU+%fv>=yBA>59<3Ck-M|p*jkaeH;h49+`%@#;6gd+w8x%e? zVjn*H7{m6%?NsJdd8F_%X3Dk;@++jBBs6mLSFWMLNXMyV*x z{dn4N`24fHElVrkw3}3K@7e1=@b&00qkH{*F^C4v&lrD2!Q=C+lfdEaNFJx}q2JeM zy7Gw5y&W#J3Wveb?->2sNov%U$G;=n&ILnn;S5p6gliHRcv|dEddYpz{gK*7{*g7{ z-I|EgohY0H(X{PyAcD5@w{tS2+UN1dfF>mwIL|^vYbd_*$LcJ$4Dku76scZMsDn#L z2-#2EzR7XdF1%8CgfeIg%-NU1Bi%*Ie1r z7i_f8>u!;LDNW2S>>EI0i`v1|g#_yr1KuLs+uMe#+7S^7IVlVg%CY7On+!H%7-P-h z*`v0bJtMR7^i3}`zqbXkGBQW8`XSU2==T%2i_N-u?~LCex%|f~r?UsQt6 zuA)cHxqfKiZHr+@b}3;V5C&pPscTiqu41ziy#L84$q-T%u;?J&i5W%!wwt9~RIUJRkT>^rV2tY+_OTK)2 zj7{S8%tca$cPkt593b7GJ}9hCNBFAoMF33^FLGbvw}+3w@7wRq*AAJywVs~iPVVYa z_y|r2CFhaVS*06^)ljP=_T^R%;)TbF&pXacFM5Z1r$q;LLD#_!)I>#?viE40dGX8kD*e=R`QtO-=_bX#uksU?b_~f020Z`Vlp6GlTRf~$ ze&da8SF5h7s66pvPainKTyMK}#8KX*1qn1~Ui#8qA^fEr`!v;4XDi#esl+?EOJ%53 zOOd~Z@Z!wm)f>04GHWemL@C0yCuem976N4jAMX8^5bIV}&sbCl>1omE6G+jzBH4C; z#n$Ku9D==R-3;;Iocoa@;+kP9uArdFHVMT|kwTTfJLhfPFG5sNK*p`1y^zY`(>VW< zzM*?mZ<;4hy=Fdd9Bt|N{vQ36BE7AtM9=E!4~rLcAYU-yAD90=Fqj`&Qe)&3b)irb zv5xHQ!(aay~O_v&)K_wA7kwd>|{LR{yYjIem+fMc3W&-X)> zi@!)oc?;})K!o)p)|=0mDQsydzmzMKz_BQN?p({gOaG;c&((3mg9XTx>M?`+%t>rT zbkvRbn6tV?x&o?Nq^C;)6OSc31Z6}Vo{iYKQ@_!pRn!8yd3hca^OlAo$_?dDx?SN3 zgT-ZEKrCL;Wj}_OnA)-Wp*{g+_M!H#-T(f9a{tgWDmwG6tVQ3t7t$e)P3@8k~0j{ zbNRZsg3=8>{c4ZPPyclzrFXFWN#sw2cGT9_ro_k?{} zj*oB}EdcqvD7CKD%2~SF`=h8h8F8)vXnX+4`n1Hic0z6&?;#p5GMXd}Q&l_*H>7@W zQ00{FllXQR2Hyqp!;Ww&Z+IOvzdn=e9nuy~>QW#>l*5hr&ZVmy_?0hF4LuXNPiG^k zbap;6;JY&`0=x_!kQGCk@$DO3T$Or7Z{`kFLA_wZg||!v4x#vtN8sN~41M{;QjHPi zC*O39HGhqI3DigT*5f=%IIe%jHJHqry>mv}khXvx3~2g|(LzFqka;a>+MVdzaqB8k z>r5ug71K^8?w;SH69w}c@)O0l2ayn$p zibzQyhX2n$ki<~j#V28ek4F0j$&sxIJV^JuVlsX?t$nM(fnX35Y5Gl!&Jz(**w|f= z{XORXn*0iLgH@~+-A9i>)Z>Qec-NIF_?on&nleR80IO_%{L-J*vft;CchyJP=8y7& z9Gc3j;eH>rxP!KAOb9Y3B1Cn9jd|llD|_gzgX465t3o7COaBgiNLaFGfUCIeg=1vUGz_z0*gUY%{o)K?2HhhA$2*pje2GwzJq^uTHn_Gs52_sFU7}un z*Evgf$KNjzU8`Wl#6m!kxjrnZXc^U~J|QB@+z8qsVjL-a@5;3bVibjkT7 zZ&C6XWO3dWZm1_H7hV^=XCX(q?(90_Cd@#szWGC{1HXRtPggoo%sLx(17qX*EU``A zlaTafVg}e@@`0ff#G9LRl&{}0o9?t_7GG1T-T9D8q))+8t{)HyElAYTCXz-*K7qSf zv17^WgWnE-+T#A9hg8X+L+q+CN^3 z^fu_~HB<}y|7Y?*WZ6yl-R1L{pHj02YRBtLb!_L<@Ms;2W^kQG!?PF+WnAkIqfw`clBE{b?&vdF@-bcKB++LaI7H-<|V8m`ZReQnfPiM1#qT)wVy(14_I7YL$&Fo3ju+lkX+JYL@wCF@DmqcbJK%2EtwHX2 zvGHc5MdCZgVIMC|{AG>H-3kZ+L6<>3<~aCTYdX;fc(xshCi~w+BxL$9Y(MsXP53!xR*c)2xufR;F&*3f= z!)7}bZ}X~I{_F7S(_Fp1Cug#%@)HC>t&XDYv9xwgAJzC(gz?SZom2yfLD878~sZx?PhW_PFZHB*SlLFDzt2YiRd^#H`CSVBkhLd z#_g8)eWoKHfkMhGVNBInDSW^4tQt2gcQ$P zme@f?jA;*oQMNM9bUf!{0U?YghfPc4wW{|bjRD#Vr#6m)84c=h*l`x6)Q;+`OiOwK zOP_Ypyuh54cv0N!CH$Tu;GV|iRPUS~=2qXjtkb!IFlk3~{Dwy7sHoCIyLW`pHSd>Y z__-7R#K`gCc4JjNPfbuo`1qKI4mbmNWB33hz|#%OZ&^i)$stPI;NGaHG%cj=j?m!Wbkck^`q_aIR(U#@1@R zlG99$VgKPC{4nVUAW1FdV0wJs+wknSWT%QvuO3)F6Z6P;u((>3wa}j+nA$d1G3Mp- zUk&!*c?1_%P&GD?Xf{4RM>XR^V<+Z|Q2Wjr2o7#F0xmnvNIv;i0YXvtwc?j~e|OB) zv4W0VdV_s8_5Xyg-g&NpSZYvhj*41Va>`VE8NW*efl03BYY>DXv}hk!S~*4&cGAol zmife_^HK+*SlByC(_qa5KBm9%!fW>H+i`)^p35PbyDQ0^JI`&b9Cl?Kk51WDkv*HW zFqec`Z`YnnD;HQw1Vy%e=uBP;7Z+8#^W~-tJn$b#a5+zM$H{j2BLld=JqmT}J9J<8 zCkgQnWcd&DzIb{xDxds4IOz(HDl*HtCw$t;5fWIUz*{|8HZw5yx7KCD0_-x|hHs-j z{&o$9a$C)Y!yZ{18Bf|ymJPtTgIx2hNVRp9xL?a!lzb>GG1BDRc>0>bhexAsyknMA zta7_~P#MHf>)1uY5CB9mAG!Xg?D}~&NZ}9|&i(_bKt(S~O#s!nTwLyFbA|!C;vr{i z;X;EJU})>_i9nE<|Gp;&j%4T<2c;V(_xQzKh+=_Elj{HEf7c-Pr0<#ZFi}tJgICOR zfJ=?bvo6wm*y-R@u<>M(+QIKXlf9UnmhiIc=1UBB2D%a;0$$;!1)EkT=cu zCn-||`B;0%{--H?1&X}`PedOB3zPAQw0(D}tH5~Mlm!N_L45ahelTe-$}^6Dq&uz{ zx8>2jxwZ)Y^aBn$UYSUEAFR^M9iHp3oHu~l<6Jwmrc3C5Rv)PJ!CcimM0UA9V7jRC z?yp`Co|m$N5hRRB9a(|!SmWdkcfJ>Y?U(uO-E z>A(DH6dRt3I1n9IE)l)L_Ko+M+=fg}7qEg*y&lF;P@CMV`sMtjuv)z^F>UvI4AEr9 zb*}wjGP$l6`sv0kUBSfWjw%N)r;RRuh#2M5WP$LWZv^70>Jn^^A>bKb|E`VPF*+Qi z>9z8f%KRbXT57%Y(PD0Wen1;)>0$i;%}uJGKwrY57}xeRa*16b#iL%jh&|H;+6Y4$ zJwCdNoIL8UgMu($?<20ti~HIR{W|FV<*x}>LfaSZU?@DvP+DHqHeKLBgZ?(JX7~zY zPAJ)})6{M|c#)f%8_rn2mpz&ktrVG8QB?3max&Ymi4PvE*blX%r+FlQqq|giKJjs{ zUoS+;gt$V{jFyiFAbb8&!@xT^0mlCnnAe&orMvKG(SdXKCX|gA(coTaux*wAJmNx{ ziHG>*O7{{{7)Rf9)y6*p2&OBVc!+z4M7COi0v6U*fFz?tqg;u`@2_v%VAKLiUd19Y z;IsbF5LH!)=4Oa6ytJ6a#2~Gj&4451dwZ?0b0J^0=FmcHM2de1T+$Sq?7F2A6`-Lu zuxX}g>eA(;zpF+=VW%VTzKym>QI5dzzPiAQys9f!#F5WTBYGf?X~Yofa#zt$nNH3bt(>#3<(2D%?=$htdP8 zL)y6!Z-?CHc)@6udT?5SEYcB<7FzsK)(_59>0FfO3fmhYF|R|6H$we9JXpsK(y$d|O4*kA%GoyAN5K<8(|>NX^Fa zoZ(bQzjAn=ie9#r>Sx-8ACuD{MT(b@E9Tb@$Z+3hC~7;Yt-}511?{z6;Hm=!`z%hRg<3OVP%}I z>NR6(mC_xx%q}v6vXWc)GAQ|^)}A9%Q9z?=(j{2uSP*f(VpPmFZRF>`&d|fbfBoQi z(idixe9T)t-ssjEY+W>HF9n$Pslf5v$2<$al@jh}POG(Qw zuR=oYaHnpyO$obH>8?3pIr8*4s#$!26C%A9Y_I3vi4re zvr0@dtBW`Fq+ zlu-M;HHSd zZcin6UQv78{K8TfA$JA6sHnOUQu=d!!_SN3V*0J&ttT5F>G+^*MJ`1o-y?+gxXDMU zx?(h7&83fODHI>QpHjyDk(P2D&2e_jelp12wR&shuh-wumylrQU-YDSIM@N6eX4L& zaqptJTrlqB5y7-M!g6QgkypZ<1}87gi4f}A!Q<`ZdiZS{sMDmDF2HfX98~aJv@)X> zt+Pc1q-R4@I(go!ahVK2De&)_ij?O8bRzpqWL95^ScnskfI(fihf2Ojjpl-E7adfI zki6Bw^CZ&YoP+pSFT`w2V*l5*{@(3qM{tuib|@hGFjZOE@6>O@))6QZ91FcfmnP!2 zVIjQ4kl06vxp)Q2iF%K}6lvl!v=hb%tAgHiz0LAN^VwI~4bt1S!-7;7gBRak2T^Li zCLT%t19>sA)WwsT9SXabWziY@)QM%$c>*eu2CKF#)t;gTDoM?~H(Gjp7;mdV|Cm)$% zU`<%IH(DiScSkP_F5)Q6=>5DC;r%DyzRhet8vHsDbkjUTsL4m_ng~Vk&5{OcH{^F< z?!DTig%xMoc^7Buy_*d^OQ?|++uw3OEo}@Kq&jQA+g!7bzW+}1x0>Q28;D8YW034r zB$oWAZ%tE3gu$H^Ne{Xy$(wgy3Y!vPepfH4QTI?Ud~7xNFlP48e{uB~nvgBbs#R-^ z{i%L4xs(@=c^sUC!jH7jSzvE1%Q@Q$yO;i=#`?$Asm`?Xb~aqsGH^<0?y7e@rtrog zhMGyP;j9CKb%(6n-12<9qf=spHD0n=L0MhqdswrI60kzue_RxmD(c%5mOSB8$CmLG zZa29pb*ghA&ndQ3`|Is$9Chjppv9PPnYVU6gTgAnxaZ225f^bwDh`I=@SZ;&Z&cq1 zc(oBvAV_ALgZuh_0R{IJPu;>z+5UFb7lBF%n2Ty(^$P>MEemDD95n-BmEAxSY;+g0 zktciG^7KTHE-;Ji+w(@vM7H<4D*97A?=a`3B=hzK)*87s!sUw|%hMDYdC!%#*6$X^ z+W(i8r;hQ!Ina3tl?;Vy>dowxuX2FzzkZ`>fK8E_2cl16o3}io2;<8)Og}3`gSd-H z=>W|hpSjz%n2^h!1mT*p)&7y-l5b-ZclubSc37QfXelY2!Up(P_l;p}*I~H%;y(lZ z90wDMJ17EAW2#Y&bc2sfAJDu%5Zr?CC<}O&HVusbV2k0oy<_C^55z;;W~3Z&-dEtc zYd;_zeh^@r1*r@|<(xkWwKrIbH>sW5jr>c2(O>Wro_S{)=znWwa6GQuv%`H|qudR^ z1Be4X2SEl$AKiV?uj5|IJr3{#k4IdP%;q$f@we~NbmABw7<~`-@ta%#Rnnr=!K=nR zX&za^%Ikj5q8M$Q|Ds0MfxK4NEDzrE5bBvFWNtL8*jeLd<>1HEWgaY7pJ`O@k5ydT zy&OEvZznNqF8k%BXJYL?5Z$#sYwtv#^J<$#YLvxR5lfOq)whvUDk$>n>N&7suUvS@ zwfnQ3wpwy*7+#=aP|CH!2Vj`@<`GR!4VHd$SQU|A(i^U-UK613$vsM+0vVx|V4O!- zWfBdDL1t@~jCn-}hooU@+t(LvyYrq;>8yfSr{1aqFsRUz zE(bE~X@Hyn#^4ibJeo5^pj@VYU#sSku0WIm>x5?|qkw5+?flVYW!dVsEX> zFh7rmAed!0^$w-ReXa#C9ua<{7VT9!WTgLy1$+D(BrVBl#VdcKz9+;n4uu6%8U+j# zr1xKb@S%hI`Z6ujsp#>gx}SyPW>P6p?wTZ{aC_-r%w$DUG$ifl3;l_UN6O46uU_4g zEo_Ru8jm8KN{RX*fK`Bn9aPvsT1dQ*i|5B5`lnDNXU%{OpkpC~i&0e|{3D2u4|$CECb3d;MsaACC4n81~bqT}{kdyX)wTiTVP4f!}(c z=5ki+B=#$^Ii}w+F86{8oO3mXEuAzoV2jK!7cSxGf!u$Qz4TmS_k^dNv8mB-_8-Wg zGezjn8=tITrol~VrlWr#euPwBVr`0Y3U@H+nHM=;VEq?=Zl|9|uWe zO<;URa=AC+82xBf0Y7;|#3@02HROKp4Mt)gjsR>bvtkch*OZWIA13YK7j$z+WI#Qa z*1f%Yje{>{^jc`gZ8dWg;J^uv;QV_6>H@e?yC2cuueL)uq9Urn!;v3v z+i|!OXHaN?Bp{1M@cZ+k{(e;ssicL)>zek5p14<^51!|A2X!doCz;Qlr^MO@?@8V? zY}0FwL5v>my4E06)x6~+f8BuMF|kq$0vzZ%3;H#Y?Lka2l|B_o(@-9=f0GHf>6T&{ zc2Hv7`YQRxM@cH9I#jVRBD~2iM2kyKUb(bc!jrM>wD-3LJ-hwfKhT4_lW{8bo3QH( zWi%P`!COI2{Jk{EPeDO`4KFp~VwtRB;WF!XZcV1l3DL@h^HpgE)VdH*C z^^~Gk$$EkLuiDU&rpeUySs6-I-A2dRT5Oo^K-T$+IZupLzn?#eHkL_caw}ePO!HvzP8qPw&~a`xh}X5okT_ zDBP5Xg;UmSby8-Lj8U2p)oL~e6|XidJl%PkmX5&9hUTe66ew7d#`oq{=n1iq556;K z-Kra^NdIS^Gi?T05fVjzzS#W(EdZ5t`**horkWQ8ktvU(8CSb_@(7zMAl^~Np1{w~ zR(EHiA$FTgHm||$wB$`wY@X4Wr7KA#0MOY$Acw#1`_=st{hU8TX8nlVP;Ls{NEU;Q zhQw!7^G)(Q=*fKZIRnM^d;Pmx-FLIZV4{NX-&uLQT^rF%IO15U^MW*^y!h?E2|b}? z16lrW9jt#;9Vd&go=hvA?UdZPEcE7A$J1}oOngVe#}_IkF;?vJzmd^XtG)4%PPvuE z<0JC-b|svdU((BT=F_lsn8}Xb+c^h2E?2k!EpBzzu=wm4qKkMMfI4!r@?!3O9!x^a z(;aVYkwA)hQd+CH3&%X+;o}QMa%nHb+aPT*2cF{O@QZLOOXv!oRtsJm#gv}MyW9eG z({&WumIEeKOVjTeVXPSPwfScB$>a!S>Rddu;>0I~(Gu^Ql-?tg)2pyk$MYMA zdOm7_4?)=GK6+eXY(==66c0OPaqO)?mMPIOz+H1eEwAL{AAA6 zKq?-e7d8Qjdf*r?G^8%%b?_V4W{6AiR{4vl1)&jBc+5YLwc`ig<>rNx7}OBqXzS36 zagq8oW;UE6NC`SZk#AIV8M{Mj5Q(x3dF82#Vas>)7cxE01#OG^*Px~tljTPuWa0Jl zvcl@jaCCd*SE{#KbP5=UVG4UWgIIDclDM1#)4$MTKDrwNFSZi99H7DeKL4 ziP}}GT>Za2isf2{Bb=chsG5ev-g7my_dw&pA5SW52y*XqzZyZpQv|hOzR#Qpxxv{C zr?ZcO$~Dh5UW%u#I47Bz1z`r6>7|gzvp-a%ulo(rIVti+@#Y-*7&JNs>IU9@gj=9H zdid+b4tP(~3hE9~)eHJdjN-#K_n7cG>ZEyJy;vu;T;bz2D0RsmmABz|p}bxfx!x3K z=itM~wzu;h|4DDOF*{*|!zq!P4H?a$T(XBcoUgZ?egt^znfKndxlDKJxt}Pp{It8$ zA)|2I!Tb@n0FJMQ*++em8+*W6nV^PP^}JyKPV!i-m;wLxDkGa!?U&~cKFkHbvyd{I zz1v*x7vPy=() z+!ZbGzJ%^XyQ*|fxp0n#j7rBH1OEUt{=#DiGBfl0Cy{zdI5v{bN1)=wD-#oxA$e`* zj=zfjGncr-kip2Xr3c)hdCRc>=zNDKuzRrN1aqeyVIhFgI;-Ii#Dmx;59NU>|1`-e4Koa#U35&ug6wS6GG}Nyt;7(!yIAU9ajp_*@{^@zwyg9|#zo6ANa~ zb1Z%?yu_!-=`5uD*P-s6M^L1;+f+`#LGlcb2U2a~dPduXYhvk&i z$FpNl_|gA5y7p+M|NlQpN-hy1m&r&7x#Sw7a;+@4T#Ir`xy$`Bmyoczgj_NrmxNqL z?w8Ch%AL6nOYYmSvF-DFe}Dft$2pF3yzTvbJzkIJJDR(7DFa-d~bAg`A^sUalIqGi7d9Qgnf`^Dcz?-SZ3d@0cL<56kMhSt(<^{ZE59d-_r*PWmL zB1ARjw)j_Y;5hOCBs{U^05iI>;lf&IS!(?GBgONs9<$&1HPYqFn$*kS){lXLSbESfwTYE;O#~w3+Oqy{TEQ}vs;;9>XxK|vd zgpG88-L+@$&uMRsmhuQ9#mbuOTP8wI9~FO)42+(tQ-RYX}6zYvL5Z)DJ?&%_Vi@F(5juc0G4nOzn@k2dR>!)fp zK#-DHazNf?+Mhj>;^)WCcQaQm9f@3m{ktI)%kkq0+aMmebOf=&?Kj}Oy%j=ONykR{ z7VqQ3Ly7B|Z-}z+Stowx6S^z0)V5@`i2U@O2yL~85o!$Eki6}~Gazw+P*HUk`7El1 z#J`txFqL;pJi*u}NjVtf86LEe<;lMO_q-#5nx=Sy9Lx}%=ls!M*6T>t3s|EWjD$GQ z+{7KOmJT&!NfVC_!D;}J+#U!|zsIU53p94Rp3d(>IY(EF^CGLLXKJtaGHTTJy8iWM z4&yMEQn6RYu^n63Le%(&SPH<9cXmAPU+D+)M<(M35)e9Y-*QT&7!`yivQJ6VR)Zy= z`wXd+eaZ44woinz35p9%5Up98uA#~}c!ESMM z%8|esAU%%UbxBHVBM48f+d83J@Ff?cEzZ_S&Kc50Z|T9aD5523r1#C%vv)3OVj#rZ zR|Qk!=Bm8qsS;JVofPJEZT5_}32lKMsbokTL}ow}BuIQHA#JzS5kQu2EIl$pqE5S z4RKZW#w1sW^ucsN;0-pBh6RPV(@NPM0DHt^tD&)vM1yOCr9dviW?pGnMzkj)d2S={y0UqtxD{5+Js37tE7)?(6@!6JtAPlsP?F@LtA^6Hmy zt%aJ}utbD5Q@q+vO6Z%y6{afzte#g@@G+4W!R387Bt;WqKVzFb`q$Xs2jsWsrBYbZ z9BPFID~MVQRBaPVItf2j+CXGyN|Q;^$NF7P(*W;p8rICbzY#Wz z_Sbb!S=!-(vXV~B6PeTU9X*{)tuLH*jWQGI^|;fSV)_*a7Tj+F6t-z<&|5M^S8QRP zDi|C5`9`2}&7DOi|YPyZBUYB?A{Z7*H8eEa~@;{KxHDQ!I zZvMST$DXMwdH(AVeadf|GI@Vk{PC$Rzeir`Z|d-6P4b;ng1SqcmIzs0?j4Z@) zG(#E8nb+|+yJUptnsQ-1V3Jz|*R!1J%1- zVZ+0@H4~Tf@;E#fd;m$3*M$fBEx1u+tLT2&SnD%PZzkZ~UR!8Q-QWz}|o*#iu!5D1dHFsw%7K!)yGeW|Lmb~fjg4b_Rynk}q;_QLc(Q-;jF=LkoXP)5*&5&1ryBk*85 zfP`a04mD8?c%;&?OJC8l8s4;Z_tq<3ea{QKVqWf-$18n?tc5ruHc!l|+=L(X&5Yf) zGs<&~A*AGyD9tBMN56bkLISfyE5iF0k}*=aYCB?d&>qFIV#~%0``nG+Ld>tZQ&6Q} zdvtuA?`YG`rKpIqCp>AVv~Hqzu6uZA`a2WyS-tAtORfx6GhX9jX)6AKi4)YHScxPA zA6M{*+E(5Z_J+^YF@136_2EAdkapH<4>k-q_ySO@D%!I1z<6%!hZ?VLRQH-|@H}X= zkO{_I^X-$FzT1SNwvEo!417F%RnVUwGWI<~F{ppVWq)v(Kym+kTRxHlHc_) z>&-6syLMbuinpG8q%XiUbK&d^qPKK`fk1&2**EgxD~a9@f2oJ&ujSVCk+{bzd|O~hCL*g zetVT0@bh+$OfCB#NvZcCaCYd)f>g(L^Zt<+Z&3d2xgGznc9q2%KU#yCW`v7Ucjj6* z=xWpl6+K>FEpL*vH9uUQKzH78VK~(h@f4yCs zkD5G)Av%k|f$(%UoV6Z)aTcA`c)sVXs^ryj6O2zPIVAt}a=7|z!><4V|M_1^iQvIN z4++Zj_lOxdpDkulvsvqT+HEh{J9Q2s5|Q$q5)zD4t)nZavhTCzrj{1nHrKHs5Bwx& zV)iNXsQb6$q$~q;ee)A%QfyLlcNqkS284S%F_2T-@9F93 z6Vn}mcO%-+j379bt8`_I9C~D#Yvt^v(VGKwWZB-lhQ^+8MN$6N`2$&gCl@Ummp>J$ zEsP52LFf-nBoO5{_RK2N#SZ5lns7ME zD2&S~J2DDL{#J6o|FJrXNZnGo{8izG^`9-xaTPRc53R=Yc%6n z;rIH%a#d69{=RTv!p_vz&qeGmxs#}`o!+^(l-h<>{InR zI?ehaR`6-g895`C?@|$@xRIZajWv!tkBjh}${{OeF+PH6i?147`ZAopcWab09g?Pts zE0HLVC(z+j8H4MP1b(L%y{UVf02g~(Z(RN++&S7EhP)hS= z9@2{-nWlz-FK(hjtoFyNe3CAYm#B@BilbV412p}BLMFM9SUX?#8&~i4Xo^uJfzhkw#@|>uALk z0_~#OxH7Iw9DXTnFe;gLr_4e_2pcLy2MJ|6{Kq@>~& z>^#?_YnU_%97G9l?1k(|3xip-$J{xN0?>b;xPLwf)gi@*9p)iXT*j`qR$jy#J8pxu z)PM~0IbYSTk#P#cA!aH*Mo~Jo#mz}7Ji-BfXANa%c1E+^oWbYVwzNr&7W5?>9+tPW zwhv8ggg=aEYvO>fE`L8(W2C^L<_rcgUJxw z(o3k$-lWAy#SL>q!s*1*jVqn_`F{;yKx9Xp4wEv zC~VVTK|m@oB2d7JgZN1PYjJMe63T4>Gsq6V2C(!KsUD|qUPbKQ3a7!~U-T3#K7_Tq zcr$Bz`%!R2CD0mL(cn+xn(F91BA2$><_z6HO0{^gQc-rw;8+yFm#1t=Thte>KZYMB zX~^pAb%Cp3bPZBr{9Yi(az74us&z;*4@mdo$1?^?gwa>%(}%`E$1Lh^R&&MlE?SsV zvJoJyiV1M_(204zWlF^rfg%Cp5JxdEK;?I#hg>|*)cC?2vzVSac>n2}9S~Ge9UX@pR&cR>ZPT0b zhO+B#Va8&NZKYF<+aEsc*?3~11_aa5YeBm&{gN?za>LyI3mIzv)2N0#*>Dulkm8k? zW@KUh?M=c4QD-u&1L9tk3W@HelDdRRxuPej3mEjp-kHWx6y9 z&d~Q^scW24eK~1JUoD#}6(ShJrXra=R`pL?;*1xS_pNaIVANCsYG}TR1seouSwD$* z#j*0>T7SCt96y7DhBpTRjIWfs5onUc_xrm{|9mhsTj@_;M&Bs=i)8OBLrhkO^ZNW$ z!(-YF1<(9|!77Y{P@ghsjRxn)M7{bpis9C>_MR2PTW?0cw0ph8GI1)6!@Yr{qq^m#GaBpr&~a^ zOzdRK&dYoiLxVfizeD_b_XxE$%rQAf|ADYQ-Q%;bwfvNP`<-r_o}2K>OC2riaSEOO zr99s7c1xkfMU8!1&|B~PiEq%if1Vx>9FJU&8-LOhT~y zJ$d`KN|--anp2=-vS07a{;>4FO0RBX;mPZfn2ijlbm+~2JfCR@Xc_QuR8Z<$F9w`e zVuzZn8M!4uobzBC;Gl>?q4$37%~s!!hwY=1TXkGZY<>g>C_eP8bhP-Jz}=E2pC>34 zl_BUqOgvjOLmLP1!c=PGRH_xI2l6%F7MukGnlP*1dRE)qW0mnadR$_WaM8mN=;rh; zCJk)ar}+T_2A__X7iR#?olaqITHKQ$s-|;mx!}t1y+V9x*z|`mJ6damY*<)ysQslN ztbKc3(@laEMy;_ytbLpB#auDt3@xbdhI<*R3|^1kncbg0awJxIHQ2(rg5r2m*^$Nl z;z3S#^(2}$R6*_lU#SrB@Qgm*9)q0A#h@Bd$ig_?*P+f?w2S(6sqGjCzGd33_2BZA zu$DJ`d^QJwjGZiZ`b6jYmp3=JC>hMmS*%pcQX*##qpsjW#19?g?_gqUS%*Y&%b# zEkr@+_&Q9%x@(!&FBBHOhqRo%aO;VJ-&<2}Z-pR? z#2w4%uzTbf|J6^=-11$rH$+r`JD=BOay#*7*3aBww~y3e*suRU|0?%l!514iu5JZP zg@jiuEZJ$DNuoBZ&WA_Q{lC3Y`0%KDc58(VpWJHe_1cT^_QD@fGlaA7c&9HSuKg2v z2`2!KTw+P@`4QTebrBRh0CGs~P-a$>kbsc>scS&l|H5ljx=TXKS6UCWN9WjWE-rKxDH&h=U#$msUx)H|gD)&ItVkXGrQn=Wa0E3V=- z5?0JZ*CH~;?5*GJ0iPeX+2SlNHv*k{|6cgl6IjLv2O+H9%tV04Y8~l+I|&uo)2EZh zg(^d(g=eeu6eWe=0C>jsAA|vEk3z!j<@-I`$@i@^se#G=uh1{3d3E`teIhLH`A2WiI#FV z6ZHyKGIfYty%}J8J0f}dQJJ2y{_)2?y(PH)7WqZ_{HzjUu%b~xdqm?*XN20QRtA1h z#nnm77aihw(O=wx{^HCHO?5ofjJ*2Ex!ALrFtKOnz9{%mX6D!`{9N19!=Fax*)uK(~MvtJQ z>xxZ4PLN@?Wh%r;&`~4}Itnx?SFs6fFmKoirqXsl(KNr#2fP=1f_$~hVqqL%=YT9R ztn_%H7F#pkc)!&L5mN;pC00sH^TgI#)TB0r9E?Cmq&$>|vs|#m8=x{gDBXrPz@3XJ zeM4L8_`qlUWc+d<eXyKKPTP?m{TFZMU?pMw!y8Q?eB&zmNRI>?j1pe_6ZSJC z(haLP-C^%V#B3P~wjjdYz#BIe35TQA4FQ6!o#y|64$J-4WML7(|6`<;`oB>4(EI7A zz6@Jm(2|PKzt57dZi8R-{~AnhV%*#`=xoso*K^wuK6eF3#-z=Mn95z(lAlHzeO9xY z)f0a3!qnF*=L3aTcg@n9Je^q1q7jWdXpEPCkEfK!;yt(0|O<>Up>k zdCSj0bWVO$(3Dg#1K>E0?xKZws7-eK>^N$5&0I$X+!GKE`*P0rU8K`kA9fP?W+Ysm zt|=K4Foj`jW!Mgl;9l>1|G3pfuMb{%R`(xk%eeR7`QH+pRqAI=Ier6lb+Vyou^XXA zjQz?<1oyzsBo4ohLmvI`G0jL0PAQSgDt%^9HvLg=*L#ilmjm{DBKj^i(0}HFa9ol7 zqST2bYj~eA+@|19>W~z6wtTJ^?>5`V^hkhNK31jy@h6`mXl8`R+kZr>l0IK|lsa-x z-vJD01#0&Z_F2-KO`&;zB!*f!R{At+43A$>g1YlU{fwFjYZ7EXG6T>JeH{8gk7AAf5K$K*Ndh58`zsG)-bS@xC!8RTJZ(KC(I@dJl*;pLtj zbHdKxKoLi+kMs|;mfg>I_g8}$tYAa~_+w3Nqt?N7?T(&k4q$O`_}fKIgqZ6#atm8C zFJ~8G?lYnjPi|dRSq@+5yyUYLMfz!Yv8G4)VB?zXl?m4WKnhYye4QG8oy-1RAh?P4 zS=0{!%Z=xR@Nf=_P_o`oOU9ZXvL7x_?T`rHcrv=kZm8LqI=$5b!5+Q@OVazF=yQkMI zo)d3T%fzfA+~UE?K6_hHl=O$_jq@Wu%{nItcE7`Oc`?sZ-z^Y!I(Nf6WFtxvz3<-aTiC0n{;u7OH$$1cwYnl!jfK{y+ye!US4CU-Exp>*bAskP0cN`gUU3%NE%j_iZM8*Ah#)Hng} zP;`&TLEh<#4;dL|@V7#-dnP55eK7cGuB|sUh!+0pws`I^{Q|4h`j6z&4NSxgmFXO| zu-2h!{jrMR&bB7orO0Up-$LJJnF&`BPBL;xDehtN3i{k#&?XW?B^`e;P%*Y>Hw`Eg z?txBxFHg}^o_Bz&u#N29G@RaGl!)2OBb7e<%-M1?;;|EB)vZ!wg#MO+*aBDoyyEq~ zLko$(WjzJ?8GPmWrl#k8V|w}vY_Tj*hCUzK(!+@l*Yt>%0Su;=kbO8z zBGR})ykf8U#c)6s|7`rPe#}4pdqC-*p&;A0wHx?SetHsAn05n{drlX!?sh>_O>E5x zH9T=wUZz5srCyq#a^T31Me4**%)hlP+do=?H926m{`ba|4N>fa6qUk~qLxtm)L4+d zfYNYFAOCv?WJ{OoDEimZ`!^1}Y08wMWbQP0V#(5Ehmjw{#W~GxRg`$aftkw&76k`_fuGnv6e${d8bt5wF$xHL!pn3 z{2T2L0Jv8cq~{^0y|0hFIi;6w(2{lc$IAf$Q~%5NcQ6YJtmPAas(bHG#senRPKS$; zo`zJli*_gs^zCD6AX#@6d>+<#yQ4AHeE~V-5me|B?YMMNN^2^3r9~i5s z4HF2u`+6woPu=NHCWbjnzedF*t^y+VOW580L^IKI*rt3wC(EUrs*lq)#+3#CIETD6 z%X1`UHarTioAw`|g)A~A4w91c3)U%POVxAAB6o zY8&)X5pO+uvD6BLba%9|g>=D#3bP|ca2w^fv8Je2JI`k=AueC%p6Ov9fO9(<{BqC3 zB+5#4%Z5B7Hr5##Aq{qjIkgCPWNuE)mH4SWx(#|<6KbN(!<^v7AJF%c*t8A2P?>aa}>qI`)jgT~_y=r9y*4Ku_cO zWCp}8U0`h5!r1IT)nEOVlth~BBnr)W3X9Tz-s5ksWT7Z2^X}Fgb3?0qCNDb?5pQ*AAaXJn?Ql<=A>^^zs|OCBGsw zBr0byq z6}~R7)Ww{*9w_OFx(|($ew9OR%`4okNUCd;M~w=FSD21J1bz$Wh%mXpT!P!henV>XV~gpW4Zyk~NGF*pSF z4cWy*v}Tx@qevCJM}uQ}3+pockBX|@LrM6hC2mG1+xlV1R{@r%9bcX{G!m~o z|Et!|HxKMxp~;Vq9>9;_QWrG! zy}Wf|W)-%BiGY7%Q5dtw$N$y_i6a_MHO zWmUA`m~tVhI3)xlCIxc zIGLy%lnus?YkpO=59RU7s)p)dHhfOTOSBvns$XdT2g1A*YI(QodEMf)t?nOul(O|O zHDdIKJk{ESRLU*NiE7Jp$;0^(2aXGTYWaCR9AqYcIQ}**qs<*J5E&2gCs#Qy#*adk z)kr1X5xVxf$wmLOG9@!;P1(X!6}K;Wsoq{_yJ>sAcuR0%PTQPBj1 z_!B$Y*s$ig3*e8MnxmDs^)r+bMrO=;Fb9`6N%+43zs((e9;7LwhY*rx?xR;#7Ays; z7p=O6=wS$Wcg~-zr=^*K2jo94`Gz^#t#v#Qp>|Vd0yL!{zw!KRbh!nMklLr#$3QzT z!M$p3+YDAHlNr_ckxHG2;O59#HB`C$Lm5QVlk|klvO0og`5fS!$4C4HRZsMW-aS>o z2Ho*rpWpu^zS143UP_4*Yy}L*L3R;A&_q{m zE>U@F$CU8h#C*I2@DJ47{GRe%uMO>S_Qc5vb-LMMbKm}Er14sE{}yV68JZvZhUapH zKIFQJY+t_wV-lC&wlP%dQN{%>gF9p8$ki7N+lotvn0Cz@F4qmR{qk7-qTxMd)XlwP z*nzUSQxb1Ky%}7o54o_ORJ{*8*WXOc(6W;k1vA?4p!tJO#fasT2>3{f)`fl{b|2b2 z59E+qJ~&iUcWg1w%c%CxXKUW7b)&jxC0846PVE%1?_dn2+!ONaOH(}6JJfS##uQ!P?TKk3mG?jiP64LCE+Fz)* zfYW*pA7K*jWLjFEpAlhSW=*2O2wxD|fu59@Ggc=!iNn4d(m$M&yqjH?kS%#hu2?bL z_?bw4<=-&@d_2C!su~~5Fe@icfhBE?9@J**4~>=*2zomO8uv;k`p>WNSKQc1pHH21 zFuqNRRl6n9#T+{dDJ6d0VCb{2M`t%Ye)!~3QS38&=tMYk`RWDKVDdXk7Feaq5QOUV zql_>4?mEv~amGrNfrrw`_^rqvT{kQ9KKBK3sXE9HocMHY>EB|%_0>3W@^RnWDB4EX zA^6Q&geG7_xNp+Z&w`UR`ZS*gqOtGJLYj&n>es7?n=3MQ39xIGM#AMnz;7(2&Rwdz zAtFzyJ8o~&I0&+gYo4zs==W_X@-#(NZz=cu;ELXU2BT=tMyg~m1r zF+W4cn2sGLy2*Gt_+>b$QnFB)_pceDEu7h=bEsaxX&+A?&=RA43bVeRP|?s=Sh7^1 zoL!#5a9jLYyvWLRZKGP$-lVKb3J!X`Auh#H-bwOvkIl!jmqGyj>w!eNS7+8J#fnb^Sw9V6m2jl@L07o}?+Ae#(Y1X^x1?zbVTH zzk)aXuG}EUb$9C&y+(`-;>q+6uCjOcq1my+)%~;L?6i)bXf&UGZjjmLUGV-|u@#jx zws9slKfn9wSlCa5ad6f23P<UKqJLjzhD+kBFq{>S2;hKhC> zronQbBl1x0UA{!^pZa92J&VcPl2cP-BeN=x{2;p*7WjOu9uTpwn z1QUH`>NC2PjI6SidS?9fs-`e+PwvZ^%M;5j)$EpD*L+_#_3m{zdCi*X(hzhOH!b$D zMUC<*A6e2NeJA}3vIw!7YFlv@+V`dYKybez= zkLBUWBpv4z~~DaUCv3o z`L+Rw=<`~6J{X08K%fQXmjjvV2`e9QetH*RfU4?0kTOpQ7B=^=V$s(xG_s9D;+z5fPKqY^ITF@g z@>>6j0!C56vq!hd+3}e=c#m7*y9y{O2BbF>Xd4%sh=k zNY4)$!uz<0Z3Ks@deyA+z~mcW2lYH$%37!fJRI>CjHe!#ItqpS#)-gDuhMnC-uh_~ zcoTI4yr9(q1Xfvjx$iFg4R=GFN87;xBVh-gG7;-7Z*$qlDNOuUo(W`?lYVpqtRb`n zY(@@$JBEHYb{t*wSb_ommg&+rTt2^1-9^uH-%b0>8IEdwf~J(-k|zIl?kg{)z155ZhZW405PVZ8}0l*{{nB246p!NNgy?HrNKi<+L!Qf6VKf7RNp{5$?$a z=tZ$L5{aANNLlPHkMq33QYgx-1xatXcV;KS*Khr^r&g;h4DcTq6OR@Bj_su|*56&rGBnogO>3cu16=HiH5- zPsTrPJOWZz``+m+T6|n-@_J4{u2aj@)h`Y3d(WQ!LiGT#163~-Qffn=|2W2jf75wH zffS_|BRJaPBV{Eqt}7dlTXYU3I{vqm7kK-J;*0QZ<;W@%f{%W=cy4pnKGqQrzkbB3(9GRRh6HO(J+PN(m6Ie!Uz zT38sBXEEq|3}3)>@STJ+-R>S>>ho#5hlbFD*BDRYz>%d~oQTz5(dPI}yEhWkYD!py z%&^Dt#(V*?Tmt3bhn3jUX8%|>UoOF_V~3dC0u;QaH8WOGh>H$D^TQQ}df!-VC6@+4_Ap)Z!`70d$?vxvgzSQ{ScjO@pdy#;@J{#)nWohz<{> z*S8yH0|rBWZ;ED|q;&>$dzVtQ=tCR3a#Bq^EMQpca&e{ZuQR|SzVL#S5`;{Ti z%}>Q}qqODVv|Z@@jL%kwpX)#EE)ox4x_49)C1JD;qCN&@cx%qCZS_T{*NPRbs$??qZr%;n}yioNWG34aI%sIqP#QwPkk@OCt&I0yMs3 zZXe@+?vYhGR`+6EnovEaWcbgi=Q-wSgZnlkW*Z}aU8UnjZt=|cpG?P+c5wAnE6UIdpzJ2Xyv$OQdEH*e4Zi=N1DVroFSnwf zq)d_#N2SLk5t|}44oN$G;btq-)JwKFe4<>+zZ|bPs+^NOmsWL!=nz=ML7!!Cy=G+U zBBpRP-IDXb-RFClbM*I79STi)vcm;7gTsIuyb>)R?zWGGRFt(Qa@g38|1+6a4RwlPeR4#41B-b_AERWNw4qi~N2-fU>>azW!_QBB?`;~tD={%T7HopuJD7dl#c&bs&{ovBWa$C;1`@_R6+53t_j*n3%g0ve- zHthLAgV?NfH+CJNQ`fnK%GU1S1yTAjKT|*)b4RI7ru~vqZrs>n-t$~E-cT&!O(lKP zt1}u#0B1N}SKu3Wvvj5uvr#qKU%d`$vg&8bDufV!-R=mNI!DRf;{sG|qgy+}{mo4- z_-ZwrNNUolue>SK>5C?|zR5M@bYA$Y3F*3_XZOPT!!5LzPyK1qT7R&E5kYoqmnRUa z6$hMzV-PF8NlJZ^ICG(Lp%s~a#!x{XD+De5`)Vp1Ra@0(k;IWT3xkf6c#K`-c`p)n z*pdS9)p*R-6B$QB6P-&r>Tn}H-Qf|w4)eo4Bf?o?-0MyRs`4Id)gPrW%BzAke+dB? z<+xnTJFu@ux_(d}ji!+#Ax{hh@|4f39-oDyx{Hh7Cie&RAW=gC?M)csFT*3CnI$=H z=UeN(!r}+d_|xua1OW?@yVp+*D)j(JTeUJ-fkA5)YKzO9{EQ!+N0l#6Zh!j@ytASJ ze|4m=XkhNkcg&p|7`y*KDVo3Za+7Oo2J3{w%V~~gOG0jgw;}^b1%28*tWb^(H^+yK zyY%|$JLcub`ePLz^UfN@4v-xCjR7ha8fVx4;$8^}?~RP2lu zr8sv=jyJ+l&)}Jo3EgsI8TI5hLk_=7rdspn9~$0t^8NajNFRPF|C?dF5~O~==gnM5 zxH`w?i79h`xvPMy&#V=WSO&8JrT9u_Q_2+$uk{X)3eGk4nBl18UrKoksymyo_zzS* zp!oa)C@I%ggs!!;cGYuRXsL&9hPk?W%T(or8Zdw(mh?e`{zqLt_7I919r;LN1n%xq zVo!S~+~ENod+@{Z@fvP!b=eN11QOfn1KL_PCqhWeOCH>4J_-JjCKG<7XUITB}%&2>`=L?j+>?caSq*{kRvL( zYKFLE$$$7P#8JXPRU0KE`%*B`!wcfH*@r;vp2WdfdVc-aKz}^oz3$qg{t`7i@BbPH{dpyak6-N8d8HXGmaCta>VW3pJmRQP?U%6 zUyecn-8A(ATn{eA`_?BmB+Tm!X7LNb+*9{{Dw{M0u4kBh4_&J+JH&u9Agn!Ta>NV$ zDoY8iR^s88kK1k^{oTaONWi2$W61HLB1tLfoIu@$jb4#$qt|t#pzIOC-0f-Wh)fbG%^LGTl|^B%n+%?9aP80Z%D~ptEW4YW#bh zG3c>XgaFYLLwt7}wxoVYWdrG{Wx9YvefSv(qi8Zp=cCcat**v*2>HXOJtq+s*A;AO zWeHIGTp-n0aHNg?e3~{7mjb;ENAsRGIo)O0Rye1i*$nh)|8yb{#0JmUGglA$z#?QV zX}jTM6C>13UxvO3cSkfg$m>)G=_({Pcw%PYCErN>#_(=GV7p(89z>0AyXTG{HbbrW zU`i~hj|^}1JcUm;K~009Wz72ko&ij`pMO-y%5TlU^Fu=YxS?CP1*A+QV9;^891Rua zpq`zmp=}7_G(ryfd7ict;k7!9<2j(3n_JghEU+Cl|1^?lsx+os^0T5CLgU!-5hJkE z0r&n%La&xqH-C}3(|Byku?Fpq6phVPy|=BPFT#X8I1>_4w27?La&Xr5z#c0zvQymY zZEz{~_$!y;br&ybaP;hhGp;N5T9VDb3z9nfOCp2kIs)1D_Ar~#ZpD-`{du=|zU5Lu zl;`}oZDO{jat+3PqXa?|f-l3X0h>wb6zUe6H9WXEpyJ#BjxhsJPG}uocqd60H`tje z7deO@0LE5l)Je`Y$^ti`LlRScahmv<*74`@aSvUMvxa%XS*MFsywLeXTCi7PW%kN$ zlIz)|2+*57YT7!XCYxjNyg}D`)IW}P{muKDB3q|DnQCkKpWrNrak?gPi;%A>BFD%b z-J3qp^gZ>SVA{W)3gJk)KnL_y0aifsn=8QiQzi|yR#JCWHKsUAaa)u^#uvkkOZgZrQ5x7^YY-R z!5S~*i8>IY(xL`V2I)#CINLd>4C_4O_P1Y06NC@NWSS@KGg%8(xqvf?1H76O2 zbfzx46;1M*fG0B}83qFY|7FuT5yA?9j!M^FN{J1h9g{+ap`LNW?Z+xb6}6@)ck`iH zWD5g5xk-5Zt32~f={paa6P?)W+0qOfH5%+sTa2|{eAiXFc3W7lBEg;f+m)?65kPZoof^_Lp15!dqgwP=%O{6I; z(mO~`r~#62z%zuInwe)!u76)I1O8E0R#OHL5fK4w z2p8abh1O0f$khn|(9#0%0ssIq05Q>B05Ks)M7RJ%LVz2DJSl;Mqg??v|AP+zND=-5 zRJ^^NJsb&{8z29d#7#kAVZoHBztXgS1z!IB;Naj;ea<1vA^233Ls?r^kVE-DzHxXu z{$&OUa@fBnWJEYTTpfaBg~i1M#Dxe&l(hu^ekuwI3JM7kNKh)|KawDalaP=ohoGRi zgrJCsptz(x&`C^GLIP+nC?sMp$YEz|&*3B~Ea=D~D##&f3lx_W77+ppi*Rrd>ie%- zkdPx>Kp}e|p%73=R7gnJkwf?|haf8?On4wJBqT}T2muAffWqRA|HYBy5E6E>0}6}U z0flTO2r^=he>s9cVPQfk2{9odk-w#c9Yuk{f`pnSg#U}LYqDE{9Z!v7K^loS;CFOCyIMp%MCwtqQ7|JfcfLMufb|C0k0B*@qj zS|Co~*!`6O3fcjIgf|4BklK*|3}!eYXX|C59yglzvO z35#;r{%<5sXypGOAxWV9|0E74g7p6&Aqfu2|BZkW5<>sdzc%;r#&&%fzk3;b(= ze=YE@1^%_bzZUq{0{>dzUkm(efqyOVuLb_Kz`qvw|H}f`a{xua4I-ky_kSkhTf~18 z$<3R@w@67yN&gbr?K`*0$jHe^Ny#b6$?s4Q66tL!YDx;KzxltF{4M^s6yc^IBPIJQ z@&7GdcL8X~Zh(kth>0EoZqN`B(-2+v0@w*K=Pd#v`WF=a&qQ>C_~tDVLX*hv5Cq`= z5SmX+e1p)~TQ><1C{Z}!Ip8MEt-B9|6iDvr*^)l=p%s3UTu8?Gysn#0{}+l2Xy^O( zHu-&e21X|CM?8<8@QR3viAzXIDZWrrR#8<`H!w6ZHhF1kX7AwWu(=^2@yva&xH6_=F4%E~Lg);GW#o0?l%zxDL?^$&a>{4qW;IW>*^ zJu|zqy0*Ttx%Fpz2YqyWa(Z@-xw!nR7ZCx={jc=D6#IYZMMKc*2H_ptB>k%w(TzX? z5!2kf^+1T^u7Vz^tHR$>Z9oFe1DPO=Mq`rM*mgqKQ#M)r`X&7 zBhCI>vHx4ISpWqw5#i+#(*Qt#t7BR!_@l>tx6~I%*z%q{cQE*2>k1ew_^7n65a&IT z9WXC?mwI7*L+R1?9|y9oWV5coSfcLo^7lNN|^y)0V;NW17PYB zjg%K|;cr+pRTj1;M2Z*(mVKp|up?8T<<&##fuQ@y?(DRm$H$DwKvs!Sz9x+6H35nb z6Gi9E2V9QkRJsiJk_3`}FGdfNWQrBZ;Z^Gwqb}UvV794sLH?s~(ygHK>b$+9$pvMsnkPD?UM zNrW3f)v?`xLkK*Hj#Mx?062`}CRC+w^{w zNc1$CHb!`BLjX6>(DC>!xP-5ZOE;@qu%0E!ns>#0gyo(GI zQFn>mDl6s9WnFD8R@Zp?Y(_ujprQ_EL4e@n&u@K9-$a3JwdR_#gV-k9{AMGy^(y>k zV}mSo4IY&$d>76hN!Cv*Z3x;-pHb(cXb}nae{8|zTeG9|(nfP4q699=3ls8wxre1<>Pn>4g z7Axm1JVmVzPQ0zr6>;1>bv_$6PfN4j)|w4v8jwRSPlJ`0}qL^zF@=E7tKy5!L@fyH{Rk%{Z?CkdDb9V-FWg83j?)i}C=EY%r44zod zFwV~A$6URHbgN)}t~7R#cl^s(#TAp2(rvvtc_XNqlhF5&FuLP}r8qrq$KI6s0M5uU zzu5UY)SUIeRgNi_5%H#ND&8-9@e2yx@!=Yv3bz8acetgqKI4=$a?ZO3eDkCb_^jm9 zL{6$OAX-uy^m+OkAnkNClXS;C`x+4C;T5;vX#Hs`@mBC*OuOWxgjeI{Z`-ux%hU9K zb4ur*UdiCc*&bmi*Fr5ddM@+&p6zhwSw#Uv?;m|JEYn`88lU(Mq5df$5=2r9{qnH8NHw z?zecA=+v%_NbEqyPO4ul z8`0gb(xh@J>+X{bE-36>jiJs^3HupboOY4;7(kh<)vxtzo^}V|wa`B9wV6IfOWRdI zN}Q~`F#K3~HC<;!p4{L@j<(Z?SOodw0a~I|d4PmSN%OY4!Hw*mhY^$7r5VZgo9T(a z6x1kZMyUHFD6-iEE($(Nz0y1{8Y(n#Eg(sbR5ytYW~5!nKPmY_Ntz89ksg8(y?IIW zfmHU1>RCCRpYm9Csfq%Ph5ozm<>be)&znWL8vALxil3yzCM?kMEm5?^#I7*nk(&-i zN>mTxV`G>16DrK!`XtAGjupS_Uo|w8*HVcbX?j&xw-%AgPt?^6F$nRBv$R9zWg8G5db-m6{u<0o14V?10;~$bMt{tSjXUj|^0qg91H3 z2kO?DdA`=y=w9WX8lLz=*mV8liahZb33gn_Foqb_y0E|0Yc`JGWX}cWI5PMR_5gEJAdpIGQ6LBA>FVzitE_3ma5x2n!zPrN`DAC z@Ud3GcQ4%&=w!tP{qpAvZg1gC4n_Ix;zN-UcNoRg*rt!^E0W*xb>i|$Ql5Rt*5I?v zaQuGBQ~{wW(RsUd!hA&^W<{6)V%XZ;`NW~#4@c>*3hVRbTCM@I;eXguFHL$OD9yR^ zxYbR#*YKRv#6#cP-*4WVII4v&#YiEQl$`v=L)1WF=dK7)3bnC_QIoHI%*jJjdH%(>T9BS+2D;MJrR`Z&?X_0h7 z=?#DP@oVt-s_zi^WC_@(_s>yPVi7#F92>-$%3wi6Pi*^)0!g&*c5Jk~@T+$=;@Dwh>k z*WF3@TxKyCX|gU!^3|WTTg37W6!PfhvBgBF zOKUHsGO8O14~<3RN@K+co_fPSr(cNOJEUL#319Ng>;Yr+X;ouZ4fp8IFe0zG(w^a*#{4qG9H6kiery zf&&5HCsDxo*NnBbgwa*Q&ZZLuW_^iKpI*t>HRBwf4W>zaiI*5yvzEe-fmy7hpk)5f zXe~WW9Sm5M6&j$hS}w5BADeAIbsQCoqjGxk2zY$yE+=X#p*C7%+NdeQ(=+-|Xc-so z{t1`YNrH%RfSOH#etE17*9=QMY)PP3YsIvn-6TxH_PH*=ev!Ec*xjADYXEUgQH2YF z>O{$9%E)1|ggCE&LLi(9^pJ1d*y`%{@u_z@9iA@i(G7Q$W^Ph@YNYws^ge@yN zWT_ehwsN2P?b6rUx1AKOsEYuh9r{lf>sdtWYz>GzSjJK;AF8A@%aMYnx;0{e;py+) z0kioQGz0%plU!b9l+i@`=$PHOtVvJyLPF7>E*jBrT)0G{@fG zn`3rHVZ2>xs8_h?$wGf9(_t9R>IG+>QO<@}`}D7J|MD?jDd?kXK({)(?mg@E>rskT_V@$_v{P95v%I+KkkS&3j^5?iJ)lQ<9LIzDx)RttV{1} zz|Cs_CccvqR}3C{B-8PH(lowN@b^3nb~PW)cOnlOdJA^L#^LhYpHD;nsrG;2ozL$? zVnWKGAHcq4U1Pj8+LWks_%IizHXUQKRp z#RAO8z85Ra&cMPq3(D&LvCAhLd7w#78(2`dup=h@Uf|Va8o=K|Z#-RDi_eBF4Up4m zrg^L%Y!e$#k)5Rqpon$V%uYQpP#diBekI)1^*P_%H$vT$6wkm7?|hxK88Wq zJ;oOVd7n7WYH0?MoK6oTddh!>?LL2;SoeZcL_e&58s)reDi!Gfcd_UMzPwE67uO|W z`x^LU0ByouxxppfYNA#-Z^u8==aY>uY{?1)i^dm=)C}W7{QvP9@ikjmeu=qg3Z2fc zFL!!y42BQ6nK09Qof!}vd%`Ldt6CDuo4L^Dsl*1~cySGoxG+r78Ltzqw$;UjI<-Jz zLba^@*x&H-AO>EM?MWIJt~LlzO>6nq6tzKylB3y!OVo=uTmYeFq{oISVM}ghicSMo~h5W6_#Miw7Y`y zaPFO`#u`T>N9iP8ptan#S)KE@MspcI%lC(U=AdXf^0uj3C)Jhum}2fxp*Ki&tMm!= zl0>(LyUfzYpDlXAx(WrG>WLJo;xMo=Y{e) zbd4EyLYF2b(Pj&|blgABsb@0IuWYN%fHzx^)t?pPx2VLahnaBs6NaTZUhi98W`ZJa zARZu=p$KXR1p2(EgEGDJHKPf}EBq)XiVNKM9RbQK+t9CBWlcnJmAJHf6swmY; z+sJv;l2F8VKfMKJ^x7@ioKFEhNct$h-H;dT7F0l*(f8=mQ$j!qAi*;6a;02KUl*XQ zB>*;42OjGZCpT8B=4QueD?iyi`YC6gq7PdvHpqUp`sOHh;6|D_?a#Kd+p*;IhmYkN z;+tt{;DD22!VZpSp)k{@#2}e4$N~4ijVnV%pD@6PlJz*47c+^cQ?U*8#>;jJ93U!S-VyO=O|#Q)Kqr zM)2~OWD5nQ?>YqP9aNYe0hVtu)X(?#p))?$16H<+k$ z8(W4o{UCTfvo%V`db)ftJVMPYQi63?E)*-aho@5xo$uWAtX#@In%fD%QT3=G61nEb z>Xd~C;+;C}ad3nS61`ZpNHgvL`7-xK+^ZTY*`|WAVe6c#yHdrE$1HbH{F$}bnN9!w zIN*4LxL@tk1d9KGs6Rp6#j5(VDmZ8`2Li{QRwwDJ@suAz%?^4dd;^{HtZEg1BAh|d zy4a_fK>yW!GxkSHif8`bYtlgjljqj}^5erhcajo8^eaxz?&iUo^>V(|iJx1oXP4IA zNgWijN4>u9@Z}wuokBl8qG`Mdxrc6xyg`#@+q!q|1k4REj8adUEbjA+Aa@U~M6U?Tj7AJIidto2Cai7f zdtYBS=gk(vUg6Xf?(*|qGkbqpst4!8V~r6BwFYCLyHDzQ-C?%T^v`R+kmj^DXRA18 zj=$zt8_4PIE&ud^#qP_=OtJ%i(XHjpP zI;4l0eT>X3o>?_i{N9o*2YEURx#F>50+Z z?w!lxYt~GJWtX=9=2WMMYe2A5}*pPxdxb>3S*A7*aB?%6z2Ckf%CQRt^xKVOhW+^{>NWrUJv5jhak)OR&4kw z%!s>BOGE_ym{qtt0@ooh*Ryn6=2>a&P>%c-5_%1=B=o*+v4)MNNq_e(dwiVJK=P^N z*ow8~HQ?F9qzq(o{VbNcJRH%-#y82>Byv7la2YYc{sT4zXFaCL-T>2BAD}cdpU!n6 zrB!uSA^mw(yOp%VfoyzRXssVba&foV7r5Lkcfjh6Iyxaohy-?4Ta;Bc>Kop3zv~ID z&50arwjR%qb&mcv8~W6HYhF``#pW2QFUvR7$&8hmmJ`E_m}a;-W<~iHKR!&-mEDyR zF%NV!?tRS1sj`gxCTqSHm|&mbEoJZXXxq`@Di0%^b}Oy4>h=X5|{7mM(M^p-f&|dDp$WlP*kj3M?1&$6}t3 zzw`JJJCDnl!Rc=H8Apm4n`ZI)!AMdBgsdjav+5e)<<@&AXyDWE(9w!&UpN8Kx_OCt z!rq67x9<&{-Vq6>pyu>lVM&B0tyqg-ZP1;msIhOJh1*pK=SCvuWR<%#Q=}LBv3p_s z*MM8EqL1&^Y15@z8FS|3xDX5B>o(qLL$XtT$iHSuVHX{u-h-x|0Cb7ze14y z)kXL%XASiIDaQ7pbZZQ~8CDmKz|tA4o+oTLM(Q?=uW+q+u3Supn{(ieHo*^YWu1>O zjVhss475YwZv!%5?TF` zv=h0IYe0gBE8^Zs+n1`=_bqJWBzPn27A#Kmd#57-HSj(YV1-m$e8mi|d9qHWjIlikqp15Kd663xbI#A-hfa>katTA zPA@&NYVPjg56JmzJ}HW63-yGD8mhLj8$G#j{T^JUMch9N`B2?tHm}0N@v3XO%d_40 z_rWbr)$d=TX_sfp^ff2azqp8S!T4+pLSi+K*hvFZl*?n+<*DFkQ6NQjtz_Sg@xDMw zw?yL$H#I7=!kh>fvP#C*cTi3f`c;jHL>#83_9fKA+bVo@s67~}K3c>yf1LDz{5Z;bh9sWLPaU5IFhcIC;C%r%`!njI-^{a1MrfDo&Mf>=- zojZsrlNTtjLTRyIEL>X?iEz}|UQbC=9Kt*YBQN>2kiCBzw@XZ?1T`NDrh$BLp zo8t<+^eoEWD*VH-bx_9s-Nf>9&|44*cu+iGo8YyXM&@-Nkj~$QaMu=Zp3j9-=f|Gk zl|BSm50qj>Cnlu9TG%Us12qah>^qF}3G%vqpI&(Wd%)*sr)RLBtJPe&8z`-WR`IM5 z&vg3)$cKIQ6)SJl(n?|-8rJ9YMU71@XOqh($$Qu&iAliMS2oFgkoMzPG>8(OlmHem zp5dw%DF7xa1JB)esPFDxvhPJM>wNh=z|zUloFpu@=2@dcirYKE>bPk^On*Y`p+tlB z-WwJ{DK4FMWFV)piM;ufYXHv{f-=a&3ilc7iv$LzDsr`4#0)va*PTk>KvD+@qIC9& z`kwPL^viknXR&A))MxAK;1j=$9c{4FsIU8bR@$iavI)not%}vP4LLQ%uW(vq*zc$ia2+dn7~_?YdnZ?pXH=$i@TY#m zBM2|f1EWIlt=%Y4PXo!$l>ZY0=BC0~oh_?{6=)(}9k> zfuM(BgqY9G4)kH{gDACzGkBs^PIFhS5ekN-DZO-DD7TvHZb}`x>wa=cO))o@K1W_7 zy;eI7v%Jdz{?omizN_~{#GT2NJ-?L)OEaeMR@A*(ZH_fSvF##zyI~B&CH|KDeag;C z{k%M4&DvKi>Au_!9$=sxa~tGex1If7FIzd+6wN(=rD^Lr=l=k|O)ReYjf#3gG=Tsu zcT=4(pW1s?_qVl>|4bXa-0VD((v4wM;hdo3dPP?BXX&}iS;9SD*`yID4Wye)^tN5< z703{tL%hLeYk~J)&;RS>M6l|pVqwva_)MC|5=R4{-&|7=aYt}@ER{?PWLu5U4AC7nNberdwM);UA5d#I;&PDRC|H#X= z)NV`n=Ku36%+=-BPKXsWtf~zXPUgfygRBk`?}uO>J?jC*8T)xmJecs}va0KsX~#+6 z{bBrP!kex;U=V)n8qgHjn=~_f1}wlt;XG}nm8xnc%=d|}-YtU}YJXbK7~t=m!gdYJ zUt*t6nCn3K*ypNsvZ!SoKVk=WyWI$&`m8vfEP3@Asku(@N|@Vy8wWD5hx6oJRV?2s z;sXNEu7-l?2KieG>`bdhiGP~$8LM^6ydS%%V}B`+k-d5mq_gJqo~^K8*El4-JuW>c zmo1!ZAB(GOi?2N4RVkCK-Besg>~pSB&m8w^lm`WxbvC2`kDmh5?*{fz#mnZ1UcSGg zfOPwu9J27|$DnUdj~>}Pq_2Z6NbWbYnZWdtPs&B(8sl+-l*-CG-%)|_CreB&s72Rv zT}$(Mj@KzX6jiWsxT=lH(8W(vZr)r&^Dhk>VLw?0@AdmmqF%W*dp4lv$^?X49$Pe- z`Q|dcV`1_YA2Z! z;@C5ae6&lY(9`u&H%mc_Fc?Yp$noofESi?h%3)!*p4{xWjw3|0Mrq4ap_xBKHGsAi z2^;;BZsZ=l$c?#s$ZX7ybGxCFn&Vz^NmI#M0d&VAXDa1+lwA6lzLLRIz6P3IPd9~f zYPFN2WyuedeM%i8UbRcuW6ZWE8Kv@LkYlS`<@?LqS!SsYqWS?pjN&GyD{lj2cQf*u zq7JFzkT745luMfuwLK}M_|=o8f#tDx`P|dc4O^EkNh@Cy*sis0ipsu7SfUSi-SN^s z>FP_YDf%nkr~QqjN3BdMUP)>7Fvh^mie+5nlQwvOC)dFH7Dg|74en{BWzu_|8R-*{ zoC_^K!Mc}W{Flv>=ypH$kT*2llb98nkgfcgmXqqT{7yes3KYFaGA$<*RLadK+9U1p zyYi@DJE@?y!oR~^2^ZJN*5mHJp|%=VR{y}CqH*4zQ&!uTBxEw5y!rbHDT7JTQ^+RrB%i=vWbDBF@ex4#` z`TFs%4}JVuCJsH9fYR)%JSW)Qy=y=OsQzRcd6rLy>Z=&3(k!rC@cc1bBRR+_b!7yJ zfD+9;4}C^~0grfvDTKdo4sW?)$_GMALr>@~m9E6_Bdyk55XzG3*6M!PE8;~~_(|(Sb7t?2-);%Q&M;<0N zox~=w6}SchP!eqhd%u6+pG0yWQU83LHi2Zr`YcoOY!xBZ9*8`)u-2)GgLp4ZG}0STr2y}7-(yXt zf0hY*Pk+tyA1sy423nHlH?m2zoF7N5dl-CM*C%@O_rB@>FyV9dV5)Wj#nCHX*(F)k z5JUg0pAzD-ypklruzPRx+Pny0`83N^X!P=A%`4vG{cN($CkuneOaqfV8yO9?>?B|O zO?}!n3-_dV{5rYXXSps-(lDFXfO9Y4?qUaVUtrFQT;#{U9Lk56p-4)nz1IdZwX3X4 zi;`pT;HVO@ZRX!dpS8L9jLS=8{*JIs1|D6T*C(q3xpO~R`#>`vJ{ClXY=Tg+7#-ct z**$(+Vb&s^Bn7ifgL{vbHr;s!LaOtiQ3BbALoQ7B7urgN@FIGcWdCeE4@~`lHSM9? z)1~K4NPaHftF>D`@z4Qm?4jI)pwG{upB8jo+F4B3f!2Ku$|h**e{0fUz}JpFkBd60+Q|afFR9Xq1n7g>(;8Zn}G^U4^bj zMjym}&lD1L0Qma7^*ODA&W^3NVIq44G2Y4xxE#BFh8LE%Nhx~JqrgAzH6nY?`*c-4 z2%2{5D)29M8ZMyfxFT@PEumXko}9E`VB1=uS)@pk>h>pbBp0jyD_r|O#FCLm}& zTxjGKqMqkl93*;{uCvnL`z&rZ`o{QE$6~*qI7yzP+6mC_oHKKF>IS`4%MecS7`W|b zoh`Jk{7>Z1lkM$T-x$gzdl)Vacv!&`P3KV)YUsO$xbMaG@l<2dW*JvfHs$L-&(Z5f!Jio_U)W6g#*+g^vc%xZ^8uCj;yX+}+Pytc zl-l4EIDhM|@13sYv{0(;F3Ig1FL}&@b6ZHmIBr(DJvnBI9bcn7DcAH(7)7W<*UkPk z%*g3kfRp^wtDrIs>6}8uln0R)nB~c*F_BBS^tQ^8$h|xnWVD}B*Zz1?f0Vj zq7KEYW(NoRqmX51SXu4D;cxr1xp9aaHIZ4pW@S~d&Cq@97R&wp0St0o1xs6rzx}HU z{Db|U((Gya9L3hO_PZ)S=*DVK_7AN>uPE@-v#`AtG}~b3)KlY9T`Io_NY4?=X~C$m z8T8k$QD0$YpXS#i8q6kH_z?*EQ?LwHu6}ZVT}SfsjTgj#d!s5ck#p!Vj@XkgCDgUe z+e*Kx9NtqO8}!&rzF40~uJA4|C&bc|Nwl6*QL0uSO}!*NxG2XvzL3~V>r`^)ibx%X z5hv@ugH_tq-*~gaE56mCy5w6VlWXjBG^fyzbndD{lEb;I%PsIucrZB@<~z?+2b{Jl z4E`dB^ON_jDPdJ!b9LK1t^7$>aaJ9E-hy*aoj#@T+Bz*yYv3J_UL86-C2T6!_Y z+MH`bk&x996|#K-vZ}JyhO3yrJg)`OJbS%U$o&1-o5?!3YRPO>lu>exfa7)r*?Qdw*sv`>(dsioRY0$Yj9&#|v|9WGnnFzq7b_%6O2-U8_;^NbjZO zH7ALo&}72A_$tU;xurAHJB$6YK-qVo#6C<#xjGn{;ieO7D9znETWo^i$Zh0D48d5E}mCT#Mw2OZeWPSJ z&w&z$vpi>D0)p>q9c7ZwGQAx2B8z%v-I4JP%4f{tUi`837-E0w>VZ4xE26J*|L>;B z^TqJl5wtBHC70I+QT?Y*U;4^q1c5T3{#~hqtL!9O)S|5D>?q;Xx)XV<9^nuZ6t^y1wXH))-1)c zh5XNmPqNwr#+X}ZAb7$XQatbMz2KdmNNqpLcW#2e4ZSio5A(yQm0Gs{YCw{Gndg9H zGY(kEG9OYGmXyS&_=G^szKj5DoIZXePv3YM$WZbuS)F%y*PIIWj8D^K$grry_2yz>#bQ?Buu8te<@Oytld6=pK0SR!`>8 z{?y^+U9_-&_(e2yq^$y99!AHEC3pk4Og;6kf|9JY?nMsPJsAn7EFpLaMU&1Rp|M?y zL`3=9_&$W$R@sc+)bCBKNqCx1TS+i`B3xc)LUy+q9o1UbkH?>`%ZW@)^@tr>@s0GV zy*&9cc`9)YxM%rwJ>Dk27{#{*o%KF@lhh@pVKzI+IQi&;jy^Acv-NORajgTdM4{PfpyPBi|)EL zy8^aQp)vRem@*lG0$y#u7 zE>NY7%SN2AbWYTp&oG(GE_@mc4LFeHHEB2P+&9U#a+M{7o|Wf2X(we}zYb-TW;GYP z4oj5YQWTM%oGfgjYM@)IzUc?dol3PAwOvq)?t5*v9!zO5GBYD;Ys6WR6DZ(1a@BW< zwER5s=CnppN7BEhNCm`uY(yE8J-ORZ?)$msaI4zEHN{p%)MKd6&F-_Sk{s`(J_)Nk zotH$VaZ`?ug7Vi+Wm#pQF{e#PMe=C)ai6o2FN0IHqPXHE6LCq>cWR6Pa!--{jf_2e zVuQKPGo7ilENtCT|HTmT$rxM9x#%hgr3#w0>|_davnF4%Xb6FPi0z>|exJAknW{V6 z&*wYKIcvu-+FvPRZy_7*lo_iPHwN>^QC#>E&Fxx`f)Y=p58pr-OOoy?gcmK{jc2GV zW#-tLyHW2poE`fIpVi3}R0FynLn;CS)19)WDDEJB$Xi zBJVmT%cwb2KPLTf@L89e-MC++jP4Y`SYfs!<=e_qsbky+WL7bI#dfM()Z|r8|3

bDMW}ly}5KMsp`f(T-%W0_7BYPnj>N1 zv1AO6x>uac_o@#n@=4^+5_nr|5Q1#q75*V}k~#JoHdeg&@4($cP&|9CE_F?9v+s7U zR`bHbDc(x0q$IX@iE&z{?x^|2SVbdsW4rdykDD!hH5GiWwBa|6erBJ969WLO&faUh z1<;=Jf0!AU`6#n~=!bRixzS&fcrrEM=pyr9n+1FenUa|_B<%hqRHjz81V3?^y|`Gz zHrqqi8Z{rl0X;?EU~!>Dnc~6Z2xsG`EW&3od>h{b{ufi2+|%18!`f#PV;=C51Oy=Z z+Zj6o&X^ehuit|_s&m{qQ?wsO(E}Y!#RXSS*Syi$T8=b~?n$hbO%EtE!`| zz4v=>hEw|N2=-C7dvjdTvzp`W;1T7sH77$Cq(%#bHw5;C#wq1Dik4TtqdG!^%c0&A zG{ezOwgHTmYm{$;aL;o_a%Vsh=s>LZwLuO(qxh@ID!};yTm;Ova;>2IfTp8xwkw1G z2YJ`51m=Qcc5GZa$1*ucZz{$Zr@f^{LVmA8j}zjLDf$Pc1O*iBu9OKhoLdwDme53u z7Wu&ValAgrR}PvPKZ1|xF@-NEU}QE9@O$}V<|Om%^1KgI-S~(F3%EtgRucZfqSoLe z&A=IR3P};E3I3SO1$4jNu*0>6&A$+44Zq0bfyX)o^e1M&HHVO)I3Jcw=${O17#kbTsHX>&=*wT^cEi8B-{zn zn{%Bxi@gRHx2@T(r41%$AIP>5-!(hb$pgme(IK{2gWz-j2qlMe()j5L0*D~(CROx? z2khztj12=m<8E_~hD#*>5EqV_;)@2Jy|_6$-fL(-8S`(Ij@PvtV?Ro`o*o4rPaHq; z}7ZqY>7#f}Tzs+}`II@47{KVsh?L*V^~%mMOQOukE&w%zs4!x$~sd8;>lp-Ut* zO%g`?!SU|HW~T`uQC4rBXUKVeej=ADl-o@1d}8%Rd1(zM_-y|9AL@~3spk(!ES)(a z`RBuL;xX^C`tW1-=er9Hcer=zwixJ?jL*^^rv;L!RhK(wEaJYr)v{))I5l zV)$xt+qYSvW?G<2D`iF@JS+-Ptss<3+pGqiLn*ZNj)q%*ru7Jj8@iISnZ_MF6aoVWi;!x6lDxRSw!@3o44ga`5bNyno`_4C8rYs9a;uP#I zS*&<;j(}^_^9bSDrnwsC=w#$O7E@KIL4~EGMH;o3lA4S*1DD8X_b4wB-N$j@^cBG= z3(i}5&Blf2lf_EXm9VP{y>QM1!Bbyt7c zcSR=8$cL9=_HOuQ#OYaCb}!k;qE77_%7C}-8)^oL5EiP7M~)xJX#F;8KYXwBOLP2I zgR4Y+;UTamjEn%uLQ~Q&gPM2n#tf zee9aB*CfRJhK11#h3?`$XQ1-pp-$@}C)ByS!(*=4hdlY=_4q8)a^U>bA-8t)39?Q0 zv0sD3`z;rgqb*9Ue;(Dce1VTJDN}zc2zs@8ez|t{llX?${ilz)-b&W}oT~Mc(LZ=m zwSEzE@0~2pV`{QAm-eS!L2%k@mpt*F&7A=X4#lSm)j2+^3x>A5dwcvmebK%uLXe*J z!uBNL^K0Lio%=BaYQ<|8pT~+ellZS4AIc2fmkAzgWE(2Vc!}Q{en*x)qRR^pd4`w^ zom#KlQ~ppEW4FCa{PmZ7oR;n5V|zH4c$jOGlCY?YPHFec!cEp6%0tQbDwej-d7M9t zM&>?KZP>bnrM`u7Ga}*xzvmHUqGv_I_YvO<9SL217=uq)tIgaWw`nb_%cLT|#5SBW zSbgJFH@;8qOH9M?m_Sg1jQP25pi54^R?`fADF?qmc`|y)-b>-GrcP-!Y1-*cbY^wIM|vTi5eT<6XT3O91Y+_$^*bMeAabK2vDQ)Ki$*I(^dNDH0T zr_6sPYzVYGr95ccx zi+Nd0(+tT;se^tBmFFGme(7j0BZzpposPO1HO4Q{yLMeamyq!h3;CtohDqJo^K{h6YaogMm+I&)`_z$*V8f%qnE?9571+dzfzd4 z{R*rNyvfec~WlpyxLsz#m?BOi( zkxlGaGcST=kH76Xi04KmF_aPQvy5IlA*I zfy~p#L-st|{b0lH^SfI8_Z(p64BWq#hPl2Qp3l$QVSeuMkg(|6?yCrgQS}ub2#2og z6An*0Ba>Z2ZMps5U5qqO%`VsGGRvt;LtKnTkhOJZLOc77Qf}rd zM=l}D2Of-n`u)Ld#jCb=H+x8RKZ9a+c!)04+n+|S*~kium7I2i-|@5+8qig164T$@ zBI#q>9<{rt1QYCI-dm{h6*pEs_d3YyVK4sJN4l0FiJM2h+fGVr{YJXcE4J)l&HTGg zt~6F|Mq>;An5yu}8;n#!i#6ZGHF6}6Ov`HLHm}DTv;*2CPsCJbRdLvL33s2=1a8T3 zVHiAq#*_1@EB2C=!?bg0B3uYL{8) zvl*+QaN`%epKcmiv`xpmHpZPXo_*Y%BDUZ*zkAY9YiKuRGjH+E$uT~ts%UI0e(w4~ z#50?8x`BNq{&?2yd>X63XQVE7Xnx{uo4+--ZffjICHfC-rsT2PSnF6^caeR_a@On6 zi@8H}A964H=^ESU%|x|LsXD|b#kjLB`NzI8U9Xtr`s?QtsX~?Ah#>gT_XU0()@$lZ z2+TKtJ5R+04I7d(`Nm2Rp0##ieH`|wEbi-fQmLHw7%UsIMRGuq|Cfd!?Mj=EDV~f- zb^5bUoZi0+o@L3!dHeP|J;!CM_4?|Zg+3P@^OUNpbW)PO8221U!*`1AbdqlvOgz@W zUma1O{=_=+ZJNJF@wDUhT~EeDbB`Ef?wD4i$Ioa1%E+gmIC`a};YI`~;vg3eX0ESq zZ*}tu7_YP}>OKz__VdVSW?1`z;du2+*Kcnd-NsnfEKYX71#t#h(}?B>{>uvqL9d}wyHcG!r-qt%A~#juoINvJLg?6=HVtH^9O3AV~|OXv=< zx#+c>vjI24^0#xZ;@DH4nue&w=?ZL7LH2>q zVh(^oKsXFWCI_%T{B$-aw#H|AP7U{UNYysY8y^+!w=}(ffwph@$V|ufo%b)s^6BlC ztz38F^Of_?st(0Dt=|-{dK7fG3sYlTT7K|#fB1Z8S2y>miZl|>dv{)FjukjKcch)NuR|TJRf6G^hbi3cXnI(9yuJq59t4eepp1RJ_ z;Zt5Z<f6uIuqyLv*S)H&|RBv^ALT`o5-1vov;P>1X?IeQQiGtyMP0 z4-W9`x8f`74p0Sa>E_Q+*`c3s2P~PVEQVLp_q&PsJ$7jFr>8%iL^V5(aQDX$-E;M5 zSc6?GBIofSE4WZ7h$FgZ=^?S++usZXM}J_$+{M6 z2GtGtT;({AF>)rcfQXa`QHoEu)fm^gQk;8u5#$2=C-&Zm1>-Xte< zk-Tyj>>^QBNxSI50kaiJCWRikLrOZ+G`q&LWZ@ORT3O4*AWvq8N$X%EgSN(`^c=rX*vOk0k=PcitaSQJj*3I@7qVs$}Mkv-4)ev8Th z=COX$jWPe%ucZ|-CCzy!;@1v*_Q2fEY#x~ z%!}Et<$7>?_YdufB2D3pH5!S+(>R_Z&4NIC*Poo&AqPXZ%4m(V%)T>op*XTd0xModE$|4-P*)umZyP ze+Csu+)CcvwzoVCbe2ik?}yWf0qe0YGO7qcO5*bcDVV1KNZDG zJB@Haktee3Mp>cx5a|rxz>aK*~Z4)K4s z@9bc3wV$yrS(MM+Aa^31)WBBq!VTGLL*nUgGW4ATk22l)G zIftgHdy=oGIhUufi&lp*?DO}MUEd8Rv%d>E8U>-%uo?(<7G1ZI-GkMOMZ6{23-?gg z2xg9k!Byh|h-a`oKeyz5)nk=3C+);1oaJ?{@Izw$ncJTGTKiq6RPR3BHX#e&&?$I zmmt|y(@hR@?`$Xr%iGCkcej?up_DQEb4rLN4>5r+;``_(-`?pnxo)JV4YFP{fgyXW zqf{Nw?q@1cotwCE`ll~7ri3j1n%()vf9>j@CH_T3&dA^)QdKr4@Z-<@#KQH{&yKg` z5|ytl_e)Mg{8U`MqH0fA1CxES?w_nLBR0QQ-*BD3AN)~_>q@EA4o9g8jVFRQYv)6& zEb(J`4N<5QVKs7F7w#m74fNjn9KO2HWecKIo%M${>(=b}Q`H(zEf~8wfy#*0?h8nI z(-;~g-K|)kS;3NZnvGcijV_3?w<2$YZ0Dr$F^Z(td{JyM)sGzaSj#r}; zcqPXn>6kGs&+CmMnhdhc4LuYb=Hr9~L^n*)~Du{@hg_0>1m%au+m{y#1Zf~VOs z7cRse0?{nX8awWc02JVuN3pa>j`hR~qX zoLfcV{9hkDmo%L$cEyq{ivwGElU30{Rnt|R8?y$tkrcT;UZSV!^xG?Q0@YoWYJ;k~ zjAi+z1@w`CChd*1k&?z&HdKAemV!2JsBG(`T4N^@jyCA$DNTn(;S2PCRx6F{ za&Pr|VISW%i^CI}MnY95o{6JP{N}|?lq}W_$E!bl9(VdxF_jUGBlyQd7XrQ><&QF6 zs*&(7I{EW;mvrsiojBMqidta)gwl=6o;7vlE4Asl$^>Nux52&jzBR<(VFxn5DK==* zW5CnCZ;fl%gV)WI?;Z$ukqh4KLRsc8vwV@nACl~e#mJL*DF>+m?pK35WAQCchp4)~ zL8m7AP^GbwT%`}83v}MvzBy8r(NjJy!2J8nyx>7R{bB94F-2SvQ(pt?Q_`>`=;d4d zknQ#@a-|JvMc2=HAsj9#JOBNnsq>A;xwy3s@wZnRzb%q<^uCw8IcZ>SpqXyMcPklr zbKAuKdX1@BhMID#|MlxzQmu(=8#KcrJ0-~e!H44Q2F5FL-EiwNg!eCqqK>K?7#kFy z`H~Ob;KCg-L+F2f$Mlzc%8F7IDReGIZ@5)YaVhl*LqdIk^SL>;y7ZO0u8McMxxwEI z`HuCHIsR=qZG8Q{18^&%m3hIxx6CI6C0t#*0UlVm2Fdk2h52}yX?F`zYRyUU-8x2s zYuCy!^s75|1(B^l>Ck#i$WgFn9SZ>Y8Ec+dxxZN!6W=k&h{BP`oO*19nm_8?|Qgc zU^jHZ_T94r!4F+ru(v;J+QSPS6JtGUyDzY-G3)pvj>XTIpJDl!g;?^AsUK&84gM*f zfPd$fYr7itd4$y&bFYtPR_v#iqy{VB2|BYb+-zx8&##wFD_-%4m0m+i3gFOnCAeGl zraQH}=Gr#KgkfSQ(cRE0wa|vlWVlHbjUR%i9nT3*XM`z-WGa1nvYo78v-E3>0 z@@|Bgu-?uq?s7Q?&a-hR`)yg&{99&U^s0>)7xwB(#HOK=EEAO=5e3oJyV31;v1l0suXskZU3uA^#gyxS8& zTQH;a;NkPv1_k@6oW^-)%4r@eaE${BV_>AsFuc0xazk)_H1@HiFj-=nrq5@#2d$V? z72qVJf->)3f*_>Ygy|hm?k&@c*c<@f`;k7^!Z4)soxzWAI$A5p12DXGauhOTmIoliq9 z7w2t6{tR>_6_ph7mxs|60x#D${~VOBwd z`);ASZq0?C=}mC+y70JdpH~5U!qa5f6jfO)joqSroERqP43khrP44XX^*iZulK0C%LNb;QUpZXH;-y6+1iKO_A1@Y)ZMlc#jLa(MDad$2h_c&$r zvKDrlJ2l-O&3QjO(P9-+jWG`nYrpFG$q0L6?fGDHKS95egJl5H3v%}G*a{Pn6z9`5Xiu*kUQRdI)THnQn58&eYHxf@S zR-Jp2>>%}KkDn;T>YxTf#ivX(m3JS-Hw(C1l@#RTuwc}1fK#d)LoU&p5r-(J4;Hi9wFWWaCz{qs&?9tNFJS{UukXo0 zIvC$xByRP?=lkKQ5if!V+06k9f#Oq|2V^JZuENLzGUbVhI}#&w$zd@4zm*}iLQg(B z%w&9Ae2LGvlx~Ax_@M!JiC>i4YlC=+RT6?E9`pI{s9~}aVBx{u`+uOgQ3U(e=+N*<{%#o6y>%oe&FJ|!m3Fi%{*_2PWSE2e4gA+p)b zXw0`m)r~$qp-J~CtwSwM+VeUq%;xYl?j1%iKM?%RbU^MsrBxq$TneieMs|>O;w#Wu zRkCL|4`o8%v#P&|YVs3~M4m`PtYIaM(@nU4M4r8SkXJYMGDsEO1OiS+=BDG#JLp!} zH=G)HVK>D%@1RziO_qA1YE{-zCD-J#(!abmrgVy@C#=etBWJR-^^+rqo0u&;H5F#bbQa8aSf z#7cn@Ve{lydSCKgjjXHx^7d zg)IuSGuqD9H&1`*Z2 zH5+&&KNg1_kDS{W0e;)~lvAcL<^uh4rAgIaN=-DYlG}XFWENjdkG<>OE-w%nFzmKH z5Dl7db-G0=w=-~fFhIPh-zmMFfJCG^RIWjWCF}3gXPQ4=KU;Tk^g1(MPsu){KL_XA zKMi})$a#oWKE_XCf2TTE6NF6PvM1$*a%7FghZO$ncwI$-=;H6rNu+{iMJM8Xgo4o2 zCyn~P!Rh1~dp9d1L7kef;k*^%unI22)(R0P9#kK(o;dNl^B3-yCgUsajTshWiuQ?oM-kn_RepWJY|#3bY9G_lsIuF#MNKAa7W`_58_ zH&WT0EUIPh`GR6>t4+)X#71Y2JxAaUtL#^0QDOJecDi%8?=XRs{8mxV41 z-O<=_t>s#aC{=YNpmz4i5L?O_a$^ol z21s>Dg@dJE_>M`8lW5cEMw54f!|X1ASanulQ_+?P?Zys2njcM5n`rI~fPvLq@!{NL z-(>G6=9}me!3x$D$mL0Bl%ac}d#-1$>^t#Kf&yYb+*(b(ReV9PikKgG8{nS2=ae4z z@#h{}HLrNt2K<;Va>}*Tg^Z|1*!Nh5-_l#}4(_<)!&%8LI&MB|b6@oGbCD}n{c)f! z@%$N>L|b6Z-b2jSP18-w&K!v_OZM30>~SRB&JY<0tI6`=jE%|8TqaSBs_q+)yST(K zw29~aU^O#(hOvGuB@gxgi3VMUN2KFI&Z{Ws`RJiR{74-p--U zp~j6JxwKpwIi+@(5&qdNETy)KcOF)wQmrEPYwRGWfz=SF7Y$eOc^{l;PBi@k_H}k@ zDC$|5#0)Ha_hvH}voNxkcH&^!Ej#>g*@MYUM|NZjUx#S09bhkB6WN_e8Z**-VE5Ki zC}oRiI5m`}p{Ak8c5vXWijvNV78md*5u-L8N_{U z^yV&IHv_l4?Eq(BF+WHD3|6&oj=t%`NmfU>*{C@sZqrB76G>l;829bcwxw;OTMB~& zK?1$T4w4Qr&qZ-(l$0{wl^qae(7X>O2@{N;)~1RVwL@g#4$;f%uYu+5yNUT)XL;6pqU z1>nMTQM|JhA_V6usl+M1uUHYj3{@!lgh$OkX?*fKcPj_I<8zNUMEiV;n0csN^3RTHS9HP zkEPH?U?YeCPzP`YFtawGZ#Cj_&^9B41c|NKR-DP@+gKa)arVg~X9Db6-yrMh)~|kX zPKu1a;&Ow%A;Y-#&dzp@;DEWG5vq~Cvwf$AHc=z3k^P8!@1q!WIBpA zm0_4+h&&Ce$?@R`*aG$s082E%-p_sy_`nExp!5{1=C^7csgeB2w7}Uj=8i0r4v*x1 zzj;fY4qFE-ZodbXP@Q0ZBIfgM^KO&2sCi|0W_U6z!*QWFz$tJ)c$eaDm2_Wor`<$i z-)l=@H@k?Yu8snGHHd@P0X|xWuL@mNrf(5)q|w#BDU`B}9`@UmTga^EIe%DVzQ4JYrqsMRA~c z#9CA%Z~yfEX;83ZwIg7VhzwCUR~_hTr;egR>!>;{!!1HB1jR(O&FsR1Y1e62eA}Hy zo-eG1?8B*|fmQA)(ps5*2GdY8M7%wN37S@Sm%%QBAXv`OP-oK=3B7Ja~%LM zQ5rG7=r;1A_>YW7DMhtdq6_JE{^zz0j17#mdo$N z=tY}XkpiOfxD3w;291<94qyzp;ZK-EwXs8$rbBf z2JV9kG2bH1;)M(;@JmNqVXyfbsp0No@0yN8wvG0A)$AY=Bh#>HU@dwA_GD>f4rBL? z9ro|1pUX7FrJrlZmdW%dgv5O7+asO^{KMY@V_yeWrJsg5WPzpWR%*Gx>Wo77qz4!U zoQhu4*wNRmqNaZ;`nu_eR{JpDY}Z31w?2b8NchItBS|j@jLf#7wxJgrJM3G~AqciO zLL+^=^+(Ha^Tv*9TJ`a~_?-BhK1-n!F@G)vAZ;#9^)^5%K#FP#-;m{E9t4vh1UU9O zVm{xv0KMDmw>{?XDf^WPFX}*D{LKFOv@YR7H#OCq@VZb1BA67H6qhvmtGW^w&6NDl zcdgaD@?<~q+%46-Qan>UZvcD>IotHBnipulMq+;PZ2%o&>7LTBoT8@Aw-WfCt|k%n z^f1#^m*D~OW)J1}jU6^E05ls~MGI+eF+*f{uB@c;33}jGr0c|HcBm;CRf@vDo>}gX zCxu6QWlVswdyM;xi*$%dDZcC?HIyCTh%Mr?p(ug%>3#zp@AaYULwy@NTtSMVouP|V zoyO21p5JqRTCm2vVgqtqaLl{{P;@NQGF&%QH}oXni`(d5k-;#@Zb1V3A^?%7doOC> z5cM=n0^Ex!+7ykPITDCSw))KA?325T+gVnZtQqTLII}vS-=f zvu~J_*j=Z=*G*s@Ipm@k0<3q76su(*)}q|(q}e;1AU7oepb5AtjU8d^MMJ{5r19!) zj|%nt!d!72MhkFRw22DOcDHml+ih9C=@*p^qpF^gD}c)KeK@<>yV);@&G*C}lLA9? z+&&_)>Q3Dq*NxCc%gEjQxzw zAB`GSjBQxCEg|oNl6i}NYy#ebyj=zSn}f_I!D=?#OOfW{*n+IZ7P-{6)Ot~x3+n+l zP;V2~@~zeCNp&RbC2YqiwMM85|T^aO6o(4H9(aD?QMHxOE zsyYg81h5wD(Lstj2x$k^W_%of1>0pQ+$7i}INR6} zpoStDl6=JW0((JpV~17?08NXQp@u@+s>$Kvo6v&s#9LcSYs2HPxi9wB*&PRavA%B( z@IUo?QrSsU>TXK#Vr9S5Y{D@Vc^R7l&>wOyNfqYcWN#L^Db9zp73{|Y#{RAS<(xC% z=U?N?4zxQcuyFi1{_gw{y@2pdtLXWkY2rjZS%JN>A&Bs0oH1{xjBiW_ALPFsPT0GMs6dsv)?Bt51KMoX<3GQ3!Kaunyd!j3 zlhN#&)6r`iJ4C5`LoFjMBUZp7qMY#7@vfDN{rj8G>%Oy3_Tfm?QDDo9p%!429I$2Y zjb-@0&8K!8=+<`I2X>F%d58xdMI2k@cwX|hEXMg!e9YPLj0;apfzVF7@Yg+)0P+AD zEW>w)?hZ9OGhemCw2d!rTb`7Z3A@v`NSgh&Z;NM|Z_a|^Dm}3Fk9a^_`??idr`J#6SI~K7b>`K1 zJ{$=#{|M~~8z$aV7Nn_8UKXt;Lgq;^uLVUT-xAO7J-;_8YYKTv_pAtYT%ktSt*(3F z;@aZsr6_S}Yw4J|2V$ok0Kl5;1!1STNT9AS6bu5l$0W2hr1kB<&6)}y&bT_NYAt|` znj8doS~QE)Y#8ypGgwnjvlP3XVz#D?QrURbW>C$UcYITWVC-Dw^uFRpj$cJOs(pXJR z38lu3VwzT{$=8U@%4CGPs>iV}>a;u*1cNW!sl)Jek$=h0Xz*q;tL6*&*;O72+iH>z zM*)axEfs~&keNqc^5I-&UuKIyD79|A?c2p=Bf4K?4d(R>LB2VBtSjURe7s&0Z1npY zPO&1VG%lRoH~>F@M_N5jt|@3;=zym>*UHvsG_{EJ$Ln8Q*by7|(f^bD$Moa`5N_0Y zVrZ*c07mDC+xC5l6rav`)H1%Q+5h?1aO*B3Ot3|p(B!z)Y9q;C;&?a4A=)7t#If4M zeB@ffP6J<9j8U{vbh;0xpY36)Y_SwVaad|Vn6&y4VfjbrP0sxRrpjB}XfqqE(WFBR z5Cz+d!vt91M75wTZEtAlFn0=emgVv-T4$fPj3#)U*s16mb@7ti1k9%$tt}1&ffGB6jp zj)FBAma*FmteZ&mL>u+If>X}6`&TwpE$-c~KGmX@uC0h|3EEd^fZ-hZ9~ zW&_9&$HuYc?B(W2P8S&>xD-O97;Y{HR2+F7dmU`tvk2(Y00+%bchPzR)W5v zOiiwpU3D=AWBuJu(N6MMcem68FQd_C%sE5K>Vfu)$HY48a=IsJ=#>8P;P?`TU zapMPbu(P+b*95Q-8)S@!Z9)RiY*}N+3fc6wWI*1hB@X+=a^W!y}2 zc~$q&MH9H=PG?{>zf}KH{nCfCnZ20}xNIrjf{5v@Ww?D~$0%)-wptD4z5!sfnpc)* zmhAcG__nA&9(@hFexN6$6j#^PxFkclfw&uZN$h42Jo&(CR#va9HUd~vT}kJ?5^kt2 zrSq!)AgQTae4Uy>f~k~c)yu?Z1>L}D$tPK<4S`^5)YbFcethp}o9DTMz$F2E>JsWA z2qWg7OgWjN3npM(&%5IDWZT4G3Mp6(1@^5NQbBmIuH!zhVG87q7gJCuBYIrpg>$L9?E*8=U3hWKr5$>s3lvESZBv1 z`EcC8?znN#0dC2(qXEe?)KLs$hOx!%k%7b`b{REBVCGMHWt20%GhdK_5n8j4(!!BcmE^0zz^za}@dNWn$gXD6&Sl3aGCk&=4?) z`H`srDUr3wvtGGJ zkt>U*E5o^9mL)?u)#bApUo`dDMR_|}P&JSQJUI|GTnLkef3eyynC1N`CS%_1t%@2h z6`P8EZz()0I4b~F10E-7(;;d z0LExzmZcgF3XfcR!`K5vOtu*8eFH?}CD2b-1~+LUCo-6_Z-zar^UhLSw12)b%X?>a zC-ly{7u%BbFu-eBpX6|P^n37Nn_bQO%ni%+bn;3pQsPkl^6wA&$bac&oPj|Txc1fn zfb)K|-=zU2e__O=)b*x}{q6hP{b3G{VD~OG{{n_NPcU_xHuq{989Y_sCuc;4AZ^ad z_J$pjt_mZ985c0;V!n&gH&gGgy!Kc%O*M_bp5@#QI@@*Ntw4_$&>@=d0RVH5f2;mm z^~2Ap{@DG$BS9zHAy{t8a4{bhbeZ1;GYuv#<}Uc_vLCDedGZC!&uSA(K_Bu7U7g_` z@k9qOPDE&gU_F?PF+}diw^|BEKxh6H*)Gsw8z1-X4slJ&vJ5v1H7mP?4$kPiz}*M> zMh&}$9Ru)pPsDx?{=H@R^2QE8)ZiflO{3tU0$_;fyE=Gv@PnnWoE<=G10j)}+R&B3 zoKZ8H*>OeA=kcxniy|X(bN#9~frG#7M0H(-3nLA9gK|~&@TW1w%2(>VDj#{JKLHa$ z0t3C)amBad-5@4vnQDP%S-@0QtblGxxF-9d8d#n?jhyNT0Wbo@5usWckr7XHwJ(H6 zK2fQ5^i7M3eJ+dG+_chHcnqTbJX8KYeB+F+ztZUm>&~pv()0_+6U_hBkIvm2Y_<$X zgNK(45c9#5ONvx?8q-t+pLYaah9R|4P|99r4(D{m0+xwu0idBg6%-c~=nO<{qQOCf z_YydaXs`odA3#u)rSFeK13#Dq)!0!$E1McAYdqbH@}}@ExUskeU^J#_!P`v@L_Ne&z$vsq z8Vg4BcJ_8w^uA6%#Ht%CJqNhKbi?RD!7-oSP!gbRcq6QDY2I z+2v8>?LJ*1(;pV&80{!_ZtOs&5Z3WQJZ&uw5FBiDbXDRXG5ugM;Hf2ayDahRmU(QN*gFlsgsI>HzK3u`GpP&{UzR(5R_|Ffrd;4yHpypr@hOC^i*L&A2ME zv4ARn68t1MBtV)Y$GWIMA2805eg)W~hPw&==ui#Nn}@&yL_#1I0$2g!p}%4wBean+ z04DiC{FF|v4$lQn`AYFh@l_vAHaq+D0BO}DWtAs>pwN+BD~tPvJF5A&4KWtW?U&mp z={ZBc0j&bQf)4TEI^&cybyN|Im@YlJ?*k$A$Z_O)UciQc&1$*8?0`;dL$B-Es_CzF zZaE~De#S{BncRN>^HJr+}H$pF)2MJ>OW}AOBLi+}vW~ zu$4G=#SNy(-wDNsqr&EE-iB{L?llLr^HN6m2AVz9ZuHyQbXKJ5skrSj+A`|p-B5TF z)Z*P104U~3gB!V9sd*h`ij2XpHeS%rK7g^nrv6mAws|w+p%XF^+S?DB#yt+~j_qC| zmC)eE3h}|;Kgqu-tAj&6h7afOyrPb3X5(VZZbce12e56o2)~VQoKh}-Rd?CNjV@K( zU&vo#p_DAy&-85A`8QTBCkeH()fo;gQt=IDEHu{wehFIMs2+}gI#eGk zdN-jcvj5T@akkrXigD?sdiC64#p^_|X!8E6<5R7xeN#v-J#^AqM0)x0Yg^O_!iCVY zHBtGC$MeVQ(2sUtgXG_ktqB?T2h3}9v>cUdQ$#;^e&k2vHlG68#FE6MxJz$&OV zuS6;_bidgYQnu%26S_F$X48#D>pY7hE3kImUmNun8yIPy=+UHYMPFP$7KFUho%znW zwan~Pdhk!>lUi1E%8%u5FJ=1Ws7AVVMqf^k-sJe(?(ttvjBQ~&yq_EoZ+!@UC~i-D zll8LwT1?hUurZOki+sT0e8Dw^-rZ&qgpppuX~K?TO}lC`kj1hI|Z@S=I@cJJkMhenHQFWWEG`G94PpU_9`N=8*o3B&n<^vi!h(=H|VW)6b2t3pY9Lz$z^GU?g?i)x?g{cA=zdDi>uO}A&y>>44QJ+fuD|c2vn@qRY6icDQUq-Sh9ZLY_3tuI#QkW~)D^Vd39heSGGEZEkI8K{78a;x zs50KWs8WCDe$jw`SF8_jv;~7N8C$|s9YYr8JWqh19$YpUlV#Aqp zZR)bI*ek)!3hkf)3pYff&;BuN4cX0QtQ&UBuB~V`fShTuh@bwFG3(sAc?{U`w^sDQ zwM$kq2db9&Q#n{N3z-M#j&fkxTBp)sKbGH`dnXcb!QPm=#mjc$u@z8XR7z&PU8?HBXDh;6i!8qTL@TSiloUN(zarc`kAC>~@zOtuR~#Z& zJzeuboZDY_zg?<@S*e)qZ>SWRX;ij_mfdgqU66dGhJ4db^_<##!kVtd@eN=H^H0=U z$Wvh3PU~hZAhyO=v4IiKCH*h-p<=t~A!OB?Yhu?fnFkXWhnR?2C`@gL={@VkaCpY^ zD2j06y(|sL?VT^_uE~oy(N}(u_s@xRTw&t(BEOM+x~rOUY>fsnpFW0CA4E9OS{r5tfNEh`s`)iwcF*c9A^vwi}!i!0_ zD$-Zp^1y;~{{6@L%5Qlr6!JWpOh-z19_O;Oycmb+ITK4_A9m6Is@S=+=)Up~KPUfR zbo(cf-ce5f_j8}x@!-O!e)z_yux(*o~3Fm zOn3O}bQh&G;EAEZzpLwa74E&|ui9JwxwaE|Sco2q^nT)dba|uhw+NGli zI^IkaoAOF{P1y8^WBR8Mx?9J}Pgl6K2GGuRXEMG>F9|%#l5U8DhBFzd5ejfPO3Gxc zOjW0@vr~0V1Dulr7wc+P;7PzI!-MehoCbiwqxZb<)urqL|p%>bdNbyoGVDK zTW!x>gQ_*Sk6lyp|L{82_r|HSq7L!O_^I{ujnahJV&2WWjES0?M-i&W5GGCa-aIfAv>nGOpbH$Lpyg3jVac#{GT3(SW-6qX9z!qvcPnnaZc- z@9#36wu5qt9e5|8R4CW;f|Mu#iJkc7^ z@ctjKql6&>D69O_PI1XZN#zkxQ1Q?|%B+FP?Ah_Pq^SqkVLb82*wUxfZ+Di3(pepe7>HTC$w--r=mg>D%3~Ku*{NGh}|G3)Rf7Qg2(&en5#{SVNPpQ*D z@E(uge5kmAO^_7RkQDEJ10N&2pemVIvW#OT7Y`v!j%EM$wU%K^rJc$}gPNaT663$r z`TF5Mp>+SG^qV=4|3&ToNZo%@>_4G+8%5KSw3_#CRnNv%{ZotnCzSUXedck{!O85O z`}|)N^>5!sE6QTu1V-b)(IG%|wXbd3jBJu5HYFE-T%tNt`&#$E_=P=*Pys3Sff@gx zy?>kM-zgDr;9uPLUliCcy&ch8e-p57PJO&bz|c6v!u?WG#Ib0=(*f@wCho0(NQsAN z#-^8CydgIA2-f+F{4&3aqGS#_NWOCQKeC1fo7w(i z@b}8r@1g6U@8E4s-(f@o>!*KaW;*E1Ad84&Cqee0OTB}RwM%D$pyIvkATpl#@vGv+ zUZ;R0*-c-E1_z_BqV;4o914~O$^UIU`d54S|M{Spz+e78fcC#N zM*`pWUyR^CWfQ$jWxwa8HR`dNL3wjmZmP#(CgzlIl9EbwzS%~p-E1pW^LXyc*R@~s zsaYxIKT2B0w~NVUx(^MBk#pb4B0ZZ=v!1M6(=5gQO{Zs+L0&GN8;}i&vS*PYfFi)@8XX z`?g(I%IgjXrLVWNm6qVo4lLpqqSq+2AN#&$d6ossaI<0^g~wChGJdI7!U&ETPcY(T zPKFtoO^k%?k<9_!83)F;B#9cv^A=ev^wV&NPv3a$~xGt+<;}fev6Gju# z3w_JRt*J+E%+FRYDD)113z5iYKl9@l{i5-+4o0!1^Feo`G;tIvG658BmAsm_eDTCG z@Mj0jZ$G}sRao1xNZDLik1OAfMCCJj!*6-lG8qUmi&V{p4V{!z76%Cg^CI657af>= zf14SP_^M*x4>RLY;GxX655Q+f)EmZN#0GX7lHJAd4&TWt~zBllbU0JNx)L<3C~-Qu)*gr7i$e_<>D zW01UfH%rmDA^M4vIawXq{QyBB-VlM^c&23Z$+b)swCX$Qrtky3Xv?CVb@7y>o1zOG zSV$WAW`sLdeGMPpX=QaWs7P57{YCzh!=8w4X*_lgYRnQ)aOeUbxfJa2fjjPH*dbeqmH$!`K@T`qq3Cs1!n^4mD%<9 zc=o%#2ebHf`XjjLew|&?^aOsQNp?m8zgQXgEMGab>JQW7FZx;U=g(r1Qps*+)nm|B zt?)sLi|I7-vQc@tgHcnGod3y{Nq*}4hh04jJ7mmH>#>TNiU9>4 zVpbLVhGXWXUwF>ZtkR@I1KcRI?|UiXYd0jLMsaWdYQp08(v*k;SQf}E<`}cD1jzZZ zK4HEB`^=25(r2acv^zQSg%dMd-x*sK1DWYFNAR@I_|@6-w9U4$w%&!_K*O3fidK*2 zOK6gZor1C`fhi_WG@r&@TYqx|m#a=#Sqd_(De6g_pS5w2iK~;AQ7c@AfR4{J2^wUO z_IaMy6wBdVU9`sPFGp0zyePd+w)(#w^ZV)Gw&v%Ex&4MeFFl8d2p7 zVUAxTE@PWt_c6CrDOv$^1knDx7#}7^`l= zNB3GGG}fL>n@ZFHExFL3v(%Dl3)B(qUsR6;*{1vc2_A&G5b+Uv>nc#A$f4&t=o@+2 z$rWIn$b6~ZGcrpt&q?kF-?m=8(c_E5y4u6}`MzcNbZK$3bU3hE{OTuA8?09)F`zq^ z<|f;BS`D9%yBRTqb=?LhKk)skWL$f5JZFh=&_(UdxBp^QxdZ&Mx;sUe#DkVqP^AsPxM@GyluXOXuN+|ZPmenuA>4t@%Vo)*b z!$N#xd?l5_V6H0%psk^e)5aO-tSZ1@G|nHy9K`r&oZpAphw;-m?}~B7pfD&_gWh1T zH`=ilK6Sj8saIEE|7v;ta-4Bkh;vwoag1?HK-f&XFqd1K85dc|-_L5(tE;ttrCP6A z|1A1sE!?ZctF0lnLv){iR)d*9(ZXS3>}2pW$3;05P5Oeh3g3-IVh-sI#xdjYm+Tj} zOD+rJI4Yg7T>x2evE8xVnvdY%U)1%m8|A-Ce8z?wx$)h}mMZXl$W;6<@{N+tv0>lI z`S};p&UnA(dvVFuDxyMBAsnMI9iV}@jQ>`?D{N+;FpXoJ9p{!$+KKGZ!``!hg{()) zVROEdc%d=ryoSMc_;zHY9@a>HK;j|1e0&Ze%RwQt{l@RbsdTDzGOSfdZb%aTvi;&t z$u(gDN2}A~5&8i2t=_gwL?(Wd{IJAtY?#i?=#I~fBi~2wpmynDSId8s^azW&eVK9b zpLn&s)6Es8we5OX@I$PqFUcahM^5tUEw2%A9(<2jnyan2pi9dIiZ zZ!~nZVSO zU8$#NP2uZW$}(CTEVAR!`P7|+9=&Z%dNLikjpTUP3{Tj{#bm~@9#Z!a=z6kB`$c_; zqfo0A{aiY$A@&NJ*(%v8i5(lB70wDpT==lkvQZg#Pbw{a&xb{zFSVTUqRVTikFzi1+H7d{yqJ}W#cQ)Y(__-Bf$t+ z9BMbANa>^D?SghurYVeZAWI7gS~x#8tS(d+QrjAo9m;&nLx9aHn94p8c_^7M|0(TF z!wvgayDToCv+TFpsALoX*r~YR2iT&r)SGQp+^tl=KD)o zJ4~RTKF(3HFg83U922eqNFN(Mwjen%AV1UA$86H8i?e@aR&Q3HYyYa=KFV2=B-9ui z&gD3EI^K%|hfc@rxJX+S{!Z34=KH$4L&;t(wfEv83;26jpo3mxUSr;+xPP41#xIig z1i!G0c8jr-FoihI5JxKbSkI9fimg6TkvL>bq(mV!5Kar1bDTITU7GhrY6EeTG4(B= zTX)BL$cO8>Dsvz6gs9ZI1Nbwk88l57!DjL2ecrv@6Opg%Ct~i45BbENUbMf0-y+^C zvD)Wt#77~C_#kj;ask|hpUw6YjBs&WIj6bX?Y^jhlnG9N9^U2lh_nl7NTaihxD7k!cUVQ^;H_{PYJiZ}1OXexD7w!NhAuXUY z-HZbCZE(9PSF6KfKalPn==B-kI&4U4hSzDb7UJV{bJkdf0N-K(2|p^NbC%Ruf%{HA z@x1;wndd$#5xW`(sYfoe1O-tK5N;^;gKW`-)SYk?;jTglr-p;t1YML| zNZmomRrrH1tOtN0pjzd3upUvNmbxH}JoNx2o=Me0C4BHROaF*u|yq#H=yAQ>0ZpyYKlI-;siRrzMRIcg64Uk>{Suph;0 z+z+^OpxmO)qAse&fcEDA2f405P0|XoXFOm$WE=!}=t+VkgV2crz#B!30)h+4ZK-{) z30DYr3$F>^fdbGw(Fc^~Kn7MfwLl3~YoQR%p>tfgbYL@2hLTq=NbnoT_my`*5-AOo ztttr%P--H@5V#0B^?Np1q>V(J_akEh1;>QcQ#)2@NJtjN`-Exn4llce~5qZBVzshXXPjFFKDO?a< z6zX%QxccCBtZ|G=jI-pR@E~+~7V`!r4CDnkCyNpYeb~dgOL4^6#bg}zuFM`vE?tl; z{0jUE4W1^0{YM;5_<2N$cP3(BS!Vm_;U zl5W zvSjO+n&NlR?cd8!Nru7g)H{e*e{93-J}I92w5kO6`A-5RwyqvI{3ii1*vE7Wd5&~L z^fHsdJ7L;)N>zm?4$_reI{f)hC-Tr`{GKNv&-3~!3rI(Q(<>RTn&K{ZxfVAst6VP6 zfi9tfM`!)9l#B%IlC%)8ukV8ey(ZdCpiWtx6}XuU8hw$?Ijg1mAjUNxi&Yo=8ZmCp^oQ z%TF{?KVSIsY^v12cKDYP#pA1#08omg;5{c6lwVBvtuWGLwZ<{!AJGy@;hTmD($l>x z>K|K=%a7dUIsw6Y&_}P~w?nrS+s=FH^9+WL{_IHyrK6VL;&$iOAb-P#78F^#YDsZ=# zAM=pgXaQ>wiZl66R2VHl4}m{>*@+*O!`O?h>&C`<3t*%ti;It=7i6CgA>uk0^D{U| zqibC81lSHw|+Z1?-z}QSr7VDbbA|3oy-&t~~fMNhxOuACgPZ~izpoUqvXv6(#11KsmJUpNc2gcBT?dG6@8fI)rQT+kz zkp@h;q9Cq+oITQvd7&s`P8JAe$L&rMj=C*e5J%1X^s*v;l)lAcrHQ?S@L#1JTNKjc z5*$>KD##=}0TQbrxd;gfyf}jw#;1aMgX7oXc0nnPZjX@nmQs#zlZ}BY-m)!{RnW~^ zz>9G^y!B&qAIn#M!TE(Iqj^NLN>R7Ie|&sI%r8?=8~Xz|bIYcmD;mcpSBb>tMaPwk z7blO1#8$>0${6c~2D{G+qwx7=J0CcO(aa5yiwDXWtZ}{`Mm~~gzi0d0$xq!XQ2Vm{ zoF)CB%(lq>8~F1;tU0tpmkLyU%0g?o3{>A3b#f=wa+6+(*rK-6;vg^qMC-KB1*mdQ zvpXH{59A!z%so4z{wd_v6^5P8pChYJgdK=uxH}9r*}Y_Een;Ym-%Ct>++wvE!3rkm zS{%9Tdk(7@#M@GgMq&CSOkZ0Q@6Lq-$%SrNfmlu3Kie=SZY;Y^dXsaX7b<4A*lZnZ z8fVN`&f4|Z?+I|3W~G+SIsmb{gLfmhLSjXn?AC-Vlj7wn$%j;-7Vk!yLMc%d+<2&B zk>uaxuYoGy;UpbRCPzPK8j(m*ml82gTdjUakY2)bp)Y&QJYA5+GKU8*D0mC z$@y;O#^cI`vRUtb>n{&8F~^fApiPd?85VciP`>w-&R~BZkyaLwJVDo;4K(8x-32mi z8z>bffG%s37aS=u1f5xj(R&wv7En$yq4q-_si6UZKmXhb6BmcWGT$xKX@G8n*ZMTK z9W=ITUI0T2SSKc`)QNNz^!hLT3)oc}=YvP|8862RK^AbQp**|B282SmG1gmMrSIkJ zQ|FI!=YcJq4D8ed)W`hP)M(((=ms_v|I8Ix2S{YZhu4*Cx*AyjM~Sci5V#Gq;wSkl zKz)fA@EmaW-}DAsnSA-;0jz3L{T^jv6I$uYDuixKueyj5fCFWtn0xsA^68qpFRoH58p= zCNG~W4uUhQ@%dGdGT3WJg%G{oBhQ%N;(;=4&WmvrUr^6u@REW^=n`4nys&)`c^5Zx z4{n|7T>(^@LsIhHA(gPV;hceV$dp?)$8-xG{n$_hPjiJ^QFII?^!^j3pu zw#6UxCf(N!2<15wUGnVr)D4R=vsX>A2iUL_&1xm8rYYfd!>U(=Z*jhdw=OQ9R$eNd z-3Vk)!|h_-0hE9(OXez}?n#TI7m5=Y z9aJ}<44yeB^n*G;Uu=dV0J7D2W`Xi9lwZAws|$K8f{KYt)YM^E?Lr_!>JyE1nyvOC zlp(o^&N1=6IatKV30=O>sQG{x+rkQxecBgaN?drN)>XhZ zq8$=DNJ0@V6JY{%QA%>h_y$N((f5)nD20W)N!bXc)E01Dwor0>kK0gX`z4N08i_(w zctd(U;Xfc`L3&Npa?uc3ktE)dmrxI<=J}7<@jt`dNK~hurdW+}*dY=e@vbR>Nwa#4 zV98W;Z&nm}-fB@pp z!`cg|5bwvRX?36>)~vtg!XX1$D=2ULgm$1YPN03hlbf|^e$iY0OnKpN@^&D9Z`Ia& z_(-54&nxF3VKbDGdHa22E|ig0K&LZcGaT+#r!7TsAgMt#Z?mUAO14a|kT{-rfuMa)Sd4!onFkH@EWSGde*}`ArMHu614)n3C}5S&{&tc*SNjri#3V)uDGC1s zoJ;7kpCSs;&=452E4Ir5GGV6&^;~yg4>5qJ6758XTMrBT38kk2o@fdGreN|1$!ehq*S(AUK+{LoQwf)r=A%*Y{qX(NbiA3| zK@uSZA$>RIId2GtCw5{^4}sadUDPbRwb#6E)8fh2hN^pU7;6>Qc@0XVOrw}(SvJkc z^@(*~)IO+EFnK;~#z`2<5#5X97qFbEEIrvb@@0}ZA&BNX;SZ2O8U{N+EPqw;o%~SP zjIXenlbjt#x{ureKdXUHRcw%Nk{l5hwKWt>&L>t%t?rTK+F>*0W5eSdMkmQmh5Dxk zK1H!kZWuO07iMtDnQyCV$M;+X7T3@`x@Q#v;RR8|C=Mf ztEweE3uc>cFn9g&P6VXu|AwB~x*UB`!49Ur=IT>RMOE*fjf z(aFwMdoI9Nd7Z_cbpLe!)Bbj$<=+z9WP2~|aKLq3>$nD9bx{V_j&s}bp&7@FV-JT3 z9QPd`T5+s61UODQMw!Fc_ZdmgdewSWjie_`E^Ntcf+Hg?v#Vd&I8+-!9TaB9WoE|t zHo=h*=bIkq+v?jY1o!(j#n0prlOt~MWllB`HCwznDLN@?s7&u>n)GEgR9VU`<#5T8 zXUUygBfl2g&709ouO^?&IXj@`4)n(e|G-{>eLp%qM{*5wxRt4YH&7LMg zucv~$K%WPA^mEm@{|`5PiENU5k~}yw4nCvT64U6*Y3CisU65#%l3xX0yKAI_Cfq;i z-@_MkwaUGrDsFJp@36Xe8+WX}p(-siF1{(giM;|xI%L8Hq3H=h;s|2=={3t$XVznN>o>yl$2%&X$SA&J9(OEsC4s zAQLMOya!KcK{Z9K5RNKVu5N~rO*WzbuKx^O10y@Wp~|!se;bxBz%zGB4^py0U|`Fc zt*jL|=7SFP&2Hu*&1=?595KwqY8`$ZKFov;PWYv$4?=;FEf=(sR^WIWz$tgpaXg4J zyhPS7uzQtRMuMGqT zop&le2kix?oH&=6%lMhW($7IBA%8>SRc8aV7yJ}~AKg@*GQ2O^1Max@MbqT0%i!A( z)Pob_W^v_a!lR|unFmKRLz5qStYH1UjC6)&EhAmv-Sk{mU*Fd%^OCn>S-(Y2ARR&A zS~W*HROu?RtVCujFTqkUcibMt0;$9*V-cA8Fdy)n{S2P`!leMKbHnl9eBy9RFl zo8BJEm5%otgM3*M^szwh+Z=KmTxw>Vg`9|tw7UML zkk)?efqzC?TUo~xcCb39IGQFhjgG_0tR??Uz5?aetIntv22_NNAKFabBuW)6<=6KK zn=_lsJ)s2(GNv*+@4b7uU{Kqv|X(r)MIvtX&udzINt3$27ABXmJaAyofA^3>TiYCC!sM&64v^9 z-Ua$J+Dufk%G&&Zy4Nh0R(_FuU5p7`h-Ji~5l9wR@e=5!XY$Bq1tv6CSP)QS6%xSG zXd$2e=Zv)O5cUi`tZroT@qOrd;w7je9wrlR&~Li$k*|>60PU{v=u7&)X>5=eAUNVi z{6@x4Q0>GL091=D0obaVRj@eN!~%uYC{hbdl~%({hywY~(KQ9$d|Z_yn{ zh{{G)bjaVnW~jD*3=#dv^I+IQon%ZZVTi9P5`?Wk0s^dU1{;(H^}rgTOo54J5~5X^ z0`Y`7{CW{M_gQ<@f%i0SAo;VvvEd3#Gd4m&;w{E6tRKo)@hpKXrH<9g+W<7AsjOvQ zSk=ZQ0LXA49boy;RxWM|21=;*G&7n9cHz9?z%o$34nG<7lB5F%v~nNXp9FzS>H1JOu~BPy(&mG9V6`mtRs3sbqo(> z@pSMr6NTumz4|GNcxn(l^=|fVG4{PT^5H?0=v>)HX=%xXpH`bR;iuJ=a#-Lw&35UY z@Y7}=F#2f+yj1HBVSZX#26y!`aL<mukO^=XBY9xj~1%gNo70|cve}6CS7)Nu`QO zaK$ATDW<`75%;hdyw?gQ72LAdcoyPP4iDX}rJLYl4LZ9q)Cveh^OxblCE@bqa;hhM zfzx}w!P4^?U^EJV`_XckmM;Uj=*M7?0QYSMI(&O!&5M~gOg(`>13D9N#j^77?mTNO z>v*qBjZumhXVNLV!B=DbCRAf$G0LFIPYcO216Ku68A(wnSQ zGf26yQ>6zwlB^G}#h*7mC{x*jOlOl`WfN8aVI%9ETLd0ca3PgjZIQE(70(L4;VQs9 zFy6#iD~z(j-a*axKxtiaiPUqZ;?Lk)1pneJR}y?R^I?AOoecKal?$~yK?5(^N!s}V*U|ly=1!5P7Kae;M3fH9i#l- z(cu-DtnvFvSLK%M#8egHiiJ+0EX!fTrxhaDT&ed9r3s)~4tov=7C`~tc$};FR2=KUNV5AtG`N;~ z-N5O3092jjQ6z0UIvi&2KRP8=G!-Uj3dh=~{CfRv#(eOk;c{E>VAoio z%IQ|+6K+%wSm*}^sHa=yp4b2)z5Nzx1s?fst26bXz@yUi%VrWblJr#?RoW`T?WGD* zhwjQGxdWI?J44P4^foXgiL>xzV1`KZX8G)?dIl>pY@L0I5}UQi~J9T)u(!_gA!9!^}p1+{0aeo-?I1kW0=Fjs)7rM@T$)%^e*Efy4xc*FP* zxOCT$tEz-u)JCr`mzj_f=vh2+0#ewn&ueVl1x;%SvdG3U( zwA_i~jkQlJzk$Ds^_4h7Wu#x=n?~P{r9_%HF)^O?N7f=mZX?4SBSmi%} zOuo8wVIC z1G)GzpYeNKZdc4d+CmAFA*KF_9ey%+4-e_fG)s>TSCnP*V=_%A;X=^NW2$g4iQ=Ns z>-nWpDyR%cbYIW3u0`JmSk_t%CcSPEg zzJru!w}sTTtH+o7l0)zD&xp#-oOqYXp18Q6QMKfT+XwR7Ue zleHDQx$L@`WlTzO-Nf?6o}{>Xu-KYNneTIP{DY&zcu7y`2j;J&+m8D>d~^yGPlcYX zY}9!Q4YX@SN1!>XhV zw)D{tybF3ZQd?)ZLM}ryfAGD3^yoel(LIIlNq32P_;Ri3-ku;8f4`q;a@3&U{xteF z%27w<@yY`cNZ~Rvce3Et_$Ao;GB+(ftsH$n)3@1TPhI8TA)ul@z_-ig{i7d97r^@l zFp!nSgY4&>d6J%G{PO*qQ>{;j*(uMtq`k{;$!}efl7Gd!1od56cE&MkiLzj3%6s>K ziqhyE+3q8DGCO(Oi#C3F8R~0Omg@MhEIO=ae{a&$vgGKgkX|Yam;0uKWONjvrL%km z7JI~%guvpF?E%6km1aO)j4DhP{vw=j-l<0t!w#Ap*)RIjrYkDDFf7!cDcwe03p;SX z>~V?ALl0LW?@R?D#bx< z;C9zm2od{Rcyw*2W30tn=Gj3HER;uL@QyU^C zXEJhKmEGqriSN|M&5FI^IDS<5Y*tEAhly}rLoBEG5jt41j16^RnCwH89Co ziLOG<_N6p^BzQ*G5HC|RG@l6>PJx0|I93qdEU;K( zAK=_nNrV<`<-x7E^MV!lgIdA90Y^y>g)a!&Y|r{fC@!5A~-m2|y!hJ$OZ~Q15EK6EYkF*{g7*Ao_GrXp4Z@ zQcVyj9Q!6|E&dnoQ{7=9V|rku15R;(YaXbg?Kf2}iN4=GsC{8KM(aKN(M|$=eLWyH zZ2Zxut<+BA>nYDoO2+$Tu$THrQ(Ip17)j8X$*(HEB7S-$)aAEM(P6qJh#^y6-b|h^ z-cQdT0d>LMTm z?7wVL%ohjInS;E{B6WJ4!hy$v3@-|4PpGS*39ZbuMKMPlqW^u6$0{;SkHgzDu0V#y zLdyU;9x}wsm`(T}i3bT!$A}G`Zu}}{I>7GmN8ZZvTSigvfc$GeLFz=hvpx^grJ#p6TtY}b(4h#mq5}=94}PA5-f9aA+1{H z2pO!KVV&q_db4i2(6BPF7M6`{8A%|gw}qA=`o9B>Hn0_(eV$~857CkW2h1fs4t()` z(Aeo^fg@?FF%|;mH_J(D}8bhuJ{fx7l9&Q|O`$CcHg}C-pYy zq>u5EX<-JpL=-lB-__(M)=5%M4+cx7K?|_e{3_vsu1FJHX7H-<4>7SiOt@r&5RS)b z7P)kkj?wxkTJFd!4Mk}lYPeaLWkKh{iq#>L>|bz^EBRN2KO2d z2b^F9tLjQ9VNWMLOpm>P(P6LH@$DqG_M={8RzxSGw7PLYdSf>R*WxExi^tbh&dP1HHiO-lnRUQm}q{gYMI zDor1mKch>3I?->RiM~Re`!+=R^VqCMHYi(~3jWKFFZ%KNBB=s;PgTE2J zm$-ujtZ%WeF<|FA_0b@yrW4PvBBmRj!*JN%sSo91io{frWPnK9z$inBHW9ZRqb_TH zf(8nnMwDup(13Rf!$PKET|XJce#DKya0YPimx zX9&`l4~n03CP{j>NHS-pjMnBTx~Z;EK1s!pGg1sT;!v%_;xg*np63>oKIq8A48e-I ztTK_Cey_jkdp6n?{?zlZ$?{ZhAz?>D)>lRHjWSzY;)z^;qSd@@SQneEdN=UJqfXZHtrI=yT;Y4t;FZO?L#(4r`O zDLo{{FJ{?sOXce_-on8C^tk@aj^NGhczoH^hH?qC!Q@Wm*gv`-JxNGn6;0(=B{i7a zEbM2R3Tq^z(1#8;$?oKzMKzU0gXHI(3ne|bC0k$|)y9X}0?={VyUeEY9EXME5K+UJ zL(l-W?O(#5NS~ry2OL5D46S+c=8=Zwe)sIyI3iDOi-GRxTh;Btv2&>wkQ zu}QIEXg@b$P@G;=kscT6AkG4FI9NEiPm~Tictmwyg~b>|7NHfk5vG*kY)S0Oh5bZR zA*aFkg2zF$(2V2WN=~RDJ8|%UiKv!}H&R%^)>r`tusoTgSO(nFMh_L3-h>^&KjQa_TF3CuJ4KS7IKJrtV;99=!M^}CaX^2I@jPy=TpMbr zN_2%c+e6LU2`&CgDZ(nqfwj$3)H|B*%M3?rtb$AkuXP8FB*rFc0w4qPhWa{w4WUIh zQwRpRd?l`91-oh{4SzR?{)3?OG7T>e6gwo(QQNSCw9Ki(-lv`<%J7J!hkj!CYssIk z&F{1=o;TF!=f~hVjYAyEIRMGlGrxJdfEwVw5@#4 z2{oJ4;0bCbX3@Vyw|_h&nG|Y}C%U#;P*XKNMjj%rMKhougIff*O@Cws5SqqV)t!`v zDrp9*-YCU?J3#KE+4^r%m@INC5&ca!lv_>-+$dv*-}r z7HAa0(hGTk_yB<9^5TkMX*)7g%r}ZjVZ+OUjyMV{F<7*gI8duNFhG;^X!(kXjxfDq z3a>2&9u|RJ`(pX{LR4)#Hit6&Ok!$l9Pr;u)G(W5{0VzKKK~denHOq!mPmVLp}V39 zoY1yo%6J%25Zv_#;Sb%Pn%**lO^p=&x1pnwIK|>8N zEm^5^2{NI-ws1LTVilI$8N5`#7%5S0?F(*j6Y6tkX|FntM=PZhV|I$f6C)v6KbN*j zM( zc)b<6?4wZ98)~RXw1nkzv5sbJL3>i;3|(2THFE#es_;LM_wtfbreNTVXf_JvkpqQ^DU^WHJJ@i)>b!l8D6UVG~)i<>;RLYn7R;D?U9NsFR7z6NQL_7M8CZz{s+0|jYEF)9*dq1by z&k|2J&rbAMH}9h|VKn{+Hpqa%#+$7`x-)%7QS%&cuQsllx)* znKnL#=+1T^(#w{UJL5E1tNOQQ_Ahg2eg?hBVs8> zDN4yi`swItkS=WXZOOb)Zc7f(X4;lrc6?YG9b)XAf9pN~YaK=wodfoKA#%{Z&$2-% z)JG(ucVTV@6U@OSKZxCSW|Y5wL@!p%J4zED^lTsPS<Zv+x-0Xvo6o%oYq>cywsS0{*AaKs#nC^~ z;J&a{*|WPeS^fk2{b+RWOOK*PeB$E!u}VVLyYT9V_Z#E-e=_UXG0^18`%v0?KWiRy zc6u6b<#_%smK#x%*J0xwo=goFS5_Wwy~`P*l~ej?=F;~L1eel|v?U)u26|-87PM+w z?v9L(QE7)OO6?``Xz&~FDB7db5Cv) zA+2r=v}`n-h^cHZ+`soX~NXS3JRwsh!TRKs{{aJ4cnTwgXVxLW(=PTKm&bW4S%r?_jx#jPz9ZlB~Fs4d&2 z>>B8dSXVn!G2Q! z;_f#1-=ahG9h?eepuzXBTF*5Gc+ zE1$5F07my)aH-{odt>VWUF=TDOQY1!tpj|qS3VuTWbMGc@=NlI&H9pW1MK5e*csyPzawz;zGVn5JB%9Yp^KlW- zXld24`lplX_xYZ<^T4I7`=L0kx-53=!TTbbn6WQ9R88hCdl@@aJh#R}#+h3qA|6|J z@0m)v^LfZJ(&M@9*LQc|15sjE;oSd%OL6zjaZMl1TcZ_5U{JAT$rAdsPHL?2Y`}zBPEykYa zbw(%^e$$0R$`j$C;?vzbYa+7iObmsjewNCmdB+&P&xL?p2!HCq`mUW+NX4H&ztGZc5-68h=GwR8lP`||P zclX0>B6cF)_tqwn+N(oK4{E&cJ)7f=PVZ+8jd_uQPXMm%=<`USjXP6n$C#nCY?VB%bQ0t z_f~(x{mJRfH=89m9 z?A3=seSJdw`gfQ5kRSke`-tpUp9*gr`kI~D?d$Jtq4e?hE;3?C`W%m7e?rTw>!O)J z%JKH)|L>~)OS4f)M#QVsQGqBP%;*k4GLsItHaHov+`=10hI=J1{{l5R9fQ48JN^}O z6Y$%X`qX~Hz;t2&5@(*L5ku`0l-hrKF;n>d6O+m+ z`Y%HuLE!(sBue}f2F~gO`(}*S%JoK}{1=h;%)|hnc`^Kdga2nH4gG!!@c7e zCg?s48uf811|5o}?D{`|MExtutbMF_EI=3>Tu+L zw0a+FHT*Xt^y$uuf3T+KZ!tp1o(oT$fJJR&13oKagoFK`sH=ay;S(mM3l1oJ{|Xlx zvLCDOzY&Rb0tmM&*czsVw0aCD)?T~$0M_XL6gltzGZyQBA*X-yld>y%ha=gMo3vcT zjrl=~eY?s}4gCG=uU(OKvv0h}_8U7-(0{>zCj7NK`k_SQHY1`gwOy z3Biq#*~*3nEmv$Sy*g)S>?_vfeBzXy46}Rs&UJ&b})8^wM+Ae`S$r!KM4M418mpFcZf^c?RGHAUTC^Nv63f9 zbK)WZy6a}-37SlJa|Z328y|p42fCV>Gz! zfZr73+1YrG#Lm@N`~4J59&KNKV%qN&kdgrj^pNI7S?Rg@(4J1PbXu4aFzk;G0QM@{ z^`wYszIqHmNdKCc%Gz;t8a=f@yCfqA?mM$4$l7m7gtWt+|Ax0ug!sHE|L|7zDd;tTIY)sZaPm zBRdzvbs&*^*Z)kme-T82_~Zw{JMNCZc1D8Yj7SwWf8 z%`s{S4%m~@IiFhYSbz!T_C$+ydDD!YoO-Xf7RVbs`@iYuf678Pw1Z)$Ei=JgL(y+`(LurChGOmBok0k6# z*q;+h(H?#l^(nr8$fyiH#UK9JW#gbZJ7Xuvg(2Y6Xa7MkH-78?Kcvi+dV_fWcTzEX zl!TPL2zd1`qtxfWr-LF4fkPw3WsISi6N~QGYL3hAFZohuP$~^t%FWJqiXQ?K^wkU8 zBQ2jjY9biK4Er58mz(?+KR5r<=AZh%(gp7cf6}W!=e4UxztUIy5`M1oK?lCbm77|{ z5Zp0|>U=8hjUKl9Ua#F0{-n#5S4)xgFV;n7efWVF&)(E;OVfd_y56D-B?psdCQ0zhOia393`xIP(jvPBTtc-W;!bj70o|WEHNimJYU$_PrY>Ek zk8}$^LB8Y4l~fz7?j{ep(nzE!y^P%Li$vuqJN>MC8TH$9qwbFe>{j%KFm#II597*N zuN(t)Z=%SnEL|K#-i8o#oWWB5!|Yz?T*iHS2NAT@&9b~}GOjcyoFiIu8@pL+?s|-L zcWfS|aVm-R+p^{=Vh($RGTEhS>E1jq)eh6E(*$wsF2ID%^Lk?*(r^~I(`rjrw=K?| z*1ko78;+bjPH|~FTa*%Wzt|oyVecltz72S(3T=s9TXSRwI?#`x>6ss7Z$5zgNUx9?$RvwAMcM_k4$exqIm?R_Ju zl#f^-vD>MMYs1eGs*B{DC3+JxJbvp$4=P+nM!ss>Dm=l{#BQZF{1UF}4kv20+o(&| zhMzbx3Jq=_88MmQvEv*w?oRU1)Y4jU)w|w#psSwZ4l(~-@4~!k3gO0lF0Z5Q z?;;MPM!c@K_t(7M!00=zAy0fqL|3{c1sIEwQ_;xHzX5xbYRm+&q-a}_K(C*R_uXze zd`eHQVa;HuFEHKnOrk_j9rn=}D^Mn%WR$S}?7htP|DuhJvOJV!*U!z)%(#$FT8a{J` zKBnG1ZX4XTcqplao=CLT)4ydz6gX9jhd$ip@`9hSPUd^qh+=v#c3Lsq;)z6W=*EtA zcVID+Hcp9ZTYNl|y3r+GpZy)<4BM%C{HZ|BnX6C!o}p(u*+gs;>=4P{3WPh{!dg+u zgudh`?rXcm7%J=zH|b7ju@OUsb$T3;r%+(1uoFy1f=V&knmM_OeudS@vCrGist0fG z5PQB0#N~Op#8>{rAytb@-}U~O*V`L($5zu@JtC431CCX)^&MKO-g)SD=e|9eMb*lN zEI`uk63^%hjD}Ihmoh9F{yNTD!ooWklL5da??tWIj@&D?AEh^dNn;m#*hCx^-iWf& zS#Bb5?>enJLg~B#{fN2~?4gez4qC}+Tl7N<@!mT=>FTDB$2L#ss`e7~p4Wt~#->ug z-Tp~e_kBFJZ9-SwQkbl~30>{(>&^S5tMb0yf={}tuB+X@BX_1)byr;VS3gwLuA{!JqHXG%B$Le@V?Vn9C^o0IBvjk8;&ADeuDY{2K7pS0CK>3 z^&8Buy<%K6>VW|AiESeVw9yw%ME+BrB+A;3<5<5N;>Mfd$cz&;cA(i1N0Z>ngiXz8%SMV2T!x*OdhQwxGk z{KXcPpVKBG&@P0BXRESRNexxztpHF78+$Kt7t?GhM90TyL$|Dhkm=p&G9C?lS z4=!vyT7v9U7087>hQ)~n(-kz|)G!ENKgpd$1B6+83?A{2^l(*Nz?g-w_3N;0w9VoT zQ^e$&(;Sc?Nsp@x;AL0g6zjwZ+;Yb#JVH>>^-9CWMQy z4HS@O-->O<4S6lhfUaYbo?bbCPp-hRHV`k+AsBljD@TNR%@$UD{Q#4hW(Mh z^8O^iZc-bFUSA;TahIpH7M&!bg3jxR*EsIdKzO%PPNiFcW9j@l!Gk{)MSWYZ!z6svIJb-V;R zh;A-zE^0*?{%hp=6RtQef?&13YptXw9`-9X;ja@9n?SsjZZ&!gnNJy>rdlNP%!p&% zAg*J)w$LRyj{CqC16%{XP&u+Ry4W%58`?LhBV`!kNabE~>r)KtcZMktz#arJvkT}6&Z2j9G)8h0A#OWtziLB1xrtWfOVY8 zlwVacpyih-Z8C#k-wI&OLUd<~6fT)@fFrrt0DH!M=l=dr)Y;RL9s$3K)Wo|cSjh^K z_D=bjCh1|zNX;|S<9N3jTS%J?UmBP{=oqasaq&PbW!Mw|AOSjn*uuDJ*l(gw*W02q z5Nj1l&TC=V;tU>!EC?buMYaKqgo-FqctD!H%6)24*}@g`A_)4n zNWsN87zC&N-*SJV96e%ke?5CW`-q8u7T1Y$#_{1o2m!}7nmaxONC-c1xk>bC$A|aZ za2+{tIN%(v!Ew{!8)3~`(lo$^{e;}i=T|M0!NIR8kij7@kVA~OEDTm-WpH4Siw#vF zO&!-FSKj3T z*El#Qg~Kq7UUU$dh|ZQ}7$$_?38`{vGW*v}6$^o9VD!|7F z;>`((5G#5Vx!~gy@i2>-GoZEHLO4g?3@tPHkntFRK-LBarRz>XT`=NL(zij9rx9%y zDtv~aK4SU)ytmZ3nrlrxmBpOL_w3c2XJK5}%5qx;4Up`kvXx6u4Zavwgd&gnE~u2i z9yDWx>Y!TE&qNl%32FlX%LN&W3k&6UGq#pI9Mkp!%&#UKppR?-bmtgn_}PcG}fK}(?&&x4Vq zUk~hnsaV5U0{O_nL0#r!w6|oTCQ1aGh)p#WSOKPfIV}eA1w%+U@hhSF882OBTBm3Y z24W^6!Xc4(LvUSyiNXa?DX54GQmfLaJTcY#UH>)eg?xboLtUf|hD3cdWanLDcoP@X&g$JE z8TQxyVps;rJfPhgXy*wvH`g69W)_Lc8=XP9Ud$4^L*Y}k|I7{i0p!7-; zK%6;pYiSCYlv^FS9XSqnE(IN@3eJq7voDypn0rG#DVuy2k~fimA@78Oe5}x9jw2@s z3YFg|zgd3&QqV_xRlBO}a`9%-{cWkGWr``}U}?_D=-6!2=y)hhiW8j_6#)qyFo%dV z5qi88?^c!8Wy$=00-0OJ%!uj0a;1qbiwYoD1)$7yJvp3+fu_0NCPQay6<_1Tr$R|?+)n1c2$8)2olj? zByufjzQ`DMGl>?9Bx6L!g9XY33KYJJ>mwd0rYJ(BIpvy07yL&ff!@e+6&)*J&cV|J zh28UX!YuBLXj4RlJv60}5iV8>i)&5eK`r>7#Y`@d_8CN?=v5~nh5jS$M=&}+BWti9 zE6^X29>`|2JvV`T(_5z3@#~3~2*8WwVQJtM8t+-%GnpGk@CB^I59kJ@8N1mG>_ha( z8TuaV#uH#Ce}S6`I2|`?%(O53mkU|$gxdK_Iv=99bB)Pwxq5qCcDB0y@?f;MqD>7 zn2*yc71zg<5ap`;xOPwqkX_QjwFA;=a2<^slxjWo{Es7dvd7f@rh2||B!B9lLafl4 z%X>-Yo#J|u#-Y8ozP*H3&Ko8dGuh$gJQ7h!j=H)l<1+X3merF(Tz<+S`)q_T-R;w9 z{m^Vp?s3E(C`|I)kxTZ5gz@cD5fkHswj1iZ^C7-H&mKA*a^~;+NZzl2JEmf^jJns6 z@)h3nO~c2tj4PD!sCTzh8A}5j-}PQF_tk&2q8!JQ*@rY5=LR{AN)NABh!5bO)T;A+ z89iIZ=1>VgA3@JLbV`RclXj%Cc#VW}H679>a}b%GNdG zVcJD1GmJ1EV-tCY@xd=KnHXWc#N2X_T!;(ZjI(BeW2e-5RiVBSH!x2_jgM(3#jt2U zv8=atAl|l}izG9S+EfU- zU6&#w9;mCzAgSh~QY>pi_H9E3WaT#7s>H>R)gk70eRwK_l$LPIq>k#5S?2{()8HC{LAez`WLL6mLg;-O)eNk$w94Q0`!KpL2Fk31fi7b79NKQ|K}w*U zjS)(W{u&*{2wh~I!%N3_djDQkj+M=IVd|+Ep`NUAX`6I-R=L1CYoDOP?PK~wL1b2_ zpjPnCHk@UxO>`xR;{t(r-8OUL>!d&r0zjN{080}cL@F+UZXO{1ZzsXLifVxeH-6I zu7j*Z-ET-3mNfytp63c#sUxV&8(1Uo^oPxv!nD9B0-kX-NjmtJe2Sh^8R2>pXoAP&I1pDyxOIcN>boN1uZf`$_iKSyv$| zT7N+G7RYRWrnR1N5F#i^TlIdyB~=@`;Ch?_Kef*;G!;icE2#z4X`d znA~Tf^k1hoUKklY;@nA1Z*$D8=@5jGl_AF)n@2_?gq_r^pBm*wLtbw)#Bo!1^$YV_ z%j+-3(Olm|*t2ebE`2kOJfhnhZWE-kSMT+YPw)ZEpfvmb99lU>UjOW7Y&Kmgx^F{c zVhjT zy~*~BJS*w1UBkb=&A{*QSyrSMzLdmH7yMcBKvX!JCdBGm(BEvw`6FffgI-tS~QRF$`#aaQ`}DDVR-7XlAQtKA1pVdFy~?7AT%{eW%hM!po&o%cbEE ze64ow%Em$PHEH;7vD~j9y!=`3fMz~qoWU%TW*!}OvKNnRi1i0t2VHZ(Smi8;P|wxA zRvupcu!!&7EzFL5R+S-s4G`H293Nib$9K18=fV?H;U%s&m>gw5W~ZzhN}Do2b@Y?(0d8;F-R&9cf#wp55z^!9X2oDOk1{>}%>gFhE?JGS2GtbKvF} z4Y`l8=5S<#xZolXm;%A!SlqsYx@6=#xOyt~^)3dEYKKC4?cgdEHPm);C`?6 zl+LVduWh*5ff;?YHeQ8bX*kVA5f}Pq^v48Q$aYLm_S?|-z%(20(^|vgNoJO^iSmQJ zZKPv~!jAG2g(E}OtIrJe2fgl!LV_())T8zVVO09(wJI9N!`)nLxI+1Yih5Eq@hj3O z-yRUgTwiD}24I6x@2O$jn*7awr=n(il&-grCBH~`W0>owT-Vc+_Rz2Z`MA_^eDVw~f39OEUghX*8ad4mM!DscRjOBlA!^jvkC za-NF5-ImEzEtRg;#MFqxxUF7SZQu9LVH9b+JdZYBX6FJ(FUhsh(U(i0oaKvSPEnp% z_33f)3{ybkKsu}KSwjmO9hIY{lu&{w>FTpcOEt+2R^FlaBH6i&^9yjKdbFd(4noq~ zW5nh%JPg9!3g>KsGe)U6Q;rXU2ZC5Szky4})7DbA~Uj%%Hf?(6JMl3ddy1uQb|tg*{32 zP2-x;Q3+W{edX?$+t!iK3sCx6ORnxBDfAh9Cg)GeVH&DiV$X|MC6y(=({Ba)0%%F- zWUnx;^6b@V0}5i)3yC{k;MiV!)L?UhUw$TTlzuu;t_JGeD2C<}e84>zC7c2DAh4S; z_-9|MaL|Dq=G*zmGcb>$@}obYBfy2idv%t6KM<{6a&;qPcYoZ&nx7Sh&P@6`?3u4B zmvngnuAesJnQR)c$Wgre3h~3rM;`lu25-CpMeUV?%6?{_1(m_8>9)rkjyAqkt0UhW zQflIlC;iSd?KAPUUU4eKL`R!j{u+s^+Edb_nD?lw-P+>0ovEIlGE$}w__5=+Z+rBg zpD4)v9hh9%(HV1zu&3m$BG*yeUNZ2+ZiVo;q3lFK{K>dcedeG{3bGX*HQ1jhD2FH9 ztAlbW^kNLDFsWr`gXQR-SpIphuhOx%w)*?9jl_9a{y)oZvp@h^Z9-%5C?Fy546@C>)|27EWsmaF zo$!Et=v0C9k2sX(ncIo1Slua}5q_}%P+?KjYf&e%YV|{Bb!2V`#~eguaC+H31tz-s zLNtss$KuUZZDwn!|M$=g0K2N;1)X_}Vf(m!?bE6lmJirQj3nETEqGAce%gUBIS%-a zA$84G#bI5+3SEZG!N~V)Pp99}6Hd{e%z7(MA29uWYlIoP6zNix$mhv}SL!W%_#grFF;ZOe?#lA&y=RusaD?r6fg};n}Ka9D_bihF%(^D8aS7yb(QqQ@~i%dMft=+_anq1 zVg5WhfKh(>$0&$>KSmjz58vwDl1QQE%CGdN7P|T9M#M|flPd>!xa&movXp1M#Q?~e z4N=9OjBG-ih3*Sg(#?~ z5Tm9@kX)*$s357e$|XXos8kUnB8f^!L@q%gL_`P>NVu7R2uTQ#dvex*@6*1&^PKlR zpY!MWz$Y`aXV2bit-bc1y}vW_U5OuAfL-<%6V3ZArLHpp0ri0Y_PC;;0cd8$tL??j zS}&t3NsZ06VOg<`x%meAhygwX7L~L10T=0G!!H3S)^C8BVwxyl7-JNjr?P<<_UFHe zVSl>3VzoWJPI2is4PKJLN?0gm@B zs*?kJ{MiS8qVn;uZ2ckqNL)72J9H1&9w5xyIJ#F?PUt7}57w2BgL{1o`eHMa1KM=q zjrGE8^AN;<3xNN|fJTY0eS()gI~boLYjWkSq(&U`BOOYB$V>>hCn|S&;Rl$Y3jD)v z7=i2|TvIOa-S)XO0AfFb!#quAHk5xpu*Y#IL=_@$cjZl{PBlU_slvYS2JTH_i2O9b zd*LMY(UHMEX(KmZwbM~{f$v@hrtyH-E_?_p^$)OK%$Eb?f3zn7;z;qpOL4~Bk+Qn- zBtYn|s)FSb*LD^xs9FBx_o#s2k<^nEoySLxkI)pBx0Gq0p@4byD?syVTq&z8JB>Sy z3wH&4W)Aqn@tal%2X_^y75`IIxRJbmfYKQ^UjP-n6UbU`!rv;?E@kwZM8Leq!@|{-M*~vl+~_$)x}ic)3%tJ(K>UmV_TNv$M+=4T z8vDZ<*;nzw69m#E^(X?)y&(RH(97abxPQ~jzU$d}@^1tku9Ot2V9HVSVs)t;*lKHC zDSnoNMhI(%bZmr^0Qx^pz_R}8um3NSS!Oce^j`{qbUFaV_zmS_kNJk4W_{>Soq?+LGk4sh zdYF@#RyV@};|OFyC!=%F#kT>!!?C`z{RuntZ*9M#Q>_cB{NLlh02powbyw*2v0FI|@t}#i-g?El2f6e%LS&~waDxt{u+Ql5RXqMDWarM(T0U1b)z(li{8GyT`~(vQa3{VGzHLLU5H!$l zcsfWiPX+RR`tP!{Q@hC+tN=BTzm51*Pt{^<1HgydTf`*OtC{ zWlKG4d;QDKMXrEtQ-4!mffAs!52*3*WthXULf-O=JxR^=jk<#1yCO@x_Ws65Psljh zKicOo4Diw_I5^+u(0?Az$WF>KWosZo)Ca=?lJKc#ZFZaP6!)I?$6DSZaSAUq^76Cr z#_$GdFI2Lk%%Lo}h2vyvYmj`x%}=PSU2Vu7NgpXe3O)Hb=WIqNh&!bQie-f2yJe>$&*?M>oa1mg+A0sc1-qRKpQ3WA2@OV!I znfD^+5kxKkieZA9l&MC=$O`20+0+fjW;hMQg%4EbreELLUbs^D5VW1SnfeZZX+H2NeamBiHslpNewW1gvk9M ziv^zd>GE{>PBoCt3Q^wdKv#I!_nzemRO)mM^)2QMkhmU-yzFpa>jgON!rt{LpmK;N_aHNB6Tov|;9l%Y#-FH58GDBF`mqg+XK=bGar@CfsCa$RQM98kCS4g! zqktuGe*!q?1s4F}>~$w6V67Hh?9cxlca?z%vwvjzNF$g6KEeLQn1$4sN?UA+gD8_1 zU;?28<;Nq>Y5SBfv9IBP0{p9!AsZ@0@GE*Tl=}CRfQ&uPZH9*+{G#5}eqd3}GT#Sz z@tXu`w68%9Hqy>(jh99WKzEuCM4$A5a$uZsuslZcu`>2ZT6CxIL?tk+Isn}10%DFYpE-fOGb`JO^xX7Ga%z;qg*+Lmn(Z z8b{Zt%ENpCgU?P70d)=YEqyJd!ec@Rfdl!0v;HM2AM*|CkBmKxRs;DdUw*L{o&_MP z_CpPrV0yMS4leaT{N^L-YRe-e6-Q4;BThL!03mv9NZjs=Jeyb)fVx;0rCoJYwuS9x-V}v=qt^Dk{g`hH2zE5aceZ3 zreCvV<|_*yZng4`aw6~m%&KVnboKzureN-wrT}F641!n!XRARwt&|UOyTr2ZY-@0i z&DyroKGtiPvPK46uqNgre6YF~f|`p6Q!LsTmI!F99Q}oD9gz7Ev?Wuj93P@njU(fmjGBNpN-&b%L>np4BG9Y~C-8*?2*5EiFboMoT^<9(r&^x^ z(ge)2@~$rjJOSRoN2QIj0q!6kK0XTcN*{`6P|ywUC0T)v&YWi*GrteW%?3bj904i` z7$k@{KweZyMi9`_`Ox>l@&ejOF*E*}(=)IQYahY53rTQ}zv_e-OYj!}@?bq}>f;7R z9g?sQaCjt#OCb)k7zCu`rH>?o#4J|)y>V_>wB(ao3#xPL@vn{g^hZ07;l_+=>W3E@9 z_3IGgK}8E0SS<$*?`kdQ~NyL}*GDMcal{W!kC0|z zcWkn)Mcjsi?U%!_kS!itOC5K?INS?5(qL98Zp;k)hXxX+Z30V$=yL7|OZ|F`G6OQE;@h+#Ysn`>2|w=>ZvYR(Jbp4BV#_uXfrQw?AJB%%Im!;8I^{-w zL-)ox@+%b;{QXFXEm2C@73)^SlkNetHPSgzV@r)mh^VEJSULtoH8;ET7Z3M#GT+iz zRWaRF`q)r^TAo4T(TGCw3-nuzJxG2R##O-;#0529kAxvU=?8a(9k~dWihqZt3J&xv z1niUr@r}l@RNAxZSkO!iQI5v3RO^*@SnB=rnDX-cR?0{|ArR>p7F-MY6KDgwp$D3; z){@T@dOWPCb_a$^%-TO_;kmAqGlgLfMb!aFtedrIv?Ney^dkV8KnzGYK|}iV=!e1= zD(K`T)=sj~4kT_yUHO&{bauC&YvKzT{Tom@AiYHh!OxJ(?EQbE1tXVzV&5QymfGR8 zI+I2Mbq25pIhq)7MOORno+gBT^HD=}Y1dA?C#mc_z|(x0V!jIt7?sQFLw)%$UK?4< z2(qB2xK3SgWb`g08ZF=LeN1B z6A7PXIT&PInRw*Tf^b!7stCeomB_egssxdi>hdz779^B$;mHP)kO*i#cvK0EJDVy% z5)z~@bV}Nt6+-itLQh)`e?6i#U>He=*0}QoTz&Z;@TlbRVyY0yek-;y0qH@O(M`T| zcmO*prN;3+K>mt^dxmQuou9m3k@plRMyat(IXrVXrdvUvEr$$BKdzzVka~4EQIPcx z9(9pYppE79dzVESr;`N_bc=p@U}!#cPsUcyE(5>v9SO=>zJS_X(SukNS09a zt86uL-AZ&Gw;rzJr;7UtaNDC}z6odI!Iw-vZ7mcE2qtfMt^iV4EBd!NoJhdqb!XR< zjM@W=$hclqh)2NB#SR3Eooir)EafM0^X4bzR@%IW&3VW+TR;e!>KfQ8i_vDhgF=^# z+<-w(+-5p*x$PLR!m4T$0bz$RQ&k4_PfH{T{g#ahFEGe3Z%P@uM&Al|3*Gdf^|o6`3GTb|DN4%9+|?NwAb>jQh-16?R} z&p-!~B2jW8ffrVnB6=`-`jGn47{92WGl7OyH^>XWcjP~n#f;r8OgRZac5y+U3I=+B zK>=FdGO^PjXCo3nuWpP9gA~hd?hEDCiJb;ztYty<9F1-v&e1AzHJ4VqdtKh2-g0A( zZJ7o48rOS6L2m(8I8%l{Im@uRdY0imnl8)sJbH=M(}KNj?x_pf5r{{ z{E@biH@!`w*j8(HT4A)~-Pp(sudnG#;s&xLokg?oDUqzm)Ssoi+(CA2%Lj_i(+Y=q zn@2L9axNq;0O=h1&i9YjjEY=Zt*8IZ+ge4*LwH+%6#{STG14*jBhlKu9Kn+4@XX}! zY@nU>Vl9me&+_Xknk7FW%a)}9nd_xN;yW0$v-Kq#lW0I!>wPIEXpq5$=_ zbNE!gZ<%{yh_;?1m>FG~nJn?br+8Iq|F}1JfIkP+UpW%rpYtr1nNVUGSjA!bKP*j5 zsGcQGetI-WyE5=H@Tp1i6Be;!`MHCt`W6RxgEyO4li8iPqh)NBsyccJ&F&b^c&v9+ z1T35m^GcCd0=4JoZ4P8im4?*$fdK{6shf{E9l>cs;%wDv7U&4pR#)D4C4Vr?2l>+( zqp7dm550C_{x+JZmajmyE+@0q?1YluPCz=tUjPT6`_W~ou%^%EPflE>T|uxZ(mEh) zeW8Jqwj@_~dhn>CEOB`iF&JJWT$C8A9gMSa(mH^?HqVfrwnQN~O+aZ8JHdN~XZZ^f zf#-!o$5xL)V5>O3cl0^K<6Whx21n4-^fKXwZlUTOGo7WbyfjNyof#GQX&ey9)kZG? zgxSfsvNuAMz_pZm9mSEy6ptgHPn-q^}sw= z=M=TkE7F-`&s2%Q)E`q$SttQsh0bGbL|0Kx z4q`499cxy#-^C-KgYKs%^L|$fGi8WOF_mV`wgseO@_?KEmA*m-T zIvajb&m~nx?$an6;mONl{62K`82(91k)ktI*~?@y3W(Z)%-q zk;U12Y&A*!T9M%m63pg=WinnD&7#kP*DDwGZV<8WSu(tj0%O`zZ2@#j+%#!{$P-)v z;AIEPN5hvCVNz?s+$4C)uueMw85q-~10tbj+c|(>>?Ww`q}GACNqPQco`DR#E}&v; zu{IXWDE}5h1_l{E&@$s}8GzHzJW)y#a3wkHb4>J5`>e?zYwgnwULqP_hu6>D6*ILgE(ld(~S;;6r`W0x(u6sGV zt%yGg`*1H%3o!@K&&DwIEgqtBTo$G(Gm5t~j^#^F14~~ViRrso1Jtzy6D#U11S$l= z)_E}WpB|j0^#Cm~8|dlQHHLZGB^>(dXoz5l^I<)Q0#?W2SJ5v+0ooDg{>?SwEWu7w z{^~I#uA#!y`{p*{Y))exOIb9_Hp4R8IJMVVl;3L2m}k1}ulLbP=5D^@F;yxN;kzNj zQj3Fe&G0e>TWXce4SZPJ-6SxPxX5~QxId4??QOpObQi9;N;9fWeP;lX%}09jY+-p6sQ)fZeBpG zYoL_k3k@}GSAdYR7>u-igwcok4YLN^ImY|HXklk*$7x}gL!Tt|1LE`>W;KgwQhJTe zB&pxmPKJ@K_~c-|f&?}KAUqAt0%F^I4t-Lzb9OSu&xW)@<~_?(^GqmUYCrxZW)Xd_ z_0*v4N)bLQ**VJ-h85P5IDs#|20GL-W0cXk*Ha|mSW@Sj&im`bwM4iFrF(A zIard65`;Uh)k>Uaf}7A;!whi7!lz?ccnNQLmF)|7e|3Q&NsA)bW>i}tHe!|88Qhs$ zF&3spAsIH>&Rg9L9$GxX=9y;ca5bkGfOe}IVTLuwfQ*7h+jZObRuSdape?xwd22q) zGkT+!8;V0`+K^5UlZ25Qy%-UY$Jfp+g{MzXDU)I7Bd3)yZB<}pe+%9y@1@s;wOMDM zE6jDhl9e2GAP{}1it;GE%GmPsKhF`Wf%WsT;Q(|OlJU*RM~|NK9uKmsTjnb|vlTwz zh(NElLVE@7;tt0M$Kr?IC`#h!A=S-Z_7WdE~~I*!%g~`&~_DX1jB;s{F3`<@+u4^CliJxp;Hn zMgJR#8>(mZ0Q2f|-gI!2Iq-(<&0d9~Fpj>Vn&V{;RBjUz0OdQ}W#y-3xw3OW`kpgL ztZi{rbo$guc8(ixfk+DT0M!@xi?Z}~882@TpIkKlP%r_U01W&;&J)O#mZLuSRIq@v z@$pD~Z;7b1%^E*fDspY_-~~Vf=oQtejJQ|H{KmVL)=VYrw#Dtz|%=TZ3j$Mf%SAqL504k%Y&yP zr+5X1Ar9TIdT76+td`57hyo- z!;^}#XQoV5jLGE9x$6J$c%ohP=cxTrd{0Kxi{T5CE)(Cv6hT%wrb2P-Ptxsx!9F|L zzMfcM87?&=mehn2~YE2qF^Fr{mQsxr01DO zCM(W_i+X#Aq`sxdpYW9F3XkD!=TMt4=V_}Av$WGWwk_4UFomcvPa8L4(oMr5kP$we zxW@Q|wU>5t5R+UK!%W6zGhj{)zWkqN2xEaH_2=3jVYWz288j$jwA;>M7_>Sb{k1urEvBhcjgUsSSSFs zLGTA{q2W{QhB#Z*zuE1Vz;H75k+uk2%`*@Go!}&}+t23Mj#Q@uyDh?Qk93!^HuGxG zp{Gysg8d18Kdod?aIQ#_oy_(Yqr+;N_06i)=4}Yz!}KaS@gGh=da& zFzeXJB*Yy;j*j-a)DiDndgdji`s=r9!^elLL4v{$%qTcT3$QF67Ad%`*6?{rzxtEu zTFX3`C;bNVgXT$>8SMuR)r4Lt!to#Q^yruR1bC@oB}v`!i~1{4r7T(lA9>u6hwz1z zYlDK+e{ZJaes zQh2slZ~dFQ7HO!X*#<2%6#kmvOZsv1HNzT&+8*y?FW76HKi*K(4)Y?Yf&EhcC(d0E zWqmwIKVL+I@6J}!Q(*x$c#kTDDZ&N~@umE#U=yvvOpw~@ueV=EKIf~ls8&?ItS)R7IFhiX)PRTc z8I86Zwh*h3a$^vGwWaCeIEHXuXn!};Q&O}I6;7T_T?BV$EN{%2HPZ?h!~sQBl7~2 z$-Qq`F;80U+TP4tF)ke;Ms@;(cR7}HY}t`m?NN?kMRWjQ0ITq@bXD814s-D2)Y6X1fo8Idq3Xobir42?oMhYnl#vMr7L|Fk{ zAfj*JWxz#=uj+tFvMUaGt4KQpcV_5h{|Q4N7I?r5y^fK@QGft;%FYXo&BN0l4xb;b zF$U`4e${H0(`}aSaO>iTL4A4B*zzNHcI*!-viV)xJV?{V*2_!E(}n_wiD82@cW!R@ zs^<(;Kxrr6Q!?Z?1T!rL>wu1_NqW}d$aaa&mv1YT?;ujQs0U&t{W^j)aWehLwr=Xd zTQj5W`4Jv&q!z#UZe_i(WK*CcdLS)aSt%YK3p90HX;CDMZDIwG^;h(dq9}LMlf|LS z(P2d%?7t)`O*zS3{vvO=pqG2BC@617lZtCLJ-T4(*z6W_L~gX4cFJ*1+^V}z>F+aI z=9F!@jG}C@kgw=A-9iae?FDay+84$gqh+b>k5Nog5iKyxWC_LORxA|FA7O^F1C_#q zuRggf_q)D6%`)8bf!A1Bl1rs8C1G>2emgx-`U&T1bC^SvDTV*?6VA**%v(!qk!W4m zzT*0YZSBg_$blFRFl~Y66L7E;%bcC+yKD}S23->wmp|A}_<|Xq%Z+`tD$@Dh-CBsu zlO~yUC$_C1tU|wFS))tUx}8n?M-Sv}%kR>i@79#Bv(~S05o$l!nzZt*d~L24mE@By z^xv0Kt+|3q+}A^1;l_J(n0M48E!LIYAtCyvOLQ4*7vTUukT|2(Z=m6`>fHN#F3wGQ z(H|1!QXhEpJM$ecXTP(AhyBkM7g+@O#?L?ri2=)uuWtZKsR!F7j)dltU}iiO4ig@1 zf4#3bs$p*x$o}(#?W|KkZw1O}?eS~QN+#bKxUZHk)?}ZE50T$)T|*NV5M$>I{2Hn} z9?Ps+H#0YO4#TNgqlB0CbN%kMHQpg<$@St}O@VGP-(6H_uGpIL5_xl&C~071Dcxzm z8@uC-M$|L9V05FF+~LX0c`m>6;7n2I=#I*kMbz+0-&bwdzBb>vX$QN%ENJ|cLmzoD zrzmHi0Bn7Sl)1SWrf!sLT5_D100Z~&5%sP7@XO}Gs0H`l@X8LCZd1NqKRE6+_cydvAztH~m=_VK zR-9Z#vb^V>{|Ct_R{nx<$SaUH`q@OTi5;y=exz zPNJRgf87|iSNV6vBqp6BJ@s`~o@9kz38&p%tKgb{uBslt_*vDXk6g9VCtiX@&PsnM z^jTH>l!*j~|9KNmxjc+q_jk5%j^LqF>)xD#OgT`H1=aZu1PaZU2`h)_ob9i@1PB3_ zHk`AaH5>U=`YX7*BQi4OzsH9}(}3!fySwSEfzXL0nBk`>H&YITp-962wCOJXg2(N5`Od%$Z8&gUy*pYru21;=bQGkv z%^Ww(-wGn?0^#0ku0AO5pQhJre@@hRU;AegLb-+1^LWmx|ezo z`7K$f;2w{rZ2-nC!wO(Sn>gBZ3BwEvcbFpw#@ zam9DPMkD))Z= z4?mp4x?!G!asOx1Wf&;OjUPK5X?DrVaeu%J!&z`s4BHgJyrn*&M$ z|Kf1?z5nf>I;Z|Dx>lM@y5`$+rH^#@;OL{M*IeVzRZ9hvmkDO~{Cxb9{KO^sxx=~T z&xutJSMGex{h$A(e=>%;+$H@gc#Y^(r zaHB$YkuybiQ<0xr<6;-R`Fvc60Xy|ulifb73fq0 zLF4_@Jm=24|Ex2#5dukMw`9Fx#Wq9XHp$n>&z6aU z_&>%C9#47A1?EO1?f>{EXp&C2R5b3wx>4BCn2pUg=JpcR$udVw#AyphjgP!vbLxjRz z25Hg9bH*(nFmCx$M3^EZfqEC&CHz2}x|OyJ7~tW@2c!w))chEuSn`iP`QL}f|9%us z+X@7c+hw`kSMG^mkXFu7US=&zH>|(_aWqm!_>seR-=7%apH(FSaWo`Eyi53BMt-Cl z{`VWiJ0lLhmCTb}EMX7BUQ^nplLbiGTOSm@1@4CV~{(C5w>px$)gd6#uS! zE`af5cge)i@ZU#*|ND_1`orHN1#%wYh#Vh@QpZQ4qvJzkM>Gu6%Y2bx0quwUwtYNt zKLUzKGeU?saa6GB-4NXagXo>H%Kt+_L|x!OH2nX3R79-!|MEWBtxNmo{kbY;iJ(e+ z=ATL9RGG*cxiJ#xSe8K%Jn_dxeXew$9e^MQYRL|fwLirqO8lt%@1E}Gcu>pGoq1UXT%Si3cg-YwY?e@;-y z%r~MLRjPSSOX`Dj+j>Yl&9u!6)K?fV0qZ2~H}gYtx~*9+SLOz@QhIc}H@}LLmW!ks z|3Itu+PZUt59Qc`x-5-pbNnj~ot|6#oHt*P5{i{ugl9=xvxq%94zTClo%`s`6<2{R z6f4;@O1+zI`+0&{PN~+5QzvNG9tBxR*VjEJ#-piLhV9NRM{?VN{RbK1J;QRB+dXvr zxkrgP(#oWsi}MKx>6)U}qEr15l?p)}Qw0sI2kE+Eu}~|Z-nNs`q6UCEPir(2|9Ufv zdO2@1m4)h~r-tV1P4|C1z!0w(5%k=)8!A3F0L+K!*OYcZuoq#y8yc8`7BrBiG)=OZ zw`V)`liY)xeq2!XhNgaW#+ra1r<6nE8%TB&#DLnlK`}o}Fv|Um6))Q|u9@R?rOWMc zQpZOZa)H(hVLfDd_Z!Z>>EkyUMiMXOR{Z7oQ24?A`s?E9qm+&DJXYkL!{qzxd47*O zUVMUZ9(I(|O{Q}za&N5Sked(xk_?oNk3XQF{&U^e*5=~%=0wftbnEgjbkEn)E$-p2o*B z@X_63(iUvdV-zI>_~(9HP!ghJvQ6rk<+sO~pDRs7mG9dGbXefU1DASZTva2`qTq{wWLi?TG6D5VN}g8@Em}4yDS-~ zG`*o0-Y}}XH&&gPJ=GdT$pPhz%jt7&BRqch)@gua@u-2crD>8}wx~%LzsovpYy1;W z%TECup(NWtifCG5Okg*qE6XLf4Boqd#8EB_56BJ1s}$nPq4wsM!u=6U_F=8^+3mb- z9Zq~-5zDS%g3z(V;Jy1Dp<|DE`-69cjzUB6zHtIMe6Uhn5IWARHt^P*1uly)0hW-h z?cwpi$lp+m$Aaj-cR|Xe?{;ANVy9RhmA%oE@}oqXY;$Z_NyM)qp(QGLOo!bEH$FY{ z$(iGSefar|rJr(6d~%{Av!$b>qvd!<$MKeqQ|AiLO#XcTdrMXPy>xMjSRhbR)03m? z#o1+w$YNb5kWt5Kd&SkiH93n}1-5vUh^}P6^1E+rRt{ya$i;|htaS0&{>&OiS}fDX z*IUqN?#<{ou^&se2u;*rG&Vo_jdoKhSJb0PN~h3p!mnsN_-573EL+6#c;z)}czl$g z^&c_iQqq4EekI#;^$mK7Am+K!BRW8g zo9SmM+B0t=mkJW6h;#7c?kRA5=WH7>2AAl~}3g>9N?D_!{~|3VX&zxe*%0dwM* z2}LbjFMOp;oX@SN+U<2d*hmNV=`cTRWQFS^)KE%kR%xrD4;$I& z`Uo?`kgUeK{c7J?qFJZ0^?z)`Oe06MHTz*@?-76XTZ5H-NIdE1i*-9=-@TsvvFu;O z6ZTAZr}AL+P4eczSFVZPym@YW(*s?dgiNM8@i_NMc=rm;Rz*#?)FiF07y3RR#HRCd z{D;TLNxWqL;dDh!KvxcgjjnN5f5=PqAHGWt<1zh*hZHqQok8kmMd2Xj?Rr_GYvN~a zXLYNwG8ff(UAbuveJqtOaZ_QXlN2@f-FBMwu<1$GEL7B_bO&p8=~q$KqFqtD(ka)i zA+D5J=#Nl@bjmdJ2dLO|iYwX?MNFr>kDkOjgRAt&a%aVt5`7e&%_J{C?HTgY_ znt6(vm~3~}De==7raLQH46zQ~St;TQCDR?hGo7-K|1m2L4U{^k;FXXIp4HAh8|p4# zyMEOFMA>d;_G(mTdTRHVzH~J#rOf8HxfghD!<9q;7f7gceolHDfaxC^0TVdSiV#y4?2n-x;hw1>NV9}PziNC_H`Ff zYp}ErF(*;JSlYiZCs00E+BD2*lphv8#x;Cr{){iBaB~ z#?fnkHka1v{o5i}VQJF^XYi}Bw0VLwycd=>TW}6v!S0f12J{Z3UOx>}zrs9+CUrF| zFgwyDu7)798+>_durp7xeoQ}u0Vj!3siFf=sK&9g{=@l-njQ_=oaH~PRMg-*J=Gbo z>0+xTiW+$*QO$)-mOJjrO!Zpr+5ptd8adM)S23Cf z$KPyL?=~;XJwfkj`Hs9)*k{;JUYeVp-!+fCF86Fq=XUa9tGm@!t5ARaEO326*;=&r_%EmM6~MoTcnH{jyZrJOAL$Pyaj& zJBuHB<$7Ks44cVl-g~(y&ojQ9_NxdvOlqIT{dNzteFpc*)EoChBIkOZbp8&G zKk_``Tvd2zU<;?@zP6!SCXed%eMo?^s^CIyMQYF3t+bx-4eT=Hz*(xJ0SU7?3nTR6|ChluUYy7B@<$OY`v5~OM;_HoHZ z*rM2HB~LAyU$<~Zx!NL5nIOI38VtpqLB;B~K#LDLbL$WH2Tw&FN_h*b6-ib;4=G9wv16 zX{Za&eGN5RI1Bcw{3zFR7-b^tVRUaERD?=qR12XgpyQ|Fmb>9Tx4JTLpR#_%f#oS5 zq35x(;mS3XrRX52W}f~R%3`z~bp6U05Dsn6IxntLc50zk7DHU&47Kt<#{cU1JzVR> z{}6w|vpVmm)}uu^j17a9h;R6_@VQXhIZ!>Udzm^EY{^Edap2F#GvUNKcsP;++hc+A z<-ftUdJE?~N9V$a&r3hohFoznDBwzNCsR`hR}w3@-2th>fO8mbPiaj;XDKKnPgYgy zKpDQ1JXM9;!!*CgM`6yOo;Y>cYbxLxRJl_RR^zTOf^rx=LiJ2YV^!ih^FaYdIj$>T zGdIxp5+V96B`{j0+CJ>9e*`(jpek(=hJlB6F#iNr&d_YoUxE|t?l5&M6oD7AyZoRC zLDqAQt_hAEX6jPD+Ulx6|VJv9A};ml!j+-=uZ zC9%3qp5bH&P-ugq->Rhc=A043wfwg#Ws*5(%y84=txC7TTt94h1(P62h`C;CkdWT$ zlpzigkIepY1^B&X|lvwLXBxO4y(=AMiI5R=;Oq15w%7S1}+Uvf2(cGyW{ro;{2z| zVo%PoZpQ{S%*U9f(FN4PS&3R4Vo`*s!jr{QY{3ciBI}eet}YU@H!R0 z?zn0TU&hU+3f85=>#&gzOQ{%Xn!i2X2`^HheD~Bpm55C(=BkesYblm8t|%eysq0y` zgndA}C^>VpX4I1FYg_f3|J*`4F;(&%ND@Q|;2lIH=?dr^MI=GVrxSkzNsRh>avmay zFrnOT;)Db7cSJgQgZyNCkhg0w_}aYeS~ZHb48~2uw`0oo4MhT;tB;* zIp5dzz?F2HFV8da!2KKV6V2gc2&xNDK)!|GW1j3BopoWQ1Q5|gJ=T2`Djc+JpUuU=2^)^sz7Wi7!B927Pn=lbc?m?M z{pq8Ai6q#+IUSBz(Y7U)$sT&{%2ja>?9p~CTkSDqDw$Jc(7evttg}Q;Z8aO;zjH%R z6YS^6R%2RqPMbq8h`jSmM*90{j@||tCOBtC|tgA%#uuR zHHyCMox_ozip$zgEX-#G0pg171qbd~a_B9_9m%i1 z;q28H8)Bry)_>U!SewRDIh8w5Nf|2j4ipWALHysS#OnKzHVYOAi8sIj-HdiL55xgq zu+&Ll5Ilw|<_oMf2|wfMR0&_TsW;$0Tg4~HGd$D_+9j#-2dW;qI!7j9;)_)}yq8Dk zKoh&g{KUC#iQcH&;44^_>wk_xC^IKA*&kxZEcW6SinzA!tloMmiNNpsT9KJsY;jDG zQZ}!>KZXrtsKD7Vv8E+M4-9t>?HMyKq%XzlnH|W2l4a<)|gluZ_|lUH8aH`?JB9H?BKX$}% z9O#GNYwFm9e6z88Frjn?>kmX7Zh>YAqE15T9M)wdf#agyjwIkq=dqZOU@ZyP7kiOX?C$BsjUj$Tw!`svuBl#AY>>ZdesAMm=+TPcA^e8nb&_ z?q(-mAynUWKS&qZhjCrQ*6ep{M@|H2o+sfQ2a=GB@Agd)eXs%Rk_T6UkdV0ZP zJy$}&)PD2Upf-6QYoTR2v;-Hg6th!HSc_e^>*#kP z)Zux5;Se$qTRwH^xdcA<7`1!V5aP2IRPbRrC^uxAdpb;F{cP;Fe(Uww>Ziy>^x_$j zh*GA*&6TxKZak)b2l)|_S-9QBlLgwD5-xKso9$YnU+ZkY6j`=fTJv7(oZ~qb0G8|& zx@9Y(P32poaanTJt7l^wqq}g~a?hrQvHZ~}98*p&IXOrSKNWPOBat7_OnY=_x4>3- ze$emjliWZ7{ch1XtvfORyu*Ar8x1F_B(zD#f)x{duKzp$d)(Q(V4A6CVm4T{(;y_P}VCKfI z-RbQ+(|@k;X>W0TH09t4r8hPgC1yCU!bZMueYE7@xltPPcUVaJ75BLN2}Osel6o&c zTon1C=g)yFe=_es<&KqJ1BBpkYow(s^ql=X*v22Lqr2)j66YikgVGmK8wVkSH^Kq^Mbz?VeB-q4{1>(@}S! zv}focf(nrL@Xq-k!L`q1A4qSnb$#SFbiOnbn7aEyhN9D9DN$9B<<3qI6UKJZs(P}k zSk|>i9u)3L4}8z*Ni5Tyoh&II$aZI^NGb+;Ml~Oh?RZ!Hhrc1a^Soqpoz`I8PTF^c z)LpReDJP%tA4X7tSx!~VEO)13onL#s@Q}=;05l-eop_d88J^`%B&72kWFHVg(*-g| zA~Bt3C!3@K>ViJ zg_Sw0Qgz-~8A`=)dSc&cr#Y_wgw&g?Dc65Y`4Iie)v$^(7v1h^_>l51G_1@&2UuV} z>O8{>i*A<54rm%j1ui(UxO>Dm!x^54vjs;wLx^jvm&FbR&;^= zB&>6p=92y&sK6Y2D%%@7jtYn_5TE#Uy1?eCUl&s&($69Fh7Vdg_9}aPWu`$zO+uzS zpaPW%S?+RxGo1MLa)2{Xun-`oo8P0ohuN2I{>^{5LcfbrVAvXfa=M6uh5andIg~e+ z=88#YJ&8Ui%s+?0b>~0BbrtFNo2R*@vR=1%=^vdQo*QHfq&W(HWeGjIoz)xkUz=Cc zrU-Tf@}n>+pW$Wtcyso7PxCrjax}h*==%p@INSkN3P*!sMbP*Ir|dvalF&7p+G?h0 z^pP56gn1Gm2D{)a{UoNcXFe=+q5~c2FMr@XV|C-yWb+d1G=`An2jw{HN#;e?_vuY= z4&TF8`yu77uzo<7K*CIQf<7s55-#p@>EafHzFa0}^rF-_Bnt@&x1FF@UxdOFkH7)0 z{Gx`9oN=+v#t}Z3_9C!>3<~j{|D1CRR@^`#wsDQPmr_%V$deEVoIY@t-i=XT={|f^ zqx1~S2z0S^K$@*npbWGbNuPh{sZaZ_E|TZI(6`f+6(MSK39Px_ zgARV@65+^Z0ROfwllCeA{X5R=xeVvhb&q~1JVu{-(fMiWE4VDQFz(_wc(4PYf?Kd` zihAg9FdVL_Ivn19cPr=F;Nbw?SCA>-)pO2Kka)pc%7ZltAn}G~xO`^h49`%=eM9rp zLz3oUoF---&oyy-`wh6Vwr3^z6ch_k;FE}002F2noh$9SbSR~W!_7O3eTP;Pz4B)Mhxe-$m5b+TN zVKda90H3K(M=qMocv9LOp*~o0pWqyTDg|^gnHL}{21~dj;yD9aco(iiBYB-w$+`kK zu#z#9FQ5>oO8d@a(1>!VFfQPUjHurUC1g2uQEF14UKl1mNAsW{Y-fe0p{nP{Dwey( zt2a+w1Z5!z0)q`@P0^DnQBW4{sYmxk&3F1)l-1}GxG2ACv!-9ahVl)Z0|2437^%k> zJ(aZ?j78G;>jNn((SogyT0Xt?m+xS*H z9hRIf`EAN2us#mn#1TiYy)R~6*)8#d)$CN5<;KD^ir?i(`LPgLgSVgZyam$=LrSUU zuN}zR`=K*_YXPzt*Yzwr09mbF>nWi~R&3x&_FW|F8JJg=z+BO)pqNZEptc}oo1A-S zH_LOK&`LY)ZlW}9AJYXWf_oA!i1UYb3ItCfb9{iw;tZL&(l%8sWL9;w(d3ZXtlm0i zS_T#73wwf)3eltg;>92p=I5T&-9{>Gx~P#sg+78~OJ&@x$l4nxG)Z8(VSbaPe}YI& z44R7Cf=FE`?CyX&U{XrmM`~w7t<9;NC$Y^?>#>HdGBH6`f?L=8OVy8e>#i}V88&eK&s0*v>VSJh?Qr6 zKxJ$ORqzpZZ1id5m}Pl$arDY^NrjSYNP#>UVwBbyB(lm{6aj7C&fNo}yF?ieqK7Ia zx{D&r^7@}sn+0J{rXr>|rawo%fYjuKpW?X#Ofk^YacBTZK&g&97a&qoWBWBq35ZnR^F>GfmymM%e_@cI>``+VxN|>uQz=b;{jDJ2RPJT{1RM`SUH6 z&hT6jRspNY7tX#I7q}=D%{8Cv0XJPDXqzi6FC>;xs2+GnZFck zZ5xY0M-N07`MS!*C1{E}x)gCZ46$6Sf&VLoH@Fr?T<(hpbxp?| z?-?XuUfctg2pL4I*Qs$l3gjWOl@6wGk)Cadv+p7xvf0|Ml1+&Cf}?9? zKmK2weR*6{*S3FKYpHd>UaO!CsiM+~iim&+B-c_!MNF*&DoWI-s2CzrAdw7O6;y@@ zsGtbBIN=1TGD}QUB!CP76`}-)kdPn`?f>=}Q`vas>Bon**3*t@~S;h(RHK)dUrw2B&z?O;V%ip%s zK|!p&^UK1&1F~FfI*!8*hP=G9uDuvCxKhI>%?S{cs!M@2%;T~`{uvkBa`SD7UF#0& zEHBzKcnc9&{P-~9WcY@snHc|2-2s~d?!yc}FapC7#&kd7@uMIo7uK09WYC-8BS0TQ zBS!g{RD;k+WX~QBM`%p8>D_|RNLS1!Z7HPtTr}FkyY$S?5~Ks--IKx)14fghEAYU; zkT!gBJYtN^-I4EaL4`)k$SndD4P<4x?;q3yS#;`Jq3u*)t;g>z?Gz#$QM1M!RE}mU zE3?jqlG^fz=4m~34MOv0g-0+vXvfCxAKGM>-1WePMeO=a8 zWOu74Z)%tO(pt^n!u9aNJhssl$6ez9(I8M&xSNaeBJv`%rxu=!1o6dMYcoh3;PJ5) z|0DY|e(jUB4>9YtuI4jb!W|PKFxJ|%(?kvIlRMlqMqgEQu2-$ELKTd+beXEU7{yZo zJR+kHi}bHG*wVR1Glu?_c3--W%RLBAmxtGBjF%3)rTw9=r*U6z7UJ4Zf7Aw>4;x<} zei=t^+b0yYpEWVMSnA@Ttcma{E~5QmPVA|pSv!{tS@vnB%r2rfe<*$u^6HEcYr(8o zT8Cu`BF&~m*cjm8Mr^>qz(u|8Mk4ZVFJkG$$OX6iH`8`7Igc^K8J0(2a=MsW8_Nz+ zJf5(yoe$Cz?MA-3O{<6ANpeFY5huQ0#$=ONIPjdtB+0q zd>8sqn(3ncN5c#29EJzxW#nCJrtVM^;{tODM7C#Mmv4)aL^SeS3OL-yBucw!F6)*B zuZST{(jQV4YfPS_)NV)pc-6$wyK?>N(ZS=|0WRz=g&Dry8;CSiZI<4Wu(++Nbl2c zEb~?RN#mga9STI!a-l%EB0(3T43owW>Erv29ABl4)V6;UQ@+?4vy9sWJQ#H@rp5XI zRg%VJGwKwP2Iybid65TEO2tj-7*G0Yrh#%yp{pc2 z0*_*aoo*U@O63pf`TfRQzRFN33u(dKnd{Av0gu6^$(C!TGy2E`fM?Sp(@eQ~Kf@cr zwDYwSr0(QJYU>O-gFBy&&)dzX2Z_$X$JK25Kd{t*e3GfvvsHW$qHCkh0SU8phfYsBs~%(c?G%%=2$_jTN>H{`^2`rq=- z7hIrwS`YKFx8=)XBp;+7M(+v|YQ&RNb3x1nJy&$0%FU`t3A7bdWcMV>l8aWWxxETo z)iTJB=)ou^Dc7q|8k2m~+~7zqBYRT^1~1i!9aRe<-}*d8ZB8>4kkbM%IUIV9ixqE4 zLaXI2iY}qa4j7<|$)qXdB0Vm_f>IN9`W{;vWXXcflx%BzVHq5!o37BFFl|{P7?>q})FM_T%Z z{(0vleo&sM^GzP^0;j1dJuEw{rNBacLOOCN`~*BNCC%=<*xA_mDi5H=XPVOOJluZ* zA%-a4zU;gP`DYZ@E9Q}B$G9cXzBQD22Swqd0>|uE8h7L_)q@ZSeb=IzrRXkRF02?@sG%?M#RK%{Af-X${C&e!{OuBbnD2 z+@W&%P<7E)`AT~0!zK}blmBA;@KaF3UrF29b1O5+GZScs3~}Hp(#&?G4yc~g;O$hu z!dQ*xHHi1uHC%;oehsbh<6|V#o7|uWP!C8S4-Yp&1>cb7b)I3fEAIzz=TNJzxWxO! z7htLAa?-~=;U|H^DANAUOYDrwqySMahYJ&e<(*??kocbSmA%8fNb_Fxnr-UUwvTAx zr1Nbq_rDw7ZrWZN-Bg4C)PI1gl>4K%KRZPS24T|MY*(*Q~%!-Z*6a=vOECFz6MX&)@ zMBW7>;newBb)y-231`D%*jx~Jvm*GcVA15pbf0C!HBiAOMFm9Yfo}GB>L6Cv4d(bf zlKI?}|2;;sQo0iC34M{Xj|UOy#=ra96Myc0%RU!?Im-!z3cQHxm z$daZhcdLF$plvctfgPME=MB)nK}AI+`D@6p9+^SLLdK9%#b*8ga9ffE4(a@l==@zeIk7FaKGzt1&&^OOB9uvNzgCl?IZQ{~llKml>2D zUo4BiC3gmwnycEISSojoV)-lfM4&O@{gaU>NmrB0kUro;Rk^PcEv16ZbN|(UII{Z` zi28|wMw&}@S8+5Z^k^5je|)C;eDtn}xXIu7V0R7_Fe_G)a7vmK;z*9`Px!-EIa?ao zzlqDdL-K#a#y}G`;_8u;l2eUI9jc@j?a>&COJh(=0SyzZAl=mO20_@?2K5BiCtYEb z$Qb`1BECwE_gjM0Ylx~I_EzluptMKF#cPxsrQI46yo`I)F!4?449_66a}fHOBNba> zsqM`iQAnmWxxQ7^wrcmqNH#SVz|_HfK=N;+ECdo<#ji&uNHQA>I#dNM+TUU%o{bRU zm4hlG`M;(tg#rcQ;*q4GctZi1IC-Q}qH473P}#L;_r^$q8?%raN=T0T(M;&4WW_DrPs&x& zjT+ND2x;!9Kc?yfbqiYL%vyp&2Hk$$I{)(k4gV&=a?B9EKaEnVKMd+pHG?6@b{B)~ zUqD&J`JHl0KP$m<*bp9(=HKCe6|FX6l4}Q>LP4MCPMptift+^AlK{+Bj?YyW(LN5S ziym-S2UM}hBz~6oOpr-jB09ns{VWQDT}Dq4Og{#)f>fnn4U!<%#J|s}FV7~H%ZNAR zxv<@MMSdM-4-Sbfq__c>@x2KnLlVEnc%dr3RXgU8q-_P;iSzF!ax#I-1jRUAlrlhS z9MT*6jsNgf21=7)STo$6QQo2k;PRC2TMFjCEE8C@b__-iN&;MNG<`|S{?}!~8-X~v z)kLgg%2~_ zLcOm_p)sjy#1m_nc1`JHUQj`_8b>Ow)Z*SN7-^7%HnHBS+*`G=;0o191W^K$uuw<` zCXt20^#8I@K$sMHahrijp)SBQU%yCIr7`)9QW2jil?^PGfJxL<5lk^ws_9!=mMKpk zm|z)aNb?M`yft~i$XC>eU8P!J5|xChL1kc;!iNv~dXYj}$Gn2MF~+2+(?1PJQ0OL_ zCg?Y*;6Jk>M$NF7?WPL-)B-N27FHV8d9Z!D!SdWx8eoNRfbg}V*@V~@XyHp$7U%*! znOlp?dcth8E80T>Vd)p6G)TEH(xUtfrFncCeNyPp(}n zJqHz7Q(VQUddwBqcPeg6{CQs`ON#rj35Q|me^c=xANy>RVy<$Zil{NMMsvX-u*)A= z22x0}Vm&DeT@rZ~unP(@dgWg zd=UEQe0n~OJOlFSJ(W6JB~$9FF&!~j2x-XDAMC#vKh*Va)(O9ktrJ2A6|16_SPKP@ ztmEDsooo$m=T8ix2jHx}HB6qgE~GI;cSW7$?kw~4=`DT3^~gi{T!@tFKkDa?QuAQ~ zng?qz7A^eZya~~YXqhXrU?Y|#1;|KO`MZuxWm+A1S!>1Nj4L69vgQD-; zPv>NYT@8DyYU-~7>o`Zc>eF}#yON`XIbccncje!^?~B^ccmGM$F0CUp5{nz+Hc0n>)Zh9beCJ5^ zRUP}JNV^(?!KjF4f`{pB_sHSBeD@&H^v3kiWh`VGr6}IEbt0?g=_BhZCX&f9p$W8A zhB(il;i%zHa(r9O{sJ248hKgaMxGaAo51m-hI#}I9~xfEG??NP756F~ApidR@CqC9 ze$_n<1#8fF2MyzgVYLJ{>8*f`=*bhsVbYdk?lHIo_)Enxk5!0`k0>%86GH@>1z)Lp zIg++U^GCf`zfj~zUZmRbiGgvA_hBT6P^?sAx?q{@A2Pvp`3h;>;8nq`v7xk+--#IJ zSlGY*j7(4+*O(rUc0F|@2dWZ3Rp4+%&;wmOj_nbSM5u8|pamMH!1t|v&Od+Z!gJ(t zK!Hu~Gm?vvCk^?iUpeZuH;sLlyb007)9>h~OlpngWx_YzdopspUFMP&y z*XiG%5e=g6h!RAT(R+pzYR4g)Jacq_ZKU^}k(&66Lw<6vJtGOlFFWJzqmGH3cod%s zl>@U~bwM%hE9)yo@p1I=w_0BYrN`K*9Z8#}ip;C(dSQyu`X1d&%hheKO|i_iE=2J& zGtu>UTBK?~mbToKX^OcdmJI+N{vOe^Q~g9;!nDCG+e>K z;FIfy`UXdjSR39~Yjq1{(OnIisvz@HU6QOpBaYL}<2Gw-tQjKtGp!|qU;SX7>*T2H zFlT!27n#b+4r}&WyVMrG~)qc>?w>9HXR&4u0KhTMWa{G7q;nG>-M zwUjDViOGtM+OB=a(K0*YiU3@4J0Hsz3>&I$%Oc}x z#+iCUH(Q-T>0&x=Db?y?R}Uv75Dp9{GN(2;e=?*cTgkV@xm|@a_Eb9+8tg4&=(Z5}RKN z<~=HESR28ADOmQX=)=h1fj;eW#U+f&BRzKg{UmE+?Xtt8p)_;dadTjt$&FcFH;aEW zn%);<8SUpP2Y0GQaQbT)oe-zrG1?s)$BE-dE%n1yB{1`HS@L9hbF+X-Vfj{4`_IH2 z6NM6UGmYV0v?%B5iq$bH{?#}1DCfZY!7{0W>p_Wfjz|GOEbl>#GrqkPdbpz|J9Y?| zfsWs$wJ+|#Hx4-9w~9anQ7PLoZoCH`FS29vu(>OIa9MSa7yCTW#gB=>cKe{*(pJzMFq=dU61rppM|uc)!m|lXN%;si9WNg57JCG@0rh){iw~YT>p~F?fkLNqjBbC zCI9fTUtZ!5#)r(hu0YY&zZ9n^5bcR=#y0}K_>&}dfh0hQ2A%O+6H>NQ$9QSyr+N%V z)MR@lg6^qC1h1#=LKvwsT}bS|y1L!VX?f{!M&Sn5m_AKs6i&Wdlt5S$+ZCx-ms44v z^htRjRpo1qKdfG1(|ETphBn%psw%bjWJh!2TnTTM+xF4_AFM{Tt-h36B@f@5A^sgnPcN&eZqsa zV}hu~gg&X=DH?7qy+=&GHYl7UGnCa;auyvc`itAXh&KKNOhfG^jB83IZG)~-9n-+y z(yRvHB{hZ`CfO;<7?j=nvzmIfYUfyr;MV`M;(uv2_2FGks`kzpMf*)^{%m}E&5piaWS;fz8%Nq=Xv0usA-)Pv599QrwIr9b|OALU0ygJ6y1e)Ag}_Otmh)`|rpQYaa{-j4=^bz=mkKKP59GPL)A(2#JG1Esb? zhlV0;?6`xpF|=89xbgAue>N?<2gzPvjrG_6v~>eL;V#l!|4PjNs(rOJ@0b5E{|5Pw zz-jh>rJ|6LI@Uo3`O1N?RGbVtkoO=m->?-lYZKBPkM9HDZJ|gq^FESnzgg67wfy=| zB!pQ_2u1d7<$a|^$n>y?%NYpUpBnTZ`qe%-bxam%>OcZg5D0aoSmCq_RAfiymYyk<)IyF}DrPy7Yfr6{|I9r^; zSQ|yeoo&d_|BoRy!*^^L{5QAC;sFSH(kH&loW|RUaW!=sD*I#$z{-G<|7l8~F);8* zH4+1PG0YtG>cL|`7d;Ce*aWmw3<$a>R)j_^-jHd=&tR;rp0OCG|9EZk^T}Vos4|L6T%-9iM zrzV)RKZ6DRzZMOV%08!0*8TE>f3>dvBzgyK0T|HiEn{;0m%j4w{zRk6c{BBYK#6$^ z2qm^2A!nJOT%q3xw;-BA++fFrfyV;nAZXD8#iw}^nQw1Q**GSC9zARGzavADuvJZX z<9UyW%spZ*SU#~Q>whr$Aamw_&OJl^Z?qRiBbVL`wl3v%J*>a5(kInw?Gh+Ns=ElV z)w2C+H>pmuiDzX}U1+HQSPjR|vYpv!D7F?`U$9Ek&Y8N`wkbG_8jRz6i<8(u75fYdtrrF!_uH9orx%JuzT`SSaaAN>h(S0%99iXfL zaFzEcxbB|-t|FnB&VW<^xN@wu)*=A7HXPYDG^BX4-XfapB%QHeQ_)O^+gOI z*14T@I`%GcpSsXW!!79J7t3o^BI=6y%0=8|FX=c6j%l6J=8-O-{bNP9*2W;;>$J&g zKK9!Ue`irxKesk^{S%H;=MPL9(T#rfiL|@c@Zr`Un1Lcuf9Yx9+HQE~P}1m=^zfv9 zdv%-anRbprP6aMMsHDc}PrO?^j>`@HM)Ydd%->R)3oRU7co56&w=s-zz=d#PzdhA^ znX|~@L+shK)(EUzpk05QdL2Jn32=PsrSNLN2;Z2((yTW)Z)DZ}mO{re@Efwx;2W~zy7<;urx}B%f&aoxY zZ3-Fy!VdLk8zOGh+yszvP_--&WM0oOW$;gl276Qspl7z%!deL6EbS%n9wfGy&+tGIS@B^acBpMT-=1+E^8F0(3!sJ|F zXpPS)Q?}Or93EkvK=!AxuJ8v3vg?SYS1$mI5Lfy+uoy1pHpp7!@v6%GPSYx1H?&a+ zG)4~Jb#P3I@(>ky_a`Z8OZASA(pnP)vUhTZs`8-IjhOpfcN+Z~f7PJpsX6~>R04Pk&fFVGHZd-d${v{uH@IcGItMz{! z8D%+g#3y0H7}Wfr#gBfAqt@?1;Pg@1ng0o=-?cS2^Pl1Ld~hZH6Hh-!RPpX3h*4H2 z(}EZ;S#)kp8*Y5PY(ngMi6GD7#th`j>t*(_>&<>fr#9-ZH2y_CcHk3}8 z{#yQ@OcIrqKmW<3?M1%Nz$YeG>-}$jVlv@2g@!=u5hj1tvv2*$WVy031V#?p>yO8{ zM!A!Uyu(SX(nmM;Z}e0};8O_^QhuBDF-E~1{9?diJ9RK}jHygK(5uAboYgeR#*7B_6BfpwO z>ULve1bF+a#CpXSq|e#khfnpX35oXXoa9r^6wI;ElaEg9nDHDS^@``)#F1;6s~Xe6 ziQF9=**hF7Q!7(bS@X8bA|C3j57Ov%Uzgu1%=JC?Pp*4^iAE-SJf( zAbI*XI+B+=r}+Q~{|kWBzXv#^S0GVJ=KaH-PiE_PLZxdT;~DQZV!lh0JSd%L_IiU zd`bBN{VgEs;lX#^q95bX8}f%X$G~T`bZl*b*t0R6zbpv+V9)Tqg8)-|3NRFCTR_zN z1aY1^>VKllM!%yx%4JNfx4YtkOL6CAWxFt*-x#^2d!)0@J!?gMPVps#UUk8pVLcB8 z4E`zBGXdNsv8rz<4pIU*<kNyKuf0od)Om92e2=#AoI34J;85v~YJ){xrVVPq7QW zX$g&0wav8wC0*b;&-7KAbu`lnU*#!joo!FjNVT+%@jhte2Aq0oN5oS27XlZ|Ip&M_ z9C?{aF<1X%jKqU9iPqsrUI?D^&-gRwdC7Fw>6jqlL}?xP%`1Z8B+gQ}N$UVN3oa*K z;4$yS-IHdTPn*U)BYIBEap9g4J(FK`;U-?M7udd2jp+?Qort)Oj3Y&NqQTwzZ&1?j z{k)^K@MLgrTE!;FyLHr+jiCAW|N5@I9w6#7{ZNHX4ad-uW+7T~>J+vku+8t2!fXuG69Zog&qDiIj^nG#L z$SkPM*yA;F6*-H&6gw&~&KF*mS>n*`Fa)QN32X%TtOjT_iy^3X0C;%!5}k5&Zj_1;Vf187JF5RCzpQ|0oM|2JAW66F@S-05@>7tqz;P2>Xui zT^p7Tu`>{G{8z-(vF>o{o$Jng~bQ{DIe&mYoBRnH}Ukqp&M@l%Mz&~sdTfL+nE^h(<1qO3eSr>GJ)m|u9^BotRe=mf&i>f#32ZDOHYhx zFM#hs#Gsme(zK@AQSJUXbYUM|pnBB?l!9WvQji!(hn(o@ZcSC5xQK#Y%@S|yz8xT2wUyo?2NEg-kpkoR;je(7u&|g{~D;HXlk}%J6AUKsCw+So1-1P zlKBO=-RcI9Hxf>G$^AB2(8kwB!>h0F%NY{C6D;h|5s}Rlncrzv#Lz*J>lCqH5{o{x zTdmKh1hpDk?vfDfWqb05Y9q7)!1}My-$V228=i`j&^!R^Q*Ac@2j>2rl!L&*V315) z4IJ#iKK=}q4jdeRRZo&b6)f%$K@<kMR64%hyftA!bw;qeL>~6&+*1^{9^_))rTJxuBfUjKK?(66&U8YdUL zJ&sMi22TI`!cgn>4aswCtp_Ya7~|*kVs-YJdJcWWJ&e2kZ0B>0gXPd*z#{P5uJ}5S zkVi014D0cg`j&}~ZuA%U3pA)Q9{l@EnfWYX1S6#%q3@0HZ}1<)7#BsnJ09x!NY1}@ zXb>M#&tb+S78Wd8qcJmI6U>G4BDYK~iD6tAjXVgJG~r zLyd=64OFU@VC49pl)vYMn{HE4)b32 zia3L~_)pXo0iBvn?9=iwRCbMMGZN24vHSk2t{;9I?=22Xg>zqdV`LYK6bb^kUyavMja zTocA$!SM1BvB=qljNIz0SLIs&7wv-Py&=t7hV#C`n1W(n{P`iDE>XJ?K@be1%fgQ@ zi98QDfUq!Pzy+@k^AYYyds(;xG+tvAF9Mrn?4U^&5dxNjn}53P(=f!Iq4eLgL%=3L z!ZRU~Akux!-h?D1Gk8_VkmTyNv2)tF?{56VEYA_s5CO@%zhR9) zXajQU$O!a^+!hrzs7feKlp7n8-W|8B(R`+}sPoHEyKOc0I+|{FnP_*YW}%K|SXoBj z^JRiF1!LirS@*bV*6S>m$pq^Q&BteN6J_PkIv4<4(}q4E7`J=xL z#*%5f9+;Q)Aa4BuonBkg*i-ndQ>8dpK$RyyV1$Bz09!vfS_|Y1+r6`AA)#Z;-=B(R zAqiId^GKW&zy>T~Ki0TDOaeea;R!o12wrp0yOB1bNLmBshZNe)P z?QU8brqC{-!(_QX?+9JE;A8q=v#RT%rU7tNW+LGTcaM!mqBqB+61aO4G|S8S^kt+x zAe0}rGrTEu6!Y<5@pvc*PL$D_FD{YwnhCzZ3U&v~;PD?=N88;6yNNkS0hhJhjixC`mvHT=L zDY7&w&Uy7}s&(H-QNMA4W$R$_HnH)l1&QCaB*@b3NWSi?w3VWcP;i;CG+K&WQ^RDc zsjx`rX1idYXO4ge=8vRrED+7i$K(L+;=PARv+|flz6)ih2+it)tWY;hoJy zqOswf?RQ9s-t<5#yy!1*ti0lcs`QOY17vymi$#i`NIkvL>AhGtKw-~-aC@m?VsB|( za!<|Cuoy{=qPM~+D(Rmh?Va`Oo!6A^*Rz2HZ+N#9uShdvB>NSQDm;f%vcRcnubfEs zLp7+nLtzh~)v@wFb_UWqo#JZ)z$=R9Cf?GRp3s{|+7crPm)1RrCU(|z)-(qZkD+2D zoC^2wCP#8Cdqwy-t(&u8p=Go-{RUxCjO26DXW>FevJ-nsxWJJd0H|6Nivh05?NI^017ggzipB3+s?ukRk&1WnL>K+d+!r*y486t7j zCVa<8m_c9NTh|JIpQ!965!no1C5MD#Lyub^^wwwS&tO~Nh0PTg*cRX=y$>A8hiH2} z)gwL9x}f(iBk6GJxdAT*2PrAO%7+?DTCpnHQEn#1NT$Iazze|1!U9pRUklz__dBub+j0X&B!?2${0x! z#M|T9io=@9JM<)QPW4sZ&}}qj`zpn{Xw#R@oBYvROys{|LTKMGYOvynk!_}hwQ0}z zUKb&9olFs<8*lQbeak(8d+y$g1l4NmRZKUMS?RcEEV1AS1tRV_I2sqwit~?TiVg#6 zz1#s_5^@tC4Q+7{`AO{u8>HIgTJ3p^yw|o)-eZg8x|n7=Bj|XPI9ivP_$b8k9sT!O zF;)>l^0%;|9_~}7*d4$m_mR9=^fTN;P%ly8qpO01yc67Nk$3`WZ{R!cXU(;?8VhZ% z^#mPhnu%0yXY$N@1C?jO4H?-uK%n%Z5fRhC=gR`~ z5cob10G0!`WzBw_isOPKB z3II-r9L4*iAY=vtuKofB_-?>J=k$(`E(XXm#L752vC|Pji63M0&m3+uhGny-hTnw8 z3IQ+8{vqm27y`==foJTh2}gzSjC-1}Hx7W&Q4C?vJSfzezqPEiSnDvnTXy4CrHd>u z{1H5!JCZ@Vi9Ep?5JniNxY_1K2)!75j_f9e}{TbTqVcGVAnM zJU(bClov3v0I(1U==^?fUPUORC5Xc-uy95;5WG6=SmAC$Lx+A_bvF*9wAOa#)DCX0 zk&A|ntH0j3)LE7Nnf`O{U`;qW!87Xfu$ z^#KzP<&i{4%Bt?H&Z-O2bH)n^nOe7-WN?@?*O|XLlvhEY-6Z4>+jWX~HB?5JO(Bq=wZSw>{1*0#pc zr`=)9M{R;9YiGRjS42zj_0xcMoer8qpQQNfUmzFfD0B1@xXAk%eTA}acGEQM;+tew zq4{@LA^6x+7Ssm%--7nAF4);vq`lYmo9ZLxeYjH3pD8K6%b&|c8jxl1XEQ^Qi%h-? z?iaWK{QdV>7u=e>4SB0Mcc23I`M94srzsx#SI`(Ih4Q0biCp|n@zuXXF3wZt=?^Qn zNM@c{CSTydi2P_Ny2VMP>;j7T3!&Y?de3^F?|_fgGt034$rKm;ZRD{llxh0QaFG|n zIYWtr!lJEfR8bF&<3$I=9@VS@)0&E0)a#H@JR zZe!n}^;!H#{bi!YeBn@;^RpHX{aAjJyZsL1MB5D3qJ5JJ&522Mg6T^W0ij$i8JsvX z5D?1WDkq;w$uG4oVff#_;8CJMIlGE>*1Bj>h0`P3LfwQnx!~QbRNRvO)u*U}i z6!eD#+R6M<`f+FSPqXm{hYIqr=-Wv1o80H3LXqb0zpk5xG*4I0QBFXb=N_M+zxfld zr33dQ#s4l+Hq70X`72VkPWjshxc22?RUrmUFy5OnHf09?*F?I z4Xww9FFW6fFyG9WGGDt8`cieHRT7Tm(0;S8!~zewsMOh7q?c7UA4+IQPTsO>owwi_ zCO7t>)@exzQxIFGod;)a>?5rkob879%OjTadEvh^ljQr1wm<;J9dERQGu@qFbSka1 z>y@c@4`sdS?LNnp%Z^wf@ZXN#EM33vMCxs>)_xy4*5b%k$r!m5wpZm2gce5myij+9 z7Db%oDnbjo`{d3l3_Y<3_;P!#SAw*0R8Uhax~& zKd73?;zuaZ)(jtsXZHnuFZI|$W3$dL*;=2;^|5sK(${7B%p#WPn2#hOyqtxW0!MPO z;y|*^0<7hoE+X0HCxfSUUrmcMMx8nodMZDld%#U7|0*zn-M&MJvVpT8tBjjQLSMT@ zVvF|r5kC)1Fuiw+Lyt?;kgCtbb&pH5Jnfx^d!(AZq@>q~p3l9;x9<>tjw@5yFDa?D zU0kYiSTbrigQ&Zlt38oF9b0jECzRNsID<mG?z3iT=Z)9Jd&`dkXH<$Tc2 zAes-;qoj8l#?`$(0{Fcg{ErG_6HeA8)rbQKNcYHDsPXX-LM3e`j25-@%WU|DoNF=#l7vTntJ>~69`O{GznUt-w z@%@pD@_H8v`CkOO<@Fv{z5@lBj*WKFcf!CsUr=$5LIYZBf;-pcAtWlkjlbXy%0$g7 z)CO0$PS?nlA1rr!aG41R7 zO^EvvRI72bkO5~?(|1BXoc;Oxgzlhn{w?)o)^9+x*QXJzGk}A&wL*)#yg7 zasK3=5l*Ud*P#D^UhjRkVKxe}C5p&RbxB|%;pxpv`&^dfwQ5mK=#<&<2p_s<OBQGh;YX7PGtm+Zn`;u4d!Y7H6)otvML@vI?I!hdpaCZet(y^ka<=bmLU` zRjvgQMa^JzzGy!63>0&CWz-IY=sIIY&KO9W_laW!0@IiWuw>j=(U4016SRPg0qNQRRfkcM<^fn@vy?aX(qpii~GDgifzVl znGd^q_uShUS}KygJ)l^&<*wR@s>-k~wIp+=T^HHu8+v2!{W7Rs73X3ln99wZx?u@D z#rjZWcXy>lpu-ud7gk7+$--<23OM!-6w+X3d?h)yuvR{QHhMjmIch@=L5scgAGJiw ze0nZlH%QSKm-`iev=ie#YNHpV)4eQhG*pD0QqJRAW!iXJx$f@EHx?s?yPdsd)nTjo zdf^P#mXjTH+@a)}Q$s%wapj|#HCdPPHKHs-YwzoCUTKV5Fxx0$KMv48YD+n#B;O?^ zR*P^&vJcE{a(>|-q*Y5Gz6Q0bZ-)Hq#CExi8XSI^Z-4xW87*3xT<~S!pjOXup8rsS7^oanJ*v+WiVvFChhIYSnB|vDWHfL}>n2Ltj*DvE**EiH*ocUe0)pgK zq)^Yqp;HIwDE;hQ{zl9}(}_zWtgw>TV(WlepK~<)T=6=w@$Kc0vJ6z4(M27|V{Fq` zm*hrFGG{CBB@^UT%LkX`HI(hcFifYLv3F5kw9c2P8$%R)ziTSOJI5=(%N;~J5HOw`MAoS9})J5o@j!-*1d63uSNzDxcP^TjfSSSvD~>-)^S+^^miy4X?6N?fzKw&V4TTCtA8; zo;a(J@-4y6A&`66w1DuF>39a`0Q&-=p5~#CRW`g~*>ex{v0lZU^B8sD5nH~p{zJ4Z zys>N__q1t--fKXRDk@R>9ISd{|M+c1w)bordTnq@7E=8@ZU`;Yut@wjH}~5^e!Ld> zEN*blR66sfe5U(;AV0~3t~_lZfFH1FSI1&cm^gIffW6_lyP`}}fc~Y*B#HKp$R|9i z57iQP#$z;yhiaYwv0(m(T3!QmaOefhZ1)07iw^H*JzM6Mnjboobv@)QcEc-dYA6uE znoD18$u>+AV+$$M2^gP5%X8gCXuvXe7lEBYsJFx@vn1HN7|(D*AFd@X)njyrxU^(~ zY{FW@C57xruqLt&ml?W=e#ms`66@BG53gk~MbJ9`n(N#T$HiWdFS_7!fqUK3L3(nD zbz|rWuSIJw3UtuB#H4WdglVs09z8Rqs^2)I$hPUr*BW*yRZl!dZFwyY^(~lL)p42c z=vd1+cKY#51!Jpa9KpvS(0at=N%)H^7uDg2kZVm z`m4Ack5LTI+A^Qbc;6+|*@B7@B=mavMk|5c_0pP7_>htx!)p<4N39^TLkRCsZ^zr! z3Gc=REcv*_xhT_g(K~T5erKX!k{te%qrKugVFvY(a)ZP__F2V)OIi5@Uwprk*LP@I zb9H9P@6m^#`eTyZ`u%s~mlo~r>pK+IYX3MRdS1tAt$J?Zk)3ITdd?iO-Ldflxv6ep zQ9IAT z^Rp_yB8LuirQ8qG50?}knzXB-Vg}(S_Qs5M?;;*NpSd$>XYS*~Xo4GSm2eKe|1mH2 z(6rvW86|nqAwb@oW7K1WffYRU1NLHqgMFaSvZysVQ~8-UQ&W;bzZ@<&WDaf=_(bjN zn|w(4!v68y=uOai_gun(&J)o3gi7DaZ)5S|16#W8ZTJckS^~#)&>+$*p$vQ->zhp{%1uNkJe;NV_y~cunH)zDdI71EP~`pGue5 z2=Ruk96LglePF!T@VcC%&KGWWrTD=Jh@UMF9RB%9d9;t4e4TKZ*AkGD&@%s;Z0;ef zcrlRBRd39w+9=0&zJ8g|QkLcM8&TX117PLaj@k-85U;zECdqqaoTYuJ>@FFKoYcjy zKoOpkH)UvihHJ|9iL%(3N?SFJXD(!;2sZYCw#%HM1FctYo=P!-`q_SOJ6~JSEh1gG zWP5XHD!xCT7YO|yoB3O|;xp*~*^+T}r|#G|*cL1EOPr!61w1Ex3DqCWNL%Lo91P?& z%J*b@_2)d7Ldur}+og%l`~A;*&kpxnYwPXYT(*xsRXZZJBaoi4$QG^^PJR z$ZuMEJX^66*t=1mlxce#{X)0I4Rf&!pORlYi*YODtPS>+OG;4jqIZnh3>VaDYK7w4 zt?0{T;?#V`GIRzs@cmlGQs-(QAdj+4|MfsLFKD|yy(D+{Bx;Jnqhx|&&f4P-6eM6^ zf<#;wv=K$1Jh+4k6rSU?)H)$Rz4L#odw#TiQC1M1%ZulJn90k0cll#M27fL#AKj#z*$SNK9FzOJ*&vH- zdSmB+JJ6T)O7jiA-z}AOGvuu6`d9Z;++iGWf2VlqmkusKpF-w0-kcJ~Qh z$6fXq4dMB;&VO-Z{)Z->C-gx?I&rq>@6;QLrmeJTgb0T~(P4@k*n!B5?gReGP=U8T zPTBOP++K8`ul$u}3clYjRem!>XXej+(m?VCL+T`{sxRLtilSs)60H>`q~y!JI9c9% z=zeSEo*W>-;;b}Fs_w|WIsBLMTSJccew!53KSGvcu&-=V<-jB}kam`WQk!|UJM`m9 zaw8|1|4>weE-Ka<&MF*1RVpPx^|rra_L;nKu~@e3%WHLA2jZ zU#oBM7-4#RNiK1c`KBWCQw10QV>M9E*o4_*x_Ak*Rv3|z&-9{Q_U`dVuVs4X@yqsE zC+W$`O>eLcn20|9tGJUMqZ4`VFxYEdKP2<`$b9@g_h(v~fh@KwG>z|Ayeu(%AN%ZB z1vu~Ur!b#iFnyz6HIS8pD^sp22@u*F7K)1xy3i&5;xk7EkEnveJ?P^71EDGWVr9)* z!(pWglx2|D5?t3pw6E5L6w^~pGsqLvIXvPv{b0$i!;^L$*$E3GU~wLg_3+OH!Kr^; z5Fq(~xgb#K{(3=xaQIgXg5?bCUoQxd2L5tE07CrB1pyH7?-m5*ycW?+dQi?E+}xWY z2RaxO>mt34^7z1Ho+wNoU($7OlKF;$0Ya9&#rjw-gQ7x!AEovU#-8{{i8@sE&fX9q zX2OIj&ipM|u^P0fNrJ1(xkF#ty|)kZI_|#5D2vB^H6~*sF9$|Kc?R8;m~W}k`M6mx zmC@}3t%ppmU{Wa=mi_EYpvSgKkwkQd?qg|qX}vk*jqiswetyVuM(w*Q1qw#Hu+Exc zy>1bbsxDbwgiB`z%2M*n2mR5lWHI4zgJs<2qbJ$9I|SpZ!~1$x)MF3f`8aFtiEvd4uSO;KIR^S=pFh z7xyUZv1gza`H@Mx(kJbzw=cWY#Q6eN1*-;L@-97~MEu`X0ix)zDgZqlTNV86zpM&C zihs2#K>FaXRt3<7l4Fsh6Z6hai#4Uq`K<7E{9+UrCKZkOB*dzIx?wrn($KA!vTf5Jd?Mlh7 zniYQwoI(& zFW{iC!Txc1G!a&uy17I6&Rl5Tj*K~m9iXNfw~>h*8n49Rh)%|s4KX@sVY-qBcQZSa zj$_1@t=){WaVhyWvut5O3eB(NQK5O83pSa?O>&}t-AkKSac4b7e-R@ywqosyM$%_s zho>q(m#lnqDm7`l{+Eu+K8cGXcBXkNgBHxP-4oW=gz|lAO5O9u#y&Kq&uB8rxwZ?X zM8l=4%c67@wCd+pNoB>(xSJoXiER%&Z<@Wlk~WjMO@HtA<+goo$bK1{ND=upp(@`eMaHzSg|iPqSU$UwouB z;@x%r36Ckpqp_}`2E1V@;3}sc+a3Ax`?0M z@%=#6>NkuS^BdDw8&RbR=H*eC2T@aHyM}g8@)JZ(t^Gq#_f_;HtEpk_T)4n{Ee^CzeRZ#}xXWX}`9&JC>0>SSoY~qPD!? zMRyYu9!Fmrd}O}*b643$@yGwe-FrthmA(C=<5(CK!I4p#5K#dY5s@Ykl2H^yL@cAI zl&Dcr5fP9QNEt;zrGtuy5D^trAR@gbA{s&sJv51sKxiQ(0n(GZ<9y$B*YCaWo!?q_ zt=~U)ot5llpM9SFlzpDF%k$Z%8WWM4SDx?pM+1Av`1x0qhrL$4jg3_TvLgR@>fUG% zV%OG$5#}AYQLUT0gW%`m#Eh^1lght@8A%dR9`Fu@CO+T~33M_)pQ<6YPQYY^dFJ%7 z3`2AqU}4+odn2t|Z~P(2N6()v`>AwqO-yfTyYIphOz&P~p_N(tbIq30@juQ5KSI$Q zu&3U%CAqRn9tgtcOj?ohPdORiBzg*0et6=W>$wX7+Q)4Mz$<}$I-$doxH8jG*J=w;oIjP(2`Txo_?&zSp{J;KHp{3wcCni{1?ZmbZ6R<~L<>2e( zD!3?&8f=ARBU*jYR=8s(cj(8CwT^lL{{$l2xOf&+eE}a*Fv0pr)nQGrj`{h# z!aEk&#$(l3c2JFX^%lu|{j7&Crstq<)Tk%hLgqB`>iKDm4QSQ2>Vbz?wT9h7{f+fM zKHO4`B78Adm8*gbThOL}6v%CZ6RcaRO5(RvdlaAwMIHS-J}R*era}jd5my1m)&s^Y z0As;@zRGJbPyOe?Pj3^k?MyM*R&3k-JWa{fQ6NsG8uh@`+!1C?jPGW^ocp_a{^MXh z=`x_Ev5Mu8D1Kq+D}24VDp3XSu;V{W!9fP#@|dWDI-=ENEe5SSQIo4mHcEkRz%>`}mvxnDqCLW@N%8{|uxh2_hDxrwfKY`%J3vXc zoRM@2VD9A99JD7)GH-M|hGo`ZD%5%rR;nS}m~dgvVQ+Mu$B5Pn#C@ceR2yUj?~QIs zRI&xsKLYN#4r&Kzxk`h;g}Oi+=76h6z?H{^f4IUqQQxM=U;N+M?5EWuRpl%AQHVOp z8rVvXxo`()4QebKp>d7i$KV|H4NxR#nxIZcC_8_=Er z8&r&QkLPL^JjHK`XKgQ$ZoCG?W&c;!Qd79fIjkDUy(+S8=LNs~uM--D z2mjYI-8iA{lm%LKL7NyORs}O4J^na;gq25aO2g;CnoonCcD`RD^*Hd@yx`YX zX3DQzUa%!C+~_bPJrC7jaXdJl_0BRY_qm^NWoNkj`p^&L)#085>Be{iv^w~#|K}ss zjyC{#*}O5jgfU3#IfWOcnS@h#Xwo`EFngwlGv{;qy_>W;cfMGzCdsmB7(f`Iez~mG9 zBLUkW*!#1Zu!pn16IX%e&}t^t_->EZ{Z0UXzNZa5#^-Q7?0LbrO*!i5^`H?vDqKx> zqCI(v&zV+o(~Ax_+GUa{`Y+GrsF#(iY_=ica-;v-pZz!Y_TTMjk1l` zTV0i0<$^ob3pl=zaHF7M;CBFXx!ohErb;#JuRu*fLw6JFz++SCPFB#P08{J#!xSE5 z050>SN-wN*W(nC!;tAQ}e{na_7&WE81J`_{ege+|Nxt7f;GBE+0{3u^zfQ^3H6Rpi zB>fOj(hC9b%3eS_KuJ?STjKwRN5q7Es!VARh;$9mh88fB12EH1*94p(Jm){H@!xHx zd`6BqtiVNy>Igq%EAaOOTIeUrCn{f8sxcfn=O0e$1SK%PaqVviKT@RU!(DI3m}wL6-b>I7{^ z9)e=Ym~}mOvMlqjQbfAfXV=Csi1AZ@dgMLr5rpdtlK(Q!k1?D2Di7b8B=LB^6f-5Y z3)~2OOOaXj+!+>-?E+OD^cykIo;!t@%Nt0{q9e1A_eV=iJ%VHU3NL-!MS4nVkY+G)K&jHxPCKJo;`JyJ&AQ7 zH_DuP9!{5ewd#$&94h}yZ(_^o%Yk0{U1Qi!Q$k-aJi&Q`RU)3CpOK*;`1UJgg-Hcs zbR_uRfm5R6h3p42N?v(P{l%fS28OBOBF^o@Ve zYv1RT7MRb6FIA{{=wU+tQ2$}RLS9>7*Ad#DP_#sj`Cte3lz846_P}J0a~-^u8&UqI zUyZv`o=LFN8T34DGiU&-Bk@oDl%)O#b$L(6z%d-Otq!jT2jgI)o98oNe6`-3f55JK` z;^ZatX3f%&i&BR}A){58@P-N)&f^476xf0-XM%%y&yXw?qh(eV+pxsK%9j(k_$V0% z7ImWs*EcmBhCf;2_@aR0otHo^>%99)Z!`p>4r&a0&j}CxUJdqQD%|y-DcH)_BWxdEO48$em6}w3f8Hb@eg>;uQ^oPvV`URnXISb@t zC3f~-jU`!$pjp|xC_$+-JUY=M#Db4&Mn4`z7*}sjnf` zK@H*8=u!WXL&BC^d(Yr7#ONM*QJ@s_|Inh4~de++a&!+@DhXf z8Z@@8J^82T|FkJTI_ZSoRhj;YHo3F8oO=4rDzZWpE4Yd<~;FSfA zJ6?Bcip_5y3_2KO2#(9h32#bu(g!U^4?_<_&UMvVU6f6bRge`AtRwWW<=6YdyU+W$ zAt%m}+e;fu8$;rH{y-_y+Kx11nz7C9=$nVYaY^-ipH|h%%9WK>fg!qyM%`}l z*%`^;&~+@|RKAI`?`FERoQE!s!IEg2+&O&Zka}^*5b`?BZ3e? zaO8v>to8==|Ed*XiLw+OLr&CFVv^NuqV*lY;i~TnyNh0idI4Mp2%k%4 zZfSJZc7(XWob|JSL>pHq`25-E* zsOkXb`~Kp+V{Rw6=O%+_Ijd+`CfZJX!Ch1rXPg{CfuEg3D7PraRhIHsY|g*3b2gMx-1Awjc;&kQO-hcKu+{C`O#7wlkNI8ez7?#4>6Ai-QY()CViOBeD&KA0J)@5ijnE{)U#AmaTSV>^o0GlM; zBr@Q6NzWdWZg=O^w?sacZbRv#^hM^pEhVU-rsIptL@Rk{aHKN9i?NgOn?b#nnI(mymY|lLl|?34n`t?cz{F{a`TTz5#6fawK8||a4?QRN&8H6kek;8imP z>Bc@zSiE!z|7&w2BniIN%$RU~I7l}!aYhb%D}Nwe$^U8s${h4@kv~R_QlA-v&EB;| ztH&RDq>?t_8lhYru$ElfqJjHXW5&kP_8=HVUxa?+4@noY!u3SDyom9KHc7NpQUiYZ zSG;_S;!l|#Y774>JjEu(#@t=1fzkl`QGbP}+N72z;fxgfhxZRRLAeBG0h3N4rQm$C zz?P~UCfL+f9xF8#1&lu|PgWQy9EY8T+iLu+^%VoMk>ywm{;%Vm&_Gz)_`}sqsLij3 zS>Ru~*K^}tuDcwEw}b5FaGL0r4x$x6EptrY<}LBiO@OFM3Yer!2H!w=+_k_%w1ZOmPWp#o%ClfWaZ}kNUKb`ZTB!ujGow z1k6-cS_Zsd;CLbDLmqL_33o`GBcHh8cah^9cjG}}D`TTj(!0_ck{HycUnVGK_{%@H zN03l2&?j~wui_wfjby(i4c&Bn+ea=YD|jxyHX!pRe@S$&qn zM~l2&}5;!^OwkBuR7ny9Os2{R?isvtw??fE|HVssDH9K zLq}lS09T8VHw_Y-09Uds&&C)g2+);N{h1v=f>K4Wis&PdU_enB3pG-f#myQ(lAA%) z>pnqB!X51k0&+}tG z1Ln{#MX71+ES`)78&C8(09o8WNSM7W-w8Mw?4mdT1`y{ZBMz;I6@U}89g41$TAlQ4 z$X+RRy_q2=P096lj}!q_sVcTMbDvT}B#bHQ&@TJLy6We6mSu^cdW-1j1Pi{vmfeEV z4P?^1tXg;dy0ByLfE}L%9Ytv01^zp`MXXIUr^1e8`*3IvAm0{z)Tmr(0RD@U6o1ex zrqRB8D*Zuo%j6s}C~sDt$$ZCD1NDUvgI81{m1hJmTxK5wmRJtPNuEHFi~OPui$rKL zrw^Oe+cI39$gr=(H&~Sl_({-jl)?&+w;9w0g766<@<4Y(@EnRTR8vp@qu39^|wO3{Zgdn->XIrmN6LQ~#F z{OKIZ8l}3V5x-U*-xXUfl)*SC-^Yg$s(gr*I9}UHRgi|*{<#}%M84B}EILA%1YJ}+GZg8KK zQt(>1i`-`+ln-$pXVF)F7oB9do5G6qMZpXzNSB~Wxz}T|Gx^>>WSAxR5r865Z_9cbDABBzU}83?CA((Zp3$)_PpE2`ZhtC)VtH zrZk%y1EO0WOG~*lkiMvC3(x$PF}rX0d<}Tx%RAi}Y1Q)5hVsI4{_K@*eYhk(GtDL& zkRr@Li3X(&eC#!rWZ|8IzHoJ{dY&tr`wf224RTuFXsTZ9+)0Xlf=e@SZ|+n zX#&^&%_kv$2U9Q)iwc9xxKCh=)5g88syetyw3(CScFk*~d*~wbdBcGK1H^mTO5WuG z&Q`=tRm}axlZ_tN6?f53%;$RsNQTti(L^T+iRlOWx?OSz>g^(*LIXh|=LKOo@eT1c zg0tjy8xYQ!FZ1G=lG}?xueL{SDguk)gQYkpA_!19$|fZ%yS5+(LZ3}b3D`}nBQx}; zlwI5|tbquNoUk1T*b09sbD8nKs6a^4D=j$}kQ2_geg4FDYei(WWl$2e9pQ!i%{&b| z(q<|Rr73bjPUPO!-;X`VGG;2HH+n?Bi$KI2D@1<4=e(-yZd)3~Yzq2Ns_fWSlMY(z z$A)vvKuqRE)!Jt@&!q3o=l#g-gj9sF83+W8lCBVep;tL2AURFPQMtsPY;?VFVRhb3|WVnKyz&FBE%Rv+Z5aLPAlbYf1+W3akQwUIQ zi^56%T}!OagD~NZIKxSLBh`A3B~NZ1JzOZX=8?#Xad~dkvNjNb(1;4Uwa$JT} zhuR8hFwx|nH>pI zw=pjfWG5VusRcAeE3xvq~JSRfFR`>#qOjFdn)a z54x*AyQ*FP>8gU_Kf9`bL*t-O{P>z;uGR&CO-jTv(PwZ9whdeW;9#2}FF-{xOmNjz zo&nR54lUw1S$H#kT<@k}HS7x+S;5_#5EG6DbwgbA-C;WbnM5PV zL725mq6^k2DKQ5Y4K-J08oO`BCjr{VDejx_kCi`Ce-3Vs!0tmILTy2j|LUs3Ou?Vr z6!$IoEKtlh$=w*Ql-@U)x)tvRi$x!Wwc3M$q*pbGpGP&skKDZt!ovW>^&SWX#=YxNPRc7C zv-V}Bzor?&X(@zUVglL`WYP~2??6q!#Q~eCo9Rj&l_v!lQH|*PiBF&zXisI4qr`ZC z0}JJ4ia>8(Q*@N~UHL;@bdy)B`~ea9fJiY3C75?@7-Oxk-Y0W7B>M&ISOV~68GxXA zDhLa2%tehlD|M|eI?h9a%cOh3SXcx6fa0agM2(;@7Uk@PHJ00(S(x?gq|Ud|1t3Ri=+6Qay@ z@p1D>1xoO1^rO(XPSP5w9?Xz#L@F(nmi%*ceEE9-g+A70w?mO7)dQhY0%klDLissJ zPR4BwINFJyiGZI}92nj&?-#3p@B1NOz&s9`1wpA4rGXTnYHLpg*2W28qg_5;E0(kg ztn~}>WU@(nUDAebIk9wjJjXWVWF*|vmrr|qj$>omNY}wh@Ph0B{~Eg!5=qwvU3zWa z;Gm?JY7Jq(TY&XEl*V$+7O_3)H9g@UY6IAA%0TQ$#ngUztI#GAGJRP7T^JS#_j4Y; zR5J5=%H6mF0T$8{L zGTr0hrLvb*OllmwSoRV;a^vU{s=PmP5n6DBE%E2{@hjGqa%i>wR8HnQ42jT}rC2YN z(&Rn|gB}JxWFy%7u{5FgAoabwGNgWxdi{{RQ|JoPBR+mLi*O0Tk1gtZFd(4z_VG)W zlmcu<87t7?I-MgK$`XX+VMw>0h}26#%GKb*uOE}h$DGGWf8`Wjmt;1#Lf-H2mwe-7 zz|TG!5a1EkxIa{7=@RW#YbF|GP-xPw2C`jM)FROzU5|s^iGW>KC|J6cPlk`wnShL;9H8Jo17TX zJ%?Ad4jTjb*0AN^uro+uA+fdeI{;zGHx<>P$?bMjQG)asz=dS8q<>=f0z_I{m^HYW zeL+V&(~XG|DMu&8>C$jz5zY+*Dph$V3qf%o2k;UUHG=m7P{G2i8-~*W`K(ZUZ9r7E z3_9x*30HBHpoYIMViSw)Yv|L`SreXvk{qlw0gY3V^N=0J+9_-NfHj6^0FVmn6fOl1 zDqyobse=+TfJSS`D*lN^BRL>BgFqZ=WYaJU)T1xF_Y;i<<(ezeXaH4`QwCoWJ$#;( z9_&wA3Mka8_hA86ikjxzkJZo;FSSo3)-8Vc+-^tmIhvIY05s{DVbl`Y?%gGA)$pwd zyt4Z5kmP_CrF^sQ6dNUc2DRwR^aO?hV-YJ+f>K>1A4j4I{+s7{vtEYP(PEh=fLn#V zxGn*R*+lj981ZDy@HfAj{V=!^^k?N`h-zSmRbYmL4MkWW0cqmY7TGJrPKqvN1~^1*(-sf(3#!#W-8%#^%R37gfGMTC4X^$~%qt5#n$j>}e9M-RW1sm+|yst>L1 zR~(dkNFd#V@roiI>9Qw9%MSF86BjMkW!lJH{rk=S{ChPMm-qif)JP2f6;ZPY`FBK( ztn=RyHE^^44Wfqk@3FJkYyTQMyZG<1vmfc1{~kL_{@=vTn*4k0EX(j;V`urj{~kLF zwfXnhS*qK=#?Fq0{g1J;67YiX33yy~3-5do zd`cFta#r-`fSP%<{>8Vqk4uVzku(-UPBA_BZrF#7FLK6UgDg5pp}gxhMg9&dT`N zPmrUqBxs!Y7e?}F*xfP}ZAXA|Ihe5)p7|O;Z~)v4{s8?OYU{!svWll@+du+XWa<_k z8@MN&-s;dI+ysJyJDBy2DkmWq(a)X$^5*1rWPC%X(boXu$=}I2AiB39sUcZC2R0=9 z%>?2)$R)Qs>p)yG)&lc8YbPohaECodFI(8l$jO%;8aTQ;8b%gs4g7%27m*p@a^s}L zEs%ql5^m9Htg64Ujw2)h4Fz~aR7%!)=p7IpzgcvESJd60jXyuu(6zV~IguLg{?_dQ z!oAaltN{psRkZ!EJK_Tjm($oi{$ODZe;us^G)ATzHHSR}1ont5d0VGW#^s(7y(`JQ zu8OJRDzPqnmxyTYB_QBCrbXk)Ja-FNeUp1G8%z`U>f+rp)&^v~W@)(tkOn*!y-TD- z(@=|e#n&RU%;!a9R+rIC+SbYCWM2Srz&jI@&}s{nWX&@oQAy?%Rfq540Iq{|N%6Ua z)&~Z(Ca!=Xdys=K0Fodd!aKm9T)JCH+{{%Sxaoh$hfKjZsGYW zjC6niD5iix&r4#5@QMlPVVQDr#EJ+&d2lP20E;Xofef(xcV)^mE})p_c`Y)=d_I#L z)@d}OVm#?hE(TWMY@)jnU`vy$SM?4OTg0;vsKA6uE1sa~umGS*V8a z!`LLT0mC_8dSRf=A{yHwGzU@YHCr)5;ky6517Z_C@4`M?3;R z&oo^+X>pnW8VAN@N3rSR^$c3R^whvEFr`y3Tr+Sl{LWTPSGYM4VI9wtNy|gnV7r>= zFWD!M6Bij5!THBqP0f7(HjeaIYAte`Dvxu`uX$F+0c)au(p>=ZwPkwSQ8*8M|N{`sULZlUBvr%#Y0+RN94r% zOB0E47bHdfX2!VvKKo=vT<6nr1Ah-4N5UQ-;4C=LU*mPmfU`ij$m68HFBp^Y=R`XO zus2m@_qm$jUaE1a8VEN80Va6q?c^vJQCRtfd5=l=S>(?&`fAaBqPFG zFm5n0LAVYE#AVa82{~>LY}`5*$bJA7MluN4ggYoJJ`lWH!| z$%6$_NdMC|WoMw)o5g+DrWZIq$Uvc6O2)C-b;xE*@*HDIy;paXL1IG8aQnkU3ke0U_k)X#6&j@U_l6nhVOgb ziST7Ko%VTHb}BCWgO0~PSP<`c6QBSO1CCSSk=j^p;c1^IWj%4(VK&2=Kd=9w>jB&~ z!KrZH@RJA|#?)z|y+0i6Sy0=eRTVMW0y%rZE8ZV-UjEw|xl;&`pyrD-`T0uPVeIuZ zz-5B@?ccSl3e9g!r(^s9#P;_P2S(LtpO~^WaoM^$Hviy3oXDl15&VSMp7`$&+yBF0 z8YPkcS^PXF2+0NVT4?tl`G z_dj(9K$wtKykDo2{7^DitL#*>G&yiQVBoyO5L;c@~wB*Br~Lj)fOu}2y>3zP0o5__&!G2GsN`~H*?52QC^O;PyVU% ztfadsk!@^OhM(wzmGY1h3Jb1?d|$aU;Vj2uB=O6%`f%EXEcu^Mx#KEnu7+6MIP`5V z?${l;FhMcDUorA+SGQPwPw2%g#XhljevN9WqE2@B%_sP7#M1%A5A5Y?pKI3@QH$$c zFDsTf-oY%wDWu{BxHB7?DqIq+Qn%*-N5(G+ssJdeiw z(y6H4GnR9-FAOe!_onca^T6~bQr)=rKKG0u|MqONx0>|bM!k2k%0}LnKUQapuIK(W zT_nTXmT_PD)a(2q7`WW`%fvMYY|Wc7GEigRX%N7~8-kHSc^t4zm$;ejoESyr+)FORE4Tqq98ZtJud z{>^UQw8PJC(d@KbD2dkm;KuyWcDHT);clanfdjJe?{>)89z`W}#_N^btg`mvL-Hz7 zm1Z}sRuwM!y7zP*fqQMv`+98A{a#@Xk?b#x3uZi{Tkt>a4WrPWZ9(wu74+%-FaXTq zdrr|j9pw;~e1jz~o1g_Vp0M(jpOv!58yqvA%M@y&cF^RR0a)?`~@@q%i7oBubkJ+=#tD<_-WHg>9KRH*Qa|9kB7Y~^r&UtyEYkO<=ni%`_!w- zX7$YDuWSzz#|!J2Ca#uY?ScM(k*W_&v&WFL+a69EH`46(WtxDW9~gaXN(?M~`{f zE6}>Jp!XoKH*EX(QTm-GnwOsgQhx!ny1Jn&7m z%sTs??|Cm2TXf+jy>qvha-kjQ=Y?3)gxLhx*jz^B%$pYo|&FdamA@?IQ?47 z#o%cx6{kVC4t3kI6T8yj<-X}8)W9D$He-G&%|NDuc zVfr-uR%p$xDKqxsiFRZm(J*1@?Bzx9VpX}vUi*QvGmBpNiINkrS(^k@P~zBg=-S(p z-YQS>S+2;~tfr!bW7D5jhA*hU0{xp~?e{I60zd@Wo!z z)S%#l{sY>AE&Eo(i**YcjGV}T5*e}22moqYD+P6DaITq=jMClm=V2}H#Fdx6M;)h1 z1>er7FbGn6qtLd2x-ct3tOVfEO0gf+o+L(kzm5(1LlQ6B6OhJQ&%y&>ij0tJ3o9zbFkcZAk_&MhEvI>-mi_y~XMj0)0 zK#O9&`Hg$8pP%s~n)pcT4BqY9wf*L;mi%rA_UcLQC;OPU3m=H*ptxD@cZ5AiaCfek zoq%w@vmOn`hwq(8FTk1lgd)wvH~5cex3NYG24>QNaOvCmO6y2^WNdRO?sAN@QFb!{ zD?F=c+v#(x_ELPp>9e zhGih~bud46RFB7ME;8-+??F6oXoaUGVmT!VxSggU-lBD_nd7(l(#{TdAE{vc4YKOB zeBJnQzP&#SJ)cTz8Tw=T{81}fUXHKbK!@}d25k8nwy-4F6ut!0<&{I_b$wiM8}Tem zw5|ftYERw=)9;NUuk!noxQcwt?-!&AMBUGkk+`r)p~8Q)@V6)h5fk#t_S-;G;=Rh= zfzJ_1@MxBPIE*PkkKlhfg^4r z80-uhdlAhfM02xov9>An*vcfcc-zjJ^H?jhGrBsS`6lt}dtcA$O`pYDWqq&GjC(l$ z;$akHZ@$;=ngblfGsJ>MaJC%T5`xfj{BA}*%yFxDN?wM1BmZ%3%DC_iIRIi)I^wRVf|&lTyn^#z{$zLOw~NB(?$)Z-_U+cg7LsZ#tSc# z!qnGr9mxDyMwFye_=9K(tI&*B7ZbSq@K#1F_R!V@$JBRgMuoQtotqO@5>+gXVx4>9 z8N21*2Drn<&=VF3D`5;B8+5?cBSz(gztgl}%{urF+4}}=|Dt3z5S>Ke-YFof&^m=L z)j>6GjHt*C;SYT)ScO>u3cafvg7)dgp%cJ|XsIR~x`v)Zb!$zb-ctkSQRnn^1n7e2dOs+@W{{DA~$s6WO~B%RCYVS9H z#*0z@di-Q#&2)Og!b_|6F}lO(^E#bg3q8N>;>gB`uHcQ+reZ9@CVu)DKI|&miMjM1 zXN_3(Ou)HR*G2z7Xj@?jp7}?$vDAADMiAl!S%nd||FL>h2zZy^w3{C<;q1Xcx6xoz z$ja$su=Twez07Bl>kTsVe1`&eG@RmFAJO%Er_NcELKifi(ok>r826ww*Qzr7W^2Xb zocHTmSbpO~u#um;-@1j;#dcz^e&Gkd3m7L{XRm=czmz4oZ}l#+!LECtUU-##VaW3I z89ZqCjs*^JICSoz@q@v47T#6XE6+=>vo8!=(azw{>7I!>7kLKWfj`pwtan{+Zm&Ua z#^SXR*Q{ULuHcOs$uz3X-x*V^nKz&rni!)zVjUiut~YJ0};; zxwNmxZ#>>PHmZJC{}yd7g{zYPTNN^G>0x4~II!LOruMl#;#&8+K65Uk>I>f5gWG#% z#+MAZ)}38<`-$OnY~+H&7A93bJ2-j*k+?d7TMYlh414oTyWqvg!is&(CY@5c&3b|O z0_kPiP1)Ns{=4>qhd{}!LKDeZ;(w5RAA?U{+WAJ1u<78k*MeQ%lXnmQ{$~5BV_)yy zT|T*KlUtI{fn|T}`$HC+8T`k$1ik8QJI)m0e0{Tw`9sYT;xw|Lx{q|p*w~`+l5x6A zsHZXCdwu=c65y~hll0CKEB9bJ#6FSF&d9Mp;GO@X6D4pkCuL4NJ%xp z2oUc(C6XLJg2LlHdx2nI>5;h!yt^RhsJ={&e|H#;`N7oa`ZB*BDL5b)sX5^@%WbQi z44E7)Y;k}4{*8O|n@s4(%OcCJS>cE4RX#bqymax3g&h51Wqd3dUI+LJ}mnaI7i^SF)xhhyJZm3dAf2z`_KlaQ`RGAE3 zBAlRxT(%#wHcu&7V`D1MC*e=}?FtM^7+^`Nu6mYLkrbhL^;%*ZyDwexqKvGxmSp-1ALi*j2OBI- zl{BbG`L6w0VZ*_zeI=Hdrp1;|?EYZ4N@qsfWC-I`)ko~#?AENyO}znN61mu^U%a80 z;E?#ZK>b4GN8hJGJ!Rffhw{bVlCC9)#Nww8GkC$*AHG$e0!Bj4+6uzXjB^Gj>DD6b zL%aNw#V2npy@}EFZ|R4X_@;`yp0%)=FTpa5_-8{GH8FP^XFQKwfsFF@;m_~EUyk%x8wxqJ#`)|%i8Wp=+q+@b)`7hOPBbUx! zGb)AzUj};u?vdO|?Pr}VTXfO$;~(*(uI88cJ{l|Xjk#9v-40XYpW6TQ$dyQobpJg% z5GQu;r7~2QdWTth3v4LfzumZ+_mULCfwkkRiXdWh8>fSa26RjG9$ax{x4Hedk}J8- za{IT-pY|VqS~s(ukS1z(;-9Ngo7qXoM0J99iWaHPd^k($B^3=9Py^Y^7Qgq{lYcP^ zmj0OfjiHj8XdYGV6sO_kUEh21O5{sS*tH8eZg1HZ>7lLnNm^+!vS<@^u}Nw_?)eeV zALOc!muJg&V}DqETJtgBf^ENkpAAn3e5>%XK016PAYnK7CCh7^%7O=04{N|QXIO4; zO>a^6+<4kp;#Q;H3*qS$P?-)z#AHF8_{=b58Y%LeQMnqM4##5(4d&k$H4_Z_B6iZ& z-pG79y{^of%NZfQ2lu2{AA$vN#BJ&D-9pSQrC=X#gdHZ%X!lTH_ zr%)Fv8PF%)JU>nKin$ivYE8O{oc`=(Bb;f^!4`b(&8uwdnyzidno@cnRo+Zu4Af%3 zf9@@;O!$j1>qMHpG~MH66VAL}i}j!SHcb;*EsHe!T>5LzHBp}qASw#}{u!G_3Sr_; z0b)%prN35hc!~?7ug79O&n~5@%*f}mYIrlX+=#!%hlAWc&)RbM8nUOtkY7HS6)rvF z@M(5@ePshxRxoTUC@-rM5lh#UrGK~GAhudkelyW(ncvbI#sS@U4oy4X;g(Js2busQ%s^!k&y7H&VN$q*k5gT3Cq zX{^~8af_8iC`0*2yx#YVXs2j&h&XJv)9V0nf<>D=ct7?qiZ@!$Z`7QuWMcm)#;_J; zt1GsCp_E0wEMeEKNGrvBFDuvaGT?i35ZS*M-m_$OQX1GrPU25LcBGSnlT<1>gywoL*ENBwhrC;?ds)*6E}blvFPjQH2Ak%&c#bx5~yTi@7?9AoIH@xt(lW zxr7%IiS|eA;%&9r51Y-wezjRzegNzCxnRbV(1Oq%v2Hi8IcO)yB(gso)CuyNsC4)g zI%{>C!hXqGtl3O-5bnR_JaROh)b=Gan?a2Igehn@2)mm#nDa=u>&y4w#}{7=5dXTD zThcrZ{A$eGWdQW5*nBXQ=%VnI-uxV@PvI{Q~9<&R%!q zru#eg(kFTbvSN0)_Alw;rN4)67w(z+b8hTM^XI6~X;CUsDtBUj*aWX;MXRBH>Fg(E zhqisn{I(OSb%AN{3TOBw5BCJ)?CZOIbq4fAAM^N+j?men%u}lRNS5jrb>6Ml!M=Yu z;w;0_;{m^RCN*r%w72MMTVGcE_kCjnbzTpJCUbkbkCqlnu zbw=)Hb>1@Obepg=7?o@+ieMrYH=X1sKbQAa*8CRiJGEIBzYez)urxR`xZmDY6CF9u zQIj~G81>!cPNqMEHrkAY<-ymG7;Ti&V1ED;oNO<~g>8}Vn%gOrvw!r5Cgf*YnLst| znD$9+nHT(6l+9~UYV$MnU%yh9nk_S1>vPGsc@=%BUYOI)QO#9m`<@L(-(Y>&99Od} zVm8j>tJ!*=gxz6RK4eZm+RY1^sI)luJLy+69-{z%4^J4*4aMD4Ls`uaX%~jhULOxA z_}Do8dD=XBBzzn@k+11v#{Fil-@oYw&qt(&rp?!qYAK+jnt?8?V9^(HhJUFEAUl$N)wlV{KsP7WChP0aYbsDuq#FxK4u98nm zJ1%edOz5+H5?b~;j>d16GOZ>^EwWYHII-&#cDJ<@E5OI-_KqwRVxo^k<$|+jYjLVlL!M%pbUjaUW}f7v zL&h!D;|1QU3>fEnR^NlC(G_a6mT8AOa>ia^9VaDyB`mkV>V1(v5lY5H^tg|(6T`4}m(R0{>vt{N zwR5pJsZZdRWD|vtmi;xnljJLf-0r(0H)b3Bwt2ATRJcj!)>{FlJ5?`+e)`zx9*aes zH3P_0qY<|~`a<2HzojYrEb(J#TE(4~u;69K&j8o6hu*4vfG=9{Wld6Iq|e<$X?z4@ z?z{qj2Rb`x}G+49Xy6pF0IbzR)&SRuMDz;V_gY@=V zbDB!ivg0~aY0J}=2%JE=dh@t=pJ>xzN7un+9LW)D|#q9#PoEeBauAdB!p^T4$lScQItIXHs_yeV{)yxA0Cz1{bzMY#ijg13 zDT>2$6Puc%CJE8db!fM>le@7;*4|H6*+MP)Vw9+1jjH+BsBzCNYugQ8=@%pSb=LnE zWA7c-)bjlc>(`?+r7ECEld1?oP--9|2rA8T6p&`5$)SYaNmM}KfK&mIk|PM{p@Vct zG$=(%1e6XTw9o?yAw9X9-|zR{Ki=oP&wHOdv$JPr&&--Nv(}o~`!h3nzS%vL^MJq&Mm8(>67cJ}!@zS0?Yyxr$td@l7Ym8I%eMkETsSegn z!jvZqG1@TXIMr0&m10n*T+%qI4UW=G8n5XUNKY)D>6SHXcS7pA2!C5AnlKVf1|PT^ z#RLkMNh@`#CXpRQ&3tAa#8=44w#Z1CdAD)AJN1&t9lAhrm^kVzy_GU8cV~d|aH-6s z5ZN>_47 zbhCX#eU(?OV2S2RLW40%86cm^bMGzbKMtK@N`m3%abF z1iMHKZ#i*K5+^IAn@R1Td8wL8balK9_mhVJmhC_eF6#sRp$w7yM(j}MGDw_gi&wH) z5!o%r_n1xtOD53l@DqDXnzP9po~dQ>N-X;O#A%(GI<+Jm_pwVyf}!#vOU)GhZ>NyX zTw>f?kkz;K4*AqQBRR;0S?k5^uA1-LB0BVYc$s9qt}a4TYZpdB~PO|t*$@U0gUz!+3SyotwejA#N6xE?4 zFv<{hUlKqX@~F_ah*YOz9`2FIAr{wZl^BVa5MG^Ek=s$id)?&TUFDu0&2W957VY}{ zGe`ifO7D8PpBOKsFv#gTXXfo9u0y}Jn>om>RX8=ZZ1)9roobD@Q(`;jb8+S}?%CB8#~k{ z*e}SJ5TG~w;$BDstgO-^ga?s81ATGj$rM~dA4QxpmI0pUs?+pn9f!}0EfBxpcmU1B zJ;IS;xgDyu+q>xt4-T`3ys&+N5IoH5I7^#0arijyrRr8VVE9&t<@rm%aBaZ@af^ch|>hZgwHP=chX87y$j*d>yHcU1{5py zKZHLB{H0faVNVSo9~LwB{)p5~4Ut3&?L~f}iy$SOQE^&rHMjd7r!^PPPW=jfcDL`js}vOSxQ#Jnvclc_(wg29}QeH9;hq^NPi6)=HJ z>}MgQM{9HF?9Hd?{x4X?yU`8CbuzL2L=4((5KEujY=GAtjU95uAfSNP_0HCwXkV>B z!5}?<=y=wste+W2%H5dpGL^?yBg2l79WC5qwitYy`}gwBl05%?zX%TqB7!?Mjp>z4DG>LSXF%Ig(O0^Yai|D zndKZ4u&lAhQUX)1mVc4HOVyIGKSf8$70V(;qtPcw8*&_YBYc&kd!0QQUZAXdS|%fD zY1_~y#YZv5`@(n&(LlYXe)o%66$}^o`20kkMxr2v2N3jw;?CR3HQtiJjhg%lxBF8Q zg?D+tz40ydh;C1pXXjjA52gsCitTPF_A*E%o;N3cpc~K7yy@^wTPH_}HEvw^WKp-? z{LX}H3B;NNi({5Da_!WhV=L^ABh3|Qb^T80O@3z=?D3@1u8)cPpH-aSN6WWLjfNi& z=Lr{BB3_AdUrvb!2?B&-0YVG>Rq!_VQ7(OG!^P;tdr`nL=OkhR4F&zsO@k*9<05>b zW0g<>i_Ch?NLVBSbd<^?blnkl(U+tY5#gIu)0+bcwa-4q0J6#-+Q`g`9RpF<22Y+}DE%TY>9AFra$|N+8TDInW zM&HY@cxh3(y)U8@d7AbYn8^lWPoYli*~K}&sLec>yaR0ev=NiKE4l94TN10*BF+ws zFlO)Z{*9*wqr=uZStj0M3am}KB4Rb zZC=t{{QFUt+M94+T=tiVmnx>7tk5LnA1Gr$O+b$CO}v2dDoFR(o+{NOz0T*tez4|F zqK=cS7rYPI=_rr;59$=yIpW!ssdtz6NP?u_sFdNYW*U@KvtE zPx*oviHI;s_UiV1WMkuAp=LX1xs6u=Ybr?(i_fh10c<+Qgd7LUu5=VE;Rd+^+K3cA zV;*2)n5wBOdwuo-G&}Dl@h0vo&hgbgl^103Rtov*o{VLJwF{q10&C|uE|G+laFJ(F zO^TI#+bh5N>@o+wP!+fjNi4x!f)Ci;7~#{civ5jIu02+3!SRXLl^Yz&+l{7La&<2` za`o;rCaj_RQiBL>k|U_|IP?IfHa+%aw^{RtThTsjsSI&WU~X>|mzIk|99eI9(XvF< z31%Ig7i@+HSF$*geQsr38To^ibA3_?;qDw6(fMRel6ib)Z7yktzf`Lp+@Z~doHw5^ zfnTp7h^!HT5ttBdM3eu4P9!KowkGdj@d|6+AJ67(M5HI)ldd-NccTAXjumEE0c>;ujOGc5z#JhSnY)iwU~6MQa)Vv2yrt1!HW7R)k#}gq zm|5yHt=bd=?6F@VOcm98jf-}ndBnF-h3Y82phOYm3G_L0=#N_Y!7juRG(X%ZwI+Fj zd}1-37oDt0RDnS*zS~9`sUbZ$#uCQQHJM&myhJ`4lmM}ij6{Dx9Kr77jmj3Va(0i2 z!eS{C`Dj=?`i5j=_6M|3dvC(T9mbhD-QMr>?^xBl{K>A*TZ!>`NgSgjL;23@`+4#^ z(fDXH#HmHNu!}OIH&X&ZjQ+s3p&4EzPGm%OK`y{n!?noVPn!JUM05ZMEy}qAd@AZA z`rwHxRMd5sL2kt$7m_$a%&`4IWdD)By_7e|MZdbIM^{Pao+1%2NK2+R=jJ{_sI+bj zgSei^5(t@%dSC4^!{C|haX~1gvMN$5d}j}YLi!K`w4oj-_eLTsJ(ZfPP`uQX)5ios zv$@BxC55SxW#6!7P8q3@xob1_(~CFo`Oqrve;Cvc0coj)4<;9b6y2hIpsBhu(T~iB zm3#xe_#hgL^e-+CAmLg+xGS2gdEbjW6FF+OTAtbDm(?(AUM5+<(a9K3#n|I~6V}Cr z;kv0~XufDnM5CpbN@-B0`i?JN_a;}<_bf&BM&y*Nl!R5!L?gf3-VKbhgiX(qcXkSI zE&o!4RELApJv_799@i84T`MRMI;O7Nc_nphruAot06+2M(!LOMtB)3aMfc*-<_4Tv zjL~YTQi8QcPAUPdoF@)wlqElZCuN1aGdgoxnCxynw&GyLCm4A-sJ|6FAzxFtt2lyu z*>;UmQPQc~$7+w!LKUyS#Xb_Qd7G)m=je2Ecl)iB_WWvoj&{%)XiDYfn2xm>@b3_; zNU=oEI^l^%blMx-G6@r`IL|n)CQBg8yAStfM>Nw}%JPj6)x>sa?6S$sr%O%`8HwPG zY!ZtgGAyu4ejplZXVaScIWH^2k}oftbo#n$rlVd97`>7S+0=&Y3-A)MIpzF2N<>!= zO(H@`bF=osTZ-LLw4F<9=jU|cJzrZyiFyN4l{<)n;-xFm&YvDFK!l z;W*LIN=|^Ca$_6xKl4l3bnQ`ofLpv=<*(%;)Tl{{>7&FGb0Zub+vF4`By{Ek;t7d? zj8OaZ_necn*ctb(S`#f4uGS4cc6V~wygvdyqo<$?Oxb!cwTbl{<3ZU^=rchN@UfyW zpKC)|_wxJ7XRIQ8BrA|FDAF5eiC#VA=g40$d+99J%h79D2O~c5n08BY zbEflm$P7PPq-P!XbvAd;LcT=|Zn0RsB|hOqdnUQ*=-`?|@2KzJ&fbektdodjMc3xRb%J$`d?IpqswB>cBnjSAZ>wl6e(^A_T#0Kh$l zD9-R~!j*YO{ye5=_j1VT9aZWWqsjP|>5e+vH5#n;3l`tLp)hN~urS2+93aW8uIh!w zS=e*UAe>b@JRi;Je+#@Cb#%QkdmWD|L3pon2Qps8@Bzw3d{j_WMvi{UoMD-e2p9s~ z&1toGP#)`*2L~;BI3fYIm;T(Hka!2Kpv6r$0|xJjFD&G@pW!PN(Usa<*En#Wa{7_< z+veVH;g|PoS7X2;d-l7n?!c5_>Fd%Lu`FOlV{0KJ_C+ikxN{XK?xWjk0TYM*{#%KA z+8G4JVT3RwpWNsUj0?PP1sf48`hlS!?1(L%b>S>92RhZ~cB$9#zry~5<3;HwlLy|) zl3MeZst=18`_dB7nFGvZ5dR^yo{4ch%z3?E)%Vrz)%Z60W33-ckMQ-$G}cu^rr%}E z9OI7Gk2v}qA1ZFCFogB z^DuMzLgd2n!$=8bV0=?+RxI!(MHnp{W2-d^Wd(g`F(%Z3DgVeWeYwT zz>TuPDm``}OHb%EUBS0)w~IFz+fjX1r8K6GdIugRSWxDipBj1l!Z3E2Bo+79Bc`T#>6>;W=qITWKz2BQrDV#2SlMm|U23#u&Rtyd!rq_orR2!qONJ7C5pIAe=)TZZDb-w25#5Wt;g~fN`OH>vk*41Nc6+9}x}Vkwa?7T( z-{y2j_#8f~2nbfQzd(c-2{%Z$)*79<(0TI*S|rl%%>1RjTwNvuL88ExbId~rn5MDaxNh@x zL|i9Ym#t3X80J+a8oi|P(2cBxr!Gu4I)0sXh3obRY2S01@i8*p%HH#Pirq11IIeUa zwZyV_8Z$Wl`sgQ$J(t~e;hF5&@Fb&x*ZYmjo$+cOF;~yiU%z4Fw7(Y*nZO%YSg!`$ zW4yp-JwB$H+<+;FvE$Z^(=xLC$Bj#=KW;Fz+SYe2bT`64<~1Eo%FdSNZ`nD z5aVgREqgaQZ-5g@jc!29?GxhWrX;mEGN%e|Mu+mjYmr;nme%|rRL}LZNY_^^jZCuk zWsa7UX6$^^t$5IGcobpVjxm{$vtLsxFut6U-Fx)0>Rnp z&EA&ulVaEtutRU{lj8Iz;F~?AV_(6pUuouNVe=`NN89jJo!Ob!<|W3KMSZ zhe|f~&v-!0FHRwwjx))elTSGh4x(L;#}?bxpN(d6ggK@Mr88}+Iquw?K>aD~wLj>4 z;N*!IsLonsg8l2$@*wL#MAH6qqwGjLRoCOs_kn zV|%EX{e+OX$N5)i1^k9hGur8epJdG9x`bG71I}zYC?HdeybfTX#Wn=%-mVK?Ytqf4 z=DAVG0Za%8nrr>zU|*lfyUK}Jx-hA|hEh2ijOg5(n#^89SsV*ScLf@6y$B&1ew{^g zhzfOM9HZ$Fwdpc-Eme7EshO1F-Z~UBKBo2=BfXzmNU86!*iqUH zo%sh#6q+zW;tU19(F2YxcfR-wc)QY)ymncu7$43Zj&|GunPysTXe z3K0$jV;4>o8jU|{tu90yTqPN*?y0YU%ei-ln!5 zPCH{NRRUz(MerAbToQ^r?iq_9y{_;PDkI5(6l!)TmYa%h#0V;)i<~t{(Ti^*1 z#kgxSV3XEs!ygn{64M-EW~>PODp0AMg+Pq8@ankfSGNSI3xnIpqv@ikBT)Y?@tCqg zswdcr1}+S|RdY5>R%CSNzKYDw@m zOYbc4)d-@k(myN_PEZ|HH>zAyRw>Z+&#q|kjqY+N8}HEB{k2mpTN-WfBdP`|pn5ZmcUdh}B*Vt>6c@0~Nr5rL==mu>#Lh$^P*Oo!LV?Zea|MN*U*FiDLT?ralKNrD0DvH017#p) zPN+;U4EgrbLl4hOfg8^*g_rt$V&g?6Y^E@u8b1zJXkY=YeM2i)t2(6~IR|+=%OcwTH)coT=nG$l-`(i)wXc-}e(18bhns(k6g?2DP%7f|OYnSXmev!V z%YF?+WN!Aov3&55+rJ(Xb*)|brVun2TNNf`$i5-L$u04!RYS=X7=&oqy&)WUUyPCt z_TW5C8M6hGEdQ1n*qTO11~v)QhLHaJySRJWSjVUd9WIlH{fhJ~TRT3qWBZ9^S;!fg zg?#9opuZ1(;5V=u$|#Fczdh18{Wrb$0j~4f%)0GhF!*Mzrx?g7cY02J6!y*~yQHPL zybEHx?QhtV-^0+H6r)#Kc^?`YIWzWwh>g>31c*!yqHEL++*t)W|rh#>u`yB+8F&^2T>B3a&;zh zpnAKrF#6AytDz@QGXwoGG8eV0`^(+1FLQdQSvx@^v!Pwi#iFPpAVC{nilAnJUg!^a`KJuh2*cDWpaB4BKFi}U{t%A$@3qbtvv!P51d~-^!$q)VuX2tTq{ntVp*4&^a;nO+{BHPqW(k(y0iR3i?%q{%% zjS*fFX0MG@i*xSCf!?ebvYB@czkO*e+Jd@)Y5TMu8*XmkL)@pTQ+KDm4?uEX48_?ptSzz7}{1R2Ac+YXK;r>^DegmBZ8E>8a( zBMg!m zCe*yOXIFtBvNkTd`GdEZo$O4OCn9K*DO5oRyU<5guQCg7p9!y+0y#g5^m>N{PP-}? z{XF1>AU}E6tY;J+M>I9xaatefT&VnwLSD(A@Gyu8yX4dX9wO`{E~<^r59it!tdbl4 z-6UN_ep0zqeLK3KU<6NwKV_4yG83Q95iQA6=+*W!-UsqjqQhCLbN=V^z-fm1$^dez z_51XRUY+q1daKZ`j)%=wUBO%5qQZm9=k;Y81Jb6fkV^&wiAzQU$R%^8bDC5&xHGZK zAGgdTXWJQX&9wFVBHw)KCS0J_@vs|zu5=}`8}Bal8FSBv>bH-y_>Dnlbfk?1a)pr6 zV_q{F`%6oxArOPe$GvQ?HxrkGbo+NtY@$Lx?Z-%D5lqU{^&_k~dE5PG_Ul+fx}nzt zoXwz3ebK(u#AHi$na2z>?5TmTO2vTg-u8!qZ{w&U7ReWQ=0uZE=BnObq5THlX?f>% zJ|WBJrUD;+zq&mPLgraA1E=xtyr>7|EW=@&^@MfX_&M6?4DIzNk94uSs;{(LzB{N~a_|^E zKXZ9|Qo-7>*-*7;b#k59Sv2<9!!0l8PVmXF#ej~hep88{H+Osttvkjy-Se+*zxyrCH0aPUPJd+aIo#Ixx5m(3T*BBvwc)Qz)-x^pj8(YcZxS&K zE=Yl9kHc$1c57GR@LxVr4j-UDtGxR;d1h9_GsZi zm5lC{p*_OL!P40IymqZ8srQI4;NHU*&BOBxS0k1tD=4GqVc@o=d+(NB!wU*3^yepw z{>omBD77SEuJ%f?r#)8(Bw>om`&Pl7R{|eXul9=KX6ICft{`fw?JD$L?dxNG-vz&x zX;S{6Z>#UXnZDY4X|rY{|A74RvBKE-7GI`cz;wFfv`hY~y~oUFxOdt^erLG%yWkSH z78{aFA&;NxQkQY9%j4l_e~pQX&s4A<`g_~tSHH4Op3T|gwfi!);e%(ljC2bGyF9Sd z`ah!so5A`*O}Mg&Z32NpDK4l!xj$*twf=oRnEdyTGhHo2X;8>saRCzc;Cr-BGd$Hm ztvzIyem({`U9x&z`yHcUTXy1F1Dsih~~7#&%93I&6N_g%&j(p~GvsoS!y zkO3;)m0dqg-QJu>0_PImw5uV-Mt^E+j78!|aVzu6@MuEeWtYLg1`xvuBl^Wg)S%+!=cj(44Lif)K8Xf?Aab{be7;I)@pGyn4wtay4#7DZ#ma#{ur z4Vi-v6&^8y-i3!9RMx_q23>0-y{NH7X-jsO7ICYy1xOqU^|%Y8Zu~BG`-S{bL-i>* zh@nS1n3p^2NKda^;`;CU6etIubV5*+VYSw)di0q=ql#^ve7AM$&6WtJkJdJk?CQS< zJTxX=AlOS#4xaUo94#-fa)fy-=;7ScxYdK_Ro)KjzjRjUJ)_KwG+Q;MMV3(@h21~c z`W?IH5D4R%VB|zSU4+=5c~gxYtD5=Am6KaW3I1(We7RtyJ3tqU33V{;bQwsb2K<~| z;m9=abk5>*1qg3repeU76u1!69uQlrZ(pyGwRfu0RYjMD8AGg%}(&mVQ=$ptcc;~&9`Yt$_jIWGlN0hJs0Pceu zzPUh(>8=wN>%nlOA$O#vXmzwAMjDKRLR3;gU zOrwEBb}?I=Ddsri?&^ge;Pj5)m_kc4-~0YZ=b5geZf2yI|K7zn>umP&nGzT*KkK(E z^`V}*Q{x{ao&Bu~mf~^en4!)CNOo4v3yKH!_~ta>(rg{YcoGsL*k8K&t3=5MrNmm zl*-TIY5SLcqa?46CaqnU*ek1#5w$vVdS7vs=WK0Ak<$@5)Qw@0Y&LQFZ7%f(#z9Al zN^$|ZhTVZl?L`m(Nz-~lE{4tvsPPq83E8b0b$5!59=m-l z;7na)?MDsz?;}Wo8orvNId&k z6Gz*n6J~BP1Tvem0}T6XwMWB5cI4=xH>dp{PD~r zkA?k*BfNWe%}FChe}7hDlve@C6PdJoW@<69kNoh8NOY5eP!?g%W~@bwT$?5B-W_l8 z#9~|%5B(YJy3kj11uhS7+LvXOu>QhdNsj0peYW;U6c~>G4Hkqh?RC!9U3CU zXYWqt%gkzAk2y`H#75iSQSi4Z^j%ahN>DXmpb&HL#tzD|zd`4h4~=Mg{9M-I>i z5Ph~64xXAB+ZF3ZWtYN1Yh-%it5(MZm%)n5-8{5TKv90~qk(X}BTn4*t zxgG~=3&dNysCEi>0LZVp$_!u9Q~dWy$}OG9PrLWG{tYqI6synEZrEOMlJC5+HF0MR zX!Z*SK}yTbm;ps@^d7SkfY{m6jNh1qztPB+&h_)?)RYYh#^;cjXM`W!i%`P!4G5c~ z?BKAg473);<3sH9&h)irHL*@{=yK>n(*lK80d}M|Pwd!WH`{Y3!fbNYSLI|zi~QD6 zygF|w$ABd`wY-g)5!>SfKFSk?=jG`$!IX@B;58Q9LJG5!D~)Uvt+$wPP9l)?#3Emd zpd3j^UPpa%+F$iZF(|AicaLGv#<`TSKEipluT%wzN>{W^9ORIr)->Uw?gxkm0BG4q z-d42u!d^!J$X^t7Q6&1GS-%cdO=Wr4i%aPiz7j9CmjUPmC;}Pl0mGR-mrZ2F?;0mV zo@@3%_*Tp6q`q3n!9?KJi>?;4I(Pt;d;$aDo{Nj5F*D1N zQDOiLOB{e_>n!sm;Ie4p!Y$4;zY&B4mKlZL9+mA(xoU+t4gG}>iv7*TY?g7Ogn$Ib zArri4m37GV$#ap$e*SEEnnHZ6Dtpr)A6EN{B|>wH&xDw~ZRqd)g1o@d-X&x}a#_{{ z0X*nKXXSh5McTk1&Wf^PPS%UqqhxsT^~ozETw#0_R!E5x4UUeHK^#E{8UF!%fLB<3 zs^S3;JA>KAU5rM)p)=321TcN*8=O-tLjcEhj#Rq<0eA+H2N2Sxi`*NN-oS_C6Eikc z1OVa>U;Zk6fKYy#4r#WhrGM)vBAYzoD2PO_@hwynAT>(w66*(D1-E|oc^j_2T$7nX zJDt_n4e9Hbo3BTz0Qg%-?RKB(xrY9>FZ4squE2E&Xc22Z`^jvOeiQvf__sAm&NEx! zxxn#z=gI+maVVu=7j`S}i_QB7AKilFZ@Zpe7cfOjhMm5L3j-D99^5_8xcT1oKkZev zOHZ>nuwRgHGq!;AhNJVFH=Cg2#sZA8xQ~8U<`?gzp!z-B6LSOg<1+^oQk_JhPUt#{ z=ZOYw|3 z7jIZTSbXcnwU-AN<#6F0IYX`2)~LI*8&gN0`38C6hZ_{e zCYNjWpB2;59a|Y&C+HXODej3+ZMQydY0Nr;UsB^|En7RbBDVf+*gvDwh75pAL8s0H z*+zY^a9{{f^O#dQGig6OlYBHLUbGD|;N=dcW} zyFGg)CV984)h<@i7~-1+Ici1=T00O&{W(YQySJCO9{57FhPG&X{ zYbum$e{^Uw`;#?pJ}K>s10t_#{kd5C-04PG>OszdH`okLytBqBNTT!KMw}T96PE$D z&9-=4%zO2G$Af$v?}u$gm1UNK$~gzt!z}c7A)!T}%sorzDX7!AgQ}Xkbsb@U zeyQvJiU-3UUA`XzR%P0|}gZh|skqlG(J(BT!kI>C! zc6eatK#!oeuHYpNCsBj*vN`6Gk*7lh2AJg-l5y(P6o`t=K^HfI|cr+ADuFb^y)5&oo)(24}!?3pEeG<0tzY zmDu19NCg#mz93~Nm?H0BYk!0tx$#2ECvBOYH6PiROX!zjH zH!9*37?$^tAU^b)Bw%-I0obAyM4Dl_Vpj9#g&MTs!Vp*qJ5W7}5-fd4N-qCQcd7i4AX4cOinQJ+sy69%nyjB?B)Y6w`^Fh zn1_r|18Hb&YzmD_G9K;%@m(l#jE7~4#T0*Azxv>NDchOUdD&vt8Dsl5=Yd`|!5beJ zg!%a(X^HO!b}>Yz2f{;-#Cs`mj(_V?WfiWW-Pr{cSqunRA@lNsttr(5pQp%HGdbNu z>-GfTTeW=XR85jv2|_Umu$>0Wy7B3^SOrPZmbB0jgj67r7k!aIT;#|cM@s!3Cx**I)MK2cxf9RSd||NXz-P9RM?n8^m=FK?sIT`u^WWXdQFywk4PV7_ zq=6v)=0#*eteUSDF|prvfceNR8=buw3rWJEQ37;FdRMp-*9Z`}x4Ukm+;hYn&QwJD zKA}g*k_%&HOiC}UP z%;QU3MPuI5)^nI-&GD8oRkZ=8*wVS6m&icjp7m_#X>;~@=zdMv%ewCmPuu(rAJ*hA zg+CA1hq4St)-~sCesrG2NoEBD_&^Yli8rZ>^qpj6?_b#5zaNQFO~d)DoGSg?a+`HC zYkn~}F_071KnS992J~zt33-rI(mVM=-BdD2*xcKWk07wb+WIhZmUbeu5Ryt(lQa(u z=SNESFcL7T#4^lr42{a4cyD?$Uf@+AJWO=sK3xXedRLO*rNVVdggx$0=+;9&g}%wf zQO^h|%t(fUsT7q9{x9p+@8WDquB}p^cmx_$lgwh`R_A*YGCLo%`bzc^F)fcC zd|m0j6`mK+rfCDKSa~eD6l_v_34Bci0%;4F)&Mr4q!ATRuu}?jF?@^Cyp3&ht8IcB zP>M$(YB0jEpQ?Qp_t0e43zKt`d%lok$^JJ3Eo^MDSebBdmVkK(py+HAICpzGdXNLO zU#*WND{9lmQa`~euAxt5j=VyXN9v*nJWYiJi75adP~)G+5((!?mH3--|^3&-5@>oxhP>F3)PEB5M64%Zx70 z8l;kaB+R`f_*(duSkpj%kWH8YvXjQBs!!+|zRKJY62)nxl3Qp8&_djuwHi?!>2kDY zDydjyRvyUYf#mlg5tL>sWytOC??a+Hr+XOA7*+rB0D|T?g5PH(JKj2x;oO}>kM(H* zpttZlsKjjX$L^pm1y$2#kloZ!B`c8La888b_xJ` zKLO`Hnbl53BP0{T-?Ln*?2^Q)fz>jCOZ#2jxAJfmXVbIxV*zq;I4LUs5{vQb-eb6s z*Q{YGc@wA@J@$DZ65s$rvP@lL77&gO#ne$!^syy4P@m_Te|Ol^vNXqKCCwux&g{tc zpu@c-%ernwT$dz-1FTlR4AumafKx{ggi%*h$x^4yy#@GP#e3+d1WP~9C4hvMSQN$0q`~ymbmME3ZBSC`DF(@ks z`V9p9)51ItM=5I{JWX)c(YVDnM0?J{`5qs!^^W@)wK{S z*RF=ZMz191rE^5}B1b8~9kMnnyFpC8d$e|Qayw$)pd!zQn;$@`JVOZQk~xJg8qJsZ zA=&C*k8<&Ux6DoE-4a02eLL+Q z>Ez-YTXJbkz}^JEuK*0zm3+!5qd7X(=-pt{AmTvFm8je}&y}ekY&n}fT}Ge#vomkd^*gMKX*G#GzjcDf&92V<^cyJkA$ZfrJZ_OwUrSk&^xu*60)zmg`7_Mz3P`pM{SVCY z3`%Wv#plH7{q4U!>e`u$X%|pCcivpy+1%k!Q)unX3afjr;gCPob~bB5D@#y2s*ZD4 zWGfBJo7&xqABA5o_$@u~Wc$uQ^Ex6Sc1pR(4rsiYd%*4LBhc1BbAywKYqP(;0JGs< zbHf!`HL0=3Q*SGBUQ>Vk=+UxwT#VJpr%p|aZhm(kPiaybFYT|g@Ug54&vqb==T3TB zc^1@%eUDz;Uf6wHFFn{dFX-tGc&(d8*oE_Q#YL|lm^1KO{Y|&4U-zK zRJX*bN)dDZD{GU!PApKQXIF$FZ$4#hTh4vFqa`k5%Cl42%rPkToclz@d*?ReQ-1xF z#0+OdQZoRP?5p7dacp(>30#SK8|Q4pCUPXVu=>RoBkZ$U?$;TUUqy|s9}T@4?}iWO zzTW`~pVOa7Y%kr~mfJ}4?gG5^zVm`5&ffpGbUw2@B(g-k-sO<0r$$kRNzLD)sA0l> z$$mXECZB$h=JjEvrXp$&sauQ%n$9novbZe=^o9|DI;BI7KC|@IKCJUz z@lQeJ@|HC#!)IFC|MY*3ds7X$njex3Epq!jJr>p{1}H6SQ*}$VuWRT^H`Tl z0}uQJg8%U}-Y_BxFYmkXw}a)-9$20WY7JxZ+%`x>sOZ_5qzMBh9tSk7bK z3n->a;_zZ|cnJqCzS^JTd@aW-?ll{~-u}V3+N`uGbkPyf*X+(#@z{h+YJ{hwmZK>^VzXNAi?EDPuY;6OFCD-&r-phR`kT{3Er5!J_I~~xS7n&{IxGWV zqo+=ihc@$jL;ldysli-;SRMzR#@NeJ9@8eduf4qi-@MwiNwd-+dCf}W0^4#kqMMmv z8303V4Eq2@VQSb1$kB~M=3H%7+Z>zBt%7{;Wy=FZA>UMU-5nb^xeXLx-|=zCgJw>? zU%&4ukIk8>8v7H|CgVj@Ai!M)oEG2?{l??cK+)sUW21r%JN7z2p=#;{Q*r?3Bmi1d zJhUBq8uFz9#vauBzBweXybSO~)IQ^x%8fvJ16O;{A=3_-2+(VINbk%^;ChCb+!ALI z^zDDkEYKyp0Wp?ypFsSN=Ivrqa{zu=CjR9?wf7mzO$4db*cOV|he!(8lWBV!I8P3R8 zVJnQQfaJ&mk|PgD4g`=KF(9r5ko^=u_PzRQ5ay0S%_jimGy*X7P)>&7fQ%0TQsnrm z9Vk4M;48b41}LtNhUFB%+uIOnm=sp_e@kbH`W`^!p?n`wm3*j@06CgFl%wXeFrJZ` z2-{9+fSFf6s{yJBP(Og46dK8O;_?An6p(#%!WP33r~$+@jIBML)p#w#8J8CJT`R&c zsU2VwK%F=s<63}<0tobC-VJ|qsE`hI;zz^Wp+jY&UeIWwTF~eUI0wLa04@%2v8qys zYC-3)QozPoq(kbcfb;|MopLDORTcnsx%L1@0Yx@35}ik{exTc_oD-; z1vvGf9!BH5V;9%TM{DdIi_t|5K{T6@J+-|t=SOcbXv|M6i?7XxWXA_6RoJ6&RR-(wX*C;cNKl%fRVieFdSX1e#H#bXI2?31Ct zdiLm1Ty!UgehJ4Nq`vw~?6<#``T)#3a=SZk)o{uA!?f$h?!5SX_^P3G)6y^K+&x!Z z;)dk&|1QMtcl{rslLry9`$bi0rXRbThoV0c!$QHP(#D1{Egy*qp_k31%h{iP=M%j` zt!@BcKqhn}ha+H>Zf7=jr!61>s~yhL*t?0;gD-PHIH7Xs{6^i*$J+l+*nBG20w=L4 znf%}NsHj>}-Kd)*!8bZQrCskOVg)yE;c_-<83qQrcyj2#=MM-}Frd_1N(aSZz@?;Fbt(rZE`ODZ_IB&0k4tR80e(4}vo?#5lNR zDcNG9&W|j!p{s8Ipem8laIq2`dF_0zfmO%;^@yJEYX*5A1P8{W-6MLaItINT1Z$08 z6m4|>NTe#zAUuSVSlS~CLdAda3QZW%zZ^QLV=u!VwjebBg3c^aHd?M5aLWW|)QJ^v zg%9MX8@p3b>2+NjgW8I;{vfj_xojgoeWckD_^0N$TP{yjr>(t?q5U46{SKo%vB=@yjl^tlKj_e6pxK)N z=s#L(0-UF?e}Xc9qmzq<{5f~d1woEs&hY_jBIcyx3V18IS>+3!m<{v?{nms!hKe_z zzfu*)=5gH2^L3#z^;Y%PqB;i1TWIIV&XGq5Rb^LRlrXTI!tjNm0FYE;p$7Q*1MkZT zRN{h6Q0%N}A3MH!B?@G2ZwsZsg03vjvpC?ua>(gyCVwS58@|B7Y~bQicTYU$dCtQx z^k(zyk+uS0RWE-*%vrq-t{B7MJ@*u2Rq}Eb=iZv(laF=%cF${%2#Luk6CRMZ0w}N> zNM$hkuZU)Hjg`zPnNyFrN>Lnx*n(6MoqW!Xo|nCRV?4Jnh%mMC<-qcp6jrz!gWM`U zNdB$zLPfwfm;H9u@itd%1#sF)eldQO4XVvl!z! z-`(?g{UD=8dEA8<%L|q0*KK-Mu@c1~=1qy`68x2rlRHLT7WQmt0BlnfN=f|M z)wT~@2KTwwxo2k6JNco@%rCP-od%hq5YoBbzcjJtDz(<`6xn)>OiE{HaT7{#uyM9u z>MIxm)+rcjivQc0G17n0DBtYc;>6|(PHClQIrHg=Q98WUnL7z`%H z7!0#7-~0aje)GpU&$;v5b6(GLo_p>&_n!Ma*FCmXt0c?0z(XIJoyT+{_n$%O2?c!f z&IbZsj75a}@4{!rZ}QPsXEJ+Mv|f7kQq%eO6Zb*#dsgh{Vk}l2P9;Y(k;&-Ypd`vo z;XY%DV!^Rsm1>UTZ@#B}q)?TtX`;!qQDn4#r#t3LAP@bbONVBhV85|gEd51!TzJ%;7THIN3ts9#fPJE){<4L1hnesN;g5AZoU6=irW3PZc zh!o=;V)^AK?m~*%2t^l|-!0o|kwlRZ^iH<NHfG%y1u^8k3A_AX? zim>2~@}@%C@gF@9#Z|Z=?62jV!@nHSStt4eTCyr}2e-RM*t;eEolZajUrjSD#^_7- zN^v%*ohCvcvgNAe_dNTQp71sZu1QI9QOze|YzMl9>4o4*=YeUZbAY($^4#L#(x zkLaS`YoLKWY@y*Ik3BW(GQr#Vmn{r?O@B%M?>~B{*lf!}#JsoycGXhjJ=J8_N zYLc;;>2#vHhcO!M)taRKQoV2cFI&r`-w8+3QgqqlHE=tP{zzSPgKcCIi+z`yiAu;V z>7cWFN83%bO7;#8pTh5^o5<$pnS-?mY@Wl=-sdd{Ol_3x??=yD+%8SxwjT!?wK<|B z@dfcKJcY_y{I$m4H z`g?LD@ts~NJ?r6Si*1KaDgD$m2%(ejod-FVLFTG#?KBdeJx0t}=ug2$l#Qe;@$bcBgcE=*(h2&&WUKWZwqX9YJe|G$Gf=@FlmLmwFs8>D~H z8EZdv3hAlz1-8>WFB`Ic-9ngioY!r#<;8_C*VkSyWJhuzy=@2L^&sxcb<_oMMBJcg znH5S$7Lh%urG8zgCy6K;bnL%|3KQi_Eo);nHTksXTgy%08)h74%(sB1Hvf$A=8bR3 zP2gnn)x~?`_gsnp{G4$UaW1DQ?K7-I>iRPOak6JSuJZrsaY4ys^@M|eSoL&xwl2YB z><>i!+RnZ?i+U|g-p(#-7w!|PQZBlGHvypzcvRryL`JaP262WBZaOj1Ee47$IMlVS#WqYvR(*!BuQ4zw}jZ))%Dn~J{cY?cmpuHR~(7OH) zVo&&E=z72$sak###LHU`sRoDdW4&JA=L93FB!hj|>sMt1lAxJ93USfzaly47y;wG=3#K;iJ2+Nf1gC!%PCI(=v+Nh^aX3hn1H z9`x`srK2Ek;en_sm4PvB7k+D5R;g&dhnigGH*t^-ba?Huz zdq)h=CjaQQygxAg}=`2a6_-3KV|VFk_M7ZLZ= z*K>Zr`nVOrvw-KEbf)vkcA6Mgi&kS42}xmM2{o-+Gv_E-SAf=*L_PR5=RFXR);nYN zVwcC51ZR)dZQmXa*oB`c^}^-uj4CW`d$2l*4Q@0EO}#