From 8d7ce75368c67e6d81e01fdf3192ebcb1037093c Mon Sep 17 00:00:00 2001 From: ymmot239 Date: Fri, 6 Feb 2026 14:52:03 -0600 Subject: [PATCH 01/12] Squash commit of PR #48 It introduces a new TrapezoidProfile, Magnetometer, and Encoder. It contains the following squashed commits: testing it goes in a circle lol Add new profile/controller Use new trapezoid profile implementation Tune PID? encoders are dead now tweak integral value add magnetometer library build magnet class for robot erm this should work haha fix magnet object now it works raise debug level Move magnet into control, log heading Update src/robot/magnet.cpp Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> move readDegrees from header to cpp reset the default offsets to the correct sign Remove .DS_Store Fix feedforward overpowering PID Low pass filter over magnetometer readings Ensure no state changes (it really didn't before anyway, might revert later) Add minimum motor power config value Increase BMM350 Data Rate Fix feedforward overpowering PID More tuning? Ensure no state changes (it really didn't before anyway, might revert later) Add minimum motor power config value Tune PID some more comment out heading reading... looks like its blocking the main thread slightly and causing PID oscillations Temp fix for now to hopefully prevent blocking the thread? unsure nvm only works if data ready interrupt pin is enabled add todo, commented out interrupt code lol. fixed magnetometer issues (and a lot of other pid stability issues) all we needed to do was measure the actual loop time instead of the expected loop time Add interrupt to magnetometer anyway Wait for magnet ready before finishing bot setup Add heading controller Properly wait for magnet to initialize configurable error tolerance, fix multiplier on heading controller output continuous pid control for heading normalize current reading, ignore low pass filter for now fix calibration, disable interrupt pin again for more consistent analysis back to high accuracy... add calibration script fix calibration cpp update pid consts Update drive test to track elapsed time, calculate accel theoretically correct whoops sign error new tuning correctly multiply soft iron matrix Added minimum speed into trapezoid profile, and feed in current position and velocity instead of expected Straight line it will usually travel straight now Precision updates Made everything into doubles. Found a better approximation for the robot Is close but still unstable Tuned a modified PID Changed PID to work on the forward and angular velocity of the robot as opposed to the speed of the individual motors. Feedback is based on the x, y, and rotation of the robot. Gets within about 5cm per forward move. Todo: realign robot to 0 degrees after forward move is completed Update control.cpp Added stop when at the destination. Adjusted power to fit between -1 and 1 for the motors. As a bonus, the robot drives even straighter. Tested backwards and longer distances with good results. Needs a bit more tuning, but is very close. Update control.cpp Lowered threshold to stop the robot and moved logging to strings that can be enabled Update control.cpp made trapezoidal profile work correctly and fixed some of the debugging info Need to edit the profile to work based on distance instead of time Re-wrote trapezoid profile Made trapezoid profile position based instead of time based. Makes the robot move slightly smoother. Rotation Added rotation support using existing turn function. So far, looks to be reasonably accurate. PID refactor Very rough readability changes. Makes the new pid work with tile movement --- .DS_Store | Bin 6148 -> 0 bytes .gitignore | 3 +- include/robot/control.h | 14 +- include/robot/driveTest.h | 1 + include/robot/magnet.h | 37 + include/robot/pidController.h | 28 +- include/robot/profiledPIDController.h | 41 + include/robot/trapezoidalProfileNew.h | 63 + include/utils/config.h | 10 +- include/utils/logging.h | 1 + lib/DFRobot_BMM350/LICENSE | 7 + lib/DFRobot_BMM350/README.md | 216 ++ lib/DFRobot_BMM350/README_CN.md | 214 ++ .../CalibratedMagnedticData.ino | 129 ++ .../examples/calibration/README.md | 175 ++ .../examples/calibration/README_CN.md | 242 +++ .../getCalibrateData/getCalibrateData.ino | 92 + .../examples/getAllState/getAllState.ino | 95 + .../getGeomagneticData/getGeomagneticData.ino | 84 + .../magDrdyInterrupt/magDrdyInterrupt.ino | 186 ++ .../thresholdInterrupt/thresholdInterrupt.ino | 194 ++ lib/DFRobot_BMM350/keywords.txt | 76 + lib/DFRobot_BMM350/library.properties | 9 + .../python/raspberrypi/DFRobot_bmm350.py | 1595 +++++++++++++++ .../python/raspberrypi/README.md | 201 ++ .../python/raspberrypi/README_CN.md | 218 ++ .../examples/data_ready_interrupt.py | 111 + .../examples/demo_data_ready_interrupt.py | 112 ++ .../examples/demo_get_all_state.py | 107 + .../examples/demo_get_geomagnetic_data.py | 90 + .../examples/demo_threshold_interrupt.py | 115 ++ .../raspberrypi/examples/get_all_state.py | 108 + .../get_calibrated_geomagnetic_data.py | 107 + .../examples/get_geomagnetic_data.py | 89 + .../examples/threshold_interrupt.py | 115 ++ .../resources/images/BMM350.png | Bin 0 -> 200001 bytes .../resources/images/BMM350Size.png | Bin 0 -> 64972 bytes .../resources/images/cal_pic1.jpg | Bin 0 -> 33222 bytes .../resources/images/cal_pic2.jpg | Bin 0 -> 11813 bytes .../resources/images/cal_pic3.jpg | Bin 0 -> 154473 bytes .../resources/images/cal_pic4.jpg | Bin 0 -> 10879 bytes lib/DFRobot_BMM350/src/DFRobot_BMM350.cpp | 483 +++++ lib/DFRobot_BMM350/src/DFRobot_BMM350.h | 250 +++ lib/DFRobot_BMM350/src/bmm350.c | 1781 +++++++++++++++++ lib/DFRobot_BMM350/src/bmm350.h | 595 ++++++ lib/DFRobot_BMM350/src/bmm350_defs.h | 1215 +++++++++++ lib/DFRobot_BMM350/src/bmm350_oor.c | 329 +++ lib/DFRobot_BMM350/src/bmm350_oor.h | 136 ++ pid_test.csv | 1482 +++++++------- pid_vis.py | 83 +- src/calibrate.cpp.bak | 93 + src/main.cpp | 10 +- src/robot/control.cpp | 473 +++-- src/robot/driveTest.cpp | 11 +- src/robot/magnet.cpp | 125 ++ src/robot/pidController.cpp | 4 +- src/robot/splines.cpp | 8 +- src/robot/trapezoidalProfileNew.cpp | 107 + src/utils/config.cpp | 18 +- src/utils/logging.cpp | 6 + src/wifi/packet.cpp | 3 +- 61 files changed, 11133 insertions(+), 964 deletions(-) delete mode 100644 .DS_Store create mode 100644 include/robot/magnet.h create mode 100644 include/robot/profiledPIDController.h create mode 100644 include/robot/trapezoidalProfileNew.h create mode 100644 lib/DFRobot_BMM350/LICENSE create mode 100644 lib/DFRobot_BMM350/README.md create mode 100644 lib/DFRobot_BMM350/README_CN.md create mode 100644 lib/DFRobot_BMM350/examples/calibration/CalibratedMagnedticData/CalibratedMagnedticData.ino create mode 100644 lib/DFRobot_BMM350/examples/calibration/README.md create mode 100644 lib/DFRobot_BMM350/examples/calibration/README_CN.md create mode 100644 lib/DFRobot_BMM350/examples/calibration/getCalibrateData/getCalibrateData.ino create mode 100644 lib/DFRobot_BMM350/examples/getAllState/getAllState.ino create mode 100644 lib/DFRobot_BMM350/examples/getGeomagneticData/getGeomagneticData.ino create mode 100644 lib/DFRobot_BMM350/examples/magDrdyInterrupt/magDrdyInterrupt.ino create mode 100644 lib/DFRobot_BMM350/examples/thresholdInterrupt/thresholdInterrupt.ino create mode 100644 lib/DFRobot_BMM350/keywords.txt create mode 100644 lib/DFRobot_BMM350/library.properties create mode 100644 lib/DFRobot_BMM350/python/raspberrypi/DFRobot_bmm350.py create mode 100644 lib/DFRobot_BMM350/python/raspberrypi/README.md create mode 100644 lib/DFRobot_BMM350/python/raspberrypi/README_CN.md create mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/data_ready_interrupt.py create mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/demo_data_ready_interrupt.py create mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_all_state.py create mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_geomagnetic_data.py create mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/demo_threshold_interrupt.py create mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/get_all_state.py create mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/get_calibrated_geomagnetic_data.py create mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/get_geomagnetic_data.py create mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/threshold_interrupt.py create mode 100644 lib/DFRobot_BMM350/resources/images/BMM350.png create mode 100644 lib/DFRobot_BMM350/resources/images/BMM350Size.png create mode 100644 lib/DFRobot_BMM350/resources/images/cal_pic1.jpg create mode 100644 lib/DFRobot_BMM350/resources/images/cal_pic2.jpg create mode 100644 lib/DFRobot_BMM350/resources/images/cal_pic3.jpg create mode 100644 lib/DFRobot_BMM350/resources/images/cal_pic4.jpg create mode 100644 lib/DFRobot_BMM350/src/DFRobot_BMM350.cpp create mode 100644 lib/DFRobot_BMM350/src/DFRobot_BMM350.h create mode 100644 lib/DFRobot_BMM350/src/bmm350.c create mode 100644 lib/DFRobot_BMM350/src/bmm350.h create mode 100644 lib/DFRobot_BMM350/src/bmm350_defs.h create mode 100644 lib/DFRobot_BMM350/src/bmm350_oor.c create mode 100644 lib/DFRobot_BMM350/src/bmm350_oor.h create mode 100644 src/calibrate.cpp.bak create mode 100644 src/robot/magnet.cpp create mode 100644 src/robot/trapezoidalProfileNew.cpp diff --git a/.DS_Store b/.DS_Store deleted file mode 100644 index 1e2babc31ddfa43033976781df3e567982f627a8..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6148 zcmeHKJxc>Y5S=xF1O@LZ!msqOE4D7zU`Pi9#QQ{|qMjxlqnZ|V)AcO9r#;+y7T2#Y?rv;7 z-a2kQlfA~&lL0p;RP%Wm)KQ1ExcRI1PgCKu&Ofw{ehF!-pRdpR7x^6q(6d?cGX`ZA z2801&V8{TU4*>>aXfZLUj}A=w3INPPtp(4zrvU?207Hw3L1-Y#gaS>dvR4dc!l4hW zUuZEgXu?V9%vi@}R`!NsIx6&mb|)1Ylvx-M27CrG=C#26e{1sn-w%>EVL%x8R}83Z zxl%4+OSZSBHpjg-z&ONUVZX$n4#8yGv3}rIynvwvwtydip~b`?G!XeCplOgv82C{J FJ^_8GqqYD5 diff --git a/.gitignore b/.gitignore index 29bfe19..1bb0e28 100644 --- a/.gitignore +++ b/.gitignore @@ -5,4 +5,5 @@ .vscode/settings.json .vscode/ipch env.h -/.history \ No newline at end of file +/.history +.DS_Store diff --git a/include/robot/control.h b/include/robot/control.h index f10a906..28442f1 100644 --- a/include/robot/control.h +++ b/include/robot/control.h @@ -19,14 +19,19 @@ struct ControlSetting static ControlSetting leftMotorControl; static ControlSetting rightMotorControl; +static double headingTarget = 0.0; -static MotionProfile profileA = {MAX_VELOCITY_TPS, MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity -static MotionProfile profileB = {MAX_VELOCITY_TPS, MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity +static MotionProfile profileX = {THEORETICAL_MAX_VELOCITY_TPS, THEORETICAL_MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity +static MotionProfile profileY = {THEORETICAL_MAX_VELOCITY_TPS, THEORETICAL_MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity +static MotionProfile profileA = {THEORETICAL_MAX_VELOCITY_TPS, THEORETICAL_MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity -void setLeftMotorControl(ControlSetting control); -void setRightMotorControl(ControlSetting control); + +void setXControl(ControlSetting control); +void setYControl(ControlSetting control); +void setHeadingTarget(double target); ControlSetting getLeftMotorControl(); ControlSetting getRightMotorControl(); +double getHeadingTarget(); void setupBot(); void drive(float tiles, std::string id); @@ -51,5 +56,4 @@ void updateCritRange(); void controlLoop(int loopDelayMs, int8_t framesUntilPrint); void updateCentering(); void updateToNextDistance(); - #endif \ No newline at end of file diff --git a/include/robot/driveTest.h b/include/robot/driveTest.h index a9538c0..5a0d43f 100644 --- a/include/robot/driveTest.h +++ b/include/robot/driveTest.h @@ -12,6 +12,7 @@ class MotorEncoderTest int startEncoderB; int prevEncA; int prevEncB; + unsigned long prevTime; float maxEncoderVelocity = 0; float prevEncVelA; float prevEncVelB; diff --git a/include/robot/magnet.h b/include/robot/magnet.h new file mode 100644 index 0000000..72f5be5 --- /dev/null +++ b/include/robot/magnet.h @@ -0,0 +1,37 @@ +#ifndef MAGNET_H +#define MAGNET_H + +#include "Arduino.h" +#include "DFRobot_BMM350.h" + +struct MagnetReading { + float x; + float y; + float z; +}; + +class Magnet { + public: + Magnet(); + void set_hard_iron_offset(float x, float y, float z); + void set_soft_iron_matrix(float matrix[3][3]); + struct MagnetReading read_calibrated_data(); + float getCompassDegree(struct MagnetReading mag); + float readDegreesRaw(); + float readDegrees(); + bool isDataReady(); + bool isActive(); + private: + float hard_iron_offset[3] = { -10.20, -2.62, -13.21 }; + float soft_iron_matrix[3][3] = { + { 1.024, -0.020, 0.027 }, + { -0.020, 0.968, 0.008 }, + { 0.027, 0.008, 1.011 } + }; + DFRobot_BMM350_I2C bmm350; + + float previousReading = -1.0; + bool activeFlag = false; +}; + +#endif // MAGNET_H \ No newline at end of file diff --git a/include/robot/pidController.h b/include/robot/pidController.h index 299a0da..85f7a6c 100644 --- a/include/robot/pidController.h +++ b/include/robot/pidController.h @@ -5,16 +5,20 @@ class PIDController { public: // PIDController(double kp, double ki, double kd, double min, double max); - PIDController(double kp, double ki, double kd, double min, double max) : kp(kp), ki(ki), kd(kd), minOutput(min), maxOutput(max), prev_error(0), integral(0) {} + PIDController(double kp, double ki, double kd, double min, double max, double errorTolerance) + : kp(kp), ki(ki), kd(kd), minOutput(min), maxOutput(max), errorTolerance(errorTolerance), prev_error(0), integral(0) {} double Compute(double setpoint, double actual_value, double dt); - void Reset(); // Extra space between void and reset because I can't see uneven indent and spacing after doing python for a long time + void Reset(); double kp, ki, kd; // PID gains double minOutput, maxOutput; // Output limits double prev_error, prev_velocity_error; // Previous error double integral; // Integral accumulator + double errorTolerance; // Allowed error before returning 0 +protected: + virtual double getError(double setpoint, double actual_value) { return setpoint - actual_value; } }; // Manually making the clamp function // template @@ -22,4 +26,24 @@ class PIDController // return (value < minValue) ? minValue : (value > maxValue) ? maxValue : value; // } +class ContinuousPIDController : public PIDController +{ +public: + ContinuousPIDController(double kp, double ki, double kd, double min, double max, double errorTolerance, double minInput, double maxInput) + : PIDController(kp, ki, kd, min, max, errorTolerance), minInput(minInput), maxInput(maxInput) {} +protected: + double getError(double setpoint, double actual_value) override { + double error = setpoint - actual_value; + double range = maxInput - minInput; + if (error > range / 2) { + error -= range; + } else if (error < -range / 2) { + error += range; + } + return error; + } +private: + double minInput, maxInput; // Input range for continuous wrapping +}; + #endif // PID_CONTROLLER_H diff --git a/include/robot/profiledPIDController.h b/include/robot/profiledPIDController.h new file mode 100644 index 0000000..b2a978d --- /dev/null +++ b/include/robot/profiledPIDController.h @@ -0,0 +1,41 @@ +#ifndef PROFILED_PID_CONTROLLER_H +#define PROFILED_PID_CONTROLLER_H + +#include "robot/pidController.h" +#include "robot/trapezoidalProfileNew.h" + +class ProfiledPIDController { +public: + ProfiledPIDController(double kp, double ki, double kd, + double minOutput, double maxOutput, + double errorTolerance, + const TrapezoidProfile::Constraints& constraints) + : pid(kp, ki, kd, minOutput, maxOutput, errorTolerance), profile(constraints), lastTime(0.0) {} + + // Call this every control loop + double Compute(double goalPosition, double actualPosition, double actualVelocity, double dt) { + TrapezoidProfile::State current(actualPosition, actualVelocity); + TrapezoidProfile::State goal(goalPosition, 0.0); // Assume goal velocity is zero + + // Generate profile for current time + TrapezoidProfile::State profiledSetpoint = profile.calculate(lastTime, current, goal); + + // PID tracks profiled position + double output = pid.Compute(profiledSetpoint.position, actualPosition, dt); + + lastTime += dt; + return output; + } + + void Reset() { + pid.Reset(); + lastTime = 0.0; + } + +private: + PIDController pid; + TrapezoidProfile profile; + double lastTime; +}; + +#endif // PROFILED_PID_CONTROLLER_H \ No newline at end of file diff --git a/include/robot/trapezoidalProfileNew.h b/include/robot/trapezoidalProfileNew.h new file mode 100644 index 0000000..67e551b --- /dev/null +++ b/include/robot/trapezoidalProfileNew.h @@ -0,0 +1,63 @@ +#ifndef TRAPEZOIDAL_PROFILE_NEW_H +#define TRAPEZOIDAL_PROFILE_NEW_H + +#include +#include + +class TrapezoidProfile +{ +public: + struct Constraints + { + double maxVelocity; + double maxAcceleration; + + Constraints(double maxVelocity, double maxAcceleration) + { + if (maxVelocity < 0.0 || maxAcceleration < 0.0) + { + throw std::runtime_error("Constraints must be non-negative"); + } + this->maxVelocity = maxVelocity; + this->maxAcceleration = maxAcceleration; + // Remove MathSharedStore.reportUsage for now (Java-specific) + } + }; + + struct State + { + double position = 0.0; + double velocity = 0.0; + + State() = default; + State(double position, double velocity) + : position(position), velocity(velocity) {} + + bool operator==(const State& rhs) const + { + return position == rhs.position && velocity == rhs.velocity; + } + }; + + TrapezoidProfile(const Constraints& constraints) + : m_constraints(constraints) {} + + State calculate(double t, const State& current, const State& goal); + + // bool isFinished(double t) const { return t >= totalTime(); } + +private: + static bool shouldFlipAcceleration(const State& initial, const State& goal) + { + return initial.position > goal.position; + } + + State direct(const State& in, int m_direction) const + { + return State(in.position * m_direction, in.velocity * m_direction); + } + + Constraints m_constraints; +}; + +#endif \ No newline at end of file diff --git a/include/utils/config.h b/include/utils/config.h index b98a5cb..a271251 100644 --- a/include/utils/config.h +++ b/include/utils/config.h @@ -33,10 +33,16 @@ extern gpio_num_t ONBOARD_LED_PIN; extern int TICKS_PER_ROTATION; extern float TRACK_WIDTH_INCHES; extern float WHEEL_DIAMETER_INCHES; -extern float MAX_VELOCITY_TPS; -extern float MAX_ACCELERATION_TPSPS; +extern float THEORETICAL_MAX_VELOCITY_TPS; +extern float VELOCITY_LIMIT_TPS; +extern float THEORETICAL_MAX_ACCELERATION_TPSPS; +extern float ACCELERATION_LIMIT_TPSPS; +extern float MIN_MOTOR_POWER; +extern float MIN_MOTOR_VELOCITY_TPS; extern float TILES_TO_TICKS; +extern int MAGNET_CCW_IS_POSITIVE; // Set to 1 if counterclockwise rotation is positive, -1 if clockwise rotation is positive + extern float PID_POSITION_TOLERANCE; extern float PID_VELOCITY_TOLERANCE; diff --git a/include/utils/logging.h b/include/utils/logging.h index ab1a3ed..41ebcd7 100644 --- a/include/utils/logging.h +++ b/include/utils/logging.h @@ -12,6 +12,7 @@ void serialLog(std::string value, int serialLoggingLevel); void serialLogln(const char *message, int serialLoggingLevel); void serialLogln(int value, int serialLoggingLevel); void serialLogln(double value, int serialLoggingLevel); +void serialLogln(float value, int serialLoggingLevel); void serialLogln(std::string value, int serialLoggingLevel); void serialLogError(char message[], int error); diff --git a/lib/DFRobot_BMM350/LICENSE b/lib/DFRobot_BMM350/LICENSE new file mode 100644 index 0000000..79f3100 --- /dev/null +++ b/lib/DFRobot_BMM350/LICENSE @@ -0,0 +1,7 @@ +Copyright 2010 DFRobot Co.Ltd + +Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. \ No newline at end of file diff --git a/lib/DFRobot_BMM350/README.md b/lib/DFRobot_BMM350/README.md new file mode 100644 index 0000000..3ff4694 --- /dev/null +++ b/lib/DFRobot_BMM350/README.md @@ -0,0 +1,216 @@ +# DFRobot_BMM350 + +* [中文](./README_CN.md) + +The BMM350 is a low-power and low noise 3-axis digital geomagnetic sensor that perfectly matches the requirements of compass applications. Based on Bosch’s proprietary FlipCore technology, the BMM350 provides absolute spatial orientation and motion vectors with high accuracy and dynamics. Featuring small size and lightweight, it is also especially suited for supporting drones in accurate heading. The BMM350 can also be used together with an inertial measurement unit consisting of a 3-axis accelerometer and a 3-axis gyroscope. + +![产品效果图](./resources/images/BMM350.png)![产品效果图](./resources/images/BMM350Size.png) + +## Product Link([https://www.dfrobot.com](https://www.dfrobot.com)) + +```yaml +SKU: SEN0619 +``` + +## Table of Contents + +* [Summary](#summary) +* [Installation](#installation) +* [Methods](#methods) +* [Compatibility](#compatibility) +* [History](#history) +* [Credits](#credits) + +## Summary + +Get geomagnetic data along the XYZ axis. + +1. This module can obtain high threshold and low threshold geomagnetic data.
+2. Geomagnetism on three(xyz) axes can be measured.
+3. This module can choose I2C or I3C communication mode.
+ +## Installation + +To use this library download the zip file, uncompress it to a folder named DFRobot_BMM350. +Download the zip file first to use this library and uncompress it to a folder named DFRobot_BMM350. + +## Methods + +```C++ + /** + * @fn softReset + * @brief Soft reset, restore to suspended mode after soft reset. + */ + void softReset(void); + + /** + * @fn setOperationMode + * @brief Set sensor operation mode + * @param powermode + * @n eBmm350SuspendMode suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * @n eBmm350NormalMode normal mode: Get geomagnetic data normally. + * @n eBmm350ForcedMode forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + * @n eBmm350ForcedModeFast To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + void setOperationMode(enum eBmm350PowerModes_t powermode); + + + /** + * @fn getOperationMode + * @brief Get sensor operation mode + * @return result Return sensor operation mode as a character string + */ + String getOperationMode(void); + + /** + * @fn setPresetMode + * @brief Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default collection rate is 12.5Hz) + * @param presetMode + * @n BMM350_PRESETMODE_LOWPOWER Low power mode, get a fraction of data and take the mean value. + * @n BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and take the mean value. + * @n BMM350_PRESETMODE_ENHANCED Enhanced mode, get a plenty of data and take the mean value. + * @n BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and take the mean value. + */ + void setPresetMode(uint8_t presetMode, uint8_t rate = BMM350_DATA_RATE_12_5HZ); + + /** + * @fn setRate + * @brief Set the rate of obtaining geomagnetic data, the higher, the faster (without delay function) + * @param rate + * @n BMM350_DATA_RATE_1_5625HZ + * @n BMM350_DATA_RATE_3_125HZ + * @n BMM350_DATA_RATE_6_25HZ + * @n BMM350_DATA_RATE_12_5HZ (default rate) + * @n BMM350_DATA_RATE_25HZ + * @n BMM350_DATA_RATE_50HZ + * @n BMM350_DATA_RATE_100HZ + * @n BMM350_DATA_RATE_200HZ + * @n BMM350_DATA_RATE_400HZ + */ + void setRate(uint8_t rate); + + /** + * @fn getRate + * @brief Get the config data rate, unit: HZ + * @return rate + */ + float getRate(void); + + /** + * @fn selfTest + * @brief The sensor self test, the returned value indicate the self test result. + * @param testMode: + * @n eBmm350SelfTestNormal Normal self test, test whether x-axis, y-axis and z-axis are connected or short-circuited + * @return result The returned character string is the self test result + */ + String selfTest(eBmm350SelfTest_t testMode = eBmm350SelfTestNormal); + + /** + * @fn setMeasurementXYZ + * @brief Enable the measurement at x-axis, y-axis and z-axis, default to be enabled. After disabling, the geomagnetic data at x, y, and z axis are wrong. + * @param en_x + * @n BMM350_X_EN Enable the measurement at x-axis + * @n BMM350_X_DIS Disable the measurement at x-axis + * @param en_y + * @n BMM350_Y_EN Enable the measurement at y-axis + * @n BMM350_Y_DIS Disable the measurement at y-axis + * @param en_z + * @n BMM350_Z_EN Enable the measurement at z-axis + * @n BMM350_Z_DIS Disable the measurement at z-axis + */ + void setMeasurementXYZ(enum eBmm350XAxisEnDis_t enX = BMM350_X_EN, enum eBmm350YAxisEnDis_t enY = BMM350_Y_EN, enum eBmm350ZAxisEnDis_t enZ = BMM350_Z_EN); + + /** + * @fn getMeasurementStateXYZ + * @brief Get the enabling status at x-axis, y-axis and z-axis + * @return result Return enabling status as a character string + */ + String getMeasurementStateXYZ(void); + + /** + * @fn getGeomagneticData + * @brief Get the geomagnetic data of 3 axis (x, y, z) + * @return Geomagnetic data structure, unit: (uT) + */ + sBmm350MagData_t getGeomagneticData(void); + + /** + * @fn getCompassDegree + * @brief Get compass degree + * @return Compass degree (0° - 360°) + * @n 0° = North, 90° = East, 180° = South, 270° = West. + */ + float getCompassDegree(void); + + /** + * @fn setDataReadyPin + * @brief Enable or disable data ready interrupt pin + * @n After enabling, the DRDY pin jump when there's data coming. + * @n After disabling, the DRDY pin will not jump when there's data coming. + * @n High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. + * @n Low polarity: active on low, default is high level, which turns to low level when the interrupt is triggered. + * @param modes + * @n BMM350_ENABLE_INTERRUPT Enable DRDY + * @n BMM350_DISABLE_INTERRUPT Disable DRDY + * @param polarity + * @n BMM350_ACTIVE_HIGH High polarity + * @n BMM350_ACTIVE_LOW Low polarity + */ + void setDataReadyPin(enum eBmm350InterruptEnableDisable_t modes, enum eBmm350IntrPolarity_t polarity=BMM350_ACTIVE_HIGH); + + /** + * @fn getDataReadyState + * @brief Get the data ready status, determine whether the data is ready + * @return status + * @n true Data ready + * @n false Data is not ready + */ + bool getDataReadyState(void); + + /** + * @fn setThresholdInterrupt(uint8_t modes, int8_t threshold, uint8_t polarity) + * @brief Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold + * @n High polarity: active on high level, the default is low level, which turns to high level when the interrupt is triggered. + * @n Low polarity: active on low level, the default is high level, which turns to low level when the interrupt is triggered. + * @param modes + * @n LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode + * @n HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode + * @param threshold + * @n Threshold, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt + * @param polarity + * @n POLARITY_HIGH High polarity + * @n POLARITY_LOW Low polarity + */ + void setThresholdInterrupt(uint8_t modes, int8_t threshold, enum eBmm350IntrPolarity_t polarity); + + /** + * @fn getThresholdData + * @brief Get the data with threshold interrupt occurred + * @return Returns the structure for storing geomagnetic data, the structure stores the data of 3 axis and interrupt status, + * @n The interrupt is not triggered when the data at x-axis, y-axis and z-axis are NO_DATA + * @n mag_x、mag_y、mag_z store geomagnetic data + * @n interrupt_x、interrupt_y、interrupt_z store the xyz axis interrupt state + */ + sBmm350ThresholdData_t getThresholdData(void); +``` + +## Compatibility + +| MCU | Work Well | Work Wrong | Untested | Remarks | +| ------------------ |:---------:|:----------:|:--------:| ------- | +| Arduino uno | √ | | | | +| FireBeetle esp32 | √ | | | | +| FireBeetle esp8266 | √ | | | | +| FireBeetle m0 | √ | | | | +| Leonardo | √ | | | | +| Microbit | √ | | | | +| Arduino MEGA2560 | √ | | | | + +## History + +- 2024/05/08 - Version 1.0.0 released. + +## Credits + +Written by [GDuang](yonglei.ren@dfrobot.com), 2024. (Welcome to our [website](https://www.dfrobot.com/)) diff --git a/lib/DFRobot_BMM350/README_CN.md b/lib/DFRobot_BMM350/README_CN.md new file mode 100644 index 0000000..0da933b --- /dev/null +++ b/lib/DFRobot_BMM350/README_CN.md @@ -0,0 +1,214 @@ +DFRobot_BMP350 +=========================== + +* [English Version](./README.md) + +BMM350 是一款低功耗、低噪声的 3 轴数字地磁传感器,完全符合罗盘应用的要求。 基于博世专有的 FlipCore 技术,BMM350 提供了高精度和动态的绝对空间方向和运动矢量。 体积小、重量轻,特别适用于支持无人机精准航向。 BMM350 还可与由 3 轴加速度计和 3 轴陀螺仪组成的惯性测量单元一起使用。 + +![产品效果图](./resources/images/BMM350.png)![产品效果图](./resources/images/BMM350Size.png) + +## 产品链接([https://www.dfrobot.com.cn](https://www.dfrobot.com.cn)) + +```yaml +SKU: SEN0619 +``` + +## 目录 + +* [概述](#概述) +* [库安装](#库安装) +* [方法](#方法) +* [兼容性](#兼容性) +* [历史](#历史) +* [创作者](#创作者) + +## 概述 + +您可以沿 XYZ 轴获取地磁数据 + +1. 本模块可以获得高阈值和低阈值地磁数据。
+2. 可以测量三个(xyz)轴上的地磁。
+3. 本模块可选择I2C或I3C通讯方式。
+ +## 库安装 + +使用此库前,请首先下载库文件,将其粘贴到\Arduino\libraries目录中,然后打开examples文件夹并在该文件夹中运行演示。 + +## 方法 + +```C++ + /** + * @fn softReset + * @brief 软件复位,软件复位后先恢复为挂起模式 + */ + void softReset(void); + + /** + * @fn setOperationMode + * @brief 设置传感器的执行模式 + * @param opMode mode + * @n eBmm350SuspendMode 挂起模式:挂起模式是芯片上电后BMM350的默认电源模式,在挂起模式下电流消耗最小,因此该模式适用于不需要数据转换的时期(所有寄存器的读写都是可能的) + * @n eBmm350NormalMode 常规模式: 获取地磁数据 + * @n eBmm350ForcedMode 强制模式: 单次测量,测量完成后传感器恢复到暂停模式 + * @n eBmm350ForcedModeFast 只有使用FM_FAST时,ODR才能达到200Hz + */ + void setOperationMode(uint8_t opMode); + + /** + * @fn getOperationMode + * @brief 获取传感器的执行模式 + * @return result 返回字符串为传感器的执行模式 + */ + String getOperationMode(void); + + /** + * @fn setPresetMode + * @brief 设置预置模式,使用户更简单的配置传感器来获取地磁数据(默认的采集速率为12.5Hz) + * @param presetMode + * @n BMM350_PRESETMODE_LOWPOWER 低功率模式,获取少量的数据 取均值 + * @n BMM350_PRESETMODE_REGULAR 普通模式,获取中量数据 取均值 + * @n BMM350_PRESETMODE_ENHANCED 增强模式,获取大量数据 取均值 + * @n BMM350_PRESETMODE_HIGHACCURACY 高精度模式,获取超大量数据 取均值 + */ + void setPresetMode(uint8_t presetMode, uint8_t rate = BMM350_DATA_RATE_12_5HZ); + + /** + * @fn setRate + * @brief 设置获取地磁数据的速率,速率越大获取越快(不加延时函数) + * @param rate + * @n BMM350_DATA_RATE_1_5625HZ + * @n BMM350_DATA_RATE_3_125HZ + * @n BMM350_DATA_RATE_6_25HZ + * @n BMM350_DATA_RATE_12_5HZ (默认速率) + * @n BMM350_DATA_RATE_25HZ + * @n BMM350_DATA_RATE_50HZ + * @n BMM350_DATA_RATE_100HZ + * @n BMM350_DATA_RATE_200HZ + * @n BMM350_DATA_RATE_400HZ + */ + void setRate(uint8_t rate); + + /** + * @fn getRate + * @brief 获取配置的数据速率 单位:HZ + * @return rate + */ + uint8_t getRate(void); + + /** + * @fn selfTest + * @brief 传感器自测,返回值表明自检结果 + * @param testMode: + * @n eBmm350SelfTestNormal 常规自检,检查x轴、y轴、z轴是否接通或短路 + * @return result 返回的字符串为自测的结果 + */ + String selfTest(eBmm350SelfTest_t testMode = eBmm350SelfTestNormal); + + /** + * @fn setMeasurementXYZ + * @brief 使能x y z 轴的测量,默认设置为使能,禁止后xyz轴的地磁数据不准确 + * @param en_x + * @n BMM350_X_EN 使能 x 轴的测量 + * @n BMM350_X_DIS 禁止 x 轴的测量 + * @param en_y + * @n BMM350_Y_EN 使能 y 轴的测量 + * @n BMM350_Y_DIS 禁止 y 轴的测量 + * @param en_z + * @n BMM350_Z_EN 使能 z 轴的测量 + * @n BMM350_Z_DIS 禁止 z 轴的测量 + */ + void setMeasurementXYZ(enum eBmm350XAxisEnDis_t enX = BMM350_X_EN, enum eBmm350YAxisEnDis_t enY = BMM350_Y_EN, enum eBmm350ZAxisEnDis_t enZ = BMM350_Z_EN); + + /** + * @fn getMeasurementStateXYZ + * @brief 获取 x y z 轴的使能状态 + * @return result 返回字符串为使能的状态 + */ + String getMeasurementStateXYZ(void); + + /** + * @fn getGeomagneticData + * @brief 获取x y z 三轴的地磁数据 + * @return 地磁的数据的结构体,单位:微特斯拉(uT) + */ + sBmm350MagData_t getGeomagneticData(void); + + /** + * @fn getCompassDegree + * @brief 获取罗盘方向 + * @return 罗盘方向 (0° - 360°) + * @n 0° = North, 90° = East, 180° = South, 270° = West. + */ + float getCompassDegree(void); + + /** + * @fn setDataReadyPin + * @brief 使能或者禁止数据准备中断引脚 + * @n 使能后有数据来临DRDY引脚跳变 + * @n 禁止后有数据来临DRDY不进行跳变 + * @n 高极性:高电平为活动电平,默认为低电平,触发中断时电平变为高 + * @n 低极性:低电平为活动电平,默认为高电平,触发中断时电平变为低 + * @param modes + * @n BMM350_ENABLE_INTERRUPT 使能DRDY + * @n BMM350_DISABLE_INTERRUPT 禁止DRDY + * @param polarity + * @n BMM350_ACTIVE_HIGH 高极性 + * @n BMM350_ACTIVE_LOW 低极性 + */ + void setDataReadyPin(uint8_t modes, uint8_t polarity=POLARITY_HIGH); + + /** + * @fn getDataReadyState + * @brief 获取数据准备的状态,用来判断数据是否准备好 + * @return status + * @n true 数据准备好了 + * @n false 数据没有准备好 + */ + bool getDataReadyState(void); + + /** + * @fn setThresholdInterrupt(uint8_t modes, int8_t threshold, uint8_t polarity) + * @brief 设置阈值中断,当某个通道的地磁值高/低于阈值时触发中断 + * @n 高极性:高电平为活动电平,默认为低电平,触发中断时电平变为高 + * @n 低极性:低电平为活动电平,默认为高电平,触发中断时电平变为低 + * @param modes + * @n LOW_THRESHOLD_INTERRUPT 低阈值中断模式 + * @n HIGH_THRESHOLD_INTERRUPT 高阈值中断模式 + * @param threshold + * @n 阈值,默认扩大16倍,例如:低阈值模式下传入阈值1,实际低于16的地磁数据都会触发中断 + * @param polarity + * @n POLARITY_HIGH 高极性 + * @n POLARITY_LOW 低极性 + */ + void setThresholdInterrupt(uint8_t modes, int8_t threshold, enum eBmm350IntrPolarity_t polarity); + + /** + * @fn getThresholdData + * @brief 获取发生阈值中断的数据 + * @return 返回存放地磁数据的结构体,结构体存放三轴当数据和中断状态, + * @n xyz轴的数据为 NO_DATA 时,未触发中断 + * @n mag_x、mag_y、mag_z 存放地磁数据 + * @n interrupt_x、interrupt_y、interrupt_z 存放轴中断状态 + */ + sBmm350ThresholdData_t getThresholdData(void); +``` + +## 兼容性 + +| MCU | Work Well | Work Wrong | Untested | Remarks | +| ------------------ |:---------:|:----------:|:--------:| ------- | +| Arduino uno | √ | | | | +| FireBeetle esp32 | √ | | | | +| FireBeetle esp8266 | √ | | | | +| FireBeetle m0 | √ | | | | +| Leonardo | √ | | | | +| Microbit | √ | | | | +| Arduino MEGA2560 | √ | | | | + +## History + +- 2024/05/08 - Version 1.0.0 released. + +## Credits + +Written by [GDuang](yonglei.ren@dfrobot.com), 2024. (Welcome to our [website](https://www.dfrobot.com/)) diff --git a/lib/DFRobot_BMM350/examples/calibration/CalibratedMagnedticData/CalibratedMagnedticData.ino b/lib/DFRobot_BMM350/examples/calibration/CalibratedMagnedticData/CalibratedMagnedticData.ino new file mode 100644 index 0000000..bbde827 --- /dev/null +++ b/lib/DFRobot_BMM350/examples/calibration/CalibratedMagnedticData/CalibratedMagnedticData.ino @@ -0,0 +1,129 @@ +/*! + * @file CalibratedMagnedticData.ino + * @brief Get the Calibrated geomagnetic data at 3 axis (x, y, z), get the compass degree + * @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north + * @n Experimental phenomenon: serial print the geomagnetic data of x-axis, y-axis and z-axis and the compass degree + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350/ + */ + +// ======================================================= +// 请先阅读项目 https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration +// Please read https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration +// 包含使用说明、校准步骤。 +// It contains usage instructions, calibration steps. +// ======================================================= + +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); +//hard iron calibration parameters +const float hard_iron[3] = { -13.45, -28.95, 12.69 }; +//soft iron calibration parameters +const float soft_iron[3][3] = { + { 0.992, -0.006, -0.007 }, + { -0.006, 0.990, -0.004 }, + { -0.007, -0.004, 1.019 } +}; + +void setup() { + Serial.begin(115200); + while (!Serial) + ; + while (bmm350.begin()) { + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } + Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + * rate: + * BMM350_DATA_RATE_1_5625HZ + * BMM350_DATA_RATE_3_125HZ + * BMM350_DATA_RATE_6_25HZ + * BMM350_DATA_RATE_12_5HZ (default rate) + * BMM350_DATA_RATE_25HZ + * BMM350_DATA_RATE_50HZ + * BMM350_DATA_RATE_100HZ + * BMM350_DATA_RATE_200HZ + * BMM350_DATA_RATE_400HZ + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); +} + +void loop() { + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + + float mag_data[3]; + + // hard iron calibration + mag_data[0] = magData.float_x + hard_iron[0]; + mag_data[1] = magData.float_y + hard_iron[1]; + mag_data[2] = magData.float_z + hard_iron[2]; + + //soft iron calibration + for (int i = 0; i < 3; i++) { + mag_data[i] = (soft_iron[i][0] * mag_data[0]) + (soft_iron[i][1] * mag_data[1]) + (soft_iron[i][2] * mag_data[2]); + } + + magData.x = mag_data[0]; + magData.y = mag_data[1]; + magData.z = mag_data[2]; + magData.float_x = mag_data[0]; + magData.float_y = mag_data[1]; + magData.float_z = mag_data[2]; + + Serial.print("mag x = ");Serial.print(magData.x);Serial.println(" uT"); + Serial.print("mag y = ");Serial.print(magData.y);Serial.println(" uT"); + Serial.print("mag z = ");Serial.print(magData.z);Serial.println(" uT"); + + // float type data + //Serial.print("mag x = "); Serial.print(magData.float_x); Serial.println(" uT"); + //Serial.print("mag y = "); Serial.print(magData.float_y); Serial.println(" uT"); + //Serial.print("mag z = "); Serial.print(magData.float_z); Serial.println(" uT"); + + float compassDegree = getCompassDegree(magData); + Serial.print("the angle between the pointing direction and north (counterclockwise) is:"); + Serial.println(compassDegree); + Serial.println("--------------------------------"); + delay(3000); +} +float getCompassDegree(sBmm350MagData_t magData) +{ + float compass = 0.0; + compass = atan2(magData.x, magData.y); + if (compass < 0) { + compass += 2 * PI; + } + if (compass > 2 * PI) { + compass -= 2 * PI; + } + return compass * 180 / M_PI; +} diff --git a/lib/DFRobot_BMM350/examples/calibration/README.md b/lib/DFRobot_BMM350/examples/calibration/README.md new file mode 100644 index 0000000..fc0f586 --- /dev/null +++ b/lib/DFRobot_BMM350/examples/calibration/README.md @@ -0,0 +1,175 @@ +# Guide to Calibrating BMM350 Magnetic Field Data Using MotionCal + +* [中文版本](./README_CN.md) + +Magnetometers in real-world applications are susceptible to interference from metal objects, electrical currents, and fluctuations in the Earth's magnetic field. Uncalibrated data can lead to deviations in direction recognition, affecting the accuracy of the heading angle (yaw) or the functionality of the electronic compass. + +--- + +## Required Tools + +* [MotionCal](https://www.pjrc.com/store/prop_shield.html#motioncal) tool (supports Windows/macOS/Linux) +* Arduino IDE +* A development board supported by the DFRobot_BMM350 sensor, with the serial port correctly connected to the PC + +--- + +## Step 1: Upload the Calibration Firmware + +Use a development board supported by the DFRobot_BMM350 sensor and connect the serial port to the PC correctly. + +--- + +## Step 2: Run the MotionCal Tool + +1. Open the [MotionCal](https://www.pjrc.com/store/prop_shield.html#motioncal) download page, select your platform, and download and install the tool. + +![MotionCal download pic](/resources/images/cal_pic1.jpg) + +2. Launch `MotionCal`. +3. Select the correct serial port in the menu (consistent with your device). + +![MotionCal port choose](/resources/images/cal_pic2.jpg) + +4. MotionCal automatically starts receiving and visualizing the data from the magnetometer, accelerometer, and gyroscope. + +> Ensure that no other serial port software is open simultaneously! + +--- + +## Step 3: Rotate the Sensor for Omnidirectional Sampling + +> Slowly rotate the sensor along the **X/Y/Z axes** to ensure that the data graph covers a complete sphere. + +![MotionCal cal](/resources/images/cal_pic3.jpg) + +## Step 4: Apply Compensation in the Code + +![calibration parameters](/resources/images/cal_pic4.jpg) + +The calibration parameters required are located in the top-left corner of the MotionCal software. +Fill in the calibration coefficients in the corresponding positions of the reference code `CalibrateMagnedticData.ino`. + +```cpp +//hard iron calibration parameters +const float hard_iron[3] = { -13.45, -28.95, 12.69 }; +//soft iron calibration parameters +const float soft_iron[3][3] = { + { 0.992, -0.006, -0.007 }, + { -0.006, 0.990, -0.004 }, + { -0.007, -0.004, 1.019 } +}; +``` + +The complete reference code is as follows: + +```cpp +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); +//hard iron calibration parameters +const float hard_iron[3] = { -13.45, -28.95, 12.69 }; +//soft iron calibration parameters +const float soft_iron[3][3] = { + { 0.992, -0.006, -0.007 }, + { -0.006, 0.990, -0.004 }, + { -0.007, -0.004, 1.019 } +}; + +void setup() { + Serial.begin(115200); + while (!Serial) + ; + while (bmm350.begin()) { + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } + Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); +} + +void loop() { + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + + float mag_data[3]; + + // hard iron calibration + mag_data[0] = magData.float_x + hard_iron[0]; + mag_data[1] = magData.float_y + hard_iron[1]; + mag_data[2] = magData.float_z + hard_iron[2]; + + //soft iron calibration + for (int i = 0; i < 3; i++) { + mag_data[i] = (soft_iron[i][0] * mag_data[0]) + (soft_iron[i][1] * mag_data[1]) + (soft_iron[i][2] * mag_data[2]); + } + + magData.x = mag_data[0]; + magData.y = mag_data[1]; + magData.z = mag_data[2]; + magData.float_x = mag_data[0]; + magData.float_y = mag_data[1]; + magData.float_z = mag_data[2]; + + Serial.print("mag x = ");Serial.print(magData.x);Serial.println(" uT"); + Serial.print("mag y = ");Serial.print(magData.y);Serial.println(" uT"); + Serial.print("mag z = ");Serial.print(magData.z);Serial.println(" uT"); + + // float type data + //Serial.print("mag x = "); Serial.print(magData.float_x); Serial.println(" uT"); + //Serial.print("mag y = "); Serial.print(magData.float_y); Serial.println(" uT"); + //Serial.print("mag z = "); Serial.print(magData.float_z); Serial.println(" uT"); + + float compassDegree = getCompassDegree(magData); + Serial.print("the angle between the pointing direction and north (counterclockwise) is:"); + Serial.println(compassDegree); + Serial.println("--------------------------------"); + delay(3000); +} +float getCompassDegree(sBmm350MagData_t magData) +{ + float compass = 0.0; + compass = atan2(magData.x, magData.y); + if (compass < 0) { + compass += 2 * PI; + } + if (compass > 2 * PI) { + compass -= 2 * PI; + } + return compass * 180 / M_PI; +} +``` + +--- + +--- + +## 📎 Appendix + +* MotionCal download link: [https://www.pjrc.com/store/prop_shield.html#motioncal](https://www.pjrc.com/store/prop_shield.html#motioncal) +* DFRobot BMM350 Sensor: [https://wiki.dfrobot.com.cn/_SKU_SEN0619_Gravity_BMM350_TripleAxis_Magnetometer_Sensor](https://wiki.dfrobot.com.cn/_SKU_SEN0619_Gravity_BMM350_TripleAxis_Magnetometer_Sensor) \ No newline at end of file diff --git a/lib/DFRobot_BMM350/examples/calibration/README_CN.md b/lib/DFRobot_BMM350/examples/calibration/README_CN.md new file mode 100644 index 0000000..d7ada6f --- /dev/null +++ b/lib/DFRobot_BMM350/examples/calibration/README_CN.md @@ -0,0 +1,242 @@ +# 使用 MotionCal 校准磁场数据指南 + +* [English Version](./README.md) + +磁力计在现实应用中易受金属物体、电流干扰和地磁场波动的影响。未经校准的数据可能会导致方向识别偏移,影响航向角(yaw)或电子罗盘功能的准确性。 + +--- + +## 所需工具 + +* [MotionCal](https://www.pjrc.com/store/prop_shield.html#motioncal) 工具(支持 Windows/macOS/Linux) +* Arduino IDE +* DFRobot_BMM350传感器器所支持的开发板,并将串口正确连接到PC + +--- + +## 步骤一:上传校准固件 + +DFRobot_BMM350传感器器所支持的开发板,并将串口正确连接到PC + +```cpp +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); +void setup() { + Serial.begin(115200); + while (!Serial) + ; + while (bmm350.begin()) { + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } + Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); +} + +void loop() { + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + Serial.print("Raw:"); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(magData.x*10); + Serial.print(','); + Serial.print(magData.y*10); + Serial.print(','); + Serial.print(magData.z*10); + Serial.println(); + delay(100); +} +``` + +--- + +## 步骤二:运行 MotionCal 工具 + +1. 打开 [MotionCal](https://www.pjrc.com/store/prop_shield.html#motioncal) 下载页面,选择你的平台并下载安装。 + +![MotionCal download pic](/resources/images/cal_pic1.jpg) + +2. 启动 `MotionCal`。 +3. 在菜单中选择正确的串口(与你的设备一致)。 + +![MotionCal port choose](/resources/images/cal_pic2.jpg) + +4. MotionCal 自动开始自动接收并可视化磁力计、加速度计和陀螺仪数据。 + +> 确保没有其它串口软件同时打开!! + +--- + +## 步骤三:旋转传感器进行全向采样 + +> 将传感器沿 **X/Y/Z 各轴方向**缓慢旋转,使数据图形覆盖完整的球体。 + +![MotionCal cal](/resources/images/cal_pic3.jpg) + +## 步骤四:在代码中应用补偿 + +![calibration parameters](/resources/images/cal_pic4.jpg) + +MotionCal软件左上角即为所需的校正参数 +分别将校正系数填入参考代码`CalibrateMagnedticData.ino`,对应位置 + +```cpp +//hard iron calibration parameters +const float hard_iron[3] = { -13.45, -28.95, 12.69 }; +//soft iron calibration parameters +const float soft_iron[3][3] = { + { 0.992, -0.006, -0.007 }, + { -0.006, 0.990, -0.004 }, + { -0.007, -0.004, 1.019 } +}; +``` + +完整参考代码如下: + +```cpp +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); +//hard iron calibration parameters +const float hard_iron[3] = { -13.45, -28.95, 12.69 }; +//soft iron calibration parameters +const float soft_iron[3][3] = { + { 0.992, -0.006, -0.007 }, + { -0.006, 0.990, -0.004 }, + { -0.007, -0.004, 1.019 } +}; + +void setup() { + Serial.begin(115200); + while (!Serial) + ; + while (bmm350.begin()) { + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } + Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); +} + +void loop() { + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + + float mag_data[3]; + + // hard iron calibration + mag_data[0] = magData.float_x + hard_iron[0]; + mag_data[1] = magData.float_y + hard_iron[1]; + mag_data[2] = magData.float_z + hard_iron[2]; + + //soft iron calibration + for (int i = 0; i < 3; i++) { + mag_data[i] = (soft_iron[i][0] * mag_data[0]) + (soft_iron[i][1] * mag_data[1]) + (soft_iron[i][2] * mag_data[2]); + } + + magData.x = mag_data[0]; + magData.y = mag_data[1]; + magData.z = mag_data[2]; + magData.float_x = mag_data[0]; + magData.float_y = mag_data[1]; + magData.float_z = mag_data[2]; + + Serial.print("mag x = ");Serial.print(magData.x);Serial.println(" uT"); + Serial.print("mag y = ");Serial.print(magData.y);Serial.println(" uT"); + Serial.print("mag z = ");Serial.print(magData.z);Serial.println(" uT"); + + // float type data + //Serial.print("mag x = "); Serial.print(magData.float_x); Serial.println(" uT"); + //Serial.print("mag y = "); Serial.print(magData.float_y); Serial.println(" uT"); + //Serial.print("mag z = "); Serial.print(magData.float_z); Serial.println(" uT"); + + float compassDegree = getCompassDegree(magData); + Serial.print("the angle between the pointing direction and north (counterclockwise) is:"); + Serial.println(compassDegree); + Serial.println("--------------------------------"); + delay(3000); +} +float getCompassDegree(sBmm350MagData_t magData) +{ + float compass = 0.0; + compass = atan2(magData.x, magData.y); + if (compass < 0) { + compass += 2 * PI; + } + if (compass > 2 * PI) { + compass -= 2 * PI; + } + return compass * 180 / M_PI; +} +``` + +--- + +--- + +## 📎 附录 + +* MotionCal 下载地址:[https://www.pjrc.com/store/prop\_shield.html#motioncal](https://www.pjrc.com/store/prop_shield.html#motioncal) +* DFRobot BMM350 Sensor:[https://wiki.dfrobot.com.cn/_SKU_SEN0619_Gravity_BMM350_TripleAxis_Magnetometer_Sensor](https://wiki.dfrobot.com.cn/_SKU_SEN0619_Gravity_BMM350_TripleAxis_Magnetometer_Sensor) diff --git a/lib/DFRobot_BMM350/examples/calibration/getCalibrateData/getCalibrateData.ino b/lib/DFRobot_BMM350/examples/calibration/getCalibrateData/getCalibrateData.ino new file mode 100644 index 0000000..36ef582 --- /dev/null +++ b/lib/DFRobot_BMM350/examples/calibration/getCalibrateData/getCalibrateData.ino @@ -0,0 +1,92 @@ +/*! + * @file getGeomagneticData.ino + * @brief Get the calibration data + * @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north + * @n Experimental phenomenon: serial print the geomagnetic data of x-axis, y-axis and z-axis and the compass degree + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350/ + */ + +// ======================================================= +// 请先阅读项目 https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration +// Please read https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration +// 包含使用说明、校准步骤。 +// It contains usage instructions, calibration steps. +// ======================================================= +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); +void setup() { + Serial.begin(115200); + while (!Serial) + ; + while (bmm350.begin()) { + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } + Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + * rate: + * BMM350_DATA_RATE_1_5625HZ + * BMM350_DATA_RATE_3_125HZ + * BMM350_DATA_RATE_6_25HZ + * BMM350_DATA_RATE_12_5HZ (default rate) + * BMM350_DATA_RATE_25HZ + * BMM350_DATA_RATE_50HZ + * BMM350_DATA_RATE_100HZ + * BMM350_DATA_RATE_200HZ + * BMM350_DATA_RATE_400HZ + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); +} + +void loop() { + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + Serial.print("Raw:"); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(magData.x*10); + Serial.print(','); + Serial.print(magData.y*10); + Serial.print(','); + Serial.print(magData.z*10); + Serial.println(); + delay(100); +} diff --git a/lib/DFRobot_BMM350/examples/getAllState/getAllState.ino b/lib/DFRobot_BMM350/examples/getAllState/getAllState.ino new file mode 100644 index 0000000..aad0cfa --- /dev/null +++ b/lib/DFRobot_BMM350/examples/getAllState/getAllState.ino @@ -0,0 +1,95 @@ + /*! + * @file getAllState.ino + * @brief Get all the config status, self test status; the sensor turns to sleep mode from normal mode after reset + * @n Experimental phenomenon: serial print the sensor config information and the self-test information + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350 + */ +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); + +void setup() +{ + Serial.begin(115200); + while(!Serial); + while(bmm350.begin()){ + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } Serial.println("bmm350 init success!"); + + /** + * Sensor self test, the returned character string indicates the test result. + */ + Serial.println(bmm350.selfTest()); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + * rate: + * BMM350_DATA_RATE_1_5625HZ + * BMM350_DATA_RATE_3_125HZ + * BMM350_DATA_RATE_6_25HZ + * BMM350_DATA_RATE_12_5HZ (default rate) + * BMM350_DATA_RATE_25HZ + * BMM350_DATA_RATE_50HZ + * BMM350_DATA_RATE_100HZ + * BMM350_DATA_RATE_200HZ + * BMM350_DATA_RATE_400HZ + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); + + /** + * Get the config data rate unit: HZ + */ + float rate = bmm350.getRate(); + Serial.print("rate is "); Serial.print(rate); Serial.println(" HZ"); + + /** + * Get the measurement status at x-axis, y-axis and z-axis, return the measurement status as character string + */ + Serial.println(bmm350.getMeasurementStateXYZ()); + + /** + * Get the sensor operation mode, return the sensor operation status as character string + */ + Serial.println(bmm350.getOperationMode()); + + /** + * After the software is reset, it enters the suspended mode. + */ + bmm350.softReset(); +} + +void loop() +{ + /** + * Get the sensor operation mode, return the sensor operation status as character string + */ + Serial.println(bmm350.getOperationMode()); + delay(3000); +} diff --git a/lib/DFRobot_BMM350/examples/getGeomagneticData/getGeomagneticData.ino b/lib/DFRobot_BMM350/examples/getGeomagneticData/getGeomagneticData.ino new file mode 100644 index 0000000..5cb3298 --- /dev/null +++ b/lib/DFRobot_BMM350/examples/getGeomagneticData/getGeomagneticData.ino @@ -0,0 +1,84 @@ + /*! + * @file getGeomagneticData.ino + * @brief Get the geomagnetic data at 3 axis (x, y, z), get the compass degree + * @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north + * @n Experimental phenomenon: serial print the geomagnetic data of x-axis, y-axis and z-axis and the compass degree + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350 + */ + +#include "DFRobot_BMM350.h" + + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); + +void setup() +{ + Serial.begin(115200); + while(!Serial); + while(bmm350.begin()){ + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + * rate: + * BMM350_DATA_RATE_1_5625HZ + * BMM350_DATA_RATE_3_125HZ + * BMM350_DATA_RATE_6_25HZ + * BMM350_DATA_RATE_12_5HZ (default rate) + * BMM350_DATA_RATE_25HZ + * BMM350_DATA_RATE_50HZ + * BMM350_DATA_RATE_100HZ + * BMM350_DATA_RATE_200HZ + * BMM350_DATA_RATE_400HZ + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); +} + +void loop() +{ + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + Serial.print("mag x = "); Serial.print(magData.x); Serial.println(" uT"); + Serial.print("mag y = "); Serial.print(magData.y); Serial.println(" uT"); + Serial.print("mag z = "); Serial.print(magData.z); Serial.println(" uT"); + + // float type data + //Serial.print("mag x = "); Serial.print(magData.float_x); Serial.println(" uT"); + //Serial.print("mag y = "); Serial.print(magData.float_y); Serial.println(" uT"); + //Serial.print("mag z = "); Serial.print(magData.float_z); Serial.println(" uT"); + + float compassDegree = bmm350.getCompassDegree(); + Serial.print("the angle between the pointing direction and north (counterclockwise) is:"); + Serial.println(compassDegree); + Serial.println("--------------------------------"); + delay(3000); +} diff --git a/lib/DFRobot_BMM350/examples/magDrdyInterrupt/magDrdyInterrupt.ino b/lib/DFRobot_BMM350/examples/magDrdyInterrupt/magDrdyInterrupt.ino new file mode 100644 index 0000000..56d4331 --- /dev/null +++ b/lib/DFRobot_BMM350/examples/magDrdyInterrupt/magDrdyInterrupt.ino @@ -0,0 +1,186 @@ + /*! + * @file magDrdyInterrupt.ino + * @brief Data ready interrupt, DRDY interrupt will be triggered when the geomagnetic data is ready (the software and hardware can determine whether the interrupt occur) + * @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis, unit (uT) + * @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by DRDY pin interrupt, then the geomagnetic data can be obtained. + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350 + */ +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); + +volatile uint8_t interruptFlag = 0; +void myInterrupt(void) +{ + interruptFlag = 1; // Interrupt flag + #if defined(ESP32) || defined(ESP8266) || defined(ARDUINO_SAM_ZERO) + detachInterrupt(13); // Detach interrupt + #else + detachInterrupt(0); // Detach interrupt + #endif +} + +void setup() +{ + Serial.begin(115200); + while(!Serial); + while(bmm350.begin()){ + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + * rate: + * BMM350_DATA_RATE_1_5625HZ + * BMM350_DATA_RATE_3_125HZ + * BMM350_DATA_RATE_6_25HZ + * BMM350_DATA_RATE_12_5HZ (default rate) + * BMM350_DATA_RATE_25HZ + * BMM350_DATA_RATE_50HZ + * BMM350_DATA_RATE_100HZ + * BMM350_DATA_RATE_200HZ + * BMM350_DATA_RATE_400HZ + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); + + /** + * Enable or disable data ready interrupt pin, + * After enabling, the DRDY pin level will change when there's data coming. + * After disabling, the DRDY pin level will not change when there's data coming. + * High polarity: active on high level, the default is low level, which turns to high level when the interrupt is triggered. + * Low polarity: active on low level, the default is high level, which turns to low level when the interrupt is triggered. + * modes: + * BMM350_ENABLE_INTERRUPT // Enable DRDY + * BMM350_DISABLE_INTERRUPT // Disable DRDY + * polatily: + * BMM350_ACTIVE_HIGH // High polarity + * BMM350_ACTIVE_LOW // Low polarity + */ + bmm350.setDataReadyPin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW); + + +#if defined(ESP32) || defined(ESP8266) + /** + Select according to the set DADY pin polarity + INPUT_PULLUP // Low polarity, set pin 13 to pull-up input + INPUT_PULLDOWN // High polarity, set pin 13 to pull-down input + interput io + All pins can be used. Pin 13 is recommended + */ + pinMode(/*Pin */13 ,INPUT_PULLUP); + attachInterrupt(/*interput io*/13, myInterrupt, ONLOW); +#elif defined(ARDUINO_SAM_ZERO) + pinMode(/*Pin */13 ,INPUT_PULLUP); + attachInterrupt(/*interput io*/13, myInterrupt, LOW); +#else + /** The Correspondence Table of AVR Series Arduino Interrupt Pins And Terminal Numbers + * --------------------------------------------------------------------------------------- + * | | Pin | 2 | 3 | | + * | Uno, Nano, Mini, other 328-based |--------------------------------------------| + * | | Interrupt No | 0 | 1 | | + * |-------------------------------------------------------------------------------------| + * | | Pin | 2 | 3 | 21 | 20 | 19 | 18 | + * | Mega2560 |--------------------------------------------| + * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | 5 | + * |-------------------------------------------------------------------------------------| + * | | Pin | 3 | 2 | 0 | 1 | 7 | | + * | Leonardo, other 32u4-based |--------------------------------------------| + * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | | + * |-------------------------------------------------------------------------------------- + */ + + /** The Correspondence Table of micro:bit Interrupt Pins And Terminal Numbers + * --------------------------------------------------------------------------------------------------------------------------------------------- + * | micro:bit | DigitalPin |P0-P20 can be used as an external interrupt | + * | (When using as an external interrupt, |---------------------------------------------------------------------------------------------| + * |no need to set it to input mode with pinMode)|Interrupt No|Interrupt number is a pin digital value, such as P0 interrupt number 0, P1 is 1 | + * |-------------------------------------------------------------------------------------------------------------------------------------------| + */ + /** + Select according to the set DADY pin polarity + INPUT_PULLUP // Low polarity, set pin 2 to pull-up input + */ + pinMode(/*Pin */2 ,INPUT_PULLUP); + + /** + Set the pin to interrupt mode + // Open the external interrupt 0, connect INT1/2 to the digital pin of the main control: + function + callback function + state + LOW // When the pin is at low level, the interrupt occur, enter interrupt function + */ + attachInterrupt(/*Interrupt No*/0, /*function*/myInterrupt ,/*state*/LOW ); +#endif +} + +void loop() +{ + /** + * Get data ready status, determine whether the data is ready (get the data ready status through software) + * status: + * true Data ready + * false Data is not ready yet + */ + /* + if(bmm350.getDataReadyState()){ + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + Serial.print("mag x = "); Serial.print(magData.x); Serial.println(" uT"); + Serial.print("mag y = "); Serial.print(magData.y); Serial.println(" uT"); + Serial.print("mag z = "); Serial.print(magData.z); Serial.println(" uT"); + Serial.println(); + } + */ + + /** + When the interrupt occur in DRDY IO, get the geomagnetic data (get the data ready status through hardware) + Enable interrupt again + */ + if(interruptFlag == 1){ + Serial.println("Interrupt triggering!"); + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + Serial.print("mag x = "); Serial.print(magData.x); Serial.println(" uT"); + Serial.print("mag y = "); Serial.print(magData.y); Serial.println(" uT"); + Serial.print("mag z = "); Serial.print(magData.z); Serial.println(" uT"); + Serial.println(); + interruptFlag = 0; + #if defined(ESP32) || defined(ESP8266) + attachInterrupt(13, myInterrupt, ONLOW); + #elif defined(ARDUINO_SAM_ZERO) + attachInterrupt(13, myInterrupt, LOW); + #else + attachInterrupt(0, myInterrupt, LOW); + #endif + } + + delay(1000); +} diff --git a/lib/DFRobot_BMM350/examples/thresholdInterrupt/thresholdInterrupt.ino b/lib/DFRobot_BMM350/examples/thresholdInterrupt/thresholdInterrupt.ino new file mode 100644 index 0000000..a75813f --- /dev/null +++ b/lib/DFRobot_BMM350/examples/thresholdInterrupt/thresholdInterrupt.ino @@ -0,0 +1,194 @@ + /*! + * @file thresholdInterrupt.ino + * @brief Set the interrupt to be triggered when beyond/below threshold, when the interrupt at a axis occur, the relevant data will be printed in the serial port. + * @n Experimental phenomenon: when the geomagnetic data at 3 axis (x, y, z) beyond/below threshold, serial print the geomagnetic data, unit (uT) + * @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by INT pin interrupt, then the geomagnetic data can be obtained + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350 + */ +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); + +volatile uint8_t interruptFlag = 0; +void myInterrupt(void) +{ + interruptFlag = 1; // Interrupt flag + #if defined(ESP32) || defined(ESP8266) || defined(ARDUINO_SAM_ZERO) + detachInterrupt(13); // Detach interrupt + #else + detachInterrupt(0); // Detach interrupt + #endif +} + +void setup() +{ + Serial.begin(115200); + while(!Serial); + delay(1000); + while(bmm350.begin()){ + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + * rate: + * BMM350_DATA_RATE_1_5625HZ + * BMM350_DATA_RATE_3_125HZ + * BMM350_DATA_RATE_6_25HZ + * BMM350_DATA_RATE_12_5HZ (default rate) + * BMM350_DATA_RATE_25HZ + * BMM350_DATA_RATE_50HZ + * BMM350_DATA_RATE_100HZ + * BMM350_DATA_RATE_200HZ + * BMM350_DATA_RATE_400HZ + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); + + /*! + * Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold + * High polarity: active on high level, the default is low level, which turns to high level when the interrupt is triggered. + * Low polarity: active on low level, the default is high level, which turns to low level when the interrupt is triggered. + * modes: + * LOW_THRESHOLD_INTERRUPT // Low threshold interrupt mode, interrupt is triggered when below the threshold + * HIGH_THRESHOLD_INTERRUPT // High threshold interrupt mode, interrupt is triggered when beyond the threshold + * threshold //Threshold range, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt + * polarity: + * BMM350_ACTIVE_HIGH // High polarity + * BMM350_ACTIVE_LOW // Low polarity + * Refer to setThresholdInterrput() function in the .h file if you want to use more parameters. + */ + bmm350.setThresholdInterrupt(LOW_THRESHOLD_INTERRUPT, 0, BMM350_ACTIVE_LOW); + +#if defined(ESP32) || defined(ESP8266) + /** + Select according to the set DADY pin polarity + INPUT_PULLUP // Low polarity, set pin 13 to pull-up input + INPUT_PULLDOWN // High polarity, set pin 13 to pull-down input + interput io + All pins can be used. Pin 13 is recommended + */ + pinMode(/*Pin */13 ,INPUT_PULLUP); + attachInterrupt(/*interput io*/13, myInterrupt, ONLOW); +#elif defined(ARDUINO_SAM_ZERO) + pinMode(/*Pin */13 ,INPUT_PULLUP); + attachInterrupt(/*interput io*/13, myInterrupt, LOW); +#else + /** The Correspondence Table of AVR Series Arduino Interrupt Pins And Terminal Numbers + * --------------------------------------------------------------------------------------- + * | | Pin | 2 | 3 | | + * | Uno, Nano, Mini, other 328-based |--------------------------------------------| + * | | Interrupt No | 0 | 1 | | + * |-------------------------------------------------------------------------------------| + * | | Pin | 2 | 3 | 21 | 20 | 19 | 18 | + * | Mega2560 |--------------------------------------------| + * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | 5 | + * |-------------------------------------------------------------------------------------| + * | | Pin | 3 | 2 | 0 | 1 | 7 | | + * | Leonardo, other 32u4-based |--------------------------------------------| + * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | | + * |-------------------------------------------------------------------------------------- + */ + + /** The Correspondence Table of micro:bit Interrupt Pins And Terminal Numbers + * --------------------------------------------------------------------------------------------------------------------------------------------- + * | micro:bit | DigitalPin |P0-P20 can be used as an external interrupt | + * | (When using as an external interrupt, |---------------------------------------------------------------------------------------------| + * |no need to set it to input mode with pinMode)|Interrupt No|Interrupt number is a pin digital value, such as P0 interrupt number 0, P1 is 1 | + * |-------------------------------------------------------------------------------------------------------------------------------------------| + */ + /** + Select according to the set DADY pin polarity + INPUT_PULLUP // Low polarity, set pin 2 to pull-up input + */ + pinMode(/*Pin */2 ,INPUT_PULLUP); + + /** + Set the pin to interrupt mode + // Open the external interrupt 0, connect INT to the digital pin of the main control: + function + callback function + state + LOW // When the pin is at low level, the interrupt occur, enter interrupt function + */ + attachInterrupt(/*Interrupt No*/0, /*function*/myInterrupt ,/*state*/LOW ); +#endif + +} + +void loop() +{ + /** + * Get the data that threshold interrupt occured and interrupt status (get the data ready status through software) + * Returns the structure for storing geomagnetic data, the structure stores the data of 3 axis and interrupt status, + * No interrupt triggered when the data at x-axis, y-axis and z-axis is NO_DATA + * Refer to .h file if you want to check interrupt status. + */ + /* + sBmm350ThresholdData_t thresholdData = bmm350.getThresholdData(); + if(thresholdData.mag_x != NO_DATA){ + Serial.print("mag x = "); Serial.print(thresholdData.mag_x); Serial.println(" uT"); + } + if(thresholdData.mag_y != NO_DATA){ + Serial.print("mag y = "); Serial.print(thresholdData.mag_y); Serial.println(" uT"); + } + if(thresholdData.mag_z != NO_DATA){ + Serial.print("mag z = "); Serial.print(thresholdData.mag_z); Serial.println(" uT"); + } + Serial.println(); + */ + + /** + When the interrupt occur in INT IO, get the threshold interrupt data (get the threshold interrupt status through hardware) + */ + if(interruptFlag == 1){ + sBmm350ThresholdData_t thresholdData = bmm350.getThresholdData(); + if(thresholdData.mag_x != NO_DATA){ + Serial.print("mag x = "); Serial.print(thresholdData.mag_x); Serial.println(" uT"); + } + if(thresholdData.mag_y != NO_DATA){ + Serial.print("mag y = "); Serial.print(thresholdData.mag_y); Serial.println(" uT"); + } + if(thresholdData.mag_z != NO_DATA){ + Serial.print("mag z = "); Serial.print(thresholdData.mag_z); Serial.println(" uT"); + } + Serial.println(); + interruptFlag = 0; + #if defined(ESP32) || defined(ESP8266) + attachInterrupt(13, myInterrupt, ONLOW); + #elif defined(ARDUINO_SAM_ZERO) + attachInterrupt(13, myInterrupt, LOW); + #else + attachInterrupt(0, myInterrupt, LOW); + #endif + + } + delay(1000); +} diff --git a/lib/DFRobot_BMM350/keywords.txt b/lib/DFRobot_BMM350/keywords.txt new file mode 100644 index 0000000..0432f89 --- /dev/null +++ b/lib/DFRobot_BMM350/keywords.txt @@ -0,0 +1,76 @@ +####################################### +# Syntax Coloring DFRobot_bmm350 +####################################### + +####################################### +# Datatypes (KEYWORD1) +####################################### + +begin KEYWORD2 +softReset KEYWORD2 +selfTest KEYWORD2 +setOperationMode KEYWORD2 +getOperationMode KEYWORD2 +setRate KEYWORD2 +getRate KEYWORD2 +setPresetMode KEYWORD2 +getGeomagneticData KEYWORD2 +getCompassDegree KEYWORD2 +setDataReadyPin KEYWORD2 +getDataReadyState KEYWORD2 +setMeasurementXYZ KEYWORD2 +getMeasurementStateXYZ KEYWORD2 +setThresholdInterrupt KEYWORD2 +getThresholdData KEYWORD2 + +####################################### +# Constants (LITERAL1) +####################################### + +DFRobot_bmm350 KEYWORD1 +DFRobot_bmm350_I2C KEYWORD1 +DFRobot_bmm350_I3C KEYWORD1 + +####################################### +# Methods and Functions (KEYWORD2) +####################################### + +BMM350_OK LITERAL1 + +BMM350_SELF_TEST_ADVANCED LITERAL1 +BMM350_SELF_TEST_NORMAL LITERAL1 + +eBmm350SuspendMode LITERAL1 +eBmm350NormalMode LITERAL1 +eBmm350ForcedMode LITERAL1 +eBmm350ForcedModeFast LITERAL1 + +BMM350_PRESETMODE_LOWPOWER LITERAL1 +BMM350_PRESETMODE_REGULAR LITERAL1 +BMM350_PRESETMODE_HIGHACCURACY LITERAL1 +BMM350_PRESETMODE_ENHANCED LITERAL1 + +BMM350_ODR_1_5625HZ LITERAL1 +BMM350_ODR_3_125HZ LITERAL1 +BMM350_ODR_6_25HZ LITERAL1 +BMM350_ODR_12_5HZ LITERAL1 +BMM350_ODR_25HZ LITERAL1 +BMM350_ODR_50HZ LITERAL1 +BMM350_ODR_100HZ LITERAL1 +BMM350_ODR_200HZ LITERAL1 +BMM350_ODR_400HZ LITERAL1 + +POLARITY_HIGH LITERAL1 +POLARITY_LOW LITERAL1 + +INTERRUPT_X_ENABLE LITERAL1 +INTERRUPT_Y_ENABLE LITERAL1 +INTERRUPT_Z_ENABLE LITERAL1 +INTERRUPT_X_DISABLE LITERAL1 +INTERRUPT_Y_DISABLE LITERAL1 +INTERRUPT_Z_DISABLE LITERAL1 + +ENABLE_INTERRUPT_PIN LITERAL1 +DISABLE_INTERRUPT_PIN LITERAL1 +LOW_THRESHOLD_INTERRUPT LITERAL1 +HIGH_THRESHOLD_INTERRUPT LITERAL1 diff --git a/lib/DFRobot_BMM350/library.properties b/lib/DFRobot_BMM350/library.properties new file mode 100644 index 0000000..23b406c --- /dev/null +++ b/lib/DFRobot_BMM350/library.properties @@ -0,0 +1,9 @@ +name=DFRobot_BMM350 +version=1.0.0 +author=DFRobot +maintainer=[GDuang](yonglei.ren@dfrobot.com) +sentence=DFRobot Standard 3-axis geomagnetic sensor library(SKU:SEN0419). +paragraph=The BMM350 is a low-power and low noise 3-axis digital geomagnetic sensor that perfectly matches the requirements of compass applications. +category=Sensors +url=https://github.com/DFRobot/DFRobot_BMM350 +architectures=* diff --git a/lib/DFRobot_BMM350/python/raspberrypi/DFRobot_bmm350.py b/lib/DFRobot_BMM350/python/raspberrypi/DFRobot_bmm350.py new file mode 100644 index 0000000..b0d8596 --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/DFRobot_bmm350.py @@ -0,0 +1,1595 @@ +# -*- coding: utf-8 -* +''' + @file DFRobot_bmm350.py + @note DFRobot_bmm350 Class infrastructure, implementation of underlying methods + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-06 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import serial +import time +import os +import math + + +# Chip id of BMM350 +BMM350_CHIP_ID = 0x33 + +# Variant ID of BMM350 +BMM350_MIN_VAR = 0x10 + +# Sensor interface success code +BMM350_INTF_RET_SUCCESS = 0 + +# API success code +BMM350_OK = 0 + +# API error codes +BMM350_E_NULL_PTR = -1 +BMM350_E_COM_FAIL = -2 +BMM350_E_DEV_NOT_FOUND = -3 +BMM350_E_INVALID_CONFIG = -4 +BMM350_E_BAD_PAD_DRIVE = -5 +BMM350_E_RESET_UNFINISHED = -6 +BMM350_E_INVALID_INPUT = -7 +BMM350_E_SELF_TEST_INVALID_AXIS = -8 +BMM350_E_OTP_BOOT = -9 +BMM350_E_OTP_PAGE_RD = -10 +BMM350_E_OTP_PAGE_PRG = -11 +BMM350_E_OTP_SIGN = -12 +BMM350_E_OTP_INV_CMD = -13 +BMM350_E_OTP_UNDEFINED = -14 +BMM350_E_ALL_AXIS_DISABLED = -15 +BMM350_E_PMU_CMD_VALUE = -16 + +BMM350_NO_ERROR = 0 + +# Sensor delay time settings in microseconds +BMM350_SOFT_RESET_DELAY = 24000/1000000 +BMM350_MAGNETIC_RESET_DELAY = 40000/1000000 +BMM350_START_UP_TIME_FROM_POR = 3000/1000000 +BMM350_GOTO_SUSPEND_DELAY = 6000/1000000 +BMM350_SUSPEND_TO_NORMAL_DELAY = 38000/1000000 +BMM350_SUS_TO_FORCEDMODE_NO_AVG_DELAY = 15000/1000000 +BMM350_SUS_TO_FORCEDMODE_AVG_2_DELAY = 17000/1000000 +BMM350_SUS_TO_FORCEDMODE_AVG_4_DELAY = 20000/1000000 +BMM350_SUS_TO_FORCEDMODE_AVG_8_DELAY = 28000/1000000 +BMM350_SUS_TO_FORCEDMODE_FAST_NO_AVG_DELAY = 4000/1000000 +BMM350_SUS_TO_FORCEDMODE_FAST_AVG_2_DELAY = 5000/1000000 +BMM350_SUS_TO_FORCEDMODE_FAST_AVG_4_DELAY = 9000/1000000 +BMM350_SUS_TO_FORCEDMODE_FAST_AVG_8_DELAY = 16000/1000000 +BMM350_UPD_OAE_DELAY = 1000/1000000 +BMM350_BR_DELAY = 14000/1000000 +BMM350_FGR_DELAY = 18000/1000000 + +# Length macros +BMM350_OTP_DATA_LENGTH = 32 +BMM350_READ_BUFFER_LENGTH = 127 +BMM350_MAG_TEMP_DATA_LEN = 12 + +# Averaging macros +BMM350_AVG_NO_AVG = 0x0 +BMM350_AVG_2 = 0x1 +BMM350_AVG_4 = 0x2 +BMM350_AVG_8 = 0x3 + +# ODR +BMM350_ODR_400HZ = 0x2 +BMM350_ODR_200HZ = 0x3 +BMM350_ODR_100HZ = 0x4 +BMM350_ODR_50HZ = 0x5 +BMM350_ODR_25HZ = 0x6 +BMM350_ODR_12_5HZ = 0x7 # default rate +BMM350_ODR_6_25HZ = 0x8 +BMM350_ODR_3_125HZ = 0x9 +BMM350_ODR_1_5625HZ = 0xA + +# Power modes +BMM350_PMU_CMD_SUS = 0x00 +BMM350_PMU_CMD_NM = 0x01 +BMM350_PMU_CMD_UPD_OAE = 0x02 +BMM350_PMU_CMD_FM = 0x03 +BMM350_PMU_CMD_FM_FAST = 0x04 +BMM350_PMU_CMD_FGR = 0x05 +BMM350_PMU_CMD_FGR_FAST = 0x06 +BMM350_PMU_CMD_BR = 0x07 +BMM350_PMU_CMD_BR_FAST = 0x08 +BMM350_PMU_CMD_NM_TC = 0x09 + +BMM350_PMU_STATUS_0 = 0x0 + +BMM350_DISABLE = 0x0 +BMM350_ENABLE = 0x1 +BMM350_MAP_TO_PIN = BMM350_ENABLE + +BMM350_CMD_NOP = 0x0 +BMM350_CMD_SOFTRESET = 0xB6 + +BMM350_TARGET_PAGE_PAGE0 = 0x0 +BMM350_TARGET_PAGE_PAGE1 = 0x1 + +BMM350_INT_MODE_LATCHED = 0x1 +BMM350_INT_MODE_PULSED = 0x0 + +BMM350_INT_POL_ACTIVE_HIGH = 0x1 +BMM350_INT_POL_ACTIVE_LOW = 0x0 + +BMM350_INT_OD_PUSHPULL = 0x1 +BMM350_INT_OD_OPENDRAIN = 0x0 + +BMM350_INT_OUTPUT_EN_OFF = 0x0 +BMM350_INT_OUTPUT_EN_ON = 0x1 + +BMM350_INT_DRDY_EN = 0x1 +BMM350_INT_DRDY_DIS = 0x0 + +BMM350_MR_MR1K8 = 0x0 +BMM350_MR_MR2K1 = 0x1 +BMM350_MR_MR1K5 = 0x2 +BMM350_MR_MR0K6 = 0x3 + +BMM350_SEL_DTB1X_PAD_PAD_INT = 0x0 +BMM350_SEL_DTB1X_PAD_PAD_BYP = 0x1 + +BMM350_TMR_TST_HIZ_VTMR_VTMR_ON = 0x0 +BMM350_TMR_TST_HIZ_VTMR_VTMR_HIZ = 0x1 + +BMM350_LSB_MASK = 0x00FF +BMM350_MSB_MASK = 0xFF00 + +# Pad drive strength +BMM350_PAD_DRIVE_WEAKEST = 0 +BMM350_PAD_DRIVE_STRONGEST = 7 + +# I2C Register Addresses + +# Register to set I2C address to LOW +BMM350_I2C_ADSEL_SET_LOW = 0x14 + +# Register to set I2C address to HIGH +BMM350_I2C_ADSEL_SET_HIGH = 0x15 + +BMM350_DUMMY_BYTES = 2 + +# Register Addresses + +BMM350_REG_CHIP_ID = 0x00 +BMM350_REG_REV_ID = 0x01 +BMM350_REG_ERR_REG = 0x02 +BMM350_REG_PAD_CTRL = 0x03 +BMM350_REG_PMU_CMD_AGGR_SET = 0x04 +BMM350_REG_PMU_CMD_AXIS_EN = 0x05 +BMM350_REG_PMU_CMD = 0x06 +BMM350_REG_PMU_CMD_STATUS_0 = 0x07 +BMM350_REG_PMU_CMD_STATUS_1 = 0x08 +BMM350_REG_I3C_ERR = 0x09 +BMM350_REG_I2C_WDT_SET = 0x0A +BMM350_REG_TRSDCR_REV_ID = 0x0D +BMM350_REG_TC_SYNC_TU = 0x21 +BMM350_REG_TC_SYNC_ODR = 0x22 +BMM350_REG_TC_SYNC_TPH_1 = 0x23 +BMM350_REG_TC_SYNC_TPH_2 = 0x24 +BMM350_REG_TC_SYNC_DT = 0x25 +BMM350_REG_TC_SYNC_ST_0 = 0x26 +BMM350_REG_TC_SYNC_ST_1 = 0x27 +BMM350_REG_TC_SYNC_ST_2 = 0x28 +BMM350_REG_TC_SYNC_STATUS = 0x29 +BMM350_REG_INT_CTRL = 0x2E +BMM350_REG_INT_CTRL_IBI = 0x2F +BMM350_REG_INT_STATUS = 0x30 +BMM350_REG_MAG_X_XLSB = 0x31 +BMM350_REG_MAG_X_LSB = 0x32 +BMM350_REG_MAG_X_MSB = 0x33 +BMM350_REG_MAG_Y_XLSB = 0x34 +BMM350_REG_MAG_Y_LSB = 0x35 +BMM350_REG_MAG_Y_MSB = 0x36 +BMM350_REG_MAG_Z_XLSB = 0x37 +BMM350_REG_MAG_Z_LSB = 0x38 +BMM350_REG_MAG_Z_MSB = 0x39 +BMM350_REG_TEMP_XLSB = 0x3A +BMM350_REG_TEMP_LSB = 0x3B +BMM350_REG_TEMP_MSB = 0x3C +BMM350_REG_SENSORTIME_XLSB = 0x3D +BMM350_REG_SENSORTIME_LSB = 0x3E +BMM350_REG_SENSORTIME_MSB = 0x3F +BMM350_REG_OTP_CMD_REG = 0x50 +BMM350_REG_OTP_DATA_MSB_REG = 0x52 +BMM350_REG_OTP_DATA_LSB_REG = 0x53 +BMM350_REG_OTP_STATUS_REG = 0x55 +BMM350_REG_TMR_SELFTEST_USER = 0x60 +BMM350_REG_CTRL_USER = 0x61 +BMM350_REG_CMD = 0x7E + +# Macros for OVWR +BMM350_REG_OVWR_VALUE_ANA_0 = 0x3A +BMM350_REG_OVWR_EN_ANA_0 = 0x3B + +# Macros for bit masking + +BMM350_CHIP_ID_OTP_MSK = 0xf +BMM350_CHIP_ID_OTP_POS = 0x0 +BMM350_CHIP_ID_FIXED_MSK = 0xf0 +BMM350_CHIP_ID_FIXED_POS = 0x4 +BMM350_REV_ID_MAJOR_MSK = 0xf0 +BMM350_REV_ID_MAJOR_POS = 0x4 +BMM350_REV_ID_MINOR_MSK = 0xf +BMM350_REV_ID_MINOR_POS = 0x0 +BMM350_PMU_CMD_ERROR_MSK = 0x1 +BMM350_PMU_CMD_ERROR_POS = 0x0 +BMM350_BOOT_UP_ERROR_MSK = 0x2 +BMM350_BOOT_UP_ERROR_POS = 0x1 +BMM350_DRV_MSK = 0x7 +BMM350_DRV_POS = 0x0 +BMM350_AVG_MSK = 0x30 +BMM350_AVG_POS = 0x4 +BMM350_ODR_MSK = 0xf +BMM350_ODR_POS = 0x0 +BMM350_PMU_CMD_MSK = 0xf +BMM350_PMU_CMD_POS = 0x0 +BMM350_EN_X_MSK = 0x01 +BMM350_EN_X_POS = 0x0 +BMM350_EN_Y_MSK = 0x02 +BMM350_EN_Y_POS = 0x1 +BMM350_EN_Z_MSK = 0x04 +BMM350_EN_Z_POS = 0x2 +BMM350_EN_XYZ_MSK = 0x7 +BMM350_EN_XYZ_POS = 0x0 +BMM350_PMU_CMD_BUSY_MSK = 0x1 +BMM350_PMU_CMD_BUSY_POS = 0x0 +BMM350_ODR_OVWR_MSK = 0x2 +BMM350_ODR_OVWR_POS = 0x1 +BMM350_AVG_OVWR_MSK = 0x4 +BMM350_AVG_OVWR_POS = 0x2 +BMM350_PWR_MODE_IS_NORMAL_MSK = 0x8 +BMM350_PWR_MODE_IS_NORMAL_POS = 0x3 +BMM350_CMD_IS_ILLEGAL_MSK = 0x10 +BMM350_CMD_IS_ILLEGAL_POS = 0x4 +BMM350_PMU_CMD_VALUE_MSK = 0xE0 +BMM350_PMU_CMD_VALUE_POS = 0x5 +BMM350_PMU_ODR_S_MSK = 0xf +BMM350_PMU_ODR_S_POS = 0x0 +BMM350_PMU_AVG_S_MSK = 0x30 +BMM350_PMU_AVG_S_POS = 0x4 +BMM350_I3C_ERROR_0_MSK = 0x1 +BMM350_I3C_ERROR_0_POS = 0x0 +BMM350_I3C_ERROR_3_MSK = 0x8 +BMM350_I3C_ERROR_3_POS = 0x3 +BMM350_I2C_WDT_EN_MSK = 0x1 +BMM350_I2C_WDT_EN_POS = 0x0 +BMM350_I2C_WDT_SEL_MSK = 0x2 + +BMM350_I2C_WDT_SEL_POS = 0x1 +BMM350_TRSDCR_REV_ID_OTP_MSK = 0x3 +BMM350_TRSDCR_REV_ID_OTP_POS = 0x0 +BMM350_TRSDCR_REV_ID_FIXED_MSK = 0xfc +BMM350_TRSDCR_REV_ID_FIXED_POS = 0x2 +BMM350_PAGING_EN_MSK = 0x80 +BMM350_PAGING_EN_POS = 0x7 +BMM350_DRDY_DATA_REG_MSK = 0x4 +BMM350_DRDY_DATA_REG_POS = 0x2 +BMM350_INT_MODE_MSK = 0x1 +BMM350_INT_MODE_POS = 0x0 +BMM350_INT_POL_MSK = 0x2 +BMM350_INT_POL_POS = 0x1 +BMM350_INT_OD_MSK = 0x4 +BMM350_INT_OD_POS = 0x2 +BMM350_INT_OUTPUT_EN_MSK = 0x8 +BMM350_INT_OUTPUT_EN_POS = 0x3 +BMM350_DRDY_DATA_REG_EN_MSK = 0x80 +BMM350_DRDY_DATA_REG_EN_POS = 0x7 +BMM350_DRDY_INT_MAP_TO_IBI_MSK = 0x1 +BMM350_DRDY_INT_MAP_TO_IBI_POS = 0x0 +BMM350_CLEAR_DRDY_INT_STATUS_UPON_IBI_MSK = 0x10 +BMM350_CLEAR_DRDY_INT_STATUS_UPON_IBI_POS = 0x4 +BMM350_TC_SYNC_TU_MSK = 0xff +BMM350_TC_SYNC_ODR_MSK = 0xff +BMM350_TC_SYNC_TPH_1_MSK = 0xff +BMM350_TC_SYNC_TPH_2_MSK = 0xff +BMM350_TC_SYNC_DT_MSK = 0xff +BMM350_TC_SYNC_ST_0_MSK = 0xff +BMM350_TC_SYNC_ST_1_MSK = 0xff +BMM350_TC_SYNC_ST_2_MSK = 0xff +BMM350_CFG_FORCE_SOSC_EN_MSK = 0x4 +BMM350_CFG_FORCE_SOSC_EN_POS = 0x2 +BMM350_ST_IGEN_EN_MSK = 0x1 +BMM350_ST_IGEN_EN_POS = 0x0 +BMM350_ST_N_MSK = 0x2 +BMM350_ST_N_POS = 0x1 +BMM350_ST_P_MSK = 0x4 +BMM350_ST_P_POS = 0x2 +BMM350_IST_EN_X_MSK = 0x8 +BMM350_IST_EN_X_POS = 0x3 +BMM350_IST_EN_Y_MSK = 0x10 +BMM350_IST_EN_Y_POS = 0x4 +BMM350_CFG_SENS_TIM_AON_MSK = 0x1 +BMM350_CFG_SENS_TIM_AON_POS = 0x0 +BMM350_DATA_X_7_0_MSK = 0xff +BMM350_DATA_X_7_0_POS = 0x0 +BMM350_DATA_X_15_8_MSK = 0xff +BMM350_DATA_X_15_8_POS = 0x0 +BMM350_DATA_X_23_16_MSK = 0xff +BMM350_DATA_X_23_16_POS = 0x0 +BMM350_DATA_Y_7_0_MSK = 0xff +BMM350_DATA_Y_7_0_POS = 0x0 +BMM350_DATA_Y_15_8_MSK = 0xff +BMM350_DATA_Y_15_8_POS = 0x0 +BMM350_DATA_Y_23_16_MSK = 0xff +BMM350_DATA_Y_23_16_POS = 0x0 +BMM350_DATA_Z_7_0_MSK = 0xff +BMM350_DATA_Z_7_0_POS = 0x0 +BMM350_DATA_Z_15_8_MSK = 0xff +BMM350_DATA_Z_15_8_POS = 0x0 +BMM350_DATA_Z_23_16_MSK = 0xff +BMM350_DATA_Z_23_16_POS = 0x0 +BMM350_DATA_T_7_0_MSK = 0xff +BMM350_DATA_T_7_0_POS = 0x0 +BMM350_DATA_T_15_8_MSK = 0xff +BMM350_DATA_T_15_8_POS = 0x0 +BMM350_DATA_T_23_16_MSK = 0xff +BMM350_DATA_T_23_16_POS = 0x0 +BMM350_DATA_ST_7_0_MSK = 0xff +BMM350_DATA_ST_7_0_POS = 0x0 +BMM350_DATA_ST_15_8_MSK = 0xff +BMM350_DATA_ST_15_8_POS = 0x0 +BMM350_DATA_ST_23_16_MSK = 0xff +BMM350_DATA_ST_23_16_POS = 0x0 +BMM350_SIGN_INVERT_T_MSK = 0x10 +BMM350_SIGN_INVERT_T_POS = 0x4 +BMM350_SIGN_INVERT_X_MSK = 0x20 +BMM350_SIGN_INVERT_X_POS = 0x5 +BMM350_SIGN_INVERT_Y_MSK = 0x40 +BMM350_SIGN_INVERT_Y_POS = 0x6 +BMM350_SIGN_INVERT_Z_MSK = 0x80 +BMM350_SIGN_INVERT_Z_POS = 0x7 +BMM350_DIS_BR_NM_MSK = 0x1 +BMM350_DIS_BR_NM_POS = 0x0 +BMM350_DIS_FGR_NM_MSK = 0x2 +BMM350_DIS_FGR_NM_POS = 0x1 +BMM350_DIS_CRST_AT_ALL_MSK = 0x4 +BMM350_DIS_CRST_AT_ALL_POS = 0x2 +BMM350_DIS_BR_FM_MSK = 0x8 +BMM350_DIS_BR_FM_POS = 0x3 +BMM350_FRC_EN_BUFF_MSK = 0x1 +BMM350_FRC_EN_BUFF_POS = 0x0 +BMM350_FRC_INA_EN1_MSK = 0x2 +BMM350_FRC_INA_EN1_POS = 0x1 +BMM350_FRC_INA_EN2_MSK = 0x4 +BMM350_FRC_INA_EN2_POS = 0x2 +BMM350_FRC_ADC_EN_MSK = 0x8 +BMM350_FRC_ADC_EN_POS = 0x3 +BMM350_FRC_INA_RST_MSK = 0x10 +BMM350_FRC_INA_RST_POS = 0x4 +BMM350_FRC_ADC_RST_MSK = 0x20 +BMM350_FRC_ADC_RST_POS = 0x5 +BMM350_FRC_INA_XSEL_MSK = 0x1 +BMM350_FRC_INA_XSEL_POS = 0x0 +BMM350_FRC_INA_YSEL_MSK = 0x2 +BMM350_FRC_INA_YSEL_POS = 0x1 +BMM350_FRC_INA_ZSEL_MSK = 0x4 +BMM350_FRC_INA_ZSEL_POS = 0x2 +BMM350_FRC_ADC_TEMP_EN_MSK = 0x8 +BMM350_FRC_ADC_TEMP_EN_POS = 0x3 +BMM350_FRC_TSENS_EN_MSK = 0x10 +BMM350_FRC_TSENS_EN_POS = 0x4 +BMM350_DSENS_FM_MSK = 0x20 +BMM350_DSENS_FM_POS = 0x5 +BMM350_DSENS_SEL_MSK = 0x40 +BMM350_DSENS_SEL_POS = 0x6 +BMM350_DSENS_SHORT_MSK = 0x80 +BMM350_DSENS_SHORT_POS = 0x7 +BMM350_ERR_MISS_BR_DONE_MSK = 0x1 +BMM350_ERR_MISS_BR_DONE_POS = 0x0 +BMM350_ERR_MISS_FGR_DONE_MSK = 0x2 +BMM350_ERR_MISS_FGR_DONE_POS = 0x1 +BMM350_TST_CHAIN_LN_MODE_MSK = 0x1 +BMM350_TST_CHAIN_LN_MODE_POS = 0x0 +BMM350_TST_CHAIN_LP_MODE_MSK = 0x2 +BMM350_TST_CHAIN_LP_MODE_POS = 0x1 +BMM350_EN_OVWR_TMR_IF_MSK = 0x1 +BMM350_EN_OVWR_TMR_IF_POS = 0x0 +BMM350_TMR_CKTRIGB_MSK = 0x2 +BMM350_TMR_CKTRIGB_POS = 0x1 +BMM350_TMR_DO_BR_MSK = 0x4 +BMM350_TMR_DO_BR_POS = 0x2 +BMM350_TMR_DO_FGR_MSK = 0x18 +BMM350_TMR_DO_FGR_POS = 0x3 +BMM350_TMR_EN_OSC_MSK = 0x80 +BMM350_TMR_EN_OSC_POS = 0x7 +BMM350_VCM_TRIM_X_MSK = 0x1f +BMM350_VCM_TRIM_X_POS = 0x0 +BMM350_VCM_TRIM_Y_MSK = 0x1f +BMM350_VCM_TRIM_Y_POS = 0x0 +BMM350_VCM_TRIM_Z_MSK = 0x1f +BMM350_VCM_TRIM_Z_POS = 0x0 +BMM350_VCM_TRIM_DSENS_MSK = 0x1f +BMM350_VCM_TRIM_DSENS_POS = 0x0 +BMM350_TWLB_MSK = 0x30 +BMM350_TWLB_POS = 0x4 +BMM350_PRG_PLS_TIM_MSK = 0x30 +BMM350_PRG_PLS_TIM_POS = 0x4 +BMM350_OTP_OVWR_EN_MSK = 0x1 +BMM350_OTP_OVWR_EN_POS = 0x0 +BMM350_OTP_MEM_CLK_MSK = 0x2 +BMM350_OTP_MEM_CLK_POS = 0x1 +BMM350_OTP_MEM_CS_MSK = 0x4 +BMM350_OTP_MEM_CS_POS = 0x2 +BMM350_OTP_MEM_PGM_MSK = 0x8 +BMM350_OTP_MEM_PGM_POS = 0x3 +BMM350_OTP_MEM_RE_MSK = 0x10 +BMM350_OTP_MEM_RE_POS = 0x4 +BMM350_SAMPLE_RDATA_PLS_MSK = 0x80 +BMM350_SAMPLE_RDATA_PLS_POS = 0x7 +BMM350_CFG_FW_MSK = 0x1 +BMM350_CFG_FW_POS = 0x0 +BMM350_EN_BR_X_MSK = 0x2 +BMM350_EN_BR_X_POS = 0x1 +BMM350_EN_BR_Y_MSK = 0x4 +BMM350_EN_BR_Y_POS = 0x2 +BMM350_EN_BR_Z_MSK = 0x8 +BMM350_EN_BR_Z_POS = 0x3 +BMM350_CFG_PAUSE_TIME_MSK = 0x30 +BMM350_CFG_PAUSE_TIME_POS = 0x4 +BMM350_CFG_FGR_PLS_DUR_MSK = 0xf +BMM350_CFG_FGR_PLS_DUR_POS = 0x0 +BMM350_CFG_BR_Z_ORDER_MSK = 0x10 +BMM350_CFG_BR_Z_ORDER_POS = 0x4 +BMM350_CFG_BR_XY_CHOP_MSK = 0x20 +BMM350_CFG_BR_XY_CHOP_POS = 0x5 +BMM350_CFG_BR_PLS_DUR_MSK = 0xc0 +BMM350_CFG_BR_PLS_DUR_POS = 0x6 +BMM350_ENABLE_BR_FGR_TEST_MSK = 0x1 +BMM350_ENABLE_BR_FGR_TEST_POS = 0x0 +BMM350_SEL_AXIS_MSK = 0xe +BMM350_SEL_AXIS_POS = 0x1 +BMM350_TMR_CFG_TEST_CLK_EN_MSK = 0x10 +BMM350_TMR_CFG_TEST_CLK_EN_POS = 0x4 +BMM350_TEST_VAL_BITS_7DOWNTO0_MSK = 0xff +BMM350_TEST_VAL_BITS_7DOWNTO0_POS = 0x0 +BMM350_TEST_VAL_BITS_8_MSK = 0x1 +BMM350_TEST_VAL_BITS_8_POS = 0x0 +BMM350_TEST_P_SAMPLE_MSK = 0x2 +BMM350_TEST_P_SAMPLE_POS = 0x1 +BMM350_TEST_N_SAMPLE_MSK = 0x4 +BMM350_TEST_N_SAMPLE_POS = 0x2 +BMM350_TEST_APPLY_TO_REM_MSK = 0x10 +BMM350_TEST_APPLY_TO_REM_POS = 0x4 +BMM350_UFO_TRM_OSC_RANGE_MSK = 0xf +BMM350_UFO_TRM_OSC_RANGE_POS = 0x0 +BMM350_ISO_CHIP_ID_MSK = 0x78 +BMM350_ISO_CHIP_ID_POS = 0x3 +BMM350_ISO_I2C_DEV_ID_MSK = 0x80 +BMM350_ISO_I2C_DEV_ID_POS = 0x7 +BMM350_I3C_FREQ_BITS_1DOWNTO0_MSK = 0xc +BMM350_I3C_FREQ_BITS_1DOWNTO0_POS = 0x2 +BMM350_I3C_IBI_MDB_SEL_MSK = 0x10 +BMM350_I3C_IBI_MDB_SEL_POS = 0x4 +BMM350_TC_ASYNC_EN_MSK = 0x20 +BMM350_TC_ASYNC_EN_POS = 0x5 +BMM350_TC_SYNC_EN_MSK = 0x40 +BMM350_TC_SYNC_EN_POS = 0x6 +BMM350_I3C_SCL_GATING_EN_MSK = 0x80 +BMM350_I3C_SCL_GATING_EN_POS = 0x7 +BMM350_I3C_INACCURACY_BITS_6DOWNTO0_MSK = 0x7f +BMM350_I3C_INACCURACY_BITS_6DOWNTO0_POS = 0x0 +BMM350_EST_EN_X_MSK = 0x1 +BMM350_EST_EN_X_POS = 0x0 +BMM350_EST_EN_Y_MSK = 0x2 +BMM350_EST_EN_Y_POS = 0x1 +BMM350_CRST_DIS_MSK = 0x4 +BMM350_CRST_DIS_POS = 0x2 +BMM350_BR_TFALL_MSK = 0x7 +BMM350_BR_TFALL_POS = 0x0 +BMM350_BR_TRISE_MSK = 0x70 +BMM350_BR_TRISE_POS = 0x4 +BMM350_TMR_SOFT_START_DIS_MSK = 0x80 +BMM350_TMR_SOFT_START_DIS_POS = 0x7 +BMM350_FOSC_LOW_RANGE_MSK = 0x80 +BMM350_FOSC_LOW_RANGE_POS = 0x7 +BMM350_VCRST_TRIM_FG_MSK = 0x3f +BMM350_VCRST_TRIM_FG_POS = 0x0 +BMM350_VCRST_TRIM_BR_MSK = 0x3f +BMM350_VCRST_TRIM_BR_POS = 0x0 +BMM350_BG_TRIM_VRP_MSK = 0xc0 +BMM350_BG_TRIM_VRP_POS = 0x6 +BMM350_BG_TRIM_TC_MSK = 0xf +BMM350_BG_TRIM_TC_POS = 0x0 +BMM350_BG_TRIM_VRA_MSK = 0xf0 +BMM350_BG_TRIM_VRA_POS = 0x4 +BMM350_BG_TRIM_VRD_MSK = 0xf +BMM350_BG_TRIM_VRD_POS = 0x0 +BMM350_OVWR_REF_IB_EN_MSK = 0x10 +BMM350_OVWR_REF_IB_EN_POS = 0x4 +BMM350_OVWR_VDDA_EN_MSK = 0x20 +BMM350_OVWR_VDDA_EN_POS = 0x5 +BMM350_OVWR_VDDP_EN_MSK = 0x40 +BMM350_OVWR_VDDP_EN_POS = 0x6 +BMM350_OVWR_VDDS_EN_MSK = 0x80 +BMM350_OVWR_VDDS_EN_POS = 0x7 +BMM350_REF_IB_EN_MSK = 0x10 +BMM350_REF_IB_EN_POS = 0x4 +BMM350_VDDA_EN_MSK = 0x20 +BMM350_VDDA_EN_POS = 0x5 +BMM350_VDDP_EN_MSK = 0x40 +BMM350_VDDP_EN_POS = 0x6 +BMM350_VDDS_EN_MSK = 0x80 +BMM350_VDDS_EN_POS = 0x7 +BMM350_OVWR_OTP_PROG_VDD_SW_EN_MSK = 0x8 +BMM350_OVWR_OTP_PROG_VDD_SW_EN_POS = 0x3 +BMM350_OVWR_EN_MFE_BG_FILT_BYPASS_MSK = 0x10 +BMM350_OVWR_EN_MFE_BG_FILT_BYPASS_POS = 0x4 +BMM350_OTP_PROG_VDD_SW_EN_MSK = 0x8 +BMM350_OTP_PROG_VDD_SW_EN_POS = 0x3 +BMM350_CP_COMP_CRST_EN_TM_MSK = 0x10 +BMM350_CP_COMP_CRST_EN_TM_POS = 0x4 +BMM350_CP_COMP_VDD_EN_TM_MSK = 0x20 +BMM350_CP_COMP_VDD_EN_TM_POS = 0x5 +BMM350_CP_INTREFS_EN_TM_MSK = 0x40 +BMM350_CP_INTREFS_EN_TM_POS = 0x6 +BMM350_ADC_LOCAL_CHOP_EN_MSK = 0x20 +BMM350_ADC_LOCAL_CHOP_EN_POS = 0x5 +BMM350_INA_MODE_MSK = 0x40 +BMM350_INA_MODE_POS = 0x6 +BMM350_VDDD_EXT_EN_MSK = 0x20 +BMM350_VDDD_EXT_EN_POS = 0x5 +BMM350_VDDP_EXT_EN_MSK = 0x80 +BMM350_VDDP_EXT_EN_POS = 0x7 +BMM350_ADC_DSENS_EN_MSK = 0x10 +BMM350_ADC_DSENS_EN_POS = 0x4 +BMM350_DSENS_EN_MSK = 0x20 +BMM350_DSENS_EN_POS = 0x5 +BMM350_OTP_TM_CLVWR_EN_MSK = 0x40 +BMM350_OTP_TM_CLVWR_EN_POS = 0x6 +BMM350_OTP_VDDP_DIS_MSK = 0x80 +BMM350_OTP_VDDP_DIS_POS = 0x7 +BMM350_FORCE_HIGH_VREF_IREF_OK_MSK = 0x10 +BMM350_FORCE_HIGH_VREF_IREF_OK_POS = 0x4 +BMM350_FORCE_HIGH_FOSC_OK_MSK = 0x20 +BMM350_FORCE_HIGH_FOSC_OK_POS = 0x5 +BMM350_FORCE_HIGH_MFE_BG_RDY_MSK = 0x40 +BMM350_FORCE_HIGH_MFE_BG_RDY_POS = 0x6 +BMM350_FORCE_HIGH_MFE_VTMR_RDY_MSK = 0x80 +BMM350_FORCE_HIGH_MFE_VTMR_RDY_POS = 0x7 +BMM350_ERR_END_OF_RECHARGE_MSK = 0x1 +BMM350_ERR_END_OF_RECHARGE_POS = 0x0 +BMM350_ERR_END_OF_DISCHARGE_MSK = 0x2 +BMM350_ERR_END_OF_DISCHARGE_POS = 0x1 +BMM350_CP_TMX_DIGTP_SEL_MSK = 0x7 +BMM350_CP_TMX_DIGTP_SEL_POS = 0x0 +BMM350_CP_CPOSC_EN_TM_MSK = 0x80 +BMM350_CP_CPOSC_EN_TM_POS = 0x7 +BMM350_TST_ATM1_CFG_MSK = 0x3f +BMM350_TST_ATM1_CFG_POS = 0x0 +BMM350_TST_TB1_EN_MSK = 0x80 +BMM350_TST_TB1_EN_POS = 0x7 +BMM350_TST_ATM2_CFG_MSK = 0x1f +BMM350_TST_ATM2_CFG_POS = 0x0 +BMM350_TST_TB2_EN_MSK = 0x80 +BMM350_TST_TB2_EN_POS = 0x7 +BMM350_REG_DTB1X_SEL_MSK = 0x7f +BMM350_REG_DTB1X_SEL_POS = 0x0 +BMM350_SEL_DTB1X_PAD_MSK = 0x80 +BMM350_SEL_DTB1X_PAD_POS = 0x7 +BMM350_REG_DTB2X_SEL_MSK = 0x7f +BMM350_REG_DTB2X_SEL_POS = 0x0 +BMM350_TMR_TST_CFG_MSK = 0x7f +BMM350_TMR_TST_CFG_POS = 0x0 +BMM350_TMR_TST_HIZ_VTMR_MSK = 0x80 +BMM350_TMR_TST_HIZ_VTMR_POS = 0x7 + +# OTP MACROS +BMM350_OTP_CMD_DIR_READ = 0x20 +BMM350_OTP_CMD_DIR_PRGM_1B = 0x40 +BMM350_OTP_CMD_DIR_PRGM = 0x60 +BMM350_OTP_CMD_PWR_OFF_OTP = 0x80 +BMM350_OTP_CMD_EXT_READ = 0xA0 +BMM350_OTP_CMD_EXT_PRGM = 0xE0 +BMM350_OTP_CMD_MSK = 0xE0 +BMM350_OTP_WORD_ADDR_MSK = 0x1F + +BMM350_OTP_STATUS_ERROR_MSK = 0xE0 +BMM350_OTP_STATUS_NO_ERROR = 0x00 +BMM350_OTP_STATUS_BOOT_ERR = 0x20 +BMM350_OTP_STATUS_PAGE_RD_ERR = 0x40 +BMM350_OTP_STATUS_PAGE_PRG_ERR = 0x60 +BMM350_OTP_STATUS_SIGN_ERR = 0x80 +BMM350_OTP_STATUS_INV_CMD_ERR = 0xA0 +BMM350_OTP_STATUS_CMD_DONE = 0x01 + +# OTP indices +BMM350_TEMP_OFF_SENS = 0x0D + +BMM350_MAG_OFFSET_X = 0x0E +BMM350_MAG_OFFSET_Y = 0x0F +BMM350_MAG_OFFSET_Z = 0x10 + +BMM350_MAG_SENS_X = 0x10 +BMM350_MAG_SENS_Y = 0x11 +BMM350_MAG_SENS_Z = 0x11 + +BMM350_MAG_TCO_X = 0x12 +BMM350_MAG_TCO_Y = 0x13 +BMM350_MAG_TCO_Z = 0x14 + +BMM350_MAG_TCS_X = 0x12 +BMM350_MAG_TCS_Y = 0x13 +BMM350_MAG_TCS_Z = 0x14 + +BMM350_MAG_DUT_T_0 = 0x18 + +BMM350_CROSS_X_Y = 0x15 +BMM350_CROSS_Y_X = 0x15 +BMM350_CROSS_Z_X = 0x16 +BMM350_CROSS_Z_Y = 0x16 + +BMM350_SENS_CORR_Y = 0.01 +BMM350_TCS_CORR_Z = 0.000 + +# Signed bit macros +BMM350_SIGNED_8_BIT = 8 +BMM350_SIGNED_12_BIT = 12 +BMM350_SIGNED_16_BIT = 16 +BMM350_SIGNED_21_BIT = 21 +BMM350_SIGNED_24_BIT = 24 + +# Self-test macros +BMM350_SELF_TEST_DISABLE = 0x00 +BMM350_SELF_TEST_POS_X = 0x0D +BMM350_SELF_TEST_NEG_X = 0x0B +BMM350_SELF_TEST_POS_Y = 0x15 +BMM350_SELF_TEST_NEG_Y = 0x13 + +BMM350_X_FM_XP_UST_MAX_LIMIT = 150 +BMM350_X_FM_XP_UST_MIN_LIMIT = 50 + +BMM350_X_FM_XN_UST_MAX_LIMIT = -50 +BMM350_X_FM_XN_UST_MIN_LIMIT = -150 + +BMM350_Y_FM_YP_UST_MAX_LIMIT = 150 +BMM350_Y_FM_YP_UST_MIN_LIMIT = 50 + +BMM350_Y_FM_YN_UST_MAX_LIMIT = -50 +BMM350_Y_FM_YN_UST_MIN_LIMIT = -150 + +# PMU command status 0 macros +BMM350_PMU_CMD_STATUS_0_SUS = 0x00 +BMM350_PMU_CMD_STATUS_0_NM = 0x01 +BMM350_PMU_CMD_STATUS_0_UPD_OAE = 0x02 +BMM350_PMU_CMD_STATUS_0_FM = 0x03 +BMM350_PMU_CMD_STATUS_0_FM_FAST = 0x04 +BMM350_PMU_CMD_STATUS_0_FGR = 0x05 +BMM350_PMU_CMD_STATUS_0_FGR_FAST = 0x06 +BMM350_PMU_CMD_STATUS_0_BR = 0x07 +BMM350_PMU_CMD_STATUS_0_BR_FAST = 0x07 + + +# PRESET MODE DEFINITIONS +BMM350_PRESETMODE_LOWPOWER = 0x01 +BMM350_PRESETMODE_REGULAR = 0x02 +BMM350_PRESETMODE_HIGHACCURACY = 0x03 +BMM350_PRESETMODE_ENHANCED = 0x04 + +LOW_THRESHOLD_INTERRUPT = 0 +HIGH_THRESHOLD_INTERRUPT = 1 +INTERRUPT_X_ENABLE = 0 +INTERRUPT_Y_ENABLE = 0 +INTERRUPT_Z_ENABLE = 0 +INTERRUPT_X_DISABLE = 1 +INTERRUPT_Y_DISABLE = 1 +INTERRUPT_Z_DISABLE = 1 +ENABLE_INTERRUPT_PIN = 1 +DISABLE_INTERRUPT_PIN = 0 +NO_DATA = -32768 + +# ------------------------------------------- +BMM350_CHIP_ID_ERROR = -1 + + +# ------------------------------------------- + +BMM350_DISABLE_INTERRUPT = BMM350_DISABLE +BMM350_ENABLE_INTERRUPT = BMM350_ENABLE + +BMM350_SUSPEND_MODE = BMM350_PMU_CMD_SUS +BMM350_NORMAL_MODE = BMM350_PMU_CMD_NM +BMM350_FORCED_MODE = BMM350_PMU_CMD_FM +BMM350_FORCED_MODE_FAST = BMM350_PMU_CMD_FM_FAST + +BMM350_DATA_RATE_400HZ = BMM350_ODR_400HZ +BMM350_DATA_RATE_200HZ = BMM350_ODR_200HZ +BMM350_DATA_RATE_100HZ = BMM350_ODR_100HZ +BMM350_DATA_RATE_50HZ = BMM350_ODR_50HZ +BMM350_DATA_RATE_25HZ = BMM350_ODR_25HZ +BMM350_DATA_RATE_12_5HZ = BMM350_ODR_12_5HZ +BMM350_DATA_RATE_6_25HZ = BMM350_ODR_6_25HZ +BMM350_DATA_RATE_3_125HZ = BMM350_ODR_3_125HZ +BMM350_DATA_RATE_1_5625HZ = BMM350_ODR_1_5625HZ + +BMM350_FLUXGUIDE_9MS = BMM350_PMU_CMD_FGR +BMM350_FLUXGUIDE_FAST = BMM350_PMU_CMD_FGR_FAST +BMM350_BITRESET_9MS = BMM350_PMU_CMD_BR +BMM350_BITRESET_FAST = BMM350_PMU_CMD_BR_FAST +BMM350_NOMAGRESET = 127 + +BMM350_INTR_DISABLE = BMM350_DISABLE +BMM350_INTR_ENABLE = BMM350_ENABLE + +BMM350_UNMAP_FROM_PIN = BMM350_DISABLE +BMM350_MAP_TO_PIN = BMM350_ENABLE + +BMM350_PULSED = BMM350_INT_MODE_PULSED +BMM350_LATCHED = BMM350_INT_MODE_LATCHED + +BMM350_ACTIVE_LOW = BMM350_INT_POL_ACTIVE_LOW +BMM350_ACTIVE_HIGH = BMM350_INT_POL_ACTIVE_HIGH + +BMM350_INTR_OPEN_DRAIN = BMM350_INT_OD_OPENDRAIN +BMM350_INTR_PUSH_PULL = BMM350_INT_OD_PUSHPULL + +BMM350_IBI_DISABLE = BMM350_DISABLE +BMM350_IBI_ENABLE = BMM350_ENABLE + +BMM350_NOCLEAR_ON_IBI = BMM350_DISABLE +BMM350_CLEAR_ON_IBI = BMM350_ENABLE + +BMM350_I2C_WDT_DIS = BMM350_DISABLE +BMM350_I2C_WDT_EN = BMM350_ENABLE + +BMM350_I2C_WDT_SEL_SHORT = BMM350_DISABLE +BMM350_I2C_WDT_SEL_LONG = BMM350_ENABLE + +BMM350_NO_AVERAGING = BMM350_AVG_NO_AVG +BMM350_AVERAGING_2 = BMM350_AVG_2 +BMM350_AVERAGING_4 = BMM350_AVG_4 +BMM350_AVERAGING_8 = BMM350_AVG_8 + +BMM350_ST_IGEN_DIS = BMM350_DISABLE +BMM350_ST_IGEN_EN = BMM350_ENABLE + +BMM350_ST_N_DIS = BMM350_DISABLE +BMM350_ST_N_EN = BMM350_ENABLE + +BMM350_ST_P_DIS = BMM350_DISABLE +BMM350_ST_P_EN = BMM350_ENABLE + +BMM350_IST_X_DIS = BMM350_DISABLE +BMM350_IST_X_EN = BMM350_ENABLE + +BMM350_IST_Y_DIS = BMM350_DISABLE +BMM350_IST_Y_EN = BMM350_ENABLE + +BMM350_CFG_SENS_TIM_AON_DIS = BMM350_DISABLE +BMM350_CFG_SENS_TIM_AON_EN = BMM350_ENABLE + +BMM350_X_DIS = BMM350_DISABLE +BMM350_X_EN = BMM350_ENABLE + +BMM350_Y_DIS = BMM350_DISABLE +BMM350_Y_EN = BMM350_ENABLE + +BMM350_Z_DIS = BMM350_DISABLE +BMM350_Z_EN = BMM350_ENABLE + +PI = 3.141592653 +M_PI = 3.14159265358979323846 + + +# -------------------------------------------- +'''! + @brief bmm350 magnetometer dut offset coefficient structure +''' +class bmm350_dut_offset_coef: + def __init__(self, t_offs: float, offset_x: float, offset_y: float, offset_z: float): + self.t_offs = t_offs + self.offset_x = offset_x + self.offset_y = offset_y + self.offset_z = offset_z + +'''! + @brief bmm350 magnetometer dut sensitivity coefficient structure +''' +class bmm350_dut_sensit_coef: + def __init__(self, t_sens: float, sens_x: float, sens_y: float, sens_z: float): + self.t_sens = t_sens + self.sens_x = sens_x + self.sens_y = sens_y + self.sens_z = sens_z + +'''! + @brief bmm350 magnetometer dut tco structure +''' +class bmm350_dut_tco: + def __init__(self, tco_x: float, tco_y: float, tco_z: float): + self.tco_x = tco_x + self.tco_y = tco_y + self.tco_z = tco_z +'''! + @brief bmm350 magnetometer dut tcs structure +''' +class bmm350_dut_tcs: + def __init__(self, tcs_x: float, tcs_y: float, tcs_z: float): + self.tcs_x = tcs_x + self.tcs_y = tcs_y + self.tcs_z = tcs_z + +'''! + @brief bmm350 magnetometer cross axis compensation structure +''' +class bmm350_cross_axis: + def __init__(self, cross_x_y: float, cross_y_x: float, cross_z_x: float, cross_z_y: float): + self.cross_x_y = cross_x_y + self.cross_y_x = cross_y_x + self.cross_z_x = cross_z_x + self.cross_z_y = cross_z_y + +'''! + @brief bmm350 magnetometer compensate structure +''' +class bmm350_mag_compensate: + def __init__(self, dut_offset_coef: bmm350_dut_offset_coef, dut_sensit_coef: bmm350_dut_sensit_coef, dut_tco: bmm350_dut_tco, dut_tcs: bmm350_dut_tcs, dut_t0: float, cross_axis: bmm350_cross_axis): + self.dut_offset_coef = dut_offset_coef + self.dut_sensit_coef = dut_sensit_coef + self.dut_tco = dut_tco + self.dut_tcs = dut_tcs + self.dut_t0 = dut_t0 + self.cross_axis = cross_axis + +'''! + @brief bmm350 device structure +''' +class bmm350_dev: + def __init__(self, mag_comp: bmm350_mag_compensate): + self.chipID = 0 + self.otp_data = [0] * 32 + self.var_id = 0 + self.mag_comp = mag_comp + self.power_mode = 0 + self.axis_en = 0 + +# Create instances of the required classes with example values +dut_offset_coef = bmm350_dut_offset_coef(t_offs=0, offset_x=0, offset_y=0, offset_z=0) +dut_sensit_coef = bmm350_dut_sensit_coef(t_sens=0, sens_x=0, sens_y=0, sens_z=0) +dut_tco = bmm350_dut_tco(tco_x=0, tco_y=0, tco_z=0) +dut_tcs = bmm350_dut_tcs(tcs_x=0, tcs_y=0, tcs_z=0) +cross_axis = bmm350_cross_axis(cross_x_y=0, cross_y_x=0, cross_z_x=0, cross_z_y=0) +mag_comp = bmm350_mag_compensate( + dut_offset_coef=dut_offset_coef, + dut_sensit_coef=dut_sensit_coef, + dut_tco=dut_tco, + dut_tcs=dut_tcs, + dut_t0=0, + cross_axis=cross_axis +) +# The bmm350_mag_compensate object now contains all the data defined above. +bmm350_sensor = bmm350_dev(mag_comp) + + +# Uncompensated geomagnetic and temperature data +class BMM350RawMagData: + def __init__(self): + self.raw_x_data = 0 + self.raw_y_data = 0 + self.raw_z_data = 0 + self.raw_t_data = 0 +_raw_mag_data = BMM350RawMagData() + +class BMM350MagData: + def __init__(self): + self.x = 0 + self.y = 0 + self.z = 0 + self.temperature = 0 +_mag_data = BMM350MagData() + +class bmm350_pmu_cmd_status_0: + def __init__(self, pmu_cmd_busy, odr_ovwr, avr_ovwr, pwr_mode_is_normal, cmd_is_illegal, pmu_cmd_value): + self.pmu_cmd_busy = pmu_cmd_busy + self.odr_ovwr = odr_ovwr + self.avr_ovwr = avr_ovwr + self.pwr_mode_is_normal = pwr_mode_is_normal + self.cmd_is_illegal = cmd_is_illegal + self.pmu_cmd_value = pmu_cmd_value +pmu_cmd_stat_0 = bmm350_pmu_cmd_status_0(pmu_cmd_busy=0, odr_ovwr=0, avr_ovwr=0, pwr_mode_is_normal=0, cmd_is_illegal=0, pmu_cmd_value=0) + +# -------------------------------------------- +class DFRobot_bmm350(object): + I2C_MODE = 1 + I3C_MODE = 2 + __thresholdMode = 2 + threshold = 0 + + + def __init__(self, bus): + if bus != 0: + self.__i2c_i3c = self.I2C_MODE + else: + self.__i2c_i3c = self.I3C_MODE + + def BMM350_SET_BITS(self, reg_data, bitname_msk, bitname_pos, data): + return (reg_data & ~bitname_msk) | ((data << bitname_pos) & bitname_msk) + + def BMM350_GET_BITS(self, reg_data, mask, pos): + return (reg_data & mask) >> pos + + def BMM350_GET_BITS_POS_0(self, reg_data, mask): + return reg_data & mask + + def BMM350_SET_BITS_POS_0(self, reg_data, mask, data): + return ((reg_data & ~(mask)) | (data & mask)) + + + + # brief This internal API converts the raw data from the IC data registers to signed integer + def fix_sign(self, inval, number_of_bits): + power = 0 + if number_of_bits == BMM350_SIGNED_8_BIT: + power = 128; # 2^7 + elif number_of_bits == BMM350_SIGNED_12_BIT: + power = 2048 # 2^11 + elif number_of_bits == BMM350_SIGNED_16_BIT: + power = 32768 # 2^15 + elif number_of_bits == BMM350_SIGNED_21_BIT: + power = 1048576 # 2^20 + elif number_of_bits == BMM350_SIGNED_24_BIT: + power = 8388608 # 2^23 + else: + power = 0 + if inval >= power: + inval = inval - (power * 2) + return inval + + # brief This internal API is used to update magnetometer offset and sensitivity data. + def update_mag_off_sens(self): + off_x_lsb_msb = bmm350_sensor.otp_data[BMM350_MAG_OFFSET_X] & 0x0FFF + off_y_lsb_msb = ((bmm350_sensor.otp_data[BMM350_MAG_OFFSET_X] & 0xF000) >> 4) + (bmm350_sensor.otp_data[BMM350_MAG_OFFSET_Y] & BMM350_LSB_MASK) + off_z_lsb_msb = (bmm350_sensor.otp_data[BMM350_MAG_OFFSET_Y] & 0x0F00) + (bmm350_sensor.otp_data[BMM350_MAG_OFFSET_Z] & BMM350_LSB_MASK) + t_off = bmm350_sensor.otp_data[BMM350_TEMP_OFF_SENS] & BMM350_LSB_MASK + + bmm350_sensor.mag_comp.dut_offset_coef.offset_x = self.fix_sign(off_x_lsb_msb, BMM350_SIGNED_12_BIT) + bmm350_sensor.mag_comp.dut_offset_coef.offset_y = self.fix_sign(off_y_lsb_msb, BMM350_SIGNED_12_BIT) + bmm350_sensor.mag_comp.dut_offset_coef.offset_z = self.fix_sign(off_z_lsb_msb, BMM350_SIGNED_12_BIT) + bmm350_sensor.mag_comp.dut_offset_coef.t_offs = self.fix_sign(t_off, BMM350_SIGNED_8_BIT) / 5.0 + + sens_x = (bmm350_sensor.otp_data[BMM350_MAG_SENS_X] & BMM350_MSB_MASK) >> 8 + sens_y = (bmm350_sensor.otp_data[BMM350_MAG_SENS_Y] & BMM350_LSB_MASK) + sens_z = (bmm350_sensor.otp_data[BMM350_MAG_SENS_Z] & BMM350_MSB_MASK) >> 8 + t_sens = (bmm350_sensor.otp_data[BMM350_TEMP_OFF_SENS] & BMM350_MSB_MASK) >> 8 + + bmm350_sensor.mag_comp.dut_sensit_coef.sens_x = self.fix_sign(sens_x, BMM350_SIGNED_8_BIT) / 256.0 + bmm350_sensor.mag_comp.dut_sensit_coef.sens_y = (self.fix_sign(sens_y, BMM350_SIGNED_8_BIT) / 256.0) + BMM350_SENS_CORR_Y + bmm350_sensor.mag_comp.dut_sensit_coef.sens_z = self.fix_sign(sens_z, BMM350_SIGNED_8_BIT) / 256.0 + bmm350_sensor.mag_comp.dut_sensit_coef.t_sens = self.fix_sign(t_sens, BMM350_SIGNED_8_BIT) / 512.0 + + tco_x = (bmm350_sensor.otp_data[BMM350_MAG_TCO_X] & BMM350_LSB_MASK) + tco_y = (bmm350_sensor.otp_data[BMM350_MAG_TCO_Y] & BMM350_LSB_MASK) + tco_z = (bmm350_sensor.otp_data[BMM350_MAG_TCO_Z] & BMM350_LSB_MASK) + + bmm350_sensor.mag_comp.dut_tco.tco_x = self.fix_sign(tco_x, BMM350_SIGNED_8_BIT) / 32.0 + bmm350_sensor.mag_comp.dut_tco.tco_y = self.fix_sign(tco_y, BMM350_SIGNED_8_BIT) / 32.0 + bmm350_sensor.mag_comp.dut_tco.tco_z = self.fix_sign(tco_z, BMM350_SIGNED_8_BIT) / 32.0 + + tcs_x = (bmm350_sensor.otp_data[BMM350_MAG_TCS_X] & BMM350_MSB_MASK) >> 8 + tcs_y = (bmm350_sensor.otp_data[BMM350_MAG_TCS_Y] & BMM350_MSB_MASK) >> 8 + tcs_z = (bmm350_sensor.otp_data[BMM350_MAG_TCS_Z] & BMM350_MSB_MASK) >> 8 + + bmm350_sensor.mag_comp.dut_tcs.tcs_x = self.fix_sign(tcs_x, BMM350_SIGNED_8_BIT) / 16384.0 + bmm350_sensor.mag_comp.dut_tcs.tcs_y = self.fix_sign(tcs_y, BMM350_SIGNED_8_BIT) / 16384.0 + bmm350_sensor.mag_comp.dut_tcs.tcs_z = (self.fix_sign(tcs_z, BMM350_SIGNED_8_BIT) / 16384.0) - BMM350_TCS_CORR_Z + + bmm350_sensor.mag_comp.dut_t0 = (self.fix_sign(bmm350_sensor.otp_data[BMM350_MAG_DUT_T_0], BMM350_SIGNED_16_BIT) / 512.0) + 23.0 + + cross_x_y = (bmm350_sensor.otp_data[BMM350_CROSS_X_Y] & BMM350_LSB_MASK) + cross_y_x = (bmm350_sensor.otp_data[BMM350_CROSS_Y_X] & BMM350_MSB_MASK) >> 8 + cross_z_x = (bmm350_sensor.otp_data[BMM350_CROSS_Z_X] & BMM350_LSB_MASK) + cross_z_y = (bmm350_sensor.otp_data[BMM350_CROSS_Z_Y] & BMM350_MSB_MASK) >> 8 + + bmm350_sensor.mag_comp.cross_axis.cross_x_y = self.fix_sign(cross_x_y, BMM350_SIGNED_8_BIT) / 800.0 + bmm350_sensor.mag_comp.cross_axis.cross_y_x = self.fix_sign(cross_y_x, BMM350_SIGNED_8_BIT) / 800.0 + bmm350_sensor.mag_comp.cross_axis.cross_z_x = self.fix_sign(cross_z_x, BMM350_SIGNED_8_BIT) / 800.0 + bmm350_sensor.mag_comp.cross_axis.cross_z_y = self.fix_sign(cross_z_y, BMM350_SIGNED_8_BIT) / 800.0 + + + def bmm350_set_powermode(self, powermode): + last_pwr_mode = self.read_reg(BMM350_REG_PMU_CMD, 1) + if (last_pwr_mode[0] == BMM350_PMU_CMD_NM) or (last_pwr_mode[0] == BMM350_PMU_CMD_UPD_OAE): + self.write_reg(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_SUS) + time.sleep(BMM350_GOTO_SUSPEND_DELAY) + # Array to store suspend to forced mode delay + sus_to_forced_mode =[BMM350_SUS_TO_FORCEDMODE_NO_AVG_DELAY, BMM350_SUS_TO_FORCEDMODE_AVG_2_DELAY, + BMM350_SUS_TO_FORCEDMODE_AVG_4_DELAY, BMM350_SUS_TO_FORCEDMODE_AVG_8_DELAY] + # Array to store suspend to forced mode fast delay + sus_to_forced_mode_fast = [BMM350_SUS_TO_FORCEDMODE_FAST_NO_AVG_DELAY, BMM350_SUS_TO_FORCEDMODE_FAST_AVG_2_DELAY, + BMM350_SUS_TO_FORCEDMODE_FAST_AVG_4_DELAY, BMM350_SUS_TO_FORCEDMODE_FAST_AVG_8_DELAY] + # Set PMU command configuration to desired power mode + self.write_reg(BMM350_REG_PMU_CMD, powermode) + # Get average configuration + get_avg = self.read_reg(BMM350_REG_PMU_CMD_AGGR_SET, 1) + # Mask the average value + avg = ((get_avg[0] & BMM350_AVG_MSK) >> BMM350_AVG_POS) + delay_us = 0 + # Check if desired power mode is normal mode + if powermode == BMM350_NORMAL_MODE: + delay_us = BMM350_SUSPEND_TO_NORMAL_DELAY + # Check if desired power mode is forced mode + if powermode == BMM350_FORCED_MODE: + delay_us = sus_to_forced_mode[avg]; # Store delay based on averaging mode + # Check if desired power mode is forced mode fast + if powermode == BMM350_FORCED_MODE_FAST: + delay_us = sus_to_forced_mode_fast[avg] # Store delay based on averaging mode + # Perform delay based on power mode + time.sleep(delay_us) + bmm350_sensor.power_mode = powermode + + + def bmm350_magnetic_reset_and_wait(self): + # 1. Read PMU CMD status + reg_data = self.read_reg(BMM350_REG_PMU_CMD_STATUS_0, 1) + pmu_cmd_stat_0.pmu_cmd_busy = self.BMM350_GET_BITS_POS_0(reg_data[0], BMM350_PMU_CMD_BUSY_MSK) + pmu_cmd_stat_0.odr_ovwr = self.BMM350_GET_BITS(reg_data[0], BMM350_ODR_OVWR_MSK, BMM350_ODR_OVWR_POS) + pmu_cmd_stat_0.avr_ovwr = self.BMM350_GET_BITS(reg_data[0], BMM350_AVG_OVWR_MSK, BMM350_AVG_OVWR_POS) + pmu_cmd_stat_0.pwr_mode_is_normal = self.BMM350_GET_BITS(reg_data[0], BMM350_PWR_MODE_IS_NORMAL_MSK, BMM350_PWR_MODE_IS_NORMAL_POS) + pmu_cmd_stat_0.cmd_is_illegal = self.BMM350_GET_BITS(reg_data[0], BMM350_CMD_IS_ILLEGAL_MSK, BMM350_CMD_IS_ILLEGAL_POS) + pmu_cmd_stat_0.pmu_cmd_value = self.BMM350_GET_BITS(reg_data[0], BMM350_PMU_CMD_VALUE_MSK, BMM350_PMU_CMD_VALUE_POS) + # 2. Check whether the power mode is normal before magnetic reset + restore_normal = BMM350_DISABLE + if pmu_cmd_stat_0.pwr_mode_is_normal == BMM350_ENABLE: + restore_normal = BMM350_ENABLE + # Reset can only be triggered in suspend + self.bmm350_set_powermode(BMM350_SUSPEND_MODE) + # Set BR to PMU_CMD register + self.write_reg(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_BR) + time.sleep(BMM350_BR_DELAY) + # Set FGR to PMU_CMD register + self.write_reg(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_FGR) + time.sleep(BMM350_FGR_DELAY) + if restore_normal == BMM350_ENABLE: + self.bmm350_set_powermode(BMM350_NORMAL_MODE) + + + def sensor_init(self): + '''! + @brief Init bmm350 check whether the chip id is right + @return + @retval 0 is init success + @retval -1 is init failed + ''' + rslt = BMM350_OK + # Specifies that all axes are enabled + bmm350_sensor.axis_en = BMM350_EN_XYZ_MSK + time.sleep(BMM350_START_UP_TIME_FROM_POR) + # 1. Software reset + self.write_reg(BMM350_REG_CMD, BMM350_CMD_SOFTRESET) + time.sleep(BMM350_SOFT_RESET_DELAY) + # 2. Read chip ID + reg_date = self.read_reg(BMM350_REG_CHIP_ID, 1) + bmm350_sensor.chipID = reg_date[0] + if reg_date[0] == BMM350_CHIP_ID: + # 3. Download OTP compensation data + for indx in range(BMM350_OTP_DATA_LENGTH): + # 3.1 Set the OTP address register -- > Each address corresponds to a different OTP value (total OTP data is 32 bytes) + otp_cmd = BMM350_OTP_CMD_DIR_READ | (indx & BMM350_OTP_WORD_ADDR_MSK) + self.write_reg(BMM350_REG_OTP_CMD_REG, otp_cmd) + while (True): + time.sleep(0.0003) + # 3.2 The OTP status was read + otp_status = self.read_reg(BMM350_REG_OTP_STATUS_REG, 1) + otp_err = otp_status[0] & BMM350_OTP_STATUS_ERROR_MSK + if otp_err != BMM350_OTP_STATUS_NO_ERROR: + break + if (otp_status[0] & BMM350_OTP_STATUS_CMD_DONE): + break + # 3.3 Gets 16 bytes of OTP data from the OTP address specified above + OTP_MSB_data = self.read_reg(BMM350_REG_OTP_DATA_MSB_REG, 1) + OTP_LSB_data = self.read_reg(BMM350_REG_OTP_DATA_LSB_REG, 1) + OTP_data = ((OTP_MSB_data[0] << 8) | OTP_LSB_data[0]) & 0xFFFF + bmm350_sensor.otp_data[indx] = OTP_data + bmm350_sensor.var_id = (bmm350_sensor.otp_data[30] & 0x7f00) >> 9 + # 3.4 Update the magnetometer offset and sensitivity data + self.update_mag_off_sens() + # 4. Disable OTP + self.write_reg(BMM350_REG_OTP_CMD_REG, BMM350_OTP_CMD_PWR_OFF_OTP) + + # 5. Magnetic reset + self.bmm350_magnetic_reset_and_wait() + else: + # The chip id verification failed and initialization failed. Procedure + rslt = BMM350_CHIP_ID_ERROR + return rslt + + + def get_chip_id(self): + chip_id = self.read_reg(BMM350_REG_CHIP_ID, 1) + return chip_id[0] + + + def soft_reset(self): + '''! + @brief Soft reset, restore to suspended mode after soft reset. (You need to manually enter the normal mode) + ''' + self.write_reg(BMM350_REG_CMD, BMM350_CMD_SOFTRESET) # Software reset + time.sleep(BMM350_SOFT_RESET_DELAY) + self.write_reg(BMM350_REG_OTP_CMD_REG, BMM350_OTP_CMD_PWR_OFF_OTP) # Disable OTP + self.bmm350_magnetic_reset_and_wait() # magnetic reset + self.bmm350_set_powermode(BMM350_SUSPEND_MODE) + + + def set_operation_mode(self, modes): + '''! + @brief Set sensor operation mode + @param modes + @n BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + @n BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + @n BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + @n BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + self.bmm350_set_powermode(modes) + + + def get_operation_mode(self): + '''! + @brief Get sensor operation mode + @return Return the character string of the operation mode + ''' + result = "" + if bmm350_sensor.power_mode == BMM350_SUSPEND_MODE: + result = "bmm350 is suspend mode!" + elif bmm350_sensor.power_mode == BMM350_NORMAL_MODE: + result = "bmm350 is normal mode!" + elif bmm350_sensor.power_mode == BMM350_FORCED_MODE: + result = "bmm350 is forced mode!" + elif bmm350_sensor.power_mode == BMM350_FORCED_MODE_FAST: + result = "bmm350 is forced_fast mode!" + else: + result = "error mode!" + return result + + + + + + def get_rate(self): + '''! + @brief Get the config data rate, unit: HZ + @return rate + ''' + avg_odr_reg = self.read_reg(BMM350_REG_PMU_CMD_AGGR_SET, 1) + odr_reg = self.BMM350_GET_BITS(avg_odr_reg[0], BMM350_ODR_MSK, BMM350_ODR_POS) + if odr_reg == BMM350_ODR_1_5625HZ: + result = 1.5625 + elif odr_reg == BMM350_ODR_3_125HZ: + result = 3.125 + elif odr_reg == BMM350_ODR_6_25HZ: + result = 6.25 + elif odr_reg == BMM350_ODR_12_5HZ: + result = 12.5 + elif odr_reg == BMM350_ODR_25HZ: + result = 25 + elif odr_reg == BMM350_ODR_50HZ: + result = 50 + elif odr_reg == BMM350_ODR_100HZ: + result = 100 + elif odr_reg == BMM350_ODR_200HZ: + result = 200 + elif odr_reg == BMM350_ODR_400HZ: + result = 400 + return result + + + def set_preset_mode(self, avg, rate = BMM350_DATA_RATE_12_5HZ): + '''! + @brief Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + @param modes + @n BMM350_PRESETMODE_LOWPOWER Low power mode, get a fraction of data and take the mean value. + @n BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and take the mean value. + @n BMM350_PRESETMODE_ENHANCED Enhanced mode, get a plenty of data and take the mean value. + @n BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and take the mean value. + @param rate + @n BMM350_DATA_RATE_1_5625HZ + @n BMM350_DATA_RATE_3_125HZ + @n BMM350_DATA_RATE_6_25HZ + @n BMM350_DATA_RATE_12_5HZ (default rate) + @n BMM350_DATA_RATE_25HZ + @n BMM350_DATA_RATE_50HZ + @n BMM350_DATA_RATE_100HZ + @n BMM350_DATA_RATE_200HZ + @n BMM350_DATA_RATE_400HZ + + ''' + reg_data = (rate & BMM350_ODR_MSK) + reg_data = self.BMM350_SET_BITS(reg_data, BMM350_AVG_MSK, BMM350_AVG_POS, avg) + self.write_reg(BMM350_REG_PMU_CMD_AGGR_SET, reg_data) + self.write_reg(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_UPD_OAE) + + def set_rate(self, rates): + '''! + @brief Set the rate of obtaining geomagnetic data, the higher, the faster (without delay function) + @param rate + @n BMM350_DATA_RATE_1_5625HZ + @n BMM350_DATA_RATE_3_125HZ + @n BMM350_DATA_RATE_6_25HZ + @n BMM350_DATA_RATE_12_5HZ (default rate) + @n BMM350_DATA_RATE_25HZ + @n BMM350_DATA_RATE_50HZ + @n BMM350_DATA_RATE_100HZ + @n BMM350_DATA_RATE_200HZ + @n BMM350_DATA_RATE_400HZ + ''' + # self.bmm350_set_powermode(BMM350_NORMAL_MODE) + avg_odr_reg = self.read_reg(BMM350_REG_PMU_CMD_AGGR_SET, 1) + avg_reg = self.BMM350_GET_BITS(avg_odr_reg[0], BMM350_AVG_MSK, BMM350_AVG_POS) + reg_data = (rates & BMM350_ODR_MSK) + reg_data = self.BMM350_SET_BITS(reg_data, BMM350_AVG_MSK, BMM350_AVG_POS, avg_reg) + self.write_reg(BMM350_REG_PMU_CMD_AGGR_SET, reg_data) + self.write_reg(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_UPD_OAE) + time.sleep(BMM350_UPD_OAE_DELAY) + + def self_test(self): + '''! + @brief Sensor self test, the returned character string indicate the self test result. + @return The character string of the test result + ''' + axis_en = self.read_reg(BMM350_REG_PMU_CMD_AXIS_EN, 1) + en_x = self.BMM350_GET_BITS(axis_en[0], BMM350_EN_X_MSK, BMM350_EN_X_POS) + en_y = self.BMM350_GET_BITS(axis_en[0], BMM350_EN_Y_MSK, BMM350_EN_Y_POS) + en_z = self.BMM350_GET_BITS(axis_en[0], BMM350_EN_Z_MSK, BMM350_EN_Z_POS) + str1 = "" + if en_x & 0x01: + str1 += "x " + if en_y & 0x01: + str1 += "y " + if en_z & 0x01: + str1 += "z " + if axis_en == 0: + str1 = "xyz aix self test fail" + else: + str1 += "aix test success" + return str1 + + + def set_measurement_XYZ(self, en_x = BMM350_X_EN, en_y = BMM350_Y_EN, en_z = BMM350_Z_EN): + '''! + @brief Enable the measurement at x-axis, y-axis and z-axis, default to be enabled. After disabling, the geomagnetic data at x, y, and z axis are wrong. + @param en_x + @n BMM350_X_EN Enable the measurement at x-axis + @n BMM350_X_DIS Disable the measurement at x-axis + @param en_y + @n BMM350_Y_EN Enable the measurement at y-axis + @n BMM350_Y_DIS Disable the measurement at y-axis + @param en_z + @n BMM350_Z_EN Enable the measurement at z-axis + @n BMM350_Z_DIS Disable the measurement at z-axis + ''' + if en_x == BMM350_X_DIS and en_y == BMM350_Y_DIS and en_z == BMM350_Z_DIS: + bmm350_sensor.axis_en = BMM350_DISABLE + else: + axis_en = self.read_reg(BMM350_REG_PMU_CMD_AXIS_EN, 1) + data = self.BMM350_SET_BITS(axis_en[0], BMM350_EN_X_MSK, BMM350_EN_X_POS, en_x) + data = self.BMM350_SET_BITS(data, BMM350_EN_Y_MSK, BMM350_EN_Y_POS, en_y) + data = self.BMM350_SET_BITS(data, BMM350_EN_Z_MSK, BMM350_EN_Z_POS, en_z) + bmm350_sensor.axis_en = data + + + def get_measurement_state_XYZ(self): + '''! + @brief Get the enabling status at x-axis, y-axis and z-axis + @return Return enabling status at x-axis, y-axis and z-axis as a character string + ''' + axis_en = bmm350_sensor.axis_en + en_x = self.BMM350_GET_BITS(axis_en, BMM350_EN_X_MSK, BMM350_EN_X_POS) + en_y = self.BMM350_GET_BITS(axis_en, BMM350_EN_Y_MSK, BMM350_EN_Y_POS) + en_z = self.BMM350_GET_BITS(axis_en, BMM350_EN_Z_MSK, BMM350_EN_Z_POS) + result = "" + result += "The x axis is enable! " if en_x == 1 else "The x axis is disable! " + result += "The y axis is enable! " if en_y == 1 else "The y axis is disable! " + result += "The z axis is enable! " if en_z == 1 else "The z axis is disable! " + return result + + + def get_geomagnetic_data(self): + '''! + @brief Get the geomagnetic data of 3 axis (x, y, z) + @return The list of the geomagnetic data at 3 axis (x, y, z) unit: uT + @ [0] The geomagnetic data at x-axis + @ [1] The geomagnetic data at y-axis + @ [2] The geomagnetic data at z-axis + ''' + # 1. Get raw data without compensation + mag_data = self.read_reg(BMM350_REG_MAG_X_XLSB, BMM350_MAG_TEMP_DATA_LEN) + raw_mag_x = mag_data[0] + (mag_data[1] << 8) + (mag_data[2] << 16) + raw_mag_y = mag_data[3] + (mag_data[4] << 8) + (mag_data[5] << 16) + raw_mag_z = mag_data[6] + (mag_data[7] << 8) + (mag_data[8] << 16) + raw_temp = mag_data[9] + (mag_data[10] << 8) + (mag_data[11] << 16) + if (bmm350_sensor.axis_en & BMM350_EN_X_MSK) == BMM350_DISABLE: + _raw_mag_data.raw_x_data = BMM350_DISABLE + else: + _raw_mag_data.raw_x_data = self.fix_sign(raw_mag_x, BMM350_SIGNED_24_BIT) + if (bmm350_sensor.axis_en & BMM350_EN_Y_MSK) == BMM350_DISABLE: + _raw_mag_data.raw_y_data = BMM350_DISABLE + else: + _raw_mag_data.raw_y_data = self.fix_sign(raw_mag_y, BMM350_SIGNED_24_BIT) + if (bmm350_sensor.axis_en & BMM350_EN_Z_MSK) == BMM350_DISABLE: + _raw_mag_data.raw_z_data = BMM350_DISABLE + else: + _raw_mag_data.raw_z_data = self.fix_sign(raw_mag_z, BMM350_SIGNED_24_BIT) + _raw_mag_data.raw_t_data = self.fix_sign(raw_temp, BMM350_SIGNED_24_BIT) + # 2. The raw data is processed + # 2.1 Parameter preparation + bxy_sens = 14.55 + bz_sens = 9.0 + temp_sens = 0.00204 + ina_xy_gain_trgt = 19.46 + ina_z_gain_trgt = 31.0 + adc_gain = 1 / 1.5 + lut_gain = 0.714607238769531 + power = (1000000.0 / 1048576.0) + lsb_to_ut_degc = [None] * 4 + lsb_to_ut_degc[0] = (power / (bxy_sens * ina_xy_gain_trgt * adc_gain * lut_gain)) + lsb_to_ut_degc[1] = (power / (bxy_sens * ina_xy_gain_trgt * adc_gain * lut_gain)) + lsb_to_ut_degc[2] = (power / (bz_sens * ina_z_gain_trgt * adc_gain * lut_gain)) + lsb_to_ut_degc[3] = 1 / (temp_sens * adc_gain * lut_gain * 1048576) + # 2.1 Start processing raw data + out_data = [None] * 4 + out_data[0] = _raw_mag_data.raw_x_data * lsb_to_ut_degc[0] + out_data[1] = _raw_mag_data.raw_y_data * lsb_to_ut_degc[1] + out_data[2] = _raw_mag_data.raw_z_data * lsb_to_ut_degc[2] + out_data[3] = _raw_mag_data.raw_t_data * lsb_to_ut_degc[3] + if out_data[3] > 0.0: + temp = out_data[3] - (1 * 25.49) + elif out_data[3] < 0.0: + temp = out_data[3] - (-1 * 25.49) + else: + temp = out_data[3] + out_data[3] = temp + # 3. Compensate for the original data + # 3.1 Compensation for temperature data + out_data[3] = (1 + bmm350_sensor.mag_comp.dut_sensit_coef.t_sens) * out_data[3] + bmm350_sensor.mag_comp.dut_offset_coef.t_offs + # 3.2 Store the magnetic compensation data in a list + dut_offset_coef = [None] * 3 + dut_offset_coef[0] = bmm350_sensor.mag_comp.dut_offset_coef.offset_x + dut_offset_coef[1] = bmm350_sensor.mag_comp.dut_offset_coef.offset_y + dut_offset_coef[2] = bmm350_sensor.mag_comp.dut_offset_coef.offset_z + + dut_sensit_coef = [None] * 3 + dut_sensit_coef[0] = bmm350_sensor.mag_comp.dut_sensit_coef.sens_x + dut_sensit_coef[1] = bmm350_sensor.mag_comp.dut_sensit_coef.sens_y + dut_sensit_coef[2] = bmm350_sensor.mag_comp.dut_sensit_coef.sens_z + + dut_tco = [None] * 3 + dut_tco[0] = bmm350_sensor.mag_comp.dut_tco.tco_x + dut_tco[1] = bmm350_sensor.mag_comp.dut_tco.tco_y + dut_tco[2] = bmm350_sensor.mag_comp.dut_tco.tco_z + + dut_tcs = [None] * 3 + dut_tcs[0] = bmm350_sensor.mag_comp.dut_tcs.tcs_x + dut_tcs[1] = bmm350_sensor.mag_comp.dut_tcs.tcs_y + dut_tcs[2] = bmm350_sensor.mag_comp.dut_tcs.tcs_z; + # 3.3 Compensation for magnetic data + for indx in range(3): + out_data[indx] *= 1 + dut_sensit_coef[indx] + out_data[indx] += dut_offset_coef[indx] + out_data[indx] += dut_tco[indx] * (out_data[3] - bmm350_sensor.mag_comp.dut_t0) + out_data[indx] /= 1 + dut_tcs[indx] * (out_data[3] - bmm350_sensor.mag_comp.dut_t0) + + cr_ax_comp_x = (out_data[0] - bmm350_sensor.mag_comp.cross_axis.cross_x_y * out_data[1]) / \ + (1 - bmm350_sensor.mag_comp.cross_axis.cross_y_x * bmm350_sensor.mag_comp.cross_axis.cross_x_y) + cr_ax_comp_y = (out_data[1] - bmm350_sensor.mag_comp.cross_axis.cross_y_x * out_data[0]) / \ + (1 - bmm350_sensor.mag_comp.cross_axis.cross_y_x * bmm350_sensor.mag_comp.cross_axis.cross_x_y) + cr_ax_comp_z = (out_data[2] + (out_data[0] * + (bmm350_sensor.mag_comp.cross_axis.cross_y_x * bmm350_sensor.mag_comp.cross_axis.cross_z_y - bmm350_sensor.mag_comp.cross_axis.cross_z_x) - out_data[1] * + (bmm350_sensor.mag_comp.cross_axis.cross_z_y - bmm350_sensor.mag_comp.cross_axis.cross_x_y * bmm350_sensor.mag_comp.cross_axis.cross_z_x)) / + (1 - bmm350_sensor.mag_comp.cross_axis.cross_y_x * bmm350_sensor.mag_comp.cross_axis.cross_x_y)) + + out_data[0] = cr_ax_comp_x + out_data[1] = cr_ax_comp_y + out_data[2] = cr_ax_comp_z + + if (bmm350_sensor.axis_en & BMM350_EN_X_MSK) == BMM350_DISABLE: + _mag_data.x = BMM350_DISABLE + else: + _mag_data.x = out_data[0] + + if (bmm350_sensor.axis_en & BMM350_EN_Y_MSK) == BMM350_DISABLE: + _mag_data.y = BMM350_DISABLE + else: + _mag_data.y = out_data[1] + + if (bmm350_sensor.axis_en & BMM350_EN_Z_MSK) == BMM350_DISABLE: + _mag_data.z = BMM350_DISABLE + else: + _mag_data.z = out_data[2] + + _mag_data.temperature = out_data[3] + + geomagnetic = [None] * 3 + geomagnetic[0] = _mag_data.x + geomagnetic[1] = _mag_data.y + geomagnetic[2] = _mag_data.z + return geomagnetic + + + def get_compass_degree(self): + '''! + @brief Get compass degree + @return Compass degree (0° - 360°) 0° = North, 90° = East, 180° = South, 270° = West. + ''' + magData = self.get_geomagnetic_data() + compass = math.atan2(magData[0], magData[1]) + if compass < 0: + compass += 2 * PI + if compass > 2 * PI: + compass -= 2 * PI + return compass * 180 / M_PI + + + def set_data_ready_pin(self, modes, polarity): + '''! + @brief Enable or disable data ready interrupt pin + @n After enabling, the DRDY pin jump when there's data coming. + @n After disabling, the DRDY pin will not jump when there's data coming. + @n High polarity active on high, the default is low level, which turns to high level when the interrupt is triggered. + @n Low polarity active on low, default is high level, which turns to low level when the interrupt is triggered. + @param modes + @n BMM350_ENABLE_INTERRUPT Enable DRDY + @n BMM350_DISABLE_INTERRUPT Disable DRDY + @param polarity + @n BMM350_ACTIVE_HIGH High polarity + @n BMM350_ACTIVE_LOW Low polarity + ''' + # 1. Gets and sets the interrupt control configuration + reg_data = self.read_reg(BMM350_REG_INT_CTRL, 1) + reg_data[0] = self.BMM350_SET_BITS_POS_0(reg_data[0], BMM350_INT_MODE_MSK, BMM350_INT_MODE_PULSED) + reg_data[0] = self.BMM350_SET_BITS(reg_data[0], BMM350_INT_POL_MSK, BMM350_INT_POL_POS, polarity) + reg_data[0] = self.BMM350_SET_BITS(reg_data[0], BMM350_INT_OD_MSK, BMM350_INT_OD_POS, BMM350_INT_OD_PUSHPULL) + reg_data[0] = self.BMM350_SET_BITS(reg_data[0], BMM350_INT_OUTPUT_EN_MSK, BMM350_INT_OUTPUT_EN_POS, BMM350_MAP_TO_PIN) + reg_data[0] = self.BMM350_SET_BITS(reg_data[0], BMM350_DRDY_DATA_REG_EN_MSK, BMM350_DRDY_DATA_REG_EN_POS, modes) + # 2. Update interrupt control configuration + self.write_reg(BMM350_REG_INT_CTRL, reg_data[0]) + + + def get_data_ready_state(self): + '''! + @brief Get data ready status, determine whether the data is ready + @return status + @n True Data ready + @n False Data is not ready + ''' + int_status_reg = self.read_reg(BMM350_REG_INT_STATUS, 1) + drdy_status = self.BMM350_GET_BITS(int_status_reg[0], BMM350_DRDY_DATA_REG_MSK, BMM350_DRDY_DATA_REG_POS) + if drdy_status & 0x01: + return True + else: + return False + + + def set_threshold_interrupt(self, modes, threshold, polarity): + '''! + @brief Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold + @n High polarity active on high level, the default is low level, which turns to high level when the interrupt is triggered. + @n Low polarity active on low level, the default is high level, which turns to low level when the interrupt is triggered. + @param modes + @n LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode + @n HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode + @param threshold + @n Threshold, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt + @param polarity + @n POLARITY_HIGH High polarity + @n POLARITY_LOW Low polarity + ''' + if modes == LOW_THRESHOLD_INTERRUPT: + self.__thresholdMode = LOW_THRESHOLD_INTERRUPT + self.set_data_ready_pin(BMM350_ENABLE_INTERRUPT, polarity) + self.threshold = threshold + else: + self.__thresholdMode = HIGH_THRESHOLD_INTERRUPT + self.set_data_ready_pin(BMM350_ENABLE_INTERRUPT, polarity) + self.threshold = threshold + + + def get_threshold_data(self): + '''! + @brief Get the data that threshold interrupt occured + @return Return the list for storing geomagnetic data, how the data at 3 axis influence interrupt status, + @n [0] The data triggering threshold at x-axis, when the data is NO_DATA, the interrupt is triggered. + @n [1] The data triggering threshold at y-axis, when the data is NO_DATA, the interrupt is triggered. + @n [2] The data triggering threshold at z-axis, when the data is NO_DATA, the interrupt is triggered. + ''' + Data = [NO_DATA] * 3 + state = self.get_data_ready_state() + if state == True: + magData = self.get_geomagnetic_data() + if self.__thresholdMode == LOW_THRESHOLD_INTERRUPT: + if magData[0] < self.threshold*16: + Data[0] = magData[0] + if magData[1] < self.threshold*16: + Data[1] = magData[1] + if magData[2] < self.threshold*16: + Data[2] = magData[2] + elif self.__thresholdMode == HIGH_THRESHOLD_INTERRUPT: + if magData[0] < self.threshold*16: + Data[0] = magData[0] + if magData[1] < self.threshold*16: + Data[1] = magData[1] + if magData[2] < self.threshold*16: + Data[2] = magData[2] + return Data + +# I2C interface +class DFRobot_bmm350_I2C(DFRobot_bmm350): + '''! + @brief An example of an i2c interface module + ''' + def __init__(self, bus, addr): + self.bus = bus + self.__addr = addr + if self.is_raspberrypi(): + import smbus + self.i2cbus = smbus.SMBus(bus) + else: + self.test_platform() + super(DFRobot_bmm350_I2C, self).__init__(self.bus) + + def is_raspberrypi(self): + import io + try: + with io.open('/sys/firmware/devicetree/base/model', 'r') as m: + if 'raspberry pi' in m.read().lower(): return True + except Exception: pass + return False + + def test_platform(self): + import re + import platform + import subprocess + where = platform.system() + if where == "Linux": + p = subprocess.Popen(['i2cdetect', '-l'], stdout=subprocess.PIPE,) + for i in range(0, 25): + line = str(p.stdout.readline()) + s = re.search("i2c-tiny-usb", line) + if s: + line = re.split(r'\W+', line) + bus = int(line[2]) + import smbus + self.i2cbus = smbus.SMBus(bus) + elif where == "Windows": + from i2c_mp_usb import I2C_MP_USB as SMBus + self.i2cbus = SMBus() + else: + print("Platform not supported") + + + + def write_reg(self, reg, data): + '''! + @brief writes data to a register + @param reg register address + @param data written data + ''' + while 1: + try: + self.i2cbus.write_byte_data(self.__addr, reg, data) + return + except: + print("please check connect w!") + time.sleep(1) + return + + def read_reg(self, reg ,len): + '''! + @brief read the data from the register + @param reg register address + @param len read data length + ''' + while True: + try: + # Read data from I2C bus + temp_buf = self.i2cbus.read_i2c_block_data(self.__addr, reg, len + BMM350_DUMMY_BYTES) + # Copy data after dummy byte indices + reg_data = temp_buf[BMM350_DUMMY_BYTES:] + return reg_data # Assuming this function is part of a larger method + except Exception as e: + time.sleep(1) + print("please check connect r!") diff --git a/lib/DFRobot_BMM350/python/raspberrypi/README.md b/lib/DFRobot_BMM350/python/raspberrypi/README.md new file mode 100644 index 0000000..33c89e6 --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/README.md @@ -0,0 +1,201 @@ +# DFRobot_bmm350 + +* [中文](./README_CN.md) + +This RaspberryPi BMM350 sensor board can communicate with RaspberryPi via I2C or I3C.
+The BMM350 is capable of obtaining triaxial geomagnetic data.
+ +![产品效果图](../../resources/images/)![产品效果图](../../resources/images/) + +## Product Link([https://www.dfrobot.com](https://www.dfrobot.com)) + SKU: + +## Table of Contents + +* [Summary](#summary) +* [Installation](#installation) +* [Methods](#methods) +* [History](#history) +* [Credits](#credits) + +## Summary + +Get geomagnetic data along the XYZ axis. + +1. This module can obtain high threshold and low threshold geomagnetic data.
+2. Geomagnetism on three(xyz) axes can be measured.
+3. This module can choose I2C or I3C communication mode.
+ + +## Installation + +This Sensor should work with DFRobot_BMM350 on RaspberryPi.
+Run the program: + +``` +$> python3 get_all_state.py +$> python3 data_ready_interrupt.py +$> python3 get_geomagnetic_data.py +$> python3 threshold_interrupt.py +``` + +## Methods + +```python + '''! + @brief Init bmm350 check whether the chip id is right + @return 0 is init success + -1 is init failed + ''' + def sensor_init(self): + + '''! + @brief Soft reset, restore to suspended mode after soft reset. (You need to manually enter the normal mode) + ''' + def soft_reset(self): + + '''! + @brief Sensor self test, the returned character string indicate the self test result. + @return The character string of the test result + ''' + def self_test(self): + + '''! + @brief Set sensor operation mode + @param modes + @n BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + @n BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + @n BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + @n BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + def set_operation_mode(self, modes): + + '''! + @brief Get sensor operation mode + @return Return the character string of the operation mode + ''' + def get_operation_mode(self): + + '''! + @brief Set the rate of obtaining geomagnetic data, the higher, the faster (without delay function) + @param rate + @n BMM350_DATA_RATE_1_5625HZ + @n BMM350_DATA_RATE_3_125HZ + @n BMM350_DATA_RATE_6_25HZ + @n BMM350_DATA_RATE_12_5HZ (default rate) + @n BMM350_DATA_RATE_25HZ + @n BMM350_DATA_RATE_50HZ + @n BMM350_DATA_RATE_100HZ + @n BMM350_DATA_RATE_200HZ + @n BMM350_DATA_RATE_400HZ + ''' + def set_rate(self, rates): + + '''! + @brief Get the config data rate, unit: HZ + @return rate + ''' + def get_rate(self): + + '''! + @brief Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + @param modes + @n BMM350_PRESETMODE_LOWPOWER Low power mode, get a fraction of data and take the mean value. + @n BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and take the mean value. + @n BMM350_PRESETMODE_ENHANCED Enhanced mode, get a plenty of data and take the mean value. + @n BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and take the mean value. + + ''' + def set_preset_mode(self, modes): + + '''! + @brief Enable the measurement at x-axis, y-axis and z-axis, default to be enabled. After disabling, the geomagnetic data at x, y, and z axis are wrong. + @param en_x + @n BMM350_X_EN Enable the measurement at x-axis + @n BMM350_X_DIS Disable the measurement at x-axis + @param en_y + @n BMM350_Y_EN Enable the measurement at y-axis + @n BMM350_Y_DIS Disable the measurement at y-axis + @param en_z + @n BMM350_Z_EN Enable the measurement at z-axis + @n BMM350_Z_DIS Disable the measurement at z-axis + ''' + def set_measurement_XYZ(self, en_x = BMM350_X_EN, en_y = BMM350_Y_EN, en_z = BMM350_Z_EN): + + '''! + @brief Get the enabling status at x-axis, y-axis and z-axis + @return Return enabling status at x-axis, y-axis and z-axis as a character string + ''' + def get_measurement_state_XYZ(self): + + '''! + @brief Get the geomagnetic data of 3 axis (x, y, z) + @return The list of the geomagnetic data at 3 axis (x, y, z) unit: uT + @ [0] The geomagnetic data at x-axis + @ [1] The geomagnetic data at y-axis + @ [2] The geomagnetic data at z-axis + ''' + def get_geomagnetic_data(self): + + '''! + @brief Get compass degree + @return Compass degree (0° - 360°) 0° = North, 90° = East, 180° = South, 270° = West. + ''' + def get_compass_degree(self): + + '''! + @brief Enable or disable data ready interrupt pin + @n After enabling, the DRDY pin jump when there's data coming. + @n After disabling, the DRDY pin will not jump when there's data coming. + @n High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. + @n Low polarity: active on low, default is high level, which turns to low level when the interrupt is triggered. + @param modes + @n BMM350_ENABLE_INTERRUPT Enable DRDY + @n BMM350_DISABLE_INTERRUPT Disable DRDY + @param polarity + @n BMM350_ACTIVE_HIGH High polarity + @n BMM350_ACTIVE_LOW Low polarity + ''' + def set_data_ready_pin(self, modes, polarity): + + '''! + @brief Get data ready status, determine whether the data is ready + @return status + @n True Data ready + @n False Data is not ready + ''' + def get_data_ready_state(self): + + '''! + @brief Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold + @n High polarity: active on high level, the default is low level, which turns to high level when the interrupt is triggered. + @n Low polarity: active on low level, the default is high level, which turns to low level when the interrupt is triggered. + @param modes + @n LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode + @n HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode + @param threshold + @n Threshold, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt + @param polarity + @n POLARITY_HIGH High polarity + @n POLARITY_LOW Low polarity + ''' + def set_threshold_interrupt(self, modes, threshold, polarity): + + '''! + @brief Get the data that threshold interrupt occured + @return Return the list for storing geomagnetic data, how the data at 3 axis influence interrupt status, + @n [0] The data triggering threshold at x-axis, when the data is NO_DATA, the interrupt is triggered. + @n [1] The data triggering threshold at y-axis, when the data is NO_DATA, the interrupt is triggered. + @n [2] The data triggering threshold at z-axis, when the data is NO_DATA, the interrupt is triggered. + ''' + def get_threshold_data(self): +``` + +## History + +- 2024/05/11 - Version 1.0.0 released. + +## Credits + +Written by [GDuang](yonglei.ren@dfrobot.com), 2024. (Welcome to our website) diff --git a/lib/DFRobot_BMM350/python/raspberrypi/README_CN.md b/lib/DFRobot_BMM350/python/raspberrypi/README_CN.md new file mode 100644 index 0000000..71331e8 --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/README_CN.md @@ -0,0 +1,218 @@ +# DFRobot_bmm350 + +- [English Version](./README.md) + +BMM350 是一款低功耗、低噪声的 3 轴数字地磁传感器,完全符合罗盘应用的要求。 基于博世专有的 FlipCore 技术,BMM350 提供了高精度和动态的绝对空间方向和运动矢量。 体积小、重量轻,特别适用于支持无人机精准航向。 BMM350 还可与由 3 轴加速度计和 3 轴陀螺仪组成的惯性测量单元一起使用。 + +![产品效果图](../../resources/images)![产品效果图](../../resources/images) + + +## 产品链接([https://www.dfrobot.com.cn](https://www.dfrobot.com.cn)) + SKU: + +## 目录 + + * [概述](#概述) + * [库安装](#库安装) + * [方法](#方法) + * [兼容性](#兼容性) + * [历史](#历史) + * [创作者](#创作者) + +## 概述 + +您可以沿 XYZ 轴获取地磁数据 + +1. 本模块可以获得高阈值和低阈值地磁数据。
+2. 可以测量三个(xyz)轴上的地磁。
+3. 本模块可选择I2C或I3C通讯方式。
+ + +## 库安装 +1. 下载库至树莓派,要使用这个库,首先要将库下载到Raspberry Pi,命令下载方法如下:
+```python +sudo git clone https://github.com/DFRobot/DFRobot_BMM350 +``` +2. 打开并运行例程,要执行一个例程demo_x.py,请在命令行中输入python demo_x.py。例如,要执行data_ready_interrupt.py例程,你需要输入:
+ +```python +python3 data_ready_interrupt.py +``` + +## 方法 + +```python + '''! + @brief 初始化bmm350 判断芯片id是否正确 + @return 0 is init success + @n -1 is init failed + ''' + def sensor_init(self): + + '''! + @brief 软件复位,软件复位后先恢复为挂起模式(需手动进行普通模式) + ''' + def soft_reset(self): + + '''! + @brief 传感器自测,返回字符串表明自检结果 + @return 测试结果的字符串 + ''' + def self_test(self): + + '''! + @brief 设置传感器的执行模式 + @param modes + @n BMM350_SUSPEND_MODE 挂起模式: 挂起模式是芯片上电后BMM350的默认电源模式,在挂起模式下电流消耗最小,因此,这种模式在不需要进行数据转换时非常有用。所有寄存器的读写是可能的 + @n BMM350_NORMAL_MODE 普通模式: 正常获取地磁数据 + @n BMM350_FORCED_MODE 强制模式: 单次测量,测量完成后传感器恢复到暂停模式 + @n BMM350_FORCED_MODE_FAST 只有使用FM_ FAST才能达到ODR = 200Hz + ''' + def set_operation_mode(self, modes): + + '''! + @brief 获取传感器的执行模式 + @return 返回模式的字符串 + ''' + def get_operation_mode(self): + + '''! + @brief 设置地磁数据获取的速率,速率越大获取越快(不加延时函数) + @param rate + @n BMM350_DATA_RATE_1_5625HZ + @n BMM350_DATA_RATE_3_125HZ + @n BMM350_DATA_RATE_6_25HZ + @n BMM350_DATA_RATE_12_5HZ (default rate) + @n BMM350_DATA_RATE_25HZ + @n BMM350_DATA_RATE_50HZ + @n BMM350_DATA_RATE_100HZ + @n BMM350_DATA_RATE_200HZ + @n BMM350_DATA_RATE_400HZ + ''' + def set_rate(self, rates): + + '''! + @brief 获取配置的数据速率 单位:HZ + @return rate + ''' + def get_rate(self): + + '''! + @brief 设置预置模式,使用户更简单的配置传感器来获取地磁数据 (默认的采集速率为12.5Hz) + @param modes + @n BMM350_PRESETMODE_LOWPOWER 低功率模式,获取少量的数据 取均值 + @n BMM350_PRESETMODE_REGULAR 普通模式,获取中量数据 取均值 + @n BMM350_PRESETMODE_ENHANCED 增强模式,获取大量数据 取均值 + @n BMM350_PRESETMODE_HIGHACCURACY 高精度模式,获取超大量数据 取均值 + ''' + def set_preset_mode(self, modes): + + '''! + @brief 使能x y z 轴的测量,默认设置为使能不需要配置,禁止后xyz轴的地磁数据不准确 + @param en_x + @n BMM350_X_EN 使能 x 轴的测量 + @n BMM350_X_DIS 禁止 x 轴的测量 + @param channel_y + @n BMM350_Y_EN 使能 y 轴的测量 + @n BMM350_Y_DIS 禁止 y 轴的测量 + @param channel_z + @n BMM350_Z_EN 使能 z 轴的测量 + @n BMM350_Z_DIS 禁止 z 轴的测量 + ''' + def set_measurement_XYZ(self, en_x = BMM350_X_EN, en_y = BMM350_Y_EN, en_z = BMM350_Z_EN): + + '''! + @brief 获取 x y z 轴的使能状态 + @return 返回xyz 轴的使能状态的字符串 + ''' + def get_measurement_state_XYZ(self): + + '''! + @brief 获取x y z 三轴的地磁数据 + @return x y z 三轴的地磁数据的列表 单位:微特斯拉(uT) + @n [0] x 轴地磁的数据 + @n [1] y 轴地磁的数据 + @n [2] z 轴地磁的数据 + ''' + def get_geomagnetic_data(self): + + '''! + @brief 获取罗盘方向 + @return 罗盘方向 (0° - 360°) 0° = North, 90° = East, 180° = South, 270° = West. + ''' + def get_compass_degree(self): + + '''! + @brief 使能或者禁止数据准备中断引脚 + @n 使能后有数据来临DRDY引脚跳变 + @n 禁止后有数据来临DRDY不进行跳变 + @n 高极性:高电平为活动电平,默认为低电平,触发中断时电平变为高 + @n 低极性:低电平为活动电平,默认为高电平,触发中断时电平变为低 + @param modes + @n BMM350_ENABLE_INTERRUPT 使能DRDY + @n BMM350_DISABLE_INTERRUPT 禁止DRDY + @param polarity + @n BMM350_ACTIVE_HIGH 高极性 + @n BMM350_ACTIVE_LOW 低极性 + ''' + def set_data_ready_pin(self, modes, polarity): + + '''! + @brief 获取数据准备的状态,用来判断数据是否准备好 + @return status + @n True 表示数据已准备好 + @n False 表示数据还未准备好 + ''' + def get_data_ready_state(self): + + '''! + @brief 设置阈值中断,当某个通道的地磁值高/低于阈值时触发中断 + @n 高极性:高电平为活动电平,默认为低电平,触发中断时电平变为高 + @n 低极性:低电平为活动电平,默认为高电平,触发中断时电平变为低 + @param modes + @n LOW_THRESHOLD_INTERRUPT 低阈值中断模式 + @n HIGH_THRESHOLD_INTERRUPT 高阈值中断模式 + @param threshold 阈值,默认扩大16倍,例如:低阈值模式下传入阈值1,实际低于16的地磁数据都会触发中断 + @param polarity + @n POLARITY_HIGH 高极性 + @n POLARITY_LOW 低极性 + ''' + def set_threshold_interrupt(self, modes, threshold, polarity): + + '''! + @brief 获取发生阈值中断的数据 + @return 返回存放地磁数据的列表,列表三轴当数据和中断状态, + @n [0] x 轴触发阈值的数据 ,当数据为NO_DATA时为触发中断 + @n [1] y 轴触发阈值的数据 ,当数据为NO_DATA时为触发中断 + @n [2] z 轴触发阈值的数据 ,当数据为NO_DATA时为触发中断 + ''' + def get_threshold_data(self): +``` + +## 兼容性 + +| 主板 | 通过 | 未通过 | 未测试 | 备注 | +| ------------ | :--: | :----: | :----: | :--: | +| RaspberryPi2 | | | √ | | +| RaspberryPi3 | | | √ | | +| RaspberryPi4 | √ | | | | + +* Python 版本 + +| Python | 通过 | 未通过 | 未测试 | 备注 | +| ------- | :--: | :----: | :----: | ---- | +| Python3 | √ | | | | + +## 历史 + +- 2024/05/11 - 1.0.0 版本 + +## 创作者 + +Written by [GDuang](yonglei.ren@dfrobot.com), 2024. (Welcome to our [website](https://www.dfrobot.com/)) + + + + + + diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/data_ready_interrupt.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/data_ready_interrupt.py new file mode 100644 index 0000000..3bd60c3 --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/data_ready_interrupt.py @@ -0,0 +1,111 @@ +# -*- coding:utf-8 -*- +''' + @file demo_data_ready_interrupt.py + @brief Data ready interrupt, DRDY interrupt will be triggered when the geomagnetic data is ready (the software and hardware can determine whether the interrupt occur) + @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis, unit (uT) + @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by DRDY pin interrupt, then the geomagnetic data can be obtained. + @n Connect the sensor DADY pin to the interrupt pin (RASPBERR_PIN_DRDY) of the main controller + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC, GND, SCL, SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error, please check connect") + time.sleep(1) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + + ''' + Enable or disable data ready interrupt pin + After enabling, the pin DRDY signal jump when there's data coming. + After disabling, the pin DRDY signal does not jump when there's data coming. + High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. + Low polarity: active on low, the default is high level, which turns to low level when the interrupt is triggered. + modes: + BMM350_ENABLE_INTERRUPT Enable DRDY + BMM350_DISABLE_INTERRUPT Disable DRDY + polarity: + BMM350_ACTIVE_HIGH High polarity + BMM350_ACTIVE_LOW Low polarity + ''' + bmm350.set_data_ready_pin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW) + + +def loop(): + ''' + Get data ready status, determine whether the data is ready (through software) + status: + True Data ready + False Data is not ready yet + ''' + if bmm350.get_data_ready_state() == 1: + rslt = bmm350.get_geomagnetic_data() + print("mag x = %d ut"%rslt[0]) + print("mag y = %d ut"%rslt[1]) + print("mag z = %d ut"%rslt[2]) + print("") + else: + time.sleep(1) + + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_data_ready_interrupt.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_data_ready_interrupt.py new file mode 100644 index 0000000..f7e1110 --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_data_ready_interrupt.py @@ -0,0 +1,112 @@ +# -*- coding:utf-8 -*- +''' + @file demo_data_ready_interrupt.py + @brief Data ready interrupt, DRDY interrupt will be triggered when the geomagnetic data is ready (the software and hardware can determine whether the interrupt occur) + @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis, unit (uT) + @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by DRDY pin interrupt, then the geomagnetic data can be obtained. + @n Connect the sensor DADY pin to the interrupt pin (RASPBERR_PIN_DRDY) of the main controller + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC,GND,SCL,SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error, please check connect") + time.sleep(1) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + + ''' + Enable or disable data ready interrupt pin + After enabling, the pin DRDY signal jump when there's data coming. + After disabling, the pin DRDY signal does not jump when there's data coming. + High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. + Low polarity: active on low, the default is high level, which turns to low level when the interrupt is triggered. + modes: + BMM350_ENABLE_INTERRUPT Enable DRDY + BMM350_DISABLE_INTERRUPT Disable DRDY + polarity: + BMM350_ACTIVE_HIGH High polarity + BMM350_ACTIVE_LOW Low polarity + ''' + bmm350.set_data_ready_pin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW) + + +def loop(): + ''' + Get data ready status, determine whether the data is ready (through software) + status: + True Data ready + False Data is not ready yet + ''' + if bmm350.get_data_ready_state() == 1: + rslt = bmm350.get_geomagnetic_data() + print("mag x = %d ut"%rslt[0]) + print("mag y = %d ut"%rslt[1]) + print("mag z = %d ut"%rslt[2]) + print("") + else: + time.sleep(1) + + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_all_state.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_all_state.py new file mode 100644 index 0000000..7faa65e --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_all_state.py @@ -0,0 +1,107 @@ +# -*- coding:utf-8 -*- +''' + @file demo_get_all_state.py + @brief Get all the config and self test status, the sensor can change from normal mode to sleep mode after soft reset + @n Experimental phenomenon: the sensor config and self test information are printed in the serial port. + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC,GND,SCL,SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error, please check connect") + time.sleep(1) + + print('Power mode after sensor initialization: ', bmm350.get_operation_mode()) + + ''' + Sensor self test, the returned character string indicates the test result. + ''' + print(bmm350.self_test()) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + + ''' + Get the config data rate unit: HZ + ''' + print("rates is %d HZ"%bmm350.get_rate() ) + + ''' + Get the character string of enabling status at x-axis, y-axis and z-axis + ''' + print(bmm350.get_measurement_state_XYZ()) + + ''' + @brief Soft reset, restore to suspended mode after soft reset. (You need to manually enter the normal mode) + ''' + bmm350.soft_reset() + print('Power mode after software reset: ', bmm350.get_operation_mode()) + +def loop(): + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + exit() + + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_geomagnetic_data.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_geomagnetic_data.py new file mode 100644 index 0000000..f64ffcf --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_geomagnetic_data.py @@ -0,0 +1,90 @@ +# -*- coding:utf-8 -*- +''' + @file demo_get_geomagnetic_data.py + @brief Get the geomagnetic data at 3 axis (x, y, z), get the compass degree + @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north + @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis and the angle formed when the needle rotates counterclockwise from the current position to the true north + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC,GND,SCL,SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error, please check connect") + time.sleep(1) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + +def loop(): + geomagnetic = bmm350.get_geomagnetic_data() + print("mag x = %d ut"%geomagnetic[0]) + print("mag y = %d ut"%geomagnetic[1]) + print("mag z = %d ut"%geomagnetic[2]) + + # get float type data + # geomagnetic = bmm350.get_geomagnetic_data() + # print("---------------------------------") + # print("mag x = %.2f ut"%geomagnetic[0]) + # print("mag y = %.2f ut"%geomagnetic[1]) + # print("mag z = %.2f ut"%geomagnetic[2]) + degree = bmm350.get_compass_degree() + print("---------------------------------") + print("the angle between the pointing direction and north (counterclockwise) is: %.2f "%degree) + time.sleep(1) + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_threshold_interrupt.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_threshold_interrupt.py new file mode 100644 index 0000000..2b4434e --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_threshold_interrupt.py @@ -0,0 +1,115 @@ +# -*- coding:utf-8 -*- +''' + @file demo_threshold_interrupt.py + @brief Set the interrupt to be triggered when beyond/below threshold, when the interrupt at a axis occur, the data will be printed in the serial port. + @n When the geomagnetic data at 3 axis (x, y, z) beyond/below the set threshold, the data will be printed in the serial port, unit (uT) + @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by INT pin interrupt, then the geomagnetic data can be obtained + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC,GND,SCL,SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error ,please check connect") + time.sleep(1) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + + + ''' + Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold + High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. + Low polarity: active on low, the default is high level, which turns to low level when the interrupt is triggered. + modes: + LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode, interrupt is triggered when below the threshold + HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode, interrupt is triggered when beyond the threshold + threshold + Threshold range, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt + polarity: + BMM350_ACTIVE_HIGH High polarity + BMM350_ACTIVE_LOW Low polarity + View the use method in the readme file if you want to use more configs + ''' + bmm350.set_threshold_interrupt(LOW_THRESHOLD_INTERRUPT, 0, BMM350_ACTIVE_LOW) + + +def loop(): + ''' + Get the data that threshold interrupt occured (get the threshold interrupt status through software) + That the data at (x, y, z) axis are printed in the serial port indicates threshold interrupt occur at (x, y, z) axis + Return the list for storing geomagnetic data, how the data at 3 axis influence interrupt status + [0] The data triggering threshold at x-axis, when the data is NO_DATA, the interrupt is triggered. + [1] The data triggering threshold at y-axis, when the data is NO_DATA, the interrupt is triggered. + [2] The data triggering threshold at z-axis, when the data is NO_DATA, the interrupt is triggered. + ''' + threshold_data = bmm350.get_threshold_data() + if threshold_data[0] != NO_DATA: + print("mag x = %d ut"%threshold_data[0]) + if threshold_data[1] != NO_DATA: + print("mag y = %d ut"%threshold_data[1]) + if threshold_data[2] != NO_DATA: + print("mag z = %d ut"%threshold_data[2]) + print("") + time.sleep(1) + + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/get_all_state.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/get_all_state.py new file mode 100644 index 0000000..36023cc --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/get_all_state.py @@ -0,0 +1,108 @@ +# -*- coding:utf-8 -*- +''' + @file demo_get_all_state.py + @brief Get all the config and self test status, the sensor can change from normal mode to sleep mode after soft reset + @n Experimental phenomenon: the sensor config and self test information are printed in the serial port. + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC, GND, SCL, SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error, please check connect") + time.sleep(1) + + print('Power mode after sensor initialization: ', bmm350.get_operation_mode()) + + ''' + Sensor self test, the returned character string indicates the test result. + ''' + print(bmm350.self_test()) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + + ''' + Get the config data rate unit: HZ + ''' + print("rates is %d HZ"%bmm350.get_rate() ) + + ''' + Get the character string of enabling status at x-axis, y-axis and z-axis + ''' + print(bmm350.get_measurement_state_XYZ()) + + ''' + @brief Soft reset, restore to suspended mode after soft reset. (You need to manually enter the normal mode) + ''' + bmm350.soft_reset() + print('Power mode after software reset: ', bmm350.get_operation_mode()) + +def loop(): + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + exit() + + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/get_calibrated_geomagnetic_data.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/get_calibrated_geomagnetic_data.py new file mode 100644 index 0000000..2ef2d11 --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/get_calibrated_geomagnetic_data.py @@ -0,0 +1,107 @@ +# -*- coding:utf-8 -*- +''' + @file get_calibrated_geomagnetic_data.py + @brief Get the geomagnetic data at 3 axis (x, y, z), get the compass degree + @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north + @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis and the angle formed when the needle rotates counterclockwise from the current position to the true north + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os +import math +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC,GND,SCL,SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error, please check connect") + time.sleep(1) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + +def loop(): + geomagnetic = bmm350.get_geomagnetic_data() + #hard iron calibration parameters + hard_iron= (-13.45, -28.95, 12.69 ) + #soft iron calibration parameters + soft_iron= [ + ( 0.992, -0.006, -0.007 ), + ( -0.006, 0.990, -0.004 ), + ( -0.007, -0.004, 1.019 ) + ] + + # hard iron calibration + geomagnetic[0] =geomagnetic[0] + hard_iron[0] + geomagnetic[1] =geomagnetic[1] + hard_iron[1] + geomagnetic[2] = geomagnetic[2] + hard_iron[2] + + #soft iron calibration + for i in range(3): + geomagnetic[i] = (soft_iron[i][0] * geomagnetic[0]) + (soft_iron[i][1] * geomagnetic[1]) + (soft_iron[i][2] * geomagnetic[2]) + + compass = math.atan2(geomagnetic[0], geomagnetic[1]) + if compass < 0: + compass += 2 * PI + if compass > 2 * PI: + compass -= 2 * PI + degree=compass * 180 / M_PI + print("---------------------------------") + print("mag x = %.2f ut"%geomagnetic[0]) + print("mag y = %.2f ut"%geomagnetic[1]) + print("mag z = %.2f ut"%geomagnetic[2]) + print("---------------------------------") + print("the angle between the pointing direction and north (counterclockwise) is: %.2f "%degree) + time.sleep(1) + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/get_geomagnetic_data.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/get_geomagnetic_data.py new file mode 100644 index 0000000..1989b7f --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/get_geomagnetic_data.py @@ -0,0 +1,89 @@ +# -*- coding:utf-8 -*- +''' + @file demo_get_geomagnetic_data.py + @brief Get the geomagnetic data at 3 axis (x, y, z), get the compass degree + @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north + @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis and the angle formed when the needle rotates counterclockwise from the current position to the true north + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC, GND, SCL, SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error, please check connect") + time.sleep(1) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + +def loop(): + geomagnetic = bmm350.get_geomagnetic_data() + print("mag x = %d ut"%geomagnetic[0]) + print("mag y = %d ut"%geomagnetic[1]) + print("mag z = %d ut"%geomagnetic[2]) + + # get float type data + # geomagnetic = bmm350.get_geomagnetic_data() + # print("---------------------------------") + # print("mag x = %.2f ut"%geomagnetic[0]) + # print("mag y = %.2f ut"%geomagnetic[1]) + # print("mag z = %.2f ut"%geomagnetic[2]) + degree = bmm350.get_compass_degree() + print("---------------------------------") + print("the angle between the pointing direction and north (counterclockwise) is: %.2f "%degree) + time.sleep(1) + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/threshold_interrupt.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/threshold_interrupt.py new file mode 100644 index 0000000..ff0893f --- /dev/null +++ b/lib/DFRobot_BMM350/python/raspberrypi/examples/threshold_interrupt.py @@ -0,0 +1,115 @@ +# -*- coding:utf-8 -*- +''' + @file demo_threshold_interrupt.py + @brief Set the interrupt to be triggered when beyond/below threshold, when the interrupt at a axis occur, the data will be printed in the serial port. + @n When the geomagnetic data at 3 axis (x, y, z) beyond/below the set threshold, the data will be printed in the serial port, unit (uT) + @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by INT pin interrupt, then the geomagnetic data can be obtained + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author [GDuang](yonglei.ren@dfrobot.com) + @version V1.0.0 + @date 2024-05-11 + @url https://github.com/DFRobot/DFRobot_BMM350 +''' +import sys +import os + +sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) +from DFRobot_bmm350 import * + +''' + If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port + Connect to VCC, GND, SCL, SDA pin +''' +I2C_BUS = 0x01 #default use I2C1 +bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) + +def setup(): + while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): + print("sensor init error ,please check connect") + time.sleep(1) + + ''' + Set sensor operation mode + opMode: + BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. + BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. + ''' + bmm350.set_operation_mode(BMM350_NORMAL_MODE) + + ''' + Get the operation mode character string of the sensor + ''' + print('Current power mode: ', bmm350.get_operation_mode()) + + ''' + Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + presetMode: + BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. + BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. + BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. + BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. + rate: + BMM350_DATA_RATE_1_5625HZ + BMM350_DATA_RATE_3_125HZ + BMM350_DATA_RATE_6_25HZ + BMM350_DATA_RATE_12_5HZ (default rate) + BMM350_DATA_RATE_25HZ + BMM350_DATA_RATE_50HZ + BMM350_DATA_RATE_100HZ + BMM350_DATA_RATE_200HZ + BMM350_DATA_RATE_400HZ + ''' + bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) + + ''' + Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. + Refer to readme file if you want to configure more parameters. + ''' + bmm350.set_measurement_XYZ() + + + ''' + Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold + High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. + Low polarity: active on low, the default is high level, which turns to low level when the interrupt is triggered. + modes: + LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode, interrupt is triggered when below the threshold + HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode, interrupt is triggered when beyond the threshold + threshold + Threshold range, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt + polarity: + BMM350_ACTIVE_HIGH High polarity + BMM350_ACTIVE_LOW Low polarity + View the use method in the readme file if you want to use more configs + ''' + bmm350.set_threshold_interrupt(LOW_THRESHOLD_INTERRUPT, 0, BMM350_ACTIVE_LOW) + + +def loop(): + ''' + Get the data that threshold interrupt occured (get the threshold interrupt status through software) + That the data at (x, y, z) axis are printed in the serial port indicates threshold interrupt occur at (x, y, z) axis + Return the list for storing geomagnetic data, how the data at 3 axis influence interrupt status + [0] The data triggering threshold at x-axis, when the data is NO_DATA, the interrupt is triggered. + [1] The data triggering threshold at y-axis, when the data is NO_DATA, the interrupt is triggered. + [2] The data triggering threshold at z-axis, when the data is NO_DATA, the interrupt is triggered. + ''' + threshold_data = bmm350.get_threshold_data() + if threshold_data[0] != NO_DATA: + print("mag x = %d ut"%threshold_data[0]) + if threshold_data[1] != NO_DATA: + print("mag y = %d ut"%threshold_data[1]) + if threshold_data[2] != NO_DATA: + print("mag z = %d ut"%threshold_data[2]) + print("") + time.sleep(1) + + +if __name__ == "__main__": + setup() + while True: + loop() diff --git a/lib/DFRobot_BMM350/resources/images/BMM350.png b/lib/DFRobot_BMM350/resources/images/BMM350.png new file mode 100644 index 0000000000000000000000000000000000000000..7978f228908f2007ae9d3aab7447844da0b94b55 GIT binary patch literal 200001 zcma(2XEdDc_Xmz*h%S2Xh8R5v!w@9e5WNJ0D5HIBogG@`JVsptn=c$IBN~ovbe9duf0EI-$}-XINy&0e2&Zk@RBJ^h+2K%K)1On+-?u_H&V%}5(5-3lid(kRa z6@I=fYBu^u?xl`Way{YlA*QPB&y0%JUp`?`PT$MlRe#Tn{xT`BrQ9RKeRV@C(=E$k zc;Ke>1T?8;NUlVLdakECZceXxNjBKHnu`4T5hFRS z&ev!~-4_mCJzt^d9C`Qdom!s@g>J^O=M%Gcl>KUTm`W>EY zXAzp3q<&C4WH_*snWhE8K3?Q`Ioc-Rr-2h+gfwMzu1uaNG-piM_?QW-+sVJ ziAx}hTdv#CqukNoihqU@=Pl2XS^cwf68e*tYlG3sIc$*BiT;lvOUyj@>kC)_4~Z%kf@7&Oq)Z

0 z_}>H_AiRELdN%3rq_|>b{anG7I~h?R~R4 z*#Df`=yAIgJmI!WrmztB=Ulqk`Sx&%iMQm(}~8Q@SDG*lB&oCd*?X zIyp@5s=e!>0%f5Bx*TpZAO!5JdMRk8G16c+*rms*bM^gyvVyK+==)7|2kOpb<{4?9 zZz$|L$k|NA*j#qU%|2F0XpNWc<#d6oBE0ZA=IxCxgiKWW^1mJ7P}H{Crfa@cK$@QG zYHdUEQ>N5#R|`@m>*vRRn(@mHI-N-VJOsqDIbm4uX~BV()xI6~CVo8=M&}AHMjk>*NrWa;J~}GjB-b`d ziQn;GM1uqPw?loprW0>rif!-h(Vu9Buo=poN_!b;S>|qR*b_t2<*H2fIo{u3{pqV{ zG{jdFE1r{lkFdq*JhXVXr%`TiWXy1QDjUd~8%aGYqGzR>@|Em%BuJm8^y?Q&H6LOD41 zH`JMvCCU5%qQAq3M+`HaARuk*!B1OtaUZCYV%x0<+4)sxEl|u0OT4#K$`QE+BB!3h z2rP_VUqt!u@O}9IV;nT|Od+;%)>m*GCp$~W4S!Hi=(>}oTTtj)pbk7pRjhpXT2NC@ z@Y)g&-%%g>y2k0FZEBS(vyDfbUuj{>=ly$*BJ{CGaJ2!+|88T%!wr-*F$-c5A>l|3 zNOK!yW(|MhMB)I~Ih())%Sp$CA#m@X0#{28vw)3bc(;LlryGL%(w78AFgnD)TPMTi z$sQ-c6!XzTZU6pOLQQsdK&{i|LQ>>mLG-kXe>NSTQmO6#_n~3uUIIHeaq6b)X9$hTjr|WH=Q*7aQ1Gq1dW1`%uPg^V9TFhyq6$f?xurwtW{CJ^VW{*iZM{; zr`=AP=uhthnQ+XciNsM2rL#gextE)kdH$s(E(2~V5)$gz*fz;f=hAbAel|n+U2_W~ zBcmYG6fhL4vz~gn>Yef1#VC(e=gf*PMX7f}w;QXHJMTnMK)S#YbA5fyqp0l)hB2B| z=XjP?FeEaIO<<1ReXy+!C?-50&}qg2;S2;Jr38gwamXr1O(f}*F0Sp}MA@)QB`X;- z<$z7@=%T~zI0KS{)PAY)&sD9FL`rkzH#QVfYXm7%2#woGzl31PLeFbx2tdxB{CfF8 zvzeY*f({xL^3={IlBdYoxV0h5j`5EoTIilzM%aqCo5N3r{vo)T`G+Y8SB`{uyXYpD z9u{37$d4%&Y+1auokUPr-2PYRv$f(X{_SyTLmzD(swG0d_Qh@sRIuePtIjogeT4Nb zgHc5VfK(!e`Z@?`q>ib@BJWwfgi-xv`5=VzNZtCcE_U*?Q`TmqVupgC?6P!aBN_)G zL;t8K#^)y9!s?*@1>9H~1w?3j^kWS6TCYM>-@+1uY8Yn7050HZ20;NwkscA_QsJpU3FsB2NtaDpg68=@V=ZTx)sDB5G>vGZOzpVlgf3cD~^mO zlk39l#(6Bi9$S1?qI$SC2AtILQ0OzNSad>`4Ojp&16n?ByYp!Azm5u}2`+fZ4quuP z(wD_(=+R=jrSf~RBu(NXWJh6%rZ-6sxIl6TOgZjHMCRY$wX0wk<|8LKMT?pf;N&Ba zX_#v>r>oK7orWy4xl9-mmnVMb?LsE`;Of~O4MqN|I{m3g{T_r=tsEw;f&<^1% zS@K~qvgeKBNtz{_=(nd2+bB9(^YfsOWrSk_MRg0XS~0b5IAP#O7yzj9^ZdN*)08Yf zXUUjhDF_|ab9C%y5U7n^_lR7AL{ta;`WqS=ItfNIj(q7wENL^1*BESc)6mM+(qvaQ z{OD9qP7D)-sd$q#H7mG43=gy8UFGjW3Dx|Vu^O0rA?WJr3Y%!$+1IDGoph?alB+1> zkNpyIrC@H_90!t2>|M{VrvRGIo*^bcrdY0`bWXs*83R{9LKdANA( zKch1U-BlS2u*IyE7695JwXwqKN4X0j-(hdP;en&od_u$b%+61^gk~4h2pm_9T(Nyk zf~r8m_?4(P#Ds^G8brVOrcZD`cBF@Un``fU^oansAK~0|Go-rALhz6OrP|42`=4xo zbKQUR_xEr9P-~giRq#|H%M>H`!|+u4`N;eG5j_VArgym6u13n7BYrTNggbG<&nKe6 z+L8*f%LjK0lI}rmB=%VVNji3N5pOfj%gxQr&K~wmH>53C2*yZIZ|a-J>V~(5qq0>R zD=E@{tvc#_70c0s{YvpO9lT3tBkYK-$lc8V!?ryvHWJmaI;QM!`~St?ukttOUYo{) zQdKAvD8M~QAz(fz+{iy=hlQLRz!JNm`}w|t=#{ByCWR4ojz7>uaBV}c#hj859xuoX zM~0Z6)H49LG5B|hc?6I!XCd^IREEBWvSJUU|sFhTi+wi>VGUoGPB-Es5Xn!Peuf1zX`}2~kn>!Y80^{dOREbmvwF zP`cTQS5tp+;lzc?nNKw1wXV@TjUE6@j;J@R4vJ_Pml1QWs92u-&16N-%$659FNeX^ ztc(GRRauKSb~q5}2~5FOgowZGzF+iPGnZq$*pvk_^Pdo2rKa^YT!8UY|9_Tyyz}mP zx`VN|A6jvY#4?ru#mKY~-zR}aY4s*v3PlVFNs5RC&sTDcfA;I5{_-M0P_r8M?_T^N zKnkAqnXl#;w4$OYgNVl68KE}$z|1rQZ-V}~F%~^u^p+*aVTvZ4qN3Ew_SNn7XrcgI zvfXm)WA|Mrb?o79j?BL2 z{-Ga_*Oz>|&|LCwP@VOby8sn&K6;>8Y5G|w{JDp#o&>qlc`9fq`n1j z>0)fVGrr%_`_M^+r{-{Nex3=QL+#sXovQ|9aTn^8e}yNar#Ee#_;=;N+K0~t*)1ip z=FP~YZl(*J^F(r(St;d!)V=zyVE=5kp0coL(uf-`(1b``tdf_`L`qTPF%f`TO?L;l ze1O{noIifxU&X|4t*oL{2z2kISw1%@eAILTXaC1`>91>!(WL^FHwI#yD2ox^e)V-xEnud3Pw&3Q z^HkB@EAx$TN(2Yi>$T6ku~K}_b2jiyw_R|}ZUvFVjYD<7< zM4hY3nK8*FpY~FY!h$iS3Si8#?b!y`-%idSgD~D?c1}o1Rv`;I0GSjaVELBv@hNT^ zlVzE@PTxB4LVGkYGH51)=}*%HkOydE=jpkgi?7-Kv! zR-=PBGU!)OyBui+w103@%OU96%Z)^7V;SH#8{DZPG9G(#<(yQOqsufr!UgwK9p2@l zsMIx@nMp};l%?);@`Z*fH5uj8-i$9uhU;XonsJNMciCRdxgumMUM*A-BqBBsQjt0b z8LE5PlKU-g$n|v`YYJM7ydh(Frjf@$JfBRsfS&nPX~34YPU*HOM4gx}TX6RN7b=Df z8D$@73$dL4{`(Jm+4N@373}D8)RiPiK4dOyuHc&xmZTRxZW_loV=CAaT2$L*;h>g- zdZ^GbBj;LeSBVqNrT-BfIim z(Qvt6s)C90Rq*bvLW-^xL&=&Z`q>ymzF=3w%@{~#!6{~VWO4W#5_KB+jnSop3VP&a zkvD66%yW~5rtMo2!$I3U+eXWl>i)-6-^m9TQlGLayL>nQSfGP7xqa1bV=4I441i4& z=ZdBP%PJGm7%K64XdhRF;sCv9{ecz)Lh-t)0S>q@K9=EId@DN^V*-IvT4 z*FipiP;!kbtEQH94rcs%Cb_pxp995Tt!^}aUQ-X5q0f;uweTS(~))d#k&{6mWt+0?ntkAR;P<=0d z=C0=~`7wEmQRsrBvdbL8CfCazi%t<|>z}VZwhi-PdP-iVzNam>A_j#L^%3G=9SH^W zI4<{_)v!nBYyYIJb9n~V0+TR5Kbel`SUM9`bWz<3Y1tc-P(WzeW!VY`YInsQT`P@$ z{M3Cn+EnxU2&Z#q`~oy5;WgFt{xR!Yw1{>KI;zb=FzVN?dKgfw>40^d`*nYJc{j}q z2wz4_jx8MVZs39wUk4QqE9&HLQ@RRbiey+a@m{@VsaMRkZqBT~coLWW0?&+>@6rkG zBYmOt7xM;6oi$fANzj$F>05UKV2r?{Lak9|0u#Cx3`RXixMtO)$@6-i_FfGztXtq& z91AI$Sv$nNNb?_+{RX2y+5CKvlr5BIAuK&!16q6wyASpv7WU!nKFNZjbWO zD03ewO;dI}We6k3MaL@dhi7q0n-h!o@n|}QZ$-QeIpWV;cRq@ZOSONLEi8X*$5Z0-2bbdjiG7PC0+^FRdV6*CMO5p#n4G z@yNQ^@I%bivgJ1J#nLKK_Fd$ z;^;KDOjM-`MO3iRE&T#gR#J48=9Y(cbyvE~>GO~A)dh98Q^d<74RYN6H&*!Mxzzv9 zvEGD&3yf|ZR5h<&9KZ89akKRUY5vT<5c3Y7XsoYK=~t!6tc&FryXoQ1sOh5F2Fxl0 z0Me$Sr0b?Z52wWJsqefFf__REj^P-0O*|kGCuU_cf3Su^F+6a{D%EWgysHJC zJ0%2Syx)y6LiY1mBtmIA@(7QVTFe~|3#Xk`S7Qzj0upZ50oiT0TdTIb|9`j)y)MRo z_emn3zEn*;8~0Oh)~&IR|4DmBn%=Okpjb3x#XUN3COOcL2@@J0{TUsVXOfk?ftZ z@J4*68_(^xe%t;i-BZ|Nd%z;wq+n6jDwS&mskHiB2;!f7KkJk`G0esVh-mFgW?Onq z6~le^0O{rRq5iiqH-6z+SfMN32A3xG5=1?(k!>l(>c7@4@}bcF=1Id1ERoGaWZNoa z>dMgjXnIrB7b#sJ&RGKRhrDU73!Tdc^(6Hl#OlOSie4vz2Yo!e=KpTK=5jgwXn^f{ zw6&4815M4A=f@|1*kJW3F&*TFQzB-FmA|MD&5QNu>&R_~y6gdX2|P&LsGIuD*}wGm zbr1-)(gsglS7Ik#yUvQ|8JNrCc}k$$+>GX;Kg}h3zoJ~ky{h^kTsA;^a0A@jmAr}F zFFS!?CVyuGGeQ`q+>yQvSfm?I_{SR$AwcK?Beu=OBvxC5hF?0HGxD zTcJMkT%T{DiQ*VCxnS?(=K&KTp@z8`YeAYPxR=LOMQIGqJA)J`o^}+ndR-h5kLTK# zui$Q^cwfOjh2H|mXUf0v* zs2_{J&`I`imi(MV_t0o)(7yeeBkGbqiag+=NUiRby4~=XLN51}Mhj9MNb-aoG@?~G-JYVcKkpNinH|@$A1g54 z9~rdxT7?;d#Yq|pt+|IWk6-I5uxL{y@)(ilXQS-Rb$6mymHsC%aXUO5GkbVjdGAL4 z?4oyvYL7Wqh!~x%sUjm!DO$>(c#t$ueme16CtT=yj5qCjDpK+3%$~KghcUR;<;ZZ> zU0Wr>1Y1knJ4pmxB2zG?TXbq!XI%amS50uQ&ud>j31Sx$N1(Git@1PFDN(dqGGtKt zVeQ?Vv;T!5F!epuI1c5pdwnz-yFEH>NnYl+hg&L85s;$QiWY=RdOdH38dIgE){6-z z8MZIf($^*|#gc*5seCn!Cbc=wseWZblVBBT7ik> zpRkvCnOp{2$8ciJC_;<>AuZ)(Q%ON zeZkO>szx850kR|x9+$0taZ9<-wyGG?YQQ7uf9QOBUqVv*@MW5iWa5EGhicvE%Iu*{ zBP%@VtfSN73^5bp@cWB;_GH(r#G#P`m1ZR|^P;bu1B`9aTEONx_HeJj96M`FzR`wB zyXWyLJI63mj^n0QlBD4N*RP@aSp*Y`e~e~(&An^}@ZGfa*1jVR^%~@@xYGiydv;Oe zRRwgKU4>lJ*z13Y%%`wC0>6`^cE}phZUY!P>zaQIr0|4(>>U0DGH}t=BX?T=EuH$8 z{{KYqO)B|Kur7n1%0nkOr4jLJR#8qycgq7aAC4|M20(JFb(&xVL}Nhb8NsJ_oxL(l z10NFq0p!Jmgxfg_U6=9dB!hYib0AzRA-naYc>crN~w7w0!to1DW-hSJ_El7eH)uG)Yh;a zwd?dwo`9c^{pj1;a@@ajU}R6uZ*Ko@Dz;FAFmC?$#Cc;{l?H(R@qh!FL{k130Fjpr zH_z=b-bU?X6TC2&Rf4iRB4rqd6J)Qw$JsF9_u=j;fB9HE3u1})gTqV7k&m){l)?!8 zm#fT|#V=mX1WUiVV{m;svxw=;q;B+J0=BgxtB8jSoHH1E z8k?~UB8oZ*Y;TC`IyLrAx|4snHYY;HObWS=6D~{p%>~HrycP&taboqBawuHk=1c3y z26M6F&$16!1?F?JfW*j{>y>w-g(bMTeWwOj69l(v2|mhwyIsTkL?STZuC@w?K&8}e zemZ34m|4EyS~QYr3~FUVD$eGvzbV4#)9Ub!3?&)<`E>KEx{u%-kPzD0b(L|F^ z)n>rc#^ALVT@7M3rtbvgUQMnuMZot_73)N)G8hd8AB*5?Kv>gSb3&;9@@pgPsb>oS zP|D3zhM}1P!okuEP4y@(ymvg-FXLXGjCRPR!|iaM{!v+VwavHx*9+jLTTEST-O_cL(rV>AtZMEkf;UQIw&*_SO;j= zupuIWVyNFZ3ES|M=%E>DPmp~1a!ubd;HeAtP*=Y^lzzVU+ux6W`(6823<_6+qo2UK zfmb7+6uwJpE+Jm9rtee_xzlIyH|h0EcjUVaCiaXwt^7HtoDiI~F0?H0_y-^4>M2er-xSG5zArP2&9Lin^=gx8M7 ztdSHxqpsdxb5|zse)bFmg>J4TE4qPuWQFi!S!9+EcybGJa3hB8xf-1|jor3g1{DSt zTN(cwqU2TL05I)S-{q!(T+=-{k9c%x7l9a#sf0in}!7R|5 z`0L;Q{BNnD>=pahytLIO+{mpBifUc!P8Ps_`2~wEP!Qk(^?(Q#<+RVgX0{SzLFMRQ z|7w1?YxXmbD54~;zvj`5;V5-%8;subVZFnaV4*^tWxbX_>U}Dd)H3N@3CCq{_*@X~ z86*lR@S0n2#WrGy4?m7z?Nkh|+fz8KJFhAGP=sRBFx@MNSb)q*!|s zMjDaD&(e;f-ltm3n$ESad`4F~gB7QDo?x=hB$}L$MyBv7{FgSAQ>0+R-MGK->UK)w zkfZ(!ar}AhonluNyn z0mp%Qnc@&I{<0`(Jw~u_k^COHZTF44e4;mwp6D0LuGTZS3Q7o!h)x`&F9z*cFZ#UX z!I^7;3wXA{T)dOg`^bn=^W$;o=*q;Ys%GG+8Tmg-}(~PJ-*du609Y* zBzl8kAlG#Y*Y+oy$K~BoQD9=&Iax$HQr`(|RTJXtD?Rrt*Lple$2U~$78un3Rh@Y| zJKuHZt9xLd0QA^a;VJuelWFHk zThc6(8Nw7rXVC*Wz>pm?gz7P$SQ(|vV}tJiu2QOa^r>JJ-dos28!zZ4 z)c+hjy)0S@G%j-e_->Tqh>Gic530i!R1voiJ{ z4m<%A(_5=PK=rqYNDc(A78O<6uJvd_3(ICvzuG2m7*kOo$ZFp3^S{1?NRx!fA-F43 z!qz^sD@|?>XvvPBn3PGBSX?1aC-c<9f zWgKVvA!`${LFJf->Ne50F*ixaA0uNRIRWM zw&=5VGJpkjt3f8j0j+(kV@^L?hjkfm_KPl7mU}p-I2>fRn#BbPX%&(x8=sp?MJ>vA z_|NMh{Q=r`ZE}TH-4;NTaA*?%vHZt=-`ls>z{fM#VJ`|MJ60k~vE*`28A4tox9xvT z51_WwTd+$y^^|I%Y|(F8kwo~Sz?BDgv{)m%aP#hwc9f6EYcN5F65DV&)7!grWG=8yQBZ0#-zMJlYg9|Fl8T|A#m;gJH zoSd-C`W8?^_W5V0oI?8#f)kK|Ud4VcNcmpwX$#@pw8w{vQ>GbjUcu0|< zGagxfA9*=w(oc-+tf@?h%O zvuD13s{Qx#o;+>d3Qtwc!|KO>qTM9CX8b4J3fkW6( zijTOM%bjK%WDpoK4D=*I=Z-A4Vq)$Vy$)SET=#iHKU~^1`@Y0tc$x%pD`fJS36Z33 z43CxL#zvd9sbV3|t<{YQCfG-%9+4J0<~)?e?tn*kP*W0@lba-Kk9z*%s1uAixTP>K zT*57xa&OUi-F9$raB+S++lNOIO{P{I4Ah>qHYh4)`%W}ee16;$tMX2cTR zxL9g@#UWJZ7?E$nwQ3)oqcI;-qX4LhdUm-wahe(_!o+4j?>E@rq@^|dtJtm~DxJi+ zARNL_OgBa>q+-P#Ekkz7{H(e0{RvW0z->>616x5C=K2gZZrB$ID`>o^4;qR|w2q3u zb%n1x*%~1``(kmcj$DzvW|SEA^$#AxH7-uE45CSs_}7UgkrdlYX|E`>VnVMj7?sz1 z;c7jO`?-k<>Cu$H-Ti0(lsmSxu&yq5v+unjZm3^+=EEVg{$9-E;BzvZX9#G?*)Acu zSpEhWOp3SW&5GNe5db229*Y620)TWYZ>tZLB)3b53gx880FLsuqvD-Q1j!k+e`?XQ z{ptZ$h*F)3C(#g3sAO)A7?1aJ_Fy+IW}mZ7SCV{p>^DG+Mt<5Pss_1913Wx*{T0WB zPDs5|(?a)jk*|Vb?_uZnC#qKU2C7Q^A{|})XoeCBz`KY_u;Z{G!h3tOri|Ly?h?Gi zvEPfpj-mXR3fpm3Bj)t=%0PoPc6+ZDD5ue(bBlhq!Y)lCfYr3zRb675`I~82y=>0( zzK!Ie%n{V<$Fw~^x{^(byTxM{e31^c%r*Mb)v+zm`$2ff;!`}Zw)TWSp{0Y!!cBn>0dMBv z*2n%SV9FlQkI9%TJFH!(`&^_oyCOGLtR-B53|ji=NAThd8uc@p)Zp#|ffV+3r?v|v z!vl=B4b3ai?0%}1QnOVHAOP>^b-kdxg$AXf+TsiQgpl`@JK7*ddFhCjbOqYc?J$CA zCjWtO@&FadFSF7WdFg@Lo4KMzfx4ptR6!vjrR-}T+TeoZrbgC#7XarIRP^~WE;HWh!8gl`*gyA%U_#Y2QqrR>Yk5*)Q#U-cCG@re%nAZx921^Mxodda#9)MR3l4*nBWR)=P6lW8yO3mC2pI2xR6I^=s?q|)b8 z7YC>l47_>zO|);se|3T@l!Letl}|?eN8{R@ zG5*t6b-m$1WL26uh_* zJp@>)cpEYeDaRfD>!4B0!x(uXB9K1uhefz$%3UhosdUfP!2pnXaLT9^>9YOm(i>6M ze@qg4&M_VWT193>ET&gC1u2(=$RB?8evL$2w0068h*&3K#3QJSlB9ON5dWU;X0uK= zJv>BD{07A#Nr7<0d=<)LB$YXH^`mf#TZbFHqzFS5&7vtOfFhFHRWZX|v#9}Fo89lf zDKH7_3l_UiYF*=I1jE9@YL26rMKGdv-$Q~k&5)#Jn&of%06FjU9#>kRT*z40ZKu{% zp6tgqDZ{gcHhd}L?8J(6!1agGDOIDy%USzcgjXpaAM<$9Wz42Jxryryvzv;02DgxG z%?8cIv8I562hZ|wyB?H|;&isktISEtyA#bm118!k)}v%g%GY$ALC0bSJr)upZ;1~i zC=L$JzI|)TSV$Rl@o+RNN+uCuy&y+!0 zA87WMu@R|l5krO~iZ2J%HbqRgj$N`)^hyQyCt>fQq{MIkX+Q>=mKOL3&mtcbx*rTD zI45crKIC@~Bu+9dwSpD@yX*{fK3-b-DoaxL=CrOu>aDmh%-l3&gz%hj7;f4j+XVc8 z>8GH!PPM(^4{OptmN;<`FL{}VFd8JK;@z!m2Q`3+*kdb`EZ-bBfz=F(RIqYce6dzVww7oS|FYwQt0yp^>(45z+};^ z)3QFz=r0!+R~EBpq2!1e$5v?cV{V{X=U;ms_vX`l!s)0kl*nbY%sI{5W~yJ=A#$kn zqkh@d@D^MM-j0KLqfyLn5|x+E!du}X;MxaWx%YMw)**L*|8|InFo+A;m>%V#9`YIh zCq)%Pq=*+9uY&zzBTX#;0b0XY$>WNe*sgs4z}?xn`Lqm4tGn5rs_|a!E6YFBNYe); zK*tm*HtJ(J~ z^%U|E^raMrSV|rAE}-%*BdQ6yD>g1}tBIM8LmS}4gQ?13abF`nh4z!5Q&!tu{Oi0} z`WlhB%_a=zUl9%Sj1bs<1BGjxd=#VuruX(2Mdnfh!f0#dMMG=>Tszq;3fo+VW)FS0)llmSZIdbdMO(*N9 zl%Kgsoo#lwqc!Z3s_lNZhL-uU^upr2(_$OwS95V2(%KCwdgteD^DfWg{}wh^GrCj* z$a-AccKym>sE7Byc@U|aQY~wGIGQitqtDS1ZlbB6zmp9*XjqX^R#erh_O-p2U9fLx z-X~nmo}5~S5|3CRfY^qHFBxy08Sy$0bHT59s%m@UW2V(2Spbq?EZ-Y+q}=r*Q~r z=-~4vEHATXT)nEB9baF(kpx;C-99<-SGE4q_Te{F;5hAscfqng$_3pSa$ zuKU376VjvkrOE&P5fp9<@}L^5<7dg+wyQh#~u5s2sr@NR3n zCL!c5EoPN3MIySflr6;`%6r<~@)M7#Rx_9xI_Dd&(-`awqPmZe1vo~>h!2iR$jj_L zE~%kJb?%*vqM(50WLMSkf$Z^*zZ02^WEaV}iG-5;r#!nw>vN>2`L;MXYSU5|v~`}J zl>|Vxfy9h|68A#AA>4bs!F`{o^zE6 zTm&b2ii+b=hSR-^xxLa;+sz!1VwQgL{$_g7e!aPim2{;Rj-S}^FX|)79USq2MUcB> z$u7@{)-00<6}h0*Rc|dUQa9;{dS9^rQmlMU2E$`8UeoH6+$)TKlPu#j#^j73MW(j8 zuztQ_xc;hnU%vUcgIrfvO#h_B$C{3o)+9-IG%d;XY1cw0vZwJ7yi8S-LnHI(C_x+M zz#+lb(zuDg`3bUvw-rwsJ_JZYfEX%1~<<*o0zJZ)+cRXu-whq9;>-*VKdY=)+C@3`0u6$V zDS}q79<)?Yxy@A;<5@$cEgr9b{KyA)tS49&CvOIox+FQ7Siy`#PHj7-@JSi60}TtE zU3Z?7T18RykA=;li{j3NBlax*M&+$5?0VL_l*~VhrbXR=-J6IvqeD6Sys{zxPqrkh zoX5g{q9ll+baFyevA1YggC)Sz&t!34cm+|7Y7||knVoir*YQ}T92LA|l}k;{kZ7>d zZfM7NdyMOv!Wag+CYLeI2mC`$>zr@$B*$GpDhnI9EES*rVk!9Qs&^%nqW{A+7d0)8 zFwxIa!l^%s9gN8*a}0%gF$Cj$1l_*949(g#xP`ZDpLM6LW#OR|2UYftHfZ%5(oUox zo#7UUIA;3qUyICetQPvTQgX$jv&NDEMml)9l7-B(%ExKp*EKny97EXCcG6L$v;y8l_#=E)*@x*hF9G zn0a42B<`6>JFAXvH-+&FVGdqi*Qy3j#8yb~$Yq2Mw)|;V%(Qp6k1XedChiy0?%Z?Z zbF2;57$1%fpI;R*=ZCtg_uBeUp6lf+xiRrtuXzL> z&F-no({Y5{7DqR$+I3GqAQw{KWv03H%)z-xEqLNNATG6Mq@@WEA2TRoQ{KBaq|_R4 z>S_*Oc*kRrm6`qA#`YiEY-d zfJ0PKj@EUu_qXh6v*^SsCXL#<92A0;+?!2nJ{ddwCUeZ4jP6bg(SS(Iu0-toc-Amo z>|j~D>h@T4YWG5jqlf8Mkhl=`5MuL3m$gd*G;9`4;Zj0}XEVaPbF7muZ?r_2Mk$N( z$&;~}l$qA1OUSHO=y!ZV&9x}pn|@@-fb8kV9qZ~@_geIk@L z`eSRYG3%%8llg=Ecd6XQoj!Kq1U)uRQgDX&`}bkjex0zO`8NGb+6Rv2#}oWi(f92f zUVf0qb)UICvMz6yYSH5OwqOP*oA32RdLlLyuI>y3XFf_OdxPdF?v9R_NF{Qa1nlyv51zejjW5ky{e&U*dE$^0}nU$wcC&Q05YYcS$c>69STBBY!V(o<4BRPDD zNr)_mv%`F#^YwHuN(qrBRJbaQt{A8)a(zS-1P_S-(mHgzT1?YgpbKO0mAS^k)E0Zk z8yD6yGv@QCzCq6F!yI$7NeH!vhRm+$r?Iib#isSJGAIAl<^9tMxI(oOxmCG@|86CO z{NW7~B5u>@8CktrSw^x~pnzzqX<_4jJ@s|}5I5l-8moJ`S+d-HKwrxiTw~&aqIFh< zaW(&2pNHvbb6>q_QV^~*LUg(Bon)0A0`Z)Mh;@-mXJ_XIMRF=V1+K;To~qyVTi#aK z4|yX-_(Jl^NYRFhIM^o@CQNes-N#IDvA9IE3L;fX-`k7xfa0QNT-bxr%6_p{AZp-?EmXD9sLUXh& zQb(G+goIWc7M*UdN|ObcW$4CaTiG;K^>ckOo=d|u{I+H_c2n-7ZKa*=O);b#V=CV@D@@wENCn_>kT zG|P?L2m;-#=c1>@UCN?p;FSwmQCK2fBnl_ z%HDSkgS(UfE#2|zfIh@>uxgo9gL0V)uR>~^jm`ep(9r5BjJj1va%-VI#J_wgvfxf- zfQIItO?ng#XyaK%dxwTXs9NGVahDq@7CQ6m|%P_{TN-p+ZePIIc0iF2~ zor&qURac(8??!AsrnySU)>J-VXr{wjx$b0q+vcx(H0U#FOv@0s@OrEy{|LIAXHQbw zEXDttELgQQZET?_0&gjm;-K1f8w#b!iw1-2o>BFzHR}-VZ{1P9^#iM@EnyVr%~m$w zrv0Yry}p!^i~f+LTe7#XZTo$bhj?%1!2t+DvFgO+Z3C!LCZ8e=c#+Q%Og&TFAgNsi z=v4&oOwHQRCs*`{*!3oYM^TdyPB*Ujln5ee8auHmr=p^wr1X-P29ULa4K-hfSAx+X z8VQhlUoJy1mNYLCRd`u{f2fc)MRtt z^w?;XuH<>$?p7%0VWtzqiux^l2<>XV(@r)-a}dy=p8hp z@=c1T%trsS_$gCJ4WW}uRjb=CdqCb_> zVMVO$eJHm#i6#w073|3!T@tP}cEtIQCKIY@ z$yc=mU5s~w-tae1Ml1#54dq)4ez(3+c4=*pJ0=?xsr%+!P2xQ~UzY9vsYSM~S$8%BTfY$D z=Kj}InUEmc48BKA?-j9ue6<2fK9|gz*#_RpdH>oLNO7XspA#=kv!4pzgA!rF5N{4N zqfvOR<{A{=EfEosX|?0aW&6O@TL$R5VhP*~KsmZ=Kbq?vDBm;6PN@9;f4u;1r?Ct2-g zJD&@_l$)o^j+qDi-bHXGX9`wpMm~^7B5ar z(5w};I89n9&3Qs)@ZpPx6!rnK=Qu#iy)SipWrcI_#~ATh{qZ6v7Z(Q)7bh>&AWK#%IPU4~HrZ)!T6yZURsvNvHV@;m%pFZCX{Nl!&N-AAs2t!S z9>mTY{b^Jxv&y+)*6VOEjbUQ)#(Aj4;lAY!pIOX3siV_v`Rpd}FKm-z$ewxYY_D8!^-CS{`Y>tPYAzGW`7!{ z7lq9wjYjSKaLIdgxzD0l82Wep(bdeeJk`si$*1RolYDGE{+;gg>QZ0nJu7m91&F2tLlhx2@Y`=1-C`r}WWuiF1>`tMjT>Z@O4H|j}46w2K% z=yxC5(;Ml2!20*wn6CE$?0yKV!iWDC02V>%zI!*?3@rUBJ46IJ5b>l1$l}7&rU(hg zfy04Rd+E}pI@i}sNJ8ZxWe@^rK`>6iG$V^5cO z3TRkKhfE8kRgv9=*y*v@E*i*n1Ij99#v;(Nu+A(L_iH$Iw~lQ+l#S6wrP$U_kr-3| zvKF?A1F2+-Szoz+^UIyOFb@~J0(;=IqEv+}0%zWeP9e*5#w zH#~9O_GiET@`jsV+jz?#x8C}1&)@dv=fD0xwqE`}w_o+2zrXSS{?ph0^y9lDkD=b5!3&TjE;|tPTf+Uy1zd> zw4qZth^y=&F@L_9kS@&BiQ2)K?|H>=uun>SlSZEcpvVqf3Rw)L^ta;A7^^wfs{ zbPr9j)>A&#VsYfJD0Z&qmyKWI z2z5!$PJ)SI5K`f$gEn0Tww$L!y^O3BZDI&Bje+fW1~xJ zLt_I2)q#O(N8ea=bm-*wkDYtY`)d{Z?1bL#;o*^qq1sq&cw&6)_@$HYo|srVHa0RgUbEd-&6;Ay zSq`=rHY67l=s*-mUI&m}2cQ)pQEGCPC>^o&Vrgr@vmmgs7DwUM$6~EdTecXikHvU8 zV0|3s)X3g%;8VD4{9T`ZbPq}+Hr<~k> z?G>m0`bXEku=dVBJbU-QY`o{ijVoW-a_cLb@7}WR?%)3E_U}A+<7F3r;bW(LaB^a7 zXt3H}sSejBCMTvOdwhI!e4-{TQ=PWgZpLj#tXnQ7(19qBybhqb4nQkHqTt8D_B6fo zfLlQTe+tB4)1^LGL!b$rD+8%|CEgY>E4Lm!9#Wt zDJe3ia@jfmI=!X>+#J9m1K5yAvgIR^x?^WaoU;azNv%7|8dF0?a{G; z+VIqK9YfX8o}Nl)*P_};&&lr}TmF^LfB&8@u7CW3*PgrZkJ~Q(-~Y7@kKXh0>ib_? z{f*5}FMnbEEw5}^_4;#n{(jp7+txqui=W(b-(8n{>Jz7&aQx^%Z%==vIx;jdI(2Vk zcywZj0i=Fa?k3A!Ek0HRIuJ3C*8$!?bO2gcHVe|NC7MX80vQJf;4cW2muCujpEK$& z=Y9HXJ7S|$fZJ0v6`uNQsi(?gJuRk;43Hz)_C|*!8wE$TxnZ3i!=+!`9&u;bjC;hX z@X10?G+4Mrl1=@ZONDddCLACKJBY&MbwGj49Csd^g?FOuQntl7TH8#E!D8KP#uVGU ztbV&aWP}-?2oS41OrQg(vr5%fjLx}%W>g;1K)-fuo8ih}wKDxidbLvN85yg5>WueZ zd(-Dv|MZ$|Yi{25%!*$;eBtdkesslEAN{*~KmUuLUAE=7H@>|7)|WQi@!Z;5wynGE zg^hPT`_#&R`q9NJuKVIumwxJ+%RlUZ?1%ddRk!&&05p{v=>CTcR@^_Mr z05UQTz>@*WNj3^-?@IH|q@D=04{IZZoU+}q5r=|+o@k_qiX?krU_ieXu=;i2BG3WN zjT^_&(NX6{lh-XfbDZhy-Ico1#)}sHazHB>jg#*1(F`TR$k?U}%dI@OG5AH5jat41Ug_VX9_Sn=LVW}%S(-Xz3sqYSEaA3QmOR!4-VD(-~YkM>z1GU^IzZb{JJZC zzxA&5kALIFE51B7IKFVfyk#dY{_K~B*8KR~?N46*`wcg}vhMm=3wyjyQ?a9ktS$EmL zzqI^6UcdDZFRt9S<;M@*clDW{`oOy;C&or5YqgQ-2UG^=vgVzMV;RVS9^qdQ5a>V@ zPF@F?Xa}Gbp^LIJE>Br_Zhc>nY);~7@oD``kORbO92l0ml07uE<89}37U0PMIg(AJ zPNp2FB@_1eEP3J+2X)VzuAjCk5kz_Iy>-c=2%SU{#Y>1RVpj3Oc&cXWu;ctS?V&83 z0{HZr@-l^zS_-4HOqdf>Rl*E0qqy0rWmu-)B^#HsVwn!89KgW=+{ETImz~3l4gL;L zc|kz9%ZuFsSGH}+Q#`^WBO?g$Mtz<<1v3F5mj>6`P;=%4=Ic@z2{o_wTP={GWeX z@&EqoegDrNzx6+#f9T&f-2dXH+n;@A`F-C$`=YO%eBLGRyY%u8eCvTTU)*%V@3&m{ zyWigM&HFC>)W<*6(_QWFA7488?pn3z*0sN-X-w>B*tu{si^9r|CvJ8;HT#yCaTZ8_ zLWrlz!|njT{n&aiI%g@nU7X62@sgj>FDV!wI#XxyCyUeoyGo+tc5k8v%#KKGd3FI? zEQMiq&>1*wUK=xhUEB$>8F~C8U;mG zR$?&@B4kBs(WuGGhV2D`0(NAIV8UHq><-wPEl#t`GW8~&`47pKj!%C;eYjSu_V-tM zdb+y0I{F7{l}dkKrSrY-8M@-)kN@-sS3md69WQUZbIY1LwyeGN+10oH(@$62d;29f zUG>?!Z$A6S-}~b0TW;F&)K!l>{FQIscJ|Fze&lNxocPuACNBQM$OWGs`P%vKzWb)r zfAY<9*8cJV4zwX8XFs#M6H++s~wDh-1s0k6J)0V286%@rr1q{n#_V@ zmYwfax9J?V3>p5ezhrl8H0_5oNnte+qX2^dGY;A~eC|{val`FNg7Td7+X;_uWWmui6liQvhqo0b7H`xG529G?i>T>jH%r{|Sl9 zi`@ZRv&Al)c_m3=a=gs{`nDN5|sIz`GW83=CBVzI4tDg6V*Dl}o%-x$;-?#2JUtj;!)!R2-`O2oNUwroJNB{9}?^=1<$~{oUQYLxW3E5I#fB zCrwyFS_V3oF(w)}Cc;gqWph((N0M+Sf~g&T2U1U!ZS58#RpQYljMh^)l59NP`mwZ- zi(iFFUZJ&PYh%p<8?z~_Xjr?AwRxE@2khjs&2`qcGb`+3cav-@+^B;El2nwG4)8s8 z_6CIwjBqNfvZxY%a-Kze)eTP2^a=~H_SFS92pKP3veV$O#MBmGml|`Rp1P(b=l->R zN1K?KSh{p+bhe^k0fy1lR=lb8q!q@yG+Mzd(+oDYNyZ(CcgvJm_x5&ocXxJmb?Cn(y%UQ%dQUiE_?DYKx9-VXU)y}o3+q;Fdh)7GPhGri z^{U@JdiUC2T=U$T3;%iBm$yB2(IekJ?~G6MPY%zTf7E|H=J2;3GwYxu4}Qn2L*8-p z5r-Z-_rPP0e%tI>e|6}=2h2X~fPwDAKmOsdOD_EAqYt0@+V3v=!`54V_4ilax9UsZ zy61vN{_&!9YcG6h-5pz>zGc(X%U3^n(|z|}aQa6ldwO~*J>y!3x&t7cMNL>j$cnbK zT}uq3CRBriUi0;YZhnbMfrg#YM#@<*bpbrg8WsoGGUCxyPN~*eRCY8hIcpULDz_vS zYdoD~OTko?-3|nj)a^vGx**a+JF1G$GPNmX=Sa)_V>FVm} z>FMh2?OxJ1I9TgB>&&J9?OW$d{py)SI|;%i&a|J~~I)<1d4=4Wo)_{yku(uafo(`sT>Hd)KKR>VZOyluMa-|M<+D>U{B7gQ+VWlwR^Tduex9JLFXGS2K z&_?a_oO-`eVqL50yUY6e`ztzAcXlp8uPc?FzP{ehO4qyJQ@Q5KQ=WX}Z(rGR{qyUu z-nxFpYcKxYKX1SFl})R*ul@S-t5F1VD6j)j-GwMM0fZ3pC0|? z4?g{;tzZ4)mMdOZyL{7c?_T@JeQSSp-R7rOY*};T^BY#JUvtOu>p!<_*>I(Ai0_@} zxhD0C#lVu&NV?|ELD=#9IC07SDrozy=zF8kGL2GBrj$4j@Y zz2doNuKtH_U3A`A@9XYZc+f!y&71u<^N;$Qc}E|7?9uNydd}NtAMw^Bj+_$fqYgj( z=pzn2X4XN+9P!t4k33-BQ3o71_kbny4>;zC`6HEMS6qJ5wkNOnzVhO_uRrt1)Y=7^UDuC_uG~0es#-B8-DPUAKvkaPoC0QSu!v%(BI#$ zKV3aII5<2!JU%|I_crVczuUBKH0&Y64LCEaab|d(8?%50DUc`}9EkWyTj&~zD5TfGO!QscR1x{5%n07i$rk%+q#<(y3@}-|GEd3p7ps?fAIbD zUfi@|?ISBL{=#Vs7tVg$JKxf^c**If5B%_l=dStf@~bX6qi5mbS%(~S1*rWbt{@khm<{fk3u}8oCm^p9hSbRv= z!b3j%?#1`5{J@qq=e@Ayf+rrm;O~F%mEZj4!ZnXy@aOF}{{ES(wmf?6WB+i=xo3ZB z@#6m8-d>ev?~qih)o6ZMqHwrujE5{$fcV@%M!Y=0XoOxe5cW!F_k9hR;53hTZbw=66`m=J4O)TB_}g0mJL zJJE52k>ZgLn<&9M{=gMtEg*iqYH57cQBVQBdCmvF@}*DSzUnh;)?Bu6!;0nCoYmjC@X&+be)O>i&Yye4+@lVg zbHu?%9QKaG-}&~#4tbmYJLI7Mde|Xvopsn-kDT?k*+;zXsM&8j=BNXYIqJZ9$G&~u zQEz$Q(qkW3_0i3%FZtC^K6mLw$Dc6Xed37=&O3YP;rq{g=4W5o_Qdi>f3)(mXPnmE z(=WZQR4V#2Py7)ay-;bTSy{A;(5Zu(cG2=7!@8rI>H@F#Hlr{S=|JjfE$F5d*0fWI zJ9^D8ok;ewWy|zk+d9o4@pxMGv>mT2)*36`K2;W8UDO43w>>@By>A`R4L2zoWC*1; z`a^VXrs_@yMhe~~+3C48RcdRo-LRN-BO@!!N~Bdu+yuCz;uP7YsEhRml>HlnPO@!b zwOWm_(75a6LAQ769%Sf9I%kY#5y`gmL`fPDZo+7N%P1dPt)@S+v+K0ASSteQPqzc> zHi?=pBj=Ruc8C)TQQ0iA&_Qwmc6MafCmZ!PzV@kye(}q@pLzU&jcZqK-gx=rzxwjmF8x5qaYw%W z!2hyf@sYC*J&6Aff9E@99eU90S%(}w`>=V(9C^%~!{;1v@R5ffbmZX&PW?CQZAZ>} z+uXVDoO{$;-+#i~Z{7W=O;2C@@Hfx@&`HCG{2zxMaKKxtJqxbB_|!)p{>lr_-tn^^ zUh|35r#?`FWJ|SmhorBsPv82WTid+l;9kjCcv_QoIk7y_q1M1M;0`eC4p<(Gottes zH!TdMqet?wO{<%1sHIDnO0v0%WMg3?YcycSZnqv~s9;yBj0!}oBs=N$XY;1~ZfyD0 znUCzDDygTl*vZ{>FWaf4PMv5OH%zz-tPT{G zz|`OTnEGqqb^d85pl-|!)1w%shj)ar5No%Mu4?_Ub~W_4IcCo9Zt|ERH*-arb``St z6i8Keli2kNw&xvWcUm&?C7UAkB!I2K*2bo?O60}|D$TDx8Z$63^-M@#UvFRE)I--j z)BhyR!uF?=?18?)kDNO3y$3FOb>pquR$sSe&GMI@`@2o+A9#N4L$7YR>y_u0Z+_bjymGdcfMoR;Rnw?^3bE^96o3EVMon5{FtMUn0M@)jwOp0E|@!i z-q8!@PyIJ{?yRGZI&{vQcg~wPue;-jPk*fIAHI9m_Ki0^`m?LAzVz(VPWjNXW$!)r zoR8mq+qtWMbIohpzVYn`FFxhuiNS#}G+NrNYI}Qo_2;nlWfX2jF`g_Ez1Z8Pusv)} zn16N|6vQTaHyDLmCki&RIb~yAv73k@M0<);Fw4>|V67i@nT}JKcDGd$_5uaKMiiV* zKCA+u8yxc7E~dW%Z1xO)+Y5_r8M{fg)l+U1pxU}YVe?rcVKE@P9Ih?1#SF3S)$s7J z-nvvS`J}n5g%4BM&r?hvx~rJ>r=OGe)5KmPb~lW53fD% z><=wEZo%w1$Id(UsD%sWE?zW$$>Ifz7tKFz;js(mA2Wa6(Z?;EzhM5ci;i2++tX3$ z?da@SxM*XURt{vhlC4D+jkUEisampjR#;fp-(ot8(anu( zDi_X-Qe>w9w`a(!K#ncZR@6K49BOdOy_Zb^B(kMqgwS49@0b+rI{oTXtqu$f^!4@i z_V#x35Xkf+ech!byVBQH?eD(i{7*mq=$$WbzHP%(S3dpNRjVIa@%+;dZd-Hjw$-b) zue*KY6Sv*F>iiGAZ*s}P z8%=w^f;!#NM@4FWDHsN3-}Ok#!y4`BRpDe5t<=MY$bnq=+ttgEQXA_Nf2A%W*)F@9 zsbph!zzXJWr)(&AXOm;HD3D!5&;f34ScxY+M(*awLZ9K61Fvb+Tzcd>U@?WyE? zAyF313e0ZWI5=olSPe`P{#v-anA>^9NEE>3B@63AV+9-O@YJQq&YGh<72^omz;^pt zymb1XwzoZN=SsE;vsALE{_Lxal1^K?_ooL*b*z?H>vN2H)S6>yPw>y3vO6msJv}|A zpLXgu@4M=E>u%k$;ihMPbK{yvZhQ9eRqG$W<>ifc|F1uO`#=Bk{g*b~bMLAzeCVX9 zcQ<=_x)v>3xM>L2Lo>0Q!W>6rdD*Cky&^M{7J-*eLFmp*^OcOUw~ z3maDa>()D7fA;QI*FEsk@9x~P@wyi_-1_>~`=4Kb_jBtWdhp)MPC0qJe{i6qw`!lu z<|c{mig0Oga8S=Gu&$VW#xq(!OoXOV)2jFJxMYE2rfGdF#=!wA*;?~*u**O-BM#OL zHn;3q-fR==z!OT=sFff6q$;;T?5?qU7EB7si|s{SA6sz7*L%U^fDyW#-{j{`wMb-S zhr$6gPId~F-QF?!H%F3gDmX2F{;tJ3$bWyfE6`Pq*>a^sebH?MvC<|lrB z$K$`e>iZ9#{orjM{BQT2`oz!AczxSV+t%Oyoo{^QV;}qINhiH$XlPJLbqk?j zr{C(XALeuqOSXPXV{>UGQw)G}H_M)dE#Qt&7~OhigNWH}3Jsb<>`x>f)#9mb$G}cx z{BbBK*^&{3w@k9Rm0^JjNVLKbmzLax4WZb z@uEcwIbS=lsB3X$aGH-*@i4X4^9lZC}4?^{*~?;NGu|4foBSJ->fo`28Okx#!ML zzx=yvURry>Pkwmgowt7eqA#6r+J{C?ShjS0_{5RgdxnRO9~i6j*D9l9)l*Iy|LiB; zbNywf{rKDGZ(e=YlvrHL) zbY-e62qPdj7Q8kHyG&8^kbB>hM+Y5X4!jCfNtj(C1oEjTW{3sHV$x!DONy1ZGwGOpyp*e2G)x=h zoI&sexE;unwXqi4F`tgeoT z($TTlDK*Wm?*87&U`Jm*@PzT&C13j3KRtZo)^)dUT66sacm3_sk;`75tGZS(5u zUtM?YKR@@q=byQK^&?;V>G!{K|LtG8>FP7D`09r)z4*PCTz>jxSAO!w8$N&k-CzCL z4{vz-*DE(aedD%guYKU&bI~T$HbLvt(+Na0}n_2>`6wqpR=!mtCkB?i4w=V$N z@)BqyoAOFXHn%KzFHsffrz~0O$o1_#!-QOLF^r=O}n)QHc>&beFb$54XN5|sDi;wH*SgbGML!%w2 z_ATx08tCipI`R0ibI$t6<$wG6uU_=o3(x)3sV9GYeB}K-9mn@{PQS%B@c)zdCeBqH z`JV60yqJidH}B59z1{9MW|PiR>#6PR`;m|kAa;zgaT~k=#$X$~gBP%kjoECBG2X!# zYy&nnV0MtuzKb1i?e2Ty&6}8rd4I%jq7 zWmZ`Atk}VjVj5A~bWBwmm$jZ+I%D6?XL`=O@x{lFuXuFUtoqXIspB7iWbujp;q z*nj%9z9XypPd;<0^_d_0+!r~1*SG%r^RN8${fnnhKHqry<>pgsJDOg<)VJ-&3)^~H zR~^~^z_W+ zqEsMexhj)LBxtyU1%|@|`+_gP>2$^{A?nVe>6wO+>ucG3Mxa#Gg2f6& zn0E;E!fRoQ0kuVJv0Q9Ake`*#2)H-HY1tS>+0YT$calk=4$C{07{M2&+QPNAXvDr~ z{0dfzdUPg}%4A#%4S&L~IPYum4uhwXbID{ zLgBHY;Mk}gGt8(I*5t5e>5-@&uF9xSJv#fq=dblOz0`H;_2c{B_^r%#ukp#AhNoMOu538;Oh@DMm(RcY!-d!Wa%J=PXW!^+UfbWc?sD(u zuBO$8_AQ=1Yl5z;p|QcJ9$a$YxFdU?Jlpi**)uPEuMWwo*1r@zyZRPT^w;Ba{c&l92@>pbZT73EZIjVB?f*He241aE3Xu z-=Rbzyu>&}Hu@Cv8crDI>ua}2pZYR0WzCc$TdZV;kpguxT0R-U7l1sBhFpMFvB=Oh z1!}ow+Z#f*cn#8}ZtE+p$ZK2$XbM^jn;;jx4*Oaf%#R%j5J}qwQ#}26JI=Zw&}&oT^qYkukAdw_Cn{@OWoT#&aB(F zd*g;R55BhguC425AN%s5AA2^oe)aN>S00&j+mx8Cj~;c4Dl0K3icL{Gx5b+xwoZ*3 z)W+LEu?-p8s;{B))`$T#TEx7;t9<}fG|BlFJj_fH=E_vP;VDWLD zt@>t>jqJoe%W9AAl?A7eNg6C0Jr=TujPf)C{K~ctd6>Q^9^-gd zT}8G}xyDu@wrv`QuBtN4*5Pmvq%H?^`58&BtQ}`;-E{Az&UKgCpX)sJXixKVJuNT& z<@@z}K7C~F+(Kn&E_&@%K|NI~S!!IORf9utmhd+P3 zuj%!^rp=wFU+-()+TZead&3)l?%RI0al?1Lo4!A{=1SkHj+3j`J$>)&!gvi^zj}M2 zsH%#+)v(HONM>up99((>uM*Cfp|w+gVk_kh^09_r|BaB1e9?&z7F$Spm~#3$vZ!+U z;;@IJvw$;<;|us|22C`R$q*O506QQncF0aD%77fjenB{h(T1#W(isK=aU4Po5T{qQ zY@R9)l=GUa6RB$>PWiPw!#zMm<299TaPvlx%_jxw7oZ+11vMhd%)2Gl3&)AFfSVGl z6%z&A43j;9Pe8mYzFQ@J74Ic4JMI{l`0=xp!W@ zsfR36oie5B!>tRCe7UNt>CNuu&8?@_x1U??_IZ|xqifvq}qvbUhVK6~d|#3XVzGk%*;) zmCCSE8Lh#RQlk}c?}0%?LPUz`L@lSjW2gJu5NEy zcl6-8Pd<8n`-dyO*t@#%#2f9+Tf5q}b~J5lYgpUUw7#!pV{h|@bB)g&`Sgk1Z?ArG z>4K_KRMABXu}-XUmHJi9}+(1iXijdpnn%+ z<3SKpk$?jmoMPwYCG6~C!{e_*2G}*&!NFo!li|z2M;4lx!BEI>ePk0v)b`L9 zD2%UM%!@@JMS&D7vWEwAI-Mp+uOgenFQkOM7@Gvrc8o%Dvpwv4$5w(A;9G(PGE@P) zfdaS8b{xyL&1lqyitRH{uuDTkv9eHjT$@P5z#u$pdtcpsnR!20ai$rGMr{lj$T}X6 zrqfB7)x=8(U)C~zg>{JyMGW94ymD9E9MT6bkdD!aY>Yr~=|>#Ej`1msZ>S(TeSx3N z7wPkpm$OYHN1pcud>g8X>pwt%yg%vu2i7tho2}HcDu=^CRh6;W-CMpmG$S=V95H09 zKDQmcdR+eQd3P*-Z0Vl2o;do+^WDeReb@2&pZhoe+Bi3Iq=(jk4OiFZWc+H^XNWe}q0m=RyHu13T?y)Co*?{$M$R4gX z;pu^`?!f|38`VJxc{ye{5eE_|-uq|=dN$x5Xq(;jKtrlu*OP#_cvsH%*e|71BVV(yx7 zL^dtWvUP7IdPviyXw1y!l2xhjv^wj7d4;DRo4od=JGQ>D;NuUL@7eY2t{p4h-TLUd zSMFQ+>Rnw(mh&}K=nrkHSzA!$1(gu(6 zm^dT8(MF^;+b2Q8o{whFE{~Y}#BJqO!vz@M7ht>fu~i(}#h;-0@eHzKTf)>O`Yg3| z#9>bnF`dih(9RKnQy{B_ik(m9@~JWAt^e-ehfNZ$vV@%-17~+^cdNRS!0Yn@$h-o&3!SUSnyoM4@Rhnl+gED?a;n}=k z;_z}DST-s6HY7bF4>S@;OJu_#1mJ+1N<1D-xt?tUS~;r>rQl6sI>;Jd%RiBhucCQV zMdYy+4%yVilfG6cb{;XoA;Y9Cnk8y9q#!@aG&*Z!V4HC^2 zNM)lXTPVZz0}udvcC%|R5tNr5jbLHT2qvLU{+}lisQjkG!srnwRF) zYG-8_zPZN$NyTy^tEA4*A4Go0TC&zNnuS>P0Nho6}`HyLcgX3M#P*L_BJw6AVwsj znPvnprIR8NDG~{3TBR(H4hBb6hQ@~EfUJjtN;oXzPnK0xRSm=N42kY8?RW_T($u^+ zyZcDZuc8cpOIVg=UDsjB6xBNPT(%0nl~in6xL>|@jtE0yT0A*qcR+&tiFxrtsA7~8 zQi)#?lUgbp9{Dq5WIW}=h=EKo5e3>3*=XKb@1RJ&0A)sRWd)+yi>;k~ALYe`tWwA+ zrY1%ZRXw7^d!wnlBvD*$BIY=NY@!Mh5car{_!ZKl9%&92*-iXWP|n7RHfTT=b`n^$ z!Ew?&9*>eZ$WD;wsiaH(|48eB{CgO*wIfk3p1^ zXHajEh$cc4ybgzhe=lT*!lT2|7+G-*5uvcVS~Bd;?75Z@!_fH}U(8{8^c)(D@Lf?n z?-Wf_aCs!6$x2XBB-MRGV?FrdCl*P; zFNK&E14B!5^Jih^#tS5|t6D0R%H?vn`$MXJgb{9;?`hI^quBs_0bh3zzp_d25|KNM z2{FWe!T8udiKEVtr9fnk0num_dtsmQi% z(cB?>-g}Z1^6^?!w6E2m-Mu)j|EHTlHB#yQ1$8s58Iq!hBsBm(XsGSvwKsSSjYG{l z;DZ6L4At{JjG0Qz)MAF==!T{0hOFx0uo|iih69okR&_-;6fGiahNKyiZpxuh2nsKj zDMq}vr{jGEBB>c3S{mJbK^iE`2)Kk_eF0?TEvj_i{|h4t24iZbZ0!V`*f`Nuc^}Ig zBqNIf#`gu-ZhcJ`=f%i4<7-#Q0<8;?DKkqUc2fSD&1Os90iSEkD!~JU@nIPUwZ*cC zVdf$Vj5#Ov1?Yu{DJ~%t)nDq4)N!E{lKZSE^jzBO5e@j|&ZZc>u4>t0P8f2@Yag=t zf+$gFU)h)f@)ivvDQ}T9b!r64PO>c51ZX({iv{EO(8#7gI4ml>oc9I+-VF^RTju8cvaD&EYhkh6x3*)ci~CjurBate5k>W!xlKEwTM^mR1Ey^lRs?^p-=3kV zy6Z9s&SEDJ%kyMZRaKI1dioK_CbfSS@dUc&y$qB4wQ|Izib^dC{htv;KKfdt$TDBJ zyhq>+k;kOijfaddWWQsxACi*nfb7fhcs!raS9?b$lL2`|0Vpj}#$ZOl!~hd#e+288 z7n4GOgoUn62L!~Yf{SS6CsRY#=vF+5lra$`s*(f9_Dw&c#;Gm=*(fJ&t*@)|kpcP9 z&yll{+|vVQ>y$@r=-NXfo3~snj90}2rf|X7!hb8P24JVJM0c3WX{wD`5kHS`Bo9o_{YVKShtqniG;EK}ioO zx}@ohp1TDNRpDdzQE7}$e@;ejGLs(Luj(Sq%qy#{6tkv8SmifN`&sY0PpEEZF#6yQU8 zvWfZzEp{SArL)ZW0qs0U7h8SL~|`m(zpG;kdiS;1r^ZV}YvfSKl8kQ@%ULydafN z`x9>lWMi{KeB2mXa#=>+<{{(bDnNcu~4Ba0ygIhj%PUvZlk*IvEqsa{Jj?Kl83=|3lSVAE{CX>OC zmM>3k|(NTmzOWHBC(+qSLidN>>oct=TBFK~x#4aX+8v^i?&%x#K zSqcgUO%#?2^h%_|&OWH^#eLJBcrGD-VH8CQB94hBoFt2pEKZ7&v#_aDN*wBNp%@c2 zc@^0-UNa9EMrc-Nwfd;Xui~10)Cd-dIph#gL24$eYz`Z!g zp~m3#h)<9gu8r46HsXWe>8gZZzs7W6@O9NkO|*6eS!E zheDxnI4ljmNLLx^P;dJ9{}-}FX#Oo>5x6%MMyA@}fot_a^&G!OA`vGVccSrVED?(* zy4T8=t5nuw61uRz2GmCB(h-A)8MLNCAe3 zd_GV4#XH0%!duJ4heI|L=bX1!pZDU6fjzP@WJ1Lj6>agn2yT=sJ9w}Z*<3P{9oVkK ztHyLR8n-M*y7rJg$2XX>m7$KCCbqZqMo_Lv@P8jI8%+G$KW_@t*a`~o7>jr=gzDfM z*@#6`y2?C zM-$_eXT-$CXzUd1jQCaTbodFE<5y-4lwpV>8Q8&j24!IiqHN$B;XnqGu+VG4SsGpd z`alK0#77y?Xu^+onI8nzw;m;zykCW184F*2D9 zSF-SOF#=cIvaL{t>mxgxb(e|5{~gaRBCLNl?3r285D(Qw9S1uNq*AVLe=?ag3`3Hn zpm&5kelhW1GmlGI{4_|^A`7R&hM^auXfuzdjv>C2kHrC{QP zl!3XE*CL<+Vj59d7BP+}06g$SHhRyR?g#Z<0uX0#xrk=uLZp!XpVNQ5F2^3k-*BoX_QQ;?fo51vvUX^Z7h%6da-;?QqDZp#x7U z^phD5)6mDorT?gHj2tMGIJ9K4`FJ9Qhig@f1cKo}D5z*^Sg?dp^@Fah{(TM~srmJP zFJuolB=GgVn&&aXDz_~If2N@u5zVp9R5G5=xtornN1%^T14G{-9mKxlgQkz^B*S3) z95{im1OhS@BmXS2Nj(vB%mq!9y#p!ZB+9~{#HU^gPdanlLJwtyFn!bszKT}?lEZ1) z6ke=nPE;Zn3c~=oPxi7JjMlbtw_Xc4Z5XQadav0HG%z+C9<|jvBwgV&u z69nXk)dH!Z;EaqMIR+rU*idjr)LA&F!11|QES5^8LZN^);^K54s~W=wM-j^4i7~Xt zNGg?pIa~A?;cy5pV^BoJia&AsQGDN%*so%-*jP0&N{VXn;>1~hoV#Gj2Dg%{uqht>*d6U?pTwiQq3F>p>+FQVls` zYgUZN^J#xHzorKdGyp(=-G?agX`^f{?EC0eyin{ij7((X40|`OV#g8tEae{*)BO(< z2jh!B(HM;m&XmjbIY`d)L>USqT8TxQ1`|Xy7JmJ)GntGiB7Q}3P^CGDaR6aeLTD^DVMrVj z*(fcaI1q=8fGv#PLcGT!rpucYFGTx5g`io84`QsAoOfUsCfG*sDay>-kC|Ki#P)|Q zhSRd)A0q0`*=#zW&l1h3Oy58Vb4o6k$>+0$LatcMvp%7fM59rxjtM)}vEuZ5mahD0 z?~zko7e3f?VD6%a<#?7J!Rp{q&Jppw@QMOZTkUnJNDs)@1P5QJ* zK!7Tp*jdo=*)K>Ru~mz|0v+NR@{U4^$`IN=QlqMr9z4*^eXbzzZibNP&S>7)gjU1| zf2G(yc0(k}!}t_cEC^2`8cNEO%!2U5u3k(NLZXaAAX{9_Elvp{D%?|mZ)Ay2CMssn zpKuaoz-^$3oN`0&g90x4jSxvb+qbBdi#j8*jtlXUs%X>(WW{=C8};2+8kEr{L_>Kz z9`_VaTR}kJ!Wj4t&@<>-~dcV3}>eOmk5SD@gHcCj9^$v0G z2vjfHP&VrVw@}FC^KLFo-=p?`O&sZPY)d7JnRLM=bv~8L#j=@1A(Jg;3b|Y?p0MJ{ zL^4;>6UC8ga+F?Fv(x6>y=48HADn9H=;}M$-rjz;r@Qg!v6ok@R0_ok)6yeOXmrSy zBgtrNRORT9bJO#X+VBVHu6PH+nzz8xcLoUz2hHJ6Q=PUHIry#mt(~T*QbL^QCdcQal>VWOA-AU@QjL1#Sw+*SCvG56MW&0ChXkkX=vg zecV)KNn;s-j$(Or}sMh*k%5Nl}$V8M(A4lgWUqgf&%3_IG5B%7kW#WRuC{ zfR;@%mT~i%9q&+7LV3sxm^4RA++?irBnT{vyR61HLCdXA5s*0sTu9(gj;^~YTO9dm& zh+w4B$V|Fp!4qrV`tr-eXPP@&+B%wATROTr&$`F?_Lj~yTi#M*iJ+_{;+cr%?rCRO zk&qe&s&4#K8~#8digzGPWHWtUO_KTojNl9Sq7CV1xYe3!;Z%s*O?@h%I0(By#r=XQOhH*@e`PUhDyzhsv_A$l!ISn zAHJe7FO9*q-q4cF<1rT@z(a;-!!&$ zwY6U8?`dsmY;HT#bFO#KfrD>v|MYlEUr+D(m)5QuS3f0aL=@YO*j6AAaNNzOZ|)!y z%L7PA@eYK6Y-S){LiYIrVjMB-i^i{F9A6mPFj~3zk)2A%?5Ghj3efNmQ8IJ^du8`3waraqv5Jp6q7X#wnxRtg{fHT;#fOcM39%v__ zvW)3In34+x_oW!(>?N!&-qr{1gevVGnM?}iW6_8qhS}#)1au5O1RxjjCxAYiO%vAn ze0DfwyXj<->1-;S&*Tc(R6ZR~r|e|hjK>33)!0ZOlCGO`?~?Uzz5n%zQ%zl6Ej>N0 zjVJrNT3XH=Z9H@Ac;m^3o?MZceEaiTcAf3)zjX1t^;_SHKFske zIqM5BLU{l&Jz@{oTeLxAuIkxvafyE2qdeK`Uq$hJ7m}^m;{gvf70VQokbE;zKx|+_!t*CA%Tz4<}?@}Qk8AW{yh(s?IpSID#iCqMUY#LW_ z2@y{Plkpi~f{+J>X>?K|6)eMDz=av_z_o}5QBf9%f$oEuC$VUR9#8U_01p;eUh=Yk=feS#LJH8basRO0B8FDp0~p9SM6)TNX6fC5K>~R7 zUh_8K_CwX1V;&T3=7q5e^!Kza_pOyw)zj%@E|)15^CG6jFqAcKtQk;~QI@oKh{y)G zA!iw{hh2bPsxGFpDJKz+rPAp_DN(4>;>oe9K3dDw&b)8MD{p?X@9@#a=BAF0j^57R z{;rD`&RxEAuD7?fq4DV6ufLcv|GrUHVew1b+Dp$Pn-oA4ETDz(ci0H{g)>dt8 zn1d+v1%`?4o<__ekJ1rYOkZHg$n=@xkicj#J!6HT_>R+(cT|-f(92*ZcCAK( zJ8EWL461Cy@+k+V4k=iWl-r9)J9kuMU0k)uB}z-k3OZ&S+Vk zd;h|&3zwHZ^-M5Qkj$KBrYb6f6%}I)ON*tWnNp5OC1kyZHeg~V1b_v07JMacFg{VM zW3*H%C3>Wgq_7+gNo`C5AqC{_n?+>Sq%+YB%^Eq9m`DW0gn3#-HcHJRlVijn_i3W0 zPs0%<;V=f9HHqx2AD$NjjPvuzh6x*v9MF8hLDoA8!+Xa1WvOU6@zESYa5&|@C4-G4 zMi7gb7JVLQum%?S1R$!|)OKmZ9c21IYa=uPaq-@ut~u-@KotX6p@1$oZ${1ti2EL1T+= z9unGm);o|I!r6SLR5h+xT^CK3D%IF%*$GFp(bD)Ok3YZl!_OMq`_Etbq5s0=?%tm6 z?#{06w*5!W95`~KqpP#Kx1+he?YXrZjMCIe_dI$0@R9EB?v9@BhW7SN?`+H0){PCx zs%DXKzJNN+p$&iF3Lmn?=*$9k27VO-Vtg?y#u39lSVJ`isbPi&H$iY3ruh|%6>#1( zO@f;i66_a<=VkN}$8liw7K!|`;gF)MhOI=bkQ#B4nK|?C+3?oeUmZWOeeeF;?!NDq zN@-+Jax(e(4=mcV|LY~omycAOkP%nSXiaThb}qDP|9h`T6qV2KSoEPz5DvA^RC zRWWi0{hfRed5yV2XiH2V9Ka`FC+20_?$-8b=Tx`xpiEsD9hN{Bk&W2}aY&%e0S^;M znOLLi3ph^tAumYIj8HVN6{UuRC_A)lME2DoQOQb!%t#6+eKVqB%mKqlIkKVNidB!> zL+LpVi(?=PDQ18$L>J|Nl%lsEm+Eophd{0Yq5AoQl?4T9#AZ!dyP<(ajl) zt%+tL6$J#WsU1UQz(Q?tpFGG`EatsE?=o1i3CVLgcN;yi9dJBggiI!dC!2ISc_X&$ z%(Vw*QFuqV(;jquJPp8g1U4MlSVeH>yd$1SWeekSrFt`78;lg3!qht!KE7i8*2dQ)AYsOefK}P;r4}3uGzG8&zJkVdb$svYMy=Xqe^D-d)wc?{OzUo z_V(`1o=X?Md+F8J62)pglNIqNhKC`xyAR)R$MuoT#6dTH^#z7Y+!u{s5uaudAehsM zFmdR@W=y0xx6H;=Bv=o99D6xnSMI^rj}16Vb7P;MWwbwn9n(xlj#$N-y60bc_0Y-F zJHPni(G@GlDu$gZq)Ou|C3SRVAeM;Vzu~$djM( z7(wb{)e{q<9!iZ8H`@njOpI^{qOr_-P;y_ChxhE^%{A2VMeUpObuqfswsfEEc?F zJD@gHa(6$~QjKQBZyg;8sQLO?4?Vwb$KDg&O&9<5Y;Q|b!_hDIe)8$g?S~J1-E_KP z-<~hlzqYY<{tJK5YvNT?=HI_?=dMrBUify^+O4tTjHlN;+tS&3uBWfFv9+(gx23In z}9lzczvT-4RD^mFCI}iqWjg(m~d}Y4WyYUJIDwRYz$c|6w z;4I6H1Z2&!W9fSqEdFHQ{==uwytLu<+G#T+JE}VI3PqQ6Ga$*)cuY~GsAFhqI5%mM zmW<1`@yTbO?)h@R6VJ$cTrsm4LVzJCSa<>u87e+T)6jvA4@B}UDk3+iZl}Ei?`cGB zkWGXa1pwo~R#+)9sfbT>TlQA;XkZ-=)391#XJCkp9qahG!*U^OsK&Uq9NCbQbDN^W z43SNZUbMR4R}O?&B3@o%l>9gl9w{`b-^k3@l=-Yqjt10)))hEuFvS8JuJ04&B z@S~@Wethc0>5o4CeEhUON~uX|@wQ3xpIG|hHoY)&=InW=PB))Ff3dmYbZ2XmYwzyw z+4|nwxm?cmJW~|Qa(zfNO-m+|;qXm6|0(VZ7~MrQiXutgtH=~Z(%d)Ux-aX6B|-5H z&3m~FSt*iKQQY`L9-6mekUBDK&6=h`7Y3k3yNBYf$j2+YOw-gnQ@gI~rW%e~nxTbN zC1g3K;n(GHPf0axoqbbLTMk1!FM`T$FNP)4ICg+kd!;BfG?Y{5E z^xjeyQ8nGrbUS8e!XYgbR4hAc$75k#4n#s)JW?2!+w$(#uKsg7KKtsnyB28Ce5GcM zRo#4Hd+}cC=57U(OeUvIoA%k>clUj{_hGSm5u-fnn#A<_^Iy7(iD;?$EK|w!ndbGC+&RSIEEw!7f%5rkYVq2#KE{A!-$Gs)UI@ z8jX_C)P@Hu*|S&;?&LLqY$S~VkTvBA;ZE++uY=}e+MNkaFpf|rYY;&+yokuAYdy<` z(E_P47swEcIT$u*K_<(9Y;v3gX9_q2t^tdnGmXD=0^vAB_YWWv5pa@`!A+WLsO;ks z7*F7-4R>h{q#5Dx2<}?XARbCbwH+r>^PH}v(ZiQTJ|E9!T-#qhSIXx~>2%f|W-{@* zaiw%BmP|RtnnIzbI+Dl+BI$rxl#+Eb?q2f7J3AX&yT3Yg)XA1_q1u#6h%oS5|(9!!(ox3>J1+ro!!@^d#h(8 zSq=l@nx;Wfh4Y;1xsHHSv}hwoQgujV`%Y4^C9KJ7{sfw<-u96Se@7?cft{ItpUKD4OgT+gRpeeuv^PsXz2#su_`YN@6Z)^!Xg znx;W>R}{sz?P9U`?DLOpeskSB@4waB-Ffc2A2z=8(UUK3xbKmbbLPy6Mx&LLm8zP~)>BwP44w5{Vc(5n3$R&6rR&p^pG+BI6Jyxd>t!U6B#BZ!rR~PSvz6NNLl|Z>@#TMC$#gMU>0~LTSA0)fTdZr1o`-}`IICOaqOFW6T3+0*< zjFc^#bywrCIikhj#(>u%vQa>c0mzQeF21Qn3<;1ko^)b~Xfo}-UE3WF)3J0an$Jfw zg@}{V6Pa|XSf@EPqe2-yIi-H~(%0U6_u%oy?|%B%uD-LcZF*zweG8s?@s)#(ZH;Z` zk2f_heDuMIGiInx-pEXPf6q53diyV*?>~9s*mpmCf8olvjV-OaKKpd;+&i+F#Au_i z?1c?I7k|3+-H#0o4Xv%s-QAr%eceZo9-TdVc4cKHRzgdX`?hkZoHvYXM3i;iMRp{j z>F&$D6nus13bO+lO{yZ`!|{+`sa7L1S6?EPnzrLOiX=;+a3b!$U<{YT6absJ<2aR4K+@%C+$ogu zSllu#RnxW^JOPCCamjr+)1QO z+tM`m;YRlM=Nf!3n)@PP!!RlXqhkp>o6jtLY}u*Swrx8;`QWpCpB_B6Y15`zvu2_A zQA$X0GC=YH4#y3=!==i~9hvIk+4-KDqkP4IsJz*vmkxdT`z5#&456sHUnkqBK z31FRcMlSJq6h)?)f;u%P7-`AzgmFhuJSZW6K7hfGGD9V2QZT}x-ss9rBMd+fA(Q!Z zG!?Vrc03tNrDLgdG?Q@(g;=sG5zA*}D?2KXu8^z8)!+Bjs?8sMcA%@PtM6=o-`W0S zr%r#oXYbDaUw^o7|I1t6S+REOH>aBq96EUDo3CD4^XeGMF{@`h`TEBV?H%X8|M81& zjo;kT_;k~1yhd! zApnQ$y&IRx?~Me);h>^Ox~>|A9*Jm%p+k)YvY}{Gx%MGj{5mABVO=4Sp)zBtaJcvY zALk)eRSktgW5>8@+F z_sU>Jku1xI#VyO$WhEGvDh)$VCgYkNiA2q?t|oH1XIHN|)zqiIY0|`W7#LOfv0pQ>MGo-^z@z{Zwe0o5I zz}n7|A`X7SpaNoCgKRO&!J-Z<{UEjgVv$^c7nIXnE>kGv#2Go+4r zMQ&1&A4I&nH3yYkAF^?kh(AV#0GvO>NQ0B*$fn_in5I6?f}=uw$c91<;8M#5)5Rq% z;vhU|;~Ut44_Whb@G94|jT&HTG|pfw9MHjwg;+XnC!9n!o-3r&*+eX1J25j^RWIAs zBZJvUZ0fuRR=%@i-y;n>(%sW{`0(K;o_J!ygh{Z3@TnZ;1sJt&gw%{9%VAX=P_%Vj)jf^d!}nDn z`_$p9KM0}W5G+mua`Sh~vM7M>LTJ|2)zx)%ba^ytx*m6g$Gbn?uZv+tZ+J-$v+ zbw!e+re*1oh@?;iP16+bkUizsiACM@<+>&*vaD-{V@Hz-cR^Fs-QXpi&7`xLSR!sY zwqcou6$zVq$k6Uyu;9?i)6Ly|&#r#eNfbwnR+LyuiKS%A329m|?DATZ!iM6Sp^zO4 zLc>v5QsRkJFeHtiRNva!wPgA7TPrFQ(+qlV?8M*)&|}diu}B>Y6hlKTN4EIXPO5;I zzKJUg0H6&OM-h=km>9@=%SyRC-KX}Fk5uzP6#|#U6t!s)=*-IpZVowIJcSexANh*p zMZIxUK)JXSlR4r-PKweJf@HDslcHXOY*aLjJ04jEyz7W;OeYe)v=IZ805tVes*S#A zpth$rCV58zGE^>DDGmlmA7Y4>4W>*9MWZlrOjVT8kT}m{7$C$Ejp!6-Uy&vTCtePK zieHf+2@8&MS_9MHg+c*S92`p!O)MsRh0kKcQAb3!r+UOwnRvcBSF9<;vuVYSRx0Li z$HXi2>M64y+OTE!iKecuzTWoUGaWrA`Z`-XTAI%^x4!$)&J{1M-M)AK&VBoDpMT%) z6syw8zq;|m_O1&TE?qp)a^{|gpSndZ{w|VFOrASo?!t}l@9Mbls`{?`+e>v0I{=y5Zr%#`$X_4Rk{#M#;p}Ok24!zh%z@PmJwR&&?iaQAjg4?zY zn}e?FG-~@&BQ9w<@kQVqCagDbD!}Mcj%=hR%W^ChD;A5HOh)$Jnl^Lh%vGyaeYoS@ zk9U9c;+j=cr%keLQ*tok(rI9RanNUY3@E#j^k8RRKUpr zJrsH+w8h~JBSbd$)&Nz(CYp4~EFzCEC9TMDF%Im096!iPoZ(l16=oSc&Jyl`FW0Q2 zXkvma0;tX0`G}BCr?cLHF3hqZ0v4cf%s?CpMo)a4!MFvp2`*2* zYVQ7j@bboR1*yd8RtU_Yi#3UH5w0oOcruqt<_qaUDId>f6(?C?Bm-tK>{Q?N!1A5@ zzCQo$RO%~Ve(g{H`v0_bb>H>y@)2q# zTA2IF>pL5}y3YT2@rwh8pL%-ToJCJP_uAH@ja~g0zi;dA-}2thx%Vx-XX!Iv968o| z>B^S}zMen-?qFr$mRoMM>_jG09gRj+RSg6Js;b(yyBJbYlvpfQ4$bSIF}(>r!_YNN zQB_&f6vNPM+vJ-5LQe9x;%V8@bpkD78fj7uy*a* zZQHgTJ@)yR`#;*aarL4H@0mJnQaqXPUMyhCvJ8s{7Sv#GId3cdINtIjX?msXF7(&q zF(Z|93WaE)+DKIeBFWLRqs0poX3e>0>CyuYtsm_>uizhAM6uJ;Jmt!?ab+wCs2?kqZS?Nsf_uP@Fl>21tQWH;Zgin?Oh6)LyClQd=iy5%A4J0(YW; zg{BPJTYzlFgydxI;4W`D3?9q{@i9=b#!zX1I8s6r1ZGx1ji>@=NmZ)PNCzS^Up()4ZX~X!pr}6r zOq@bQI<&D+od>4*6~e%l4XZkYq#+ms0C)-r;##Ip?`f0>3F2WQm&;UFm-6{6hXhgc z#YjW{LR{$W4COAg!Jdu9V$pNfb{9;-paic$R97yS!E#Ctexx=>6k4LjjjO7y9al=G zN|{U{pH8IWp@=y`GRK%jEj#o14X+d(?d_eP9yxOFvX_53x+;>Nv*xXLziBw!-`{_^?}xVDD{Y-; zTU$EXn_ABG^ffoN9r)&CTkn-4CyuXKyGD=5p^DMDRMOB*O}7JKGaL@X>4LUYS(foS z_TlI`%z4)sqG<~LEXznFVqVj7*FeKWOKS5g!97fxS5I^I4{dN|ya;Qk@PHj00VPSo z*J82w#1l{K+O_M=H{YB$Z{C}4JoD6(^Y58I<$(w8SoF~Slcv>2Y)3U6_hsjf6OFp_ zkd|cu2QCfeh!Js2D`v%#<0jNUxNP|w@4f%&*I#e{a{sOaN4I{wZ}F2akDGS)l)3kB zcz1jIrOPjDe0$vVJN^(*#>f#XmDTN7(AAtxLyu^>r0HSPl1;}|pcUO#BMC|lX;Jf% zBw2A&w>8&^&~OD%6|=HJi8=0Tqjg<}gu1T7s10u%ip?c9p04G3;-Y_vPJXaQL$#zk z1PlV@h7ni~pt|vydpIQ*5ny~^E~0%EifzU_u&x5=z$F}kz)&jb5C$498H$mH z`Y%*WAPdq$RVVZrAFT@$+E``7O$u2#@p#-cO$-1SVDJ+hO9=XFcJia12x~P~xB%r4 z9kqZ$CX;d8A;5ajv&Y>9kaUI#B^tFY%b-)5&(@Lk4i*wOFO^EsR>jAS!6%x57m{%l zL3Z(Y9M1=67Tylm*;1(l$;Al`n0qvo_Rf{8}m%s;k{M)nL@g=d-SJcPX38r_!0Y>-&*$-StxG zSTYrj<%)@{YqpN3%v9Pgr^6gLd?LU6Hv8B1a?aa>IJN0x?N|p88M54N8>zZYmG0Sq7Zo?S^smZeY`kQ1jSt^yrdB<(Dr$r1ok#r;_ zD63LflVYjl*lrJ$v?y>cBILC#+mD>AB^zRzLl~+gmo( zPo49-TaA!vC=n}~%tT`e_l22(0F-Vi640XoGhH!n@f}|rKX~v=t}I23+(ws>5U-)n1(Oed5=0ZJKAq_~`7!G{}HHPAwj!12jPu zW+4VRFwpXVCw{ChCOTO<-yp&BBqUIVuYf0=LqwlH3I+lAl;9JCBZ?S*z%W9uJD>-{ zrsG(wGLBtDHneOYo0G*fn9!3NG^bWe*bOSPF0*M_M~#SQSiggn&g85rBCep`rx1c{HM;|{yP^f zlhU=%t$VYny|cZorK7X^qtEs~{mSM|AAEMKsk6JMudlbeskPnF~fIlaDqVpUbKP)sM1cJ;VII-5{+<(5$+HPa}KuX*PAr?QvYB5Z! z3s2$mjj7F4J{j@E>9U~%;1GS+m1L6K~&HT zVPr9YY`R{E)(_8zdZ6;@(LrRx!`bF%L=pg6|j};01^}$>+1x)unQK3uulFq>{;av6xS#64AJoOviFn z`E0RdMKdAAxn)dxbf}oCxpUQP@9aO?aHhSr|9pE(+tEYEkM^8Dd-414+xq$r96!14 z&8>Id`#_<#{{Q@auuwZ?-TF-@nmX3MzgI6#pFDR__xbPJn;ZN3`Z{{gwe?@_yYf@_ z*^7;hji-+vX>2-k_WZg2b7yyb_UVE}3**T|AQY?&2B6=;sz5};Qo*k`5{Sp6k%;Cv z)*W}=w)xGCpMLi7Gb@(o@^QmdqA??vPfnOPZpO^Xvu>L@b=t%U6USALD@>eJTRXn0 zwyq{$%uSgwefg75yt{q-%WGC0IQZp}Bj4=){Ikt(zEwMM@~{7Sgl5Dw+f3!M5!;eg zC7v8u-DBIfC>vl+WP^9$HNr4t2ZKQ(a_Q2g@4x^4bI(1es+HMvWYGh&S3I@o&0F!x zo1L8(9$NP52)WkIO@Hjk=f3~$&nupP|Chh7|NUq=Q7Fz^FmKVrOLQ~kI0Z#D70vbG z`?pZ8$$BX4$OTVPaB3zQf$RZT2>;NL2}<^BU%(fE2{2hP9RgHTC;5#s+i{a_P9BmZFrgqaMqda3k*N5KBLRSm2#8GjVUU2cBUO7O!W8&*0NLV-L{i&x z!5+9NMD}1cU9$rp?ao~N2!d0owG@%`DwV?I&ILvZn2n$Q3CXY3Xd^{PSz+9st7-c$fkx47jJ0j z-1SM2)_qW5J!4d(?Hh`Ap^)>2hb+rp^!5qy4E?E6F`G`gM#XqC;UqJPm8g)N5tR`; zH+A;i%eL+Ks^{WQJr}PuG&i+$oN4boeeuu#vT@tH%T_+OO!$Y>rbdGRjT;0XFA)QPhIj_NDu*@Ch>+!l zoL|j&2QZ2yEfBz`4x^;F9L5<)!h(oOHxj3)(4*m6n#;K_2IAgQNS1S+sOqa)wolO> zRG;IBM>_)s1R7Gn9k9=JEsEOQ*2BkED#aijm_=#mj>F*#bqc*3z|Fdc`*s*=*+|M$ zW8J%tX+1z0)+n?IT6Ks&(NF`M1NL|VvN_UVfN|HM#a#0pT$;EB$J?Dul)8&UjxJ`ZZ=^LfkGv)Oc2bxkap8(AU!_STRd zE7Z@PzwYg~jy9dS_~VbKn_CZjbG*0r(uE6uI@8p%dgJEmDKoT0CTzySW^DO0FEn-b zcl2K9y7E7E?m6_-)6bP^ru=g#{?Agj?zRWs{_wMNJsn+b%}r+-PIyOqTg!$1o-613 z-g)oc+wYhY42NV@Nv2blV~1r)c2{2yZ1(|m4EV;hl}JE_%VCW(VX5NPwJ%=2(%;_E z`24CTCQYuY8kd+bDL-{u-He%&X3U&4c}ng0y5jh{;^Zl{GiTM0A74`}<^zF>TStxj z)vtfMXvxy2RzClazxmyy@pVxIdkUBo^$7I%b!{{f8qQu z4<31V`4gE!$@9=~*WF{OPFNaKH!<7Pap1tQ&*$DhZ{{EGeqi}SJHFc4+jsWu9XpXr5F-CdiuY}oS7=7UF$*Vf%0v8t3v!i+~P%fdtgc#4|; zTNv%T77rP|PnxzxM#H*IRIvjBXJoW5Kvv>BFaPV1O&rrqA)XP#RG%> zBAaL?f<X2j?*?Y~qA3q!NvBeoY&P%h)>mCBRmamQGa8drb8IjYkeqzY)Tdu~ZQsEY&3%pMzU%3~ z)P1Vqcy~{K-`OAE+V=T^hgLuE$g(dEpV;-~!D)BQ9~m^lR(kQ{&!1{Pcf6(V?1gW? zy?kZ=fg_JTyLRDIue|r^*X>>XogHnB4X2u$oBR9wFJ8RZ+uOT$&u1%FJe^3nuc}gY z&5k;jV@rx0mLJujquix-;{p6Zbb#m(T+UYav zrcIwTslIl6T~+<$@iS*lnK5&6-Gu5~KIu5tm@#91@rz&l;=laY|MY+S=gHG&u77=V z{q&iYmBA4sMkbT#La{29&OW(f<)Nd;KHmN5%sXzc2nB<(l+EYd*VXNLgs){+!F(ZswGyd4o*?07K+k{E;|LZ?0LAA90t&czcs4Gh}2v@LslO(2}SWo&qqG$tO8!%qfo2|zZ5 z_wo0y`^q_3n1f&hLv~muPCSVO7uiIZ_;^j&F#?gzq{MUvZL=;;!C!zC0+6cYFEw-@ ze_{8a$M}4Q2-q zP@79y07`1XqQebtmAf@kKF&Csx&RLr$N(Wxa3UMdb9B2FrxxK2!qx2<&^9<-NvQw!{DwRp6v%q&Ek#chRF>>VANP+K_)|Q4JfBgQ?u~T<1S~h*&;%|V`sJb&d>*M+_-Klb*zGnS_t&a}0)_4M?7^UXJ# zHf_4&&btD^u%yU#)G;g*R*_gDo=7DX&D}Pn90Ua4jRzztR8vzub=stSA)POzX5BXV z&bc$|C)bQ0UsGE4&A{sc2nbtajhMi%y>GIC=WQy$e=XPnfrD`xm=DZdUD@ z{M6gu`gl)A=btuj*sJLE|LqU4ii(O6BmQv5+&QPubSzxF@}FRMwPVs2BMQoe=|1k^ zS1J`sr9xFz(cQbp-41)8)UZ|~8p;R*3+jZnY`BqBSC_=$0X0l9sB4S1?0l}2%NDbl zVkTWkC38_H8PRQ7(tleS8YLSwljpp;@xwDM7cN}-m+qc(jc1yh8aghYyV8E9`NMbL z{(R3TJNNC{_~Cnv7tekF)1RJO{bJR`$!j)kJ=S_|{-ZDa(^yBzPFt~RRd-iwcgyk4 zwuaW;zJsTmTDrPUojlTe{&IVFZ%=Rk-hE%*IropDuC5z~mqW0qsfsv@h3 zX}c>?fC)@F!j{S zJqMzK%XI$3Iut12AQxnoWjPXwBoYb3FtEH^QY#EoNhRY;AA0!ZmtL)@os=k4{cdb! zP>GBUN?|qPZmDWm*aa{Y3Q5u!MIGtH$3F7d{U^_yI?>#+d;gw>?uOpJ3m@&>@#(4E z$GVPu_tUpeJig)&Vu-Uh8YAeC7{EDIERUoP-dZVb0a4hyP-?cU;>uWxzK0*fcFK-NL`pZ?BHab zyC6jjLpO&DV9`5pGceGl)9Ji78=3dEEWkdKaH_`u;A-REmUwuE;xL=@4)1=rZ=(n0 zMGJd2n}#g~KcSd~LJlWmF(;i)V(kpvy-U?qu)0)L74x}NE}Jam)46o4Dwm2{S|OjV zt*fzO$$%OQsF_AAdY~=G3v%$A9?K_h(v~+b(t;ZR&aOu}wx| z$|FxbbE^4BXGim2zWd9^U!0a=`Q^_)|LuSO>B3Lne{-_wp=GNBQt7eBpV{}tR~IgR z+tuBB;?(goEe)OBZB1xT_fi5TuWOxfKAR&!UR=(eW1o99I$kytD?sea1DNmETHDXI2o zcf)W=l0uH-dOucHjJI+&NcOSLdK^2?+@y z5IG}qP9_Hv3>cHaWH4ZIHaUZYa?Uv+FgT6J6L)rYX7&wls}H{JmF@R-wmv>lU0q#W zRo#8=`OiJ~{#uoR*>hm?*Wb2WxO6e0-w1|Jrn5yXA)N;g=~+TvL?a{>u@U=F_{2ln z|JPP%H{#kfI2O8rdmH|NYg6}aU+|@MBB8)&fG?`&0duq`K|diQKn*X%FBI@I@y)dPPALN}i+c!T zB@Xf$vH{8fXfRomiRU;5Wits2T;DgFa)z8tTE~OYH?&Jo+_rM*)t>$l7fttA%$sgratn z#jIgiu|g9NuGI2od-UiL931@ayYIGZ*G?*x`uPXH*SU+`XD~Lcs%vXb zoH{>u?vhA}`h&%*4j(-^VsvVJzvRA21MJc6-TU_M-Me?{)Twg0JTfxU?RM*Qx{#0% zo6YvGUXem6(P$M6qXXI0>sg(a(`tlP)S;oFN~PLjwWm&)viIPTMN3!dc?&SqYPFKS z9~l|xa=ENlYmXj1BBLZGn>}1AmFlz>x5qy+%3!ibh!v3%Wq6caqvw~dSabW{<15#0 z_l(p%t3+?l3E4~LL zuI(!d6I7AVOmNm_1rSUaM`=vjjdlQ*{UT)3K2V~8q!31MCZw789)w;+E9hScG$65? zo~0E!H(#*EvxotdKBd?I#R4bu^S?MCwj)m9$Rzmulzyby1Hgy@JrJOgRK!d!r0v2W zjKUej+Y2`p? z*N+Q9Ha-=Kx&U{lcL5*AcL*?z)+VR=M=BoGI( zd?|_lJ51c8j`RZ|g!@8{pQ$|f#vU2s^`*+GKif`Y# zwrtVDNR_l#s6@rZoxJ?Gvgz5wCy&a?i=I4soH8agRHn7KlRSNg*gQ##SFFBz`*w9h z&6BJrrR60>C57pk8O5a~l~pyzPn;S(W}IHHS11%{H$izenM_7M=6`kN7a<$40@4jk zkxIoqdv@>ArL#__NlfgUk}{xQzXZKr8xau^6cp5@OP6--+I8;SIV>!!M~@yNk?760 z-qADM!o?pPJ$^VRKkNC+){3g~^vsM=V<-Cug^!ys^~{A!v*&;C;ku7*-MhbZ<%;gA}^GBi1XaI93Sh2Bs~okSw>c2eT4Hpk~DPk(XaX8)8y zsZ*yqoz9Su5SdKoa5#YS9LM$S*)udOg5~&W(`W8Kd}PeTi2-3@Qk_<+(?-eUYCWSj z@G6}?LL$|1hDFPkXXh83xp7Zru!&V1V{ilpMoJWFrCuMQ{BNHN!8F}o-#bho3lzpf zdPy5(|23rk`F50FQk9LbEC3h+RuaawS)pP&AUk0hkj@tbab(&~>=?gO8amIKlA&k#z7jZ-?!4jQ|HQKTvyu5u)e5JNq^u^d;#AgMow;Oesf^1Hg@I ze9f|g>PunBzi!y04v8+giXEz0!nNMtss133I*UG-VVec zVglY8ae~5tuNdOHj$4552eD(PQ|P4t)TUc(_b$F!N_+;ubb@R=gq(s`w83jAJYJbz z@FN0(A#mI6R&qch{J@_BN6qWwIBlNT7XHCWy&Ozun=uzJ(B%%aM? zl7?OTPxl!(k#`SB88u<+u1_yrxtyN%C@(AX`lU7KF?(s>~Olfb?+Sz80w0SG25b5T29ZI zcYM0<*vZog0|w}LUZ&9~RC1%4=XjPk8B7*qcx0GTt(ZJ@Qb9$TKo9AS02gh72LUm# zf|xrc&!9o$Rla}&r1s^}gi+KN1-cLpMSK3#77ED1^BlwISXNJVh#!-Cue)YLj|QXy z%>g>3RzoKNo4tJk8)@%-qk_JYKyN7Dk=D6`Q7M{L#r?&OwgRH{IvlfR*m;ocE9X)qF zr?e)oxU{0OIxX$Vjcd1?>sqq%3T7`@7@^cDILF5Ahl{IPN-8Q#%L>wSvTi>}OV27R zDrv5*dC}1Lw6HiMJMUIqV^vv2@qO8;bLY-t zv3T6LaVuA@3=NBVw^NrfW5+i%HvjY0|M|Cn|Ksoe_?x=MioEXkudH68rT} z89a#NS*cv&a=8F)EGu-^gP;0;aXEUu@N%Ra>0SxueSDp_=$Z<*i2ZcvSr82dFw>n+1eG`)9YQBA^Zs8Kufy2jl?%A)_GcuK0!{|Al z4Gs;G$|bCU5lf?#YGLM@NO8od@uQ#Q6kNZZkvw>6q}(jk@H#Um*GCX^(zUd?;lGB+ z*dNal#ipaR0qCDUB(SEZ@LEKA;4dlKAc+LizAL_v2a4SWD?x03L~JWPOGFq42Q)(w z2G{|ViDgrA66Z$4YhWV6jNNYc-Jjm;*Uq2b8m(90xW@r~-yQn6!{HF5&L5XHF#wxs zkU=Q#YomP4vN4u7nRu4fL&6560)PmS$qnMGJNu$G(uTf6ejL-6S(E4iJ(pOj?+Wb$ z0!|E_iYkHoq(wl2__;7b`9owNUEam%bh_Q{XtIM?t$=T&9NliW$K!#{h))YC2!K1{ zs>8c@skZ>xzIY9(1k-v!d`D=3^iMT41ldNTfo1hp3-56Y)3jS`RxP0qwOya;WsrG{v8?p+k3rp+rODeA2zPIPV;mOnHjvhVb(4jLm zwN1Ij#REr-@C%n2Z2cFl*pgFNT2z{oTUeA|Tv}LEo|Rqv;C|YjJ9pC4?w6KkXXa#H zx^i*B!ufiZ@ed4;D^%zO3Ktr{+Lyi&BK)f>Z4d;IO&e9-eo|f*FU%9BRLXnx>f!I- zJ3KtJM~`k15n(fC%osj=cxY&-NF=gat$X+G-MxGFfB^%#bnPw@z0I(uTelzlpMSpk z=c`xEPn&k`-lo%XQi)Q?3JM)dv}Uu><#P1x8y6iNt<`E_hQoEiWc{yR4$Bx-DveSp zRK$3jt0-hLi9#un$O00RTr*~+E?79XU;iY#D|Y?IJJYjDZO%R-(K~(n4H`6b49nYx z3?FAOIp6Kvvt!r573;R{+Iw{5xXB7NBao|gMHxe}6 zCWiYXSpB#E0iC~yiM|w-fSX{n4P+BVH5!G<*q~ne?gJe6Wpc#paZIo@=+~q~;~eOW zNoyuq!x#Fo5mE-_Q9+q)Hd}ObbWBVP#U9^t`?2K3h%>=cI5N!*WVKp;{~5@_xV+2GeG_5pVLx<`JF*N7$1*|ARUb(Gck zzJzY6)naf*+j*W->lqEphbdH+*u<3^x8>(nG}J#Uuc$qJ{^ID=iQ#h9&~Z~rYoAqC z)Ly*w#qrNiEnBt5?v4)%Q-(?S{)48TK6B;S%NMuP?~b1_%Rh`Y+6SG#a`R!v&5W$v z^o*>>k00jbKB=lKX{fKREG@f#>%q!Zt35G&Lc<~yDy5L*)Tw0(sZKELy`Iqu4W4L- z?F$G0(mJ6t@oV*u)i+QWWHOmVBI(klb5vABpFS~CsW>pu-`~G?P*A|imCK(#eVUz} ztxzaLBGIBni{{Ut->Fllu3fwK_V)`23=R#I&Y80`BeV2LM$zgu8)R~INJ!X_A;U~2 z!TQ;+Uq1ozOsqs25gs1SFha94qyZs!{x39omN9D7j7B3&?ygp=rBbm*tFYNkDMRhs zcda~i=0JMp!;;eSlp$j~bq-$f;f@=()7-KBd-{d5ymRP?2~q_sdgI+;BPZ@Ta(3~` zO`e3o?zp7E!$$K)b8xUQFGN^agxPG>YV}g7++wjY3?~*#Ef$+jqt$3Mj+mI^=Py0Z zFCIQ|dW4*1jUGTS0dAX*2HOdysqG)(tS{oX+4<)%?Yjk#jkpC*5#9wSpz}Ho0es-v zgnDgOXyD&w`_I#QAfEpZ$Oi5cKP71bM+T2ZA&f6r6G{@8`gZ!pYk`|MK4>^DisJ;g zC?@}cB1fvGZcr~tYA+%84_Ng(StRm^DT&sOZ6VkH>>S4e|ykh5C_tzwT8+cLrgJyxXALxR#h0H#8q; zCK$Uoopz5Wn$aqFgI*?+ghob%$rKSv-I!@}o|M$I)<4U6l2c#XaPjgbwVn~Hb)W1$ zcsHZ)_VpWu`2|9K-SE+K7cO7@@g9qNNN|*6)QCy@j~r;2ZEU?GDqIM>gd(G-_e8bCtIyMy*z|tUh@_;_NxoKG{BR=bmMm zIX6B#zJKYm6`Qvn7&&ToM3i~Xf))23uvHpuq@jKk?A2! zZ@#_=!c)>o2y+RPfy=%Oos`C9DM5_>q9)j_5R%C=X=%gBLb$89)NG{HDpIeJJIa41+G-W5s~JW|(F;P`v#1;tej#nrXz zwrq+}$|4l1gu&ihW40Y1*1qA>xX`qB?v;xG3PVKv!!64LqXf>=(Ym`Z~a+%KK zj+;Gu?y5D5IHOMVhN%5J9Yt@vrDt_wS@?|E6BaF=larfPR$jPz&5Fp#@HgLlvsW*_ zfPkQ=NExH&wOYMgt_%wcQz#TJmjho6l}ZsF9%?f2I-MpYBnVE>#Kc6H@zFD$`QbkClp$?BdLMGvDHmOo!G#Z3? zeZ4agwuc%a#R(n+?{)5Q$u-m71NbLM=49(rUQy@Nlv)0zk!L zvE6Q0s3XF{!Z^mR*BF%wiJ4cM3>vLcn0?|G7Yl1O=!}e-XJkPsaE|159Cd|NMFk<{A#6&ujWNUymW^W*<1rXzW0MIyXn9va( zDCbE50Q(yZLgSYj)KLA=A^@MYPwGtHg@Kz|L{fDeEpu#Cp+zP1nu4tUCU z9k32NAc-W{0iaA9DFA?$f;E$;4I7a^g!~N%CMg_#KA7ad%3&)MDp0)XJ`^01v`zMB zL3M}Ub(I;J4{~#}%Svk>KFBXBE^T@G zEImDa)~s2WCdO>EXjED`W46a6C>c`^|6qnUFZf{5_3JlVTU(DGKc1MF7#0==ho3^B zKxG~9nxxPFA!Pr2xA5>#i9}-Lt&HB-qq~3q{sYdQJ-cVm?k(Ftx_tHgh*85uZ@eWE zy=}EQ(laxvYAWyCz1q-N{q;A`3kq}Y-Mh1H-8!XG9UdNO;LH-SA}~;}xNsbYS=d8D zf&v2kz#gPhad>#B&1M-qIK}017>&mM{re{-CK`=Kl}Z&I9gS;=ii$88*a;IR95`@j z`LYjVJbg84R;3gsmV_5L{uCX;A1y4aY$^XAPv_W8cM56+yuwEf_o z#Zyz`95%_If$otbQ^rq7-M#PN#jCd&gGD0OELgPs^3_{=4}4~K#dhuCKQ?vBzJurX zA3B+o+;8c!>E};xUB5bY{fd#R7NiUx-e04YN6E$3XlJBct~YQjtJi6TCf#zm99}w! zMB;Y4w{G2(WCNeTmE{n97%)f}&!bY72h^!TCGQva?aHL_VM4S;qlTN2|xm;$ma5RNN zhLkdx3VvUhIvwzY>E(O{1YazsBa_7fR%?PYROt9tprG#s%Hn(n#2{g$7b9|GPAJTo zfJlH?P7*VX1F%9&880CpFzF<|ES_-LcYJ^_;4Apx(!i;G_arTwdi!Az^BS^YW1y*k z2+;_3Nn!?n1dRoDlblUC6F@&mI#3vZg>|4L02kmz1RS~n$|#_0cs$XVs|A*Da3$a} z;2y9@ML!wFUa9ivyOG%~qTCRa-p=27EjT)KAW zNlxC}MT-K%!<9OA_JW0v((`i*%ByOdD(jlA-nutq{xY*OQD=%heBpFPQGQNQL0a0A z{G7s^%%ZG}(uVr4@87?_Y}qoG%gwPS17}t#^)jiz!kjT9JH8*;%U_W?dEV)Bmn*6& zTVFI+))c>d`SR$|qsht1a=BcsR-4Ucj^i+w3gI;%3~)@ey3GplYhQ}3)oNLmb-CP1 zh1SShw{PEh?)<48J2&0DeSXL8k5ea&+OzLdPfYy#U3w~&?AmpkpTGF_n{Qv#)mMH0 z+iw~h>woy+`#=Br&+FE$V;Ih8G?6zE-O>K0e-N6G)$4uXnjz$;nA8R;;*k<;tm3XR@<%Pn|q# z7N<2#BGK`@ST4*CtP>iCsCizHL9|+}N~H=43UW9cTeog4 zt81J(XQ5Qdu|}7kvr42&A@(x@#G_lG#bOBy3-j~ygAjE1#Nm67GgMlKTxrsA27{4d z4U9@DNb|qAC^b?&r#4wRtHWrr7&u-i9?~&dM$fa1(ZHE`gT=s^Io8DJdA-h{XVhAq zQmv6|bxKxX=8S>Yvz*qKH3Lu0W-|m6LOrT~!E}g#V|o^ZgOC)wm~<5YvD4{99ujFM zr_)LBN1_V+V<=cBft&PeU#3s#M9_TjGjia;*ymfhLoy2vf`^DPbQ-=y9w|x$Eeb`n zCxD33p$3EDHDr?&ge)153kYP1DgxY*Ln9^*%!LgZLIlxjfIa{kx(bLhK$c)qKvq=% z03ZNKL_t)SvXL-f!~5Y|G6R(ZbemLfLU0rf8VoF%MhLrUG(f=v#2C>Hi-QHefV>J4W7<%d`L)G z-@b`AZ{9w9_@LWkoj7^efy0~o^mT-U2c%9Mzj@2H!GlM)Z{NMsyZ$@2ANlux|F>7K z{?Fh4{vY3c_uXIq@|W}H&#TpHZ*vdEY_@vm9AHL{9Dd}p1NjBnx9?n^J!iUFBWGAm zQvbdqM-3f3WPm5eIcoH9 zTJ08-N#$}XM-8*=+&aCv{^rr6`__H*;nI~WtkKb|$=cIDAUZl)E!4*=tX8X9t(Hh6 z2sxplp;D=I&Bv>sfAh`9TlR#8>l7-h(GqR2@Zr)xnM@{?N}+MZ#Ka63Fd#ZQx<`*5 zBPWl0kdc=#V0@&+pkaC5YSglf?AIZiw;DC9R-%+jWMYL%snrW*pI&`{XIX<@&tfhi ztyXC5$1ohrX*q+AHws1> zEYK=(G#WG$bEg%sU264=-#FQ{!L^C|L)2zj7LfqTJ_5P#iGfz*1ZYt1dkF-@IDb3^ zxF@bn(Fo7tC3K!YRX;-gAnTs57((SLRQ-WE5kg@AF|ZFvO@-Q22xBxF=yL*w!UOIL zXXuaz6s8zJL>M0}2^}QP&~#sj0d%(LH;uso{(?#)ALx4=oDUG3(!PY(Al)zpQoCx0 zcd^^;9*>7YI`t*+O5Q@7LvqMKsDToq)v8tA-V_RjOr=t2wQ9Xyu$=+^gn^_|qSYxF zR;|-3WlB!R+F0H>ebxurdBtT_wd*#191|ZGsWiy-)=-&VZ}fbyeEr4i51-_f6<0Mq z$FJoMz7-ytix#Z=vbRf$<19j@9x6~ zxrN2~MV0l9-yAr6DS69^r-y@KASOPp}(I*9K{zE zmHh5^e|YukRYgU`+_`fV3Po6082VgCMn=gysriHS)_NXX94-nDC& zOeV}&Hf`FJojbQDBqZo`IQBucD^cE>TCUapi$WWv0Utbu_^T%%K)ZP9!79^ATp zo7-cTNc|05$Oj9C&YzbuX7sQ{i|23NzHR5;1Mav)i9&6$*fc6N)imk#dXved*X!kS zx$xyN$d|8P(e(7Iox48|3DZgxEMqdsb;4Z9F)=YZolYzkPn|mT(W6HX9z0mTe*M<{ zyKX(q7?nD|cYs{O@~nvy%Vmtg@{1H(nB4n)ij25IBzzb0?4OoDW%NKtkc_Wzw zWq?2pxCxAIGXjR-fY*|F!)CLAxs%-Nn;s-B0>5;CBl*gKzhK`i%Tfo6Hg80^O?qpb zvoBuzuG8^}iIeP(@dQzOY$q1~Qz;GQ6=4EFY=oTyJ|P)9(Ry9wWc_}*7ph`&>wfMxY+wNmNr5G0dHWHJd*TiB?Osg!b! zTB*}2^*WVKtI%rX8nsNR(ilxPrIJ-BxS2B-rKRQ8)-|VRWbZk8eD9GHhfiF%dG|?a zRYO^2U3ymb{l||=OR7o=E1os9<~({lXG&^Jv~K*wKC9NHdZLvod4NVKaXH*Noh3L_ z**|5}(Ua%13m%kK>BPojZ3PK73eGQc_h_b@l4ixpU_l zjmDs$pf(UpWpZth`WGJ(UZcsf*=%(>+^bfuJ#*&Vq{-uLcEg-`6DLj{pO_RsbM~}N zn>XCPd*|?x&u7kD)U9i%%jr3O?Bw=syR24wP*8|eD)q7tp(t4_jvO~`Ohsi$Lu1W{ ztC#gp?wgP(wAJpP+;{YtVFOe8d14&>lH&R&_wAqDcktlB@$vC)w>vB>tatC;B9SO5 zDe2g;V|Kd}zap7T(yw1awA-%HDweNUeD&(pl$4aHs3^DF-M@c-)JzH!h%iR8$^P-i z&1cV^A3AjSs8OSa4I9$8Z`}0h^Y`pIvUtf#u|ydeC9^xCRcftLr3nrW)N0ijU71Y0 z!(n3>oe-W?N}I!e;?$XyD_3gNa)yyjOdUKR**h#keuj>aT%?=&Y)8% zRZ^8&#;_WTmA5<07Ap_Ugi20;s>mL}2!LTLCT$^$1(4L&0|s6U1f+Iv*uiGA5duO3 z@oh^@tQK}&v;u{20r7;~W#D9Z3qUrgy47kWF{jP(iAUpIh~pz0(MB`DmC{IpZUsV= zziHnPatIW&bUbpuXW@t39dc9Vs(=dz<0xN#KsE@!IIvr-Si8UD+yUl2| z@GPUzY7~rKZFLwU#Su!CPOCLbCEV!I({A2;+|=~q*>^9CE6cMBii*lAii%6~^K*+! za>~ndOG^q$3bS@?UNa=gwP4ohySGl&)aKUI72LkDXUe3c(4g)?0m1$H4gPrZr*|J^ z*0emUtSTufEx2{(_K*=HJ9qaVJ#ltsesyMHU3qzVj&~_4DypccC@3iS=%bJD`}aj{ zLg8P;Xy1*rClJAVD+C8y*Dk##O`Kj;RrBG8A95U%l-z&LyxHe3o&NUwFE3v`KWWOu zW5-W^@WBe+VDH^4NG4UYj8QC>3Kii77CFPv&|s&_x^MsP&yF4#Gj@1fyep}HpJBrX zBqVxbV(o(l_ZvJUsb5lT|KvEg$LjHTq*AHBzkfhLK+m2%yL9Oi6&015ntJNg8NHtM zx+$!7hq+%;+_dQvE31kgK76=h#fqe)q&|K6xLhtYIF(AJ4!fssd{RWXR)x$f$-rkh{3+ zgMrKRM!qTv9DyWCkSGdG8JJ5Xof3>V0eB>s|b4`BmWO70f~002E)E;Q8ejZZi} zK>Rgi!+Z_#0lGF=Dj7V8AOlQ)&E!WI4bUeLC(4Pgt!TAD`Z(YcPH>CGL>1?xiU8Ts zo)o+o;7%{ZMi~BLV?FQ)l0_QmjO&8K1XtRIdV9-jqG7#scozh7*g}wJz=uS$RK&!@ zz|BqZ7WAB=l+kEVsT5MFSfx_1f&oE`!Xl3+Iw2uGIXP+2pn-!2r;HtylH4ygF2{^ip_9&^zg1X~myw^5Us8}?Sn%-S{jAK# zHB~v~WsfgkIy7y{!0{v9=TCm}vZdhbFY8*GnqPeRoA1BPIe&WdtQlh#EnIN%(zVK( z=CZoRwA{SXlA5Bz%88Sv`v-?jnla;EMp|xJVNq>)R#sMKW@b@QQC?nNc6N4MUEQNc zkLJ&x54@&aA_1{4I{)H2_9R5`&dJLu720T5yv^zvJ!;~K&rh#jy;h~x4jn#Z>yAxp z*DqVWZpoedH)hS5nU9=VKoL`7wxuq zCxrC$O>hrPNr;Pg4H(!rF5YE#@Ck_?hE)ax1o->=w`K@!e${9+;Zgott#;vpRhQ0RkB{?kdYM`gY2t)0=r1k`RVd3zlKSy0mW=%3;>McN zlP{Xjzid3y+HkJ9_H=#a=e6a>>MD*m*Pi~e`QkUvufBSf^XK2+c;0-vx$g64jpv(d z&lYCwyMN>3x$|Zu4@l56Duq(a8MGFw!D{0zR>2QP3+cSRa-F?w$C1e*O$xZLxQt_>5fzN;By$t3243T69LHf? zPSUyW@qN!0+i6UIknkF^V`F0x4PcQ$Q1Yq-!pTEwAb&K}570x>j;X-iS3U+(qk|ol z!vH|R&2>7B(P#j+f-fU~h!RTRGJ*sWcf`uUUKvKm^BhEQhr{OaM7!NCyd91M4-CQ& z5|XglQS~F;JA6ps)Uf`*4vCBtxlJfwU{K;RI~*2koX72PI#@>Iu$$xKggY4>@6hO! z8o8EL@{%AatKq^Tg00cUkwdM^J{Ym%<2i?SEk1v2#f@`IuV0vX>+Qvw3yOf?4r{2N?SH)tgy^(`wUe8L3R6VGK$gr{yd$eUmTWy_!>+S6Wm0Br7dD zE4{2B@8*T`YZomVHM-yS9jmi*Za24-v_30;{$=HtFRGqBuXy^bpt?FgJ1ZkABeSS5 zCqMs5UQTXRc|%QI?YRr*m1>oqWtOd2-qg}uQC0aQE3>>jKRYWuKc}#~q_(WMro6PQ zy1KZ$B6I%y`6_R5Ia>YUFS^d4R11vr4rsG z82;dTwA<}&x7%nm%4D*zurP{Y06ydiBO)S#gM-ClF`Us7nMTgWt3q|LvD2fB(&`zkGk^ufG-keb;)ivhc{G``fNw*|2=c@Udf@4!exwWj2SI zGg-w_HX@2m>_6n}g)eIB8tUt+YAOrPoY=Eq_Q(Y@huye&s<7xGz`EsWY3sA{XU{8I zo|d+><~@I2)6`gBT~$_GoSBw(EA8?9@{;PB+WJ#x&IN~ri6yc*bLSVAlvUT%6&07> zy?3LouCA%^*|jh3@85Uy_U*fsRV4*QX}P(%t5&W0uObeKM1q{muYm|{_a)|-|C?pm z*w|Q}=Ye9V_0VWEiHV7qFJE4=WQoJ!m^W|Uph1HsPo6w~{`~m(c!$HG)oSH(IePA> zya`&~xN!0EkfFmJF6X$^@zZ8ZkM_7HPo46~md!_w zerC2>R2sEdDp9HhaD>_MN1u;SaYM>JLKJHK;gk@Ig=r2T;_JNSIdC+a&F09+NP|I` zo+&gmRIk^sT)Fb{<;&Z)?w&Ydn$7A`tAr|{sHiA~Lh$*~U2U@>kx1Z`W?42eGBPYI zY}l}2Cr_Tdar?pOaZ|SMJaX#H4UYFjNf?dZWU>mqu_%uE)~{<6Qjc4BR<4v;ZJbQn z)1dcTziRxGwDqkG=e~dOptbHoWzoKptnFpl`x}bSKdrk`SAMp-_)J69)vFhFI!&_n zB2fpCsIy2U^%p(3_Tg`ypH08Jwx;m2)|&GrnV(h^9BisO+1hZSAm`*qAI?!qqk4Al z;jr1GJ#LH5%A16KJ19337^Hy*lHyJx!a-6%Gfq^H6QDy$fMeR}?Nk9h0q{yN-Dbs? zsuN`6$iALG90U*#`VX`vB8<^FsWdngv2{{)z|+Y(LODsChTU$5Z4sghaeSOJ-u*RX z!@mNZ+hj69arXu>{ud<<(zx5KAph&@$R@k;LMCZH2&b z@NV?XLvang1=MPfCz|GXL?j?DBP1l;Zd9ndy$e(@=Z_00wl{9`h(jdY;~b(rE{Dr* zF!BZ?Z?iki78_?Un#@*(g6rMepVNtl4&ZluJT~LOhUVIXFP~M`0_>7)7G-)r@8eFMU4&Bjg6JJ@0|Z&;iTci2h5o@H@~3xNoJ12=?)2vv^%0d z-E*L*xU8Y^X(`GQIdaI5 zA!f5#EEdCS2tKIMXmB)@O3}Gjr!xkIs!Ax(7iGBO^OE4M@y?gh3@4a{Z z{CfHM^?LW+4#6RQe*WEi^nCxVw?)H83|g~x#l8DCE2~OAJ9=`!z`;>sdB3FO!$*!T zUA`=)Pwdp`({}Iq^vKcAKH9j!YPa?B>#b**m_D&`r2_m5sIBrYdc7X4OLX1^=#1J2 zV6@i~Ck$-~vM~u+WMrgFCd05AvziIkZ>26GToM&2<9Ug$Xust08KK zg@rkt&KWai^zGYMr_+raH}2NGhZnEh$SbTmbmW}DYZFpwIjK^Zd6EPWqS(SL7HVOx z1_3uYDaQpR#*24s8eLm-H$4cciZ7 za&z;&vu8GQZ0K8Wh`M#_*t30mO=Q>8M;F#t9?MSKR#9}MqUcao+Q(&?`zrGe9#R?;*a}R<0fEZ|n!rZrq7Wo}AsfB}3LfOzZgXykKrG8b83)Sy>OaUp zBKEXVNJw6P4cR1zleY$M21F+MOq`dh_)v2QJhj;@R9Q}ZoS+$?N%Aoe+3B>K%|;~R zoK8Dr4Jh5Tr!PaN`4&K#!R{Rn8$@m2c2VHzBxqoN3K*cz$St7Ts>{1jg2Lflpm})< zy#&)96mXz65ZvN4#U=>zoolpuo84)(Ih0CeRFqI{92d(U*s~-vZTHtLr<=-mJ+0VY zowu&0U|-(DHANXK%JWuKkqXwo;!MI(ZFP0&qS!TQT^;LX<%RVRU(P9+pTeNu`ZWGt5pXE`giHlxqJ7n zojZ4W`|UTobm=UWiv9e%zxB4LN6+_T`?$`XKiSk=`|_*SjLb)M^)1=C1>3govRLi2 z=ghlwQXEVQfdg?c=$FtIR_VYyfzb8tt>9?$&T%LXSo0jwGch=NZoTw@}nxB23tng%M z;kiTmmLN2nk4BrHtJkRqCBgkAhX9N!%6F&_c z!MBQ%C^la88nT^ECtl|C8rpE>Uig09_6XQb$Vlv!gbqmFM2)dR5J~Aiux9w)0L_%` zL_8p|_%$Y4UbpHd#Kdlh8QAD_+7VRn6j@WqFG#0>_+hhIV9rCT5K0I}QuHN27$h=I znM@Md5tDQ#wKK+Hb=eF;(wmn_BO@XLj0X9_MM*bqZvNBnGyn3(j8}ip`{CK;@9R!C zW`9~=c%(9CS3~KJ=8Ekt6?s-z)rW(VHDaqJ@+D7d+Tg{AhDi*}k%@ zjg@8F3UfBpm+bkf;mp&jGg;}MuHP`qWbdI0>o{((2wOW}>_Wu~L6Xk3J5Wps-QZPIsrG~5;uuQAfcI(zH zA|fI#E-o-I5XT1^D!dCY(W?S;GMU8RzxTWEc6k5&_vCV^$;7MG%D_PX(9qzXJ-c`4 z(7t>3u3~YdzrSGV6NyCO;h|w+AtOf)zkB!gU;p}-AAb1$AOHAURdqvsLrX?huElD9 zw^Qe#!-s9&x@GXtAz=~W8l6_5QmVBYlf`UzIut5pq*!R1<%`Q8-O!XF+2dJUweL+p z45OE0qDV~A1~g|`Hclwpi7}ZhTCLC~P^D4`Syr9W!2i@?wGC>k)oT2(9S+Cf!Gp(* z8<(1zI(6#Q0x3M;NUt{s{FRL#8?fcwU z|55jE-{duyUH$&WgKuA4uBq7d;Lg(Qv@Ml|C$b;!$$YrIzVK8@+VP{?7ard`_p7F} zfBenO^1RO~axbQiOwlSN8kx*(k2V@C27}OUp5yhtXhjqi=|S*f_)L5y5prMnCKUm8 zKmXeXYRRPWbI3+yMfL?>e)u;4n*e2;EuAyY1nLUp8jxu89>EK7C=3yN1#3XIZ!E#d z8;!=-knMK6(J%%0h0-Rko9%ToXdp7NY-;^MSPbq7xb)?=ptqpdu;}4g)GLyNLRJ%E z^w=5O0pGp{A;_jvLiQ3lQg};%v#<~P9>?2x%7H))$DY%>z_$@6Y_2QQLsyokH@>?28o;FoKZE0#~XaG{T zJ}Ym1RxU``PfMS+mI?owbH4hrthKqIuJ%Dy)s?$<_iXrRR_d6++jeX(Dk-jSY^bcR zdX)Bf+m7usX3d;BecIafpB(-COlD4DbzO6HeN#qG?%ECOIg?Q=7Kem{#Ky+z_4?ku zd*fS61`=O>P3xpzBbARCq@hMDy%Hbb6IeufqHO{I6E46^q4kZ&^)HP>{dBKZ+iMg9E+7i$W$Szj^%6e@lP$D(lt1KWr*L znRRz}!Q%ssWhb*A?6qlwJBdV5y*dnx550JL=JzkIRTrL4zkh1fpcr|0keOvoyjibj zjb`3r6XYOd0)d0jd8yqJG71=B0QVS(4ak_gETfMbGe%Kl+qUFaAf+B6X`rSd4b2lfp;1nETD2i_Iv*C@S#6oZ|C z+R)R{;sc`rIta-%2+_Dqd`NKJ!y4(Ee1N(Q{|Q|(4JJ~C^s_rm8nsd(iDZsmL>v$Jry5~0omFqB3U}TFH#KT&x7LpjN^UydvCYfAPO|AX@?XjmmP+VR= zL$JMF|2hD>E|Bj2vba`XDWcjI%6#pW-7-UbZMyltX^B*ZqN^#r4(9P4011|9Cf-SGE@S zUfORzTR$~_i}{h^`*=_SywYSA#bGkpP%&ie{M8D_ve(N}L;qgq_*p$euCJ={=Is2u z#_!*NF>~wrnIGtt(5JR<+Wc|db;n<|4sJ0_VnBGQCK-bQ1!cvKK`mCI0+LZSRjDB- zaD05EivffJxCbC>5>EU1)6W^COS(7!Ch`s?Somb=JIc;?baa#-KY(K96Fwhs3|T(> zZyR~GX#e@%2912BAQ|R+Ud2(QbUR-h36wqgOdp}q>gor0vI7H&i_n&$&s}vt{w)!F z-CS$7Tpl4DZTSdscjfJ$VRfm{vtYeQ+9!<}K&eSY6j~v5j2WcR1b0jJa%SQBA#=iv zlGkDFDc~x}{w7V9)`wNBSTd+nt617=L2O$vr~^bo>AceUNo8z+DfHE`b{MmC;m_?O z&Vf6Ai6O8>x(8i>&AYbaOoFTOXYsVO;H;9DiUTg472-Txie;J(+wHX1fk;aRTzQp) zOPfDjnwl;pZAYK4#)*lB_knwh4dfZs+3N3`3+LNx+uIE$Yendx$`}R6msFQ8Hlv=l zP)_I%XM_nZ*PQfYc1~|m%XjcKpE_S>PeU`*($Tm2aM1TW}{2E;FuT1x5Uu z%mg-+W2;}4x6?1*a6`#?mg*@=9%`Af<1ys?*u|oPVaWYUgL);MSaB2O~ zoULzgknIPED8b==AVJq_CAAbWaUjX8L8AI*VWIkNCoP6a|m?thb_=)R6z3tCjH z6PlDGPh_C^3O8QAbaBFjByx4v4EN}=5!aQ1PzU5NhcwEH;z)AfAf|so|3`2uG?$$JP57M)iAx!7`GQXe`2& zfRqfYKyM#wkuT>92%3G9EmayDEHArBf;bM|ClIK3E9gErvCY-y_q`vu!rQ(gJ;T|O zSrZ~v3TgKBy4=qwz(YKQ)?v?ii`_Qu_E5de^_}=!$hG;nBzV&4qIQ3n>HPgQ`nee? zLzf(SE{${`u$uE`B%%J;Tv{B;;LUCQ2r@}e{5DgYK8OHBhhkV$7BIWwyUkrn{!gPp1iKp;JuALI+ViD(3tD8U8}%yF)m-RP)P1DY3II{C%O zA%oWB-9S;vZ)aTY*}o`~_<`jtW*;&)HeLBou{B{P)Dg8*s;W!~hUta3j(2CZor3CT zUq(X1lJN@sKUbfB@6y^s;gg}6I{bVeu>vKVoDKX#h45E*@+%x-o7)!GPc|(&ctW*XF* zX$?)CX10&}*}6^q8(qeA%+z6XW}8=7RXQW-h#*37mN&)-k=P+b9IRyLAj^cM^ff#v z7El^ipTs)fnw3Jnfk*=3C#)!|M$CP&AP10Uf?0k6Lg=`rVB2_c5Psk}F|0&L0e%o! z`M-&xrRLeu1fIn|R6bzvMZYTu`EB@^=|ZE8*9$+9y;~;clD^?-=qhFM>7xE{d9y~<)K@J%?C=@9Vn6L_(M2?!%b~$AQW{x)-_imnRnd9 zuctPp@B<(2O6rRV2l3=5Bwr{w61#(oyzL%q#;5(o2W~EFs_(Mmy}I>dT@*CIN=jA^ z=Oq4Lb@ca~u<*0z(~vq0u8yzQQfS|=fdO0G8s4@}^X)Y$n$nU9;>ee7V)@ky|!s69+STFTUbnf-5IY&rgWMj zy3;wk(;<>o(H$yiPT*v~TbwoEWJu#=%HZNeX5zs0SkZl68K0(3r8i-;%wJu%d0YQm zg3qMSS#`TRS(}NqY4yIelbXAX=;u*5|L5p%MZjC{x}6`G-o_m!Q;JSWXq87npZL|F}B`hKFgU0PlQPD0CocYD!JeEt~sKkBx-?x+K!O&&<#A5u>-+Vz?JGb^I=H>9I}>5M*;Z?~GAxxiGMUa(2=u!z*Sh{a zYT^OSEB!Q)e&woP6GqJW<;oScYf-S_-U+Wy(c#YO*5ZZXZ0TGb15rKRdmHkps)ecm z(WNk4l`3gVelPy#PgIXz6ti~48YN0HgVK?!ef1$>VKB+kyL4VlA|^%oP=Y@Sqje3Z zdYZLM7vA>-bWeXgA+mlQ6QDF>Et1FRKV)Svoh5Vss$xl_g=%8o&_B6984jJnL0ZAQ zuB7ADN^x#1*-;VuoQtSzki*DLKB%s)*mzhWxNGrgl_Wr2dqDgdJ6(`-9r@ngg)v*G ztvB=d{2loDG)?@4U$CVu>XRLG-9shoWTbjm(Zl;PVT-@r(P+N3k@TX>hx-eNrM4cO zT2)i2rQ@*v?K~F#g(FlFBds!lp@C>w@8JEK37Y}xegh9uDdaDeN0@>*NtWlQB23Jt zPeVlBSIpo^f(dwiC!hfRF=At|<&Z0iAXan>IT0jE?7yH8DD{vsZVmFC!MHO~RK!Nl z2T+*;sii8v@ z`rvNWdTPlOR~mWw;M)6_OL_6DqV`zdeP$*Dfv&UF@kXZUFW(i1LxHcGliSN|N2P2f zfuEAlKaIY}>w5O}tyK-+X0P=uH7)RfYHu@D1PZ+BImr#L`gTsfTAmM-S8BJ+RCn52 zh&XRm5$G&?{p&2xXD@9g-!~WeWobCQP_kD#Wh^IWj3`HjI3{ znP8iee!|w~kLTUNR*rV&k2&&WaeT7y!Ta$3&PI*k3G){=n7m7YP^(&S2Wi2z&)-D2 zbj*Z^6J3#jD1G7(0C(^K0$;$P4v@BZTrMcl!h?tfqlb45Mv9U6os52)tM~0UzF96; z)~Q+Had!e3Tw7Tr5KDJaQHUea)N$fNxH=7z6&4Hd8V*eaq*Agq>!(4^{XITFCixBR z?Ju4Q%y>Tp2YbhNGBzD5ofD_>xj%^FTQ;ucDgmIVUI92~-zp#xOXr4bg#Oi7e~EQ2 zpXwY7-GF$H+5}{wLP(O&!nY>BY51Zd4jRE);$S>(VtH-Zd?sxOV31?A=2sepU0Z zkySsPcL{!UwWHtyf0^w{I`>2Sk$!{6-}wSuw|tvFWj^ZfJ2unNciJ4)whSGwV(zEY znTOES6G*x}E+@;;0j04FTRqzEd+O$f1A)`kXTW%KW$^BHfQmesIZ8;Q-B26ehfR}Z z_xIx33k@n)e%0Tov9#<#9g* zZQR5mHa2!7=1eZTH{6Y7T@b_Xu;g&1U?pb9UyqaOtE&s-3K>~k`UV~z;`O4`d5W+^ zL`1*pICbb#>2>P$j;k5&;A7--668yj0XbA}j}Y-L-Cw|L0&viN2{_f;<@>;9_?~`j z!_~jg5^aemNEJ9@(N>2IU;umz9JaEHz4{v3;%iyA#oNH!D~=2QA^GS$cIUVNgCBq2i+32(vmLs<9iV&q-hP~#3;1BVX&WTbkj>zNQO|6895`qo zM*8p|3wDftKN$sTy$Pso0P2yNyVIiAS2(qo@ow&UWW3itlBqQGRPx3@R6yzqIKA9NP zfrU{xrrp)T{_e+#kIV0`849k8KXA>aY<=2$Iv(v@H~l}Cv#z&OIC!~Oh43%@^?h7i zf_eo_WSxY~?23A9-Qr?Hu)2QUdZpTmrlZV#3G|5z=cdwGX!!Urd~k({2x=6B$>+_IUf@mS(z$igDN$wI9D*si#NtzO zl7JDPp1{Sgnp_z-CN@SjE|ti#Ft5tX56^5sE}K^CyPfmeUY^Q8kfOt0xQ9 zpe&^8X+O2l`TYqFdgdu`nL%SKJ(7L=EOTT=j7vA(HLKFtT23~kO-|;~x6HI?5A={y(QSD&J znt|~7M}w7sCIomPjI%NO2u7nq)PxxnQt_kVqV$M=euJnV9WaG|rR0H9@U5e-0o0wI(koPU zA+Nws5CH-^jH}T(6#rPS2)Zn|60^(??mCbb(h-w#(R5uE`rtcdGxRoVfE9mkY}78u zZ5apC8Hr)!iWffzm6Una;&f1=aGV?hGA;Mx%k>t&c@^K>GjGr3Qd>?)LsgB#n}xh< z=k$3s-|I)_dR0wqu}r`w6Ycx})5gNoI?~L^gWX`jdsaa|p8+wSK_PG94?73E3%_Dm zLxmsjl}(=^t18y4o%pP*meCek_l!^*Nu1LFXwL2e-?Xx&LCvR@f zAiRcf3|L=pskLyau`n;b4y$}!$bWuLt*QhtME{sH9)@?9#Se}AUS;a&4)!_I-*}k` z;}t*fT6(_w6F2VH!@E+!}m@Wf}yvoXn zObGvOoZ8$@FMyrd=likm*KX(+&W|6JWo2os=1NvptXqiL;=2y3ZbYW!+T@9{IlMn< zcVWb6^TWuJZ&k+T@1q8zCX1pbNd?auosy~5aNHX@0xP|xj^%!+t~-gdM-gGYN#&vIG^6?SrXgacLx;f9+g|X)!*wcgqg>)mhkxt0uJfbIi@E`= zzu3szCgCQ?U;2KtSr9=RFf=$+up(YTL5$O`(Nj=q4q>mG@Kq&k&8sNEZ}u*uy`nfE zy?hoT2%O-=v`UTo=%6rS1<=g@`cnMuNk+vZ;P$SYlU{)(rLQk7L>^oneV4cR*Kb%s ziupo`V1j%uZb`&hS>Q_$+@(;VfN+C8n-7?zxIs$l3NZmgxfG3P1~z*EU@(&GXyKxI zJtE~WvS5`r5e?4II6D_R>%y3}MQ0%Y0$hw4e+p{J67EnXJD`XV@<9j0S+TQ-jha=p zE#AD|gyrvT_t<>w^87>g#r|A*S|Z^)^mZOf$vM|>9@|R?`;Op95IF=9^vrE&PlUf1 zlozCy8>U!VrWbmm*FpKk6p&}XuTJFoTfx))+R65K;OMc#8eBnc+Xag*yCk2!>ra<& zUR_6NyKml>m4)|PiHxb){8>g*`>(|OO#`bXOG{6l>lU`({B7}$fO;vxF;|;j$K~bX zuHu-VrmgkQ#dtN%cYB|Y!>)kxmEVhJZ-L-T;*RGxk}dkRk5h`Ft3_8=fAANVdwkdR zvAlFXF8Yt0)&Gn`;LPa~=TT!A;6$S-gc;iVFeQWMKT?i{;KCZApreS?KFq+A)Ya7q znvNRX0i-QzYHA3uz9cH;6gpjW47?EB6m=E$&~CHa_i@~n1(t-5kB=`N_xjS(;~L+O z^S7t#{~#NH&k+MdjC3fT3U+oUA|`dV(4iH9cS3$xMi#BqlvF+=i{02_xM<8AJ6($E z&mEOAMO1DayS>uzJ+^YGY&IdfJqfW$XXowoRbq)Opf1EtmwYvvj>60QjgG(WcKAO1 zUcg78a9sUr#nt#xJa^;Jp*P)tmo2!%;8HjYBI0RiX%q2r(EWQsoh)5!nGL3 zCZlTGJ~63%NOMHNZJ-txY8n?=ND(qMf$%o$@TYY5y^>Wd$yL#>!qv>LrX#W|x2Ciu zwIZ}5F>znblV@^HKPs~#uqM`1F;5{cw5umHJ2y5k^cd?m2QBYnH2OI%_5sTAj?jI7 zPI8s|Ix~0%N8wJ5jf*CSWEAa%?L`0!L4qj->1x79q=zUp63&~PrTrm@ zxO5r#7ms*F5*c(AA|jsH9}MMNR?%n)cq)Ju0iYeMll|)cxT4_#2M%rMIf}S2&-GPQ zXx026d{N(;d!y%>Ic&j4$SiAts~5>JAgrUNkZluJxt^y z8m{=C7J#Z?es8mV+LYY7OKAK4sseQ4?X$UiE$525s>FV@03Z8`F-_wY+S2pQ;tl!? zv7Nn8$9l2p1p3Tl5gE6fUZ6eIvBPS;N!gPAh=I%1>#FUY%k=Jh7M+&;;YKqqS=*Bh zf$!tJmgB_mM#!T`g2m<^IrUx1VwQ zBZGlxI(0%`ukH^zPW&(-N##p%@Xt6z9V0|UV1$NnFVOojr}+0~^^3l%M2 zFegRoz#A+L5-Dk+k)Swu2yc#tt(i=m!^y?v>0$DCKRKqX%tAqGVyvJCV%E%})Ji_2Q3zaynxct>Y@JG)mG zmj`F8E|tKn%FN8pgvZ3#6ADL)x_40={8p${cV1fhq5o{*yMHKxi>Z*5un^SeN`F1q zsBI1GR+K#NjvflBr0u<&WHqGQmHvprF+{Br%7OR@xx@OA&;H!Sm+(b(5vfE5$(T6~ z6b6$;4|}1U47LZOqVQ|(4bUeMyadHXHO43NBZP#)qbq9}bqXs8Ik`bG8fXL=WwXc! zQ4S>_T7TpvDuJ!@Q3*t+l3s?~$bvqU^`93`fQP`+FBmsrAqs%52M;3albYJM7aRmJ z$3oMI8<@d4Oaz+?X-JSRrcS2j;#yt)0@Y2Pd<9vK?GINZ8@GUopZK~mfvycz>9iowGCei*BO56)*O()qD55)9EgFNqoi^M!KER8ThClt|H8 z{^#Pt-MHB)jgGIq4{1{`R-J>hXr-sYN$q~h!#aCx){LnIOP0<@uy;K>LbW<6Eo^=hxd=3hZLDOwob16>?dcF zCBGV^tQlR-qP4k2o;+nzr53n3|C%s9rEgmx4tQ%AhAx-+*t$RO-G)z{*B1p~QFCQ6 z6u}PC5+h#I-JHh)Glxk8gtk>7&KY7ks48EfuV3M-Uab;XJZ|8{#l*zK#jk)!<)w<> z3#PL1;}Bz15x|LLi9=;+u{(>4#&YXDorBu8Mze*8m6eyCo`{}4Mik6GojU$*fkovM zn>s#i;*hC`*?(ir%y{qM;PzYMu!3v`FB=;$f0i4gCSk+N(e00(7Y9kxg{gM$(zf`4 ztJubJ*~g;!q{qw4_hlR-IhkXmv>4i>O*E8KZklkjr>>`Ie{RosVcAwKx@AqhlbI+- zwp5vF5rTEbuZ{OE`kj{kYdo_D!>D1^3W$t4bd(g$2qQ_X%d`L2`6xcC`OtY8tBFE$?zLOBj&*eP|{cGbA}Xled6N+ua1Zk75=a z_nZUs-(YPMyjV1YqvsmEkNdf3LDW={QVCGVNDJdI5Qlv9(;{(**n$oUUc&<^^j(pG ztYvk>9-+;I=>RTY|PR1F@7W35cdn2C~0R@EltSjRG+d zVz_&mLHJ?Bgu5sXZotz*WQCtcx2xRTw3P`PX7v!_@a75qdEkS+Fe5<+z@IM_r@5mr z%T^E|5Q>$U8fig1kVr^F2T&u2033sz5+!-0_|Mur*kEBS#+`aKAzd*0pMOM2Q>EN! z$%Es1NfT>yH*Z~@SG(4sVVE9cu#WUOrZ-p;zmS%a* zf$h62?QxskDJU3utdx`yqnew(5A`?Oq=DXb2No_PYH)?*6zSrdL}E<>=5$(aZX8aw zMS%zaHid*FFDn}r8w*VUxkzGMSBa5PwaGxFJdD#ZV2|64L*VrXV6J*Kv?KnjZz|v)b-%lD3 zqg)~@Eib=kr>3s1d^DYH9nC>qYE&$j$+T4-ZRA%E?INh)8p{Mw*e;%Kd{&WtKf0TW zy&o%ISWG8*Tp#BT#*{ZVvb{dEO=hxLeF_pJV*uX!0%Y!Fn|p)9{_vC$TK3R;8hD^M z4=ecx9QPObmoN`b6X727DJxuXpOGCTD^#{{n4&|$aj9d-I(^1E15z^vvQsXLc{TQ{ zG_(eN+M3L3dv!Crjy5CD>d5Bm_WH=e>XJUf(VpLGtfPaygRA4MlY<=|$MCdGWmjTg zVP<4Sjl`td+AF0Fr*9~uJ_lML5>XYq0l3U_4PKr$1NoM z94zth-m7gbn?)^mr{l`B2~)+eZ{*SmiHV?mLO%#KX#zl9A-o`d1f9@x3hl0dNkS?j z!A^!<_Lc0ANJ&W<)L|t+^$LRR@-sU3&LA(sJ|`EIz_xa_1Ph_D8egAU5Q8p}L5WqEs>M5od4a2Na3rB(m)aBF^ZMYroi2kur_i>-a5w1ff{m}Hx zl_Zsxl?}4pY+lFhfX$^rg?FbVPn1Tr=S=?Ha`r0y$~~RU z$t$3YO|TbkAI9$vof6}e^CqtAb9(PkYM+J|;?Btv_II$=E_D<{LE$?OhpU7YE&KG? z^wJ#t{0xol8>aKbg8!CAV%?OH71K$k>@ay`+mL|`HonEmdB)Um3`YunL-SDCA6zE( zPNpRejwD`h6*oXh_ufhNGJ=`KUAHs1dkXDRa(tEHV03-orCCz>#cKTaT3K=I;>^1B zsb@ZCf%DLA0=$5MjYJ#(hxCQ5f5@07QqEL=yLbuQn6gwN+d$zaQX-F2Bf{vJYx_YI zI7XHrh0g6ylP5!(0Hmr=LV>MDAwY?cq6x9@FaA+(v0hI}OiWBmJGr_-!uAm4lO$CF zs@F-_p#KPxrGv{+n;U*7O+y>f#Y+Nnuyo;6CY2rlZO8(qWx$dD>(_DunT!hcQWlpZ z03Y;xxijV`V2B8?ssc`9w3vaiMEkasR%gJmy3n+0bQ=yO78`HqS!&AtQWAPv* zj{f~d{%4*ABez<^gO+sUCZ2%qVv@Uusr==LwGtFE;rtql#=`l_n~Tsg6U#H^I|Z@%yCM<;!%pZG4I zIy#?Q{QHcPKD0*%z*@E!B%qCFms;MDSdm#6SrM4ccXYrxJ+ZK~J~1_B;SWCBn+wB0|YD4%_&aPeW!#M;B(3zSPraCDWmu;tG??@@C(gb5vvgK1T6uu}|R zrX|D!krfGmr3L>3MhakV?c_kdy?F79daqis6N0>p5y`0`4jL2AQQ9MmVm(6!yo2Bq z6*cAPs;dDC)_BIAsp(68?%wviyq*gWpRlAk40IvIBl% zXqOH$1ahRm8nKB6Vt_7_Bq<6qLYW8c0pldwq8j}(4#f($Szf5uBk2g~9VZy`=Prfb zx!~FEKBLNwTk8_^%9L(H&=C{#KgUl zi-=5#1iBV!nftB4KdK$QV_;k#V;r0c!`*SWnye12n`V~Vn!lAJu8C(i3sqRMr!AGl z%V#(1yOk{%SuG&4cjGGc;M$y7bi7>r^f5lI?(aNo^E5p^rscFZo9?zwhi-`$Navw3 zUAc(PEvZ&7r=EPNtUG%R-CeGc;HF!HD$HLpvJyeZReP)vY<6$etgvlN!wHFAV!+3= zRp%37N%NzI8FgW<_aE@99&LJyS)1qQh6h4UGinH~B9 zAo1|<=;-JGz{_Trr>ltxxylHXVCX4bV4q*a-_h}CQsEsOJ4=7(AW`BWO@gbdD*!FX zJ-VMjUpq|R0Sy|DKjSnQBgGj-PzF45EvL((-Pa08(WAse2jKHIl9q!xNt~w zEFm5YV0h_uI&b=iSTvifpC0Yg`3>jSW&|)~+`du72mqesrHW$W{7H@2Qvwi7qGy55 zx350B)SA^ zM1@%GRord3nSeM6B)}K82->{Sy`Oi1grN>FKr#a#ff}*x(A`;!I}2Y#(`=76dLmF~ z&uRnUc$DZU6X3A0^biph{T9EnAr;i1E%BV9@RvR?xuoKZan%?H?**ls$=1psXe5UT zy-1{R@_9k-%WOJpnWIp4$b-7n?6qK2aJWPJ;z)pwQ4M_rZ*Qe=zGClFL@^;4w5(`^mC{_a|bAVPX7%RLmGe19%LGw!% zh%wdE%PTLZrl6ppp@A>ww{O!ToYSKJ9$^sp3X1fN8_(7aW`J&U4cLeeSK#!~QD8=j zh=?3drYi%^`d_~ufyo2_2PxEW@1UTd&|n}M?TO>fnw&@KR%MyfPfky5Yz626y&U0A zaZy=`Y|iL0Q(|HSvu=7$8Ko)akU1^ zxzTO@%rb4!TsS?w{6dNGW|!-~-abAc9zC9Bu&phWhI-t=!C};hI&mx}nut*9!1w6# zjUce?(#JaW)Cetf%E-};a}EfRVZ|p&!6%68ko)|Yy{uj<=q`!$p8CywCNI#_qP*g4 zqv+jUdVBC>o3q{Hl7_#(@2AhNv&FyV4;UW1eeiR1s)1vmj}JdE`1y5!QGF#(r0?(Z znPXFpB=o5x)SZJLW7w&EG5;(-V^hiEoITt4WCRz=VZl|D|CSZIwk3zhmhAViDP@^qUZFRRyf zhNUt@8b=-nbeZ%iq{xN@F~-Eox>+qbf-mp3jq4J_N`LhZXLkAf?*0Ks-x?M>Nio}GY#05t8i=S3&F{As#31A)%sediD6 z7Obf%?m`b>Ch1ubVE@XDqT{w6$kcCY{(4D{4HsjFEhF1Dt@`cXQ-k7tw7U-F zYK&XA^UiCrmdGzBBwCO!K8WSU;Zkc0hpfPI<@FUuS>dvW_HG~x09W7hkVxAxoo4e7 z9+%3zJb+4A(%Q;NN@@h0irCoL0MI9=*YnMIG7T~TKd&*|mTZbFxg+NfY7AQ~5V8Wn z4DfQKHVVHBR!a&TI7kLTI2B+BrqE>Q88Fph;$DRNorX*(5^?lMT!XR z8=zI?}xm>8sVF~FTUWzgl{?(x0eA3+Ah6spv!Uc5xy z+$kg9BuU*QU^p2DYreivrL6SVT++qK_Q}?OKLL+HgBZOQQVTBo2N&IvZ|z}L@v+DL zLSc4Osb}VlE1>al(f)Ed8Oz=3dESkcBk^vDy;h$jhivCI@CWrl-R%S3;m`P8So>R8 z`=HUAwA#4QuvsjIr?MbU_T)j*;X%<*H+OD5{unHht;4ND?2P3uKE#fxF4JvgsN)%!irtc>na-A9sJ6arJ+(9%tM&7(xkKcZ+tC5y}KlyCqcOiCJRl$3~I>=Tf z!i3R7hcu;LUKl9WS#i7Loe@TQ=ooeS#Il4W1O8YcB1f~vgietzw&baqyUbjI%PN5i zALsg-y4DBPn0D@-nqt8fRTVF*>Rg&5b|iQtAPwW+&C^qK1VU_VOav0VJPb0*TtVuz zELUPjUEP_9?i)*FxBY0)#Hx7WnwdEVLX%|^8_B>Kkxa$dET@shiA9gHhx>Z9^=feF z(e*R0^+Nf9w`N0+8prOxLn^V6Ulq92-9GCtKCPRKYU}F{(lwUvX9K;XnK|8`P%!Mo zMNt2(PV8wK2*WN_-69p&y_R;k=g{p}O^aFUT|O2Wtkgt{@iNiBq#=MFCIDTJhz1-u znNvuxu; zmj_BzGzb#nSqK~g8oC4EPY7GdN+;0L{vBDFuz!pSPdAsgMLw?06LfW5sWTh_R<@AP z5H9Y&V`T5%p6vYYijTXv(c;@{%Q|mU*IPhvDzHx^ARq`Ab-Ft^1>P|QDaxsniINgC zur5W)?A$_}lmxQ`?4Zd?e~uu$`u-Dw3Is)n5ii`KYk;)s_8T(!IhOzT6H&RFZNt*t zrMBVG&GjQar{pdh*F<4z$3}47tJa2ovwLf?!s%$03*UDq$rNW==28F@80z|xog}uXru!OaY zw2UZosF&7j=-6gFTIk2EDG<7j9Rylu8!yfz${5B*T z9vAq%rEq7n4>*=^*le`w^#yppJua=R0319@z!6JGs0T#R05r|1@$oglJp_oh2~QM= z<9mA{b|n@qfbt+%l42z?#43s`P>5LU5y*3=fjJpPGOA*hMudkSkP%zB&7({*3S@Q7 zSClMOZqss+l~u8`)6>$5>glN|EcBL?jO%DnR&i5Qt5vuiEA)N+9MIF{36;VQ)%W-R zL<=_p&R~wFGuVL~$aiaP-c>%eQ)XAESLPppuELN#^E-nM4jLL1Xl&XE#0EP>l9;Gy z{Fq9*Yp775mkRKP@Rz?9^`EP|=B#zSDl8R^Y3s z?m&F|h{U7S^B~4R*6>$_PU7BmxJboQ_;QD%ce)aJ4zU=m_ZJ$XmH9;e4 zQ*>C~d6dI1AyTkvCo5d#WX2H_4NKg-+#lxB=Vb6v@$=(5_xjl*`LH*~m^0e?X@Wx* z`|*>Ez}PXcI*W6|?%=ERJpZ{xVzO!UE5ZocWYho=3H>VA#f}$KvBn_8dW>mA5=|x2 ziI~O4BgGN+69l$&jFNuhHs`LGFc5^aK$ppLz@j9dgoGuHTX7uWpcVvEb3$rN&{%wn z9}vwRXwmD8U`TSSN$auoS|(K);>O9!4n_(JE%7BWA;Tcya9ChZ9y_X1V=Q8TrXc>7 zpvA0Ep_Z%?-S$_b1&YF=udwg@dVh_8Aepn;RoQ&MQfZ}eQDN?MQ3^B)Npm^|286Q6 zbqnODW^}e5ev6Z~=Vis$JD(hJ@7?wMyPo$?^?#8pXf{zjHHMO{3Zh8@(U=Nh@Uby4 z=(pyY>{V_rXC>3Kd2`L?&Q&;c)&6PGasw%tfz>8?$E)itbl~6&5ACl&?X9FmWBoT@ zQO&|VFWsniy+gjyp}}GFd8k0A`OCmHbm-)>X;UDZiDBaEV&%#buB==Nhs8o%yRNb+ zYvUR}5&8>F9AClZJLAUFqj#)576Xb|Hut6eRMQp#r1q&1I+%bg?=rgASnf0`^2;-XY z5WGmChgVl;7Z)(`jsgM%wze}jy@EUlBqI`^Be~r#Grn&wc^!0YKQYg)dpsV>t=F6D zR;?(YC3FcGkbj4sNN)FS4S&6^=YGBCe!br8ir^~<63^RRlWcKh%M!7qBhV-IVZZ?# zmCP}t&|opY!XH;8ajv6A%ww<51cp~%cY#*y-#OYE(zTERhf3zKRH!3|ckJg|_aJ=V zoO5dtE+y{I3bmbwsKCmP)moU+G;3Q*p+l@SB)?4Z)V32WPq_K=_%*-EPqgO7XHq07 ziU%p5{k_Ul!*)|iqb6maa#{KH_APu~g2^_ULVH+r@NEP>Pxd;4r3Tqn`y(Y%ziu}_ z1UebqKLB*mG0$4g#kCpjnFaNFt%FWjY^pSsl+16N)n=RJ_jJ4bG8Jm0!5PK>X#uEr z;a|}X!q&M1nE)hWzrf@C`WQws>>nb(|l@ptFr&pAai3xSA z+f1)+oa1Y@1Jem1T^5Yb04Q`E(V)SCY{#cWzk8v`i;lwQ*wpHYd9Jv9SmhJA z1jzc^IO>;3K>>{S%L^SL)xTTb5_s?}y29=0ED;k8m#W0Z$f1qL28E)ycc(t-7yCVAdl?i}s1B&@%-76{YAem$q>>x?BymZ| z%4e+c-GNXb@Ge5(H-H1WP`N$LA_;xM+ju$|8vrm_tZZ!7YmKmLv$Lm8{JF@Vyl}x_ zlQ3F!Ku|qgaKMzw#GwOJASyOC6mB~OHf z04pPA#X%&XdlprVV5FT##tr52ASUcU;sT-d(af>%B&A@}dG0j5h{`;E6hkhNF75ldwG%@aE6pBI!e9c5AE!Q*GjQW4U zGRfioOg?H>Ana6gUrKYGea&EwE9!ENb=8Lkt{+_1p8n0AvCWQ-zURxsr4_j<)4ukO zI!g_gn{;g-))I)?!70`7+ZF`;ZAstEW4R23gyi`@v6{_6A9zISN}Rtg&t-TP#WI@P zv$S!k>OkR8gXN<&n!WnQ7Q~3tS%Di75vY=epQ11?w!Or`pdS_#GxGo*A}P)RYOhvn z0%I{$DohX@s16YlEFZ7+7>|}h-Xjnh00wp!u!baH;^+2!R%P97Z-7`9jTAm*B60w= z1#J%LVcbg?G#NY^3!{Zko((7~mhXW0#)IWhr9VN6;ApF$Wd7dZ$|0_bE(l?0D2bwN*91exZLCyMu+igjW3dDJLc4sN?$5;W zoRFu&j8Z}tY-RFxZgwtqyov&n)I%SSZZhh`RD5*C6T?lB-{ocG_7?v9RKhPl`#cng z;k~Zjtgzy&V9u2L({h!aPd^M>ieqQc6I zALI2l5ZOGZIa~f7=*?#0?d&_Unfj!l#nslWH&Z~OJ9%!_%{Ke6SX4#8+?;V=1&E1+ zw)NOKx_r0!8E@vzD&KDM2aL*B%ycqkAD~34ey*^>Rr+d_6|VqGZ}DHX?GeAL`WqnWoM0u ziHCG_bi6*hxqGyGdbEEFhed#*BO;;)@YdASa3z z39#Z0q&cc<3lbz7BC(w~XyH55#lGTit@|gum67?qrM%+b_NmO2_i={q4>OOHLhBCJ zMdg>0>obm!`TulE56SO0whsdDieFW`MJ0uLW;c_Xn{73+sZpClAfaal6f@6!_F~RMCiuTIHQ30Q^!72(WqyqfjTd&h@ znIbK^y?aq?p9)CU8sJ+V#$CtDUlllrB)s^HHx7&eCl`qGH)6)Vzk#F$kH_bvN_&rU z0Ts7G2ZtcTLDh-N|H(Or`K`|=U=bN2=?2LPROP#$IS`Lk{#zu0^qy3i(ui8MK#M-u zLQb*{H5>xYatZDJBVQ3bNXdHjY5T$E-7~aOM$u65=|{d|T2|Jiv11U}R)*>X($#jo z;kl{RFH$xlqsu*WzK6q%<$vIEFK-;A;_f?B_<#_+kANq&;lx^ZRdGAnHAH$}a7Ere477#N(~`V+yyaPjP$wtzWN<0NZ@QtXyKZY3T3k?F(+5)r4KH z{I&rTn-`Xi3Wv%8!7HmJZ{!G!kz$wXa0{Z~Hfcz~Tk=0`G`0C?PN@ zVjzKJJTx@4o#rW1RwH{HVq&FQL1C`&WE(LnOJP&S7NXR^HW&!7D@wJn@zSU3mAvI;O`%0HVN^nE}3YKzA$B&4Kx`S^Hw zcmU_CHXp1qBpA_;?4YmO5dxQYFkeJZ7aIDax)d${n}{J}v{4FUFj7`_dPcg8@gv6< z{=ebWniMSB{BX$;-AC}J2w2&pJMfVHB0!jCJrMfG=WZ`43FW__^uj?lRrq`DvG}rd z$0u(^$ZXY?SAlK^PMbnCIyH;1!EgSct8I_?Q|p6o-$c$my`;)RS$}2Qt)ug^tc?@U zn5&)7lfNECDak$gaB|QlifpiQb?#1e0S{mM3!1qGqWLDmS$D#Jc4Lc;xmMMTyzhf* zNWE-5u!SMUgKu-&ZkS(+?iDYq=^NQ{=pppRrv7@;lk%7VglKVjoXe=)#2p}9$NAJt zjmr$uA3TbuyBD|sVi}$yB2?Sx38Dht1sN|hU6om=pl3%mOdYDT8cH8kiLZlHNjLV zih=3uKPa?A~4imYg?ZptsJMzFypw{GPv$`}r(Ce`HeoOj1{4O#3&JN%qu^?@-QN(JXPQR##_g) zk4j-0FHV29MX2kLV(^V_V!O#sO6N7W#iL`Dadu6RKDcN7Qf z!`vS)Hsp&b3{9Ao9I6+R20Gh0v!}M*>HLm`pU$`aDg?6XJ-Fx7Z41HwtEL6&D;6rReI&0(`tB=D=bTBmVrcv*;^K3bft z7ZXHT6b-b89mS%@B|P4r2vIm%BQ(|D#Igyo0B$a7w;PZG4+x(I?{q*_bBQ8@pn&|u z;Ri9DVFp z91{-{zf+-&qFI5#LM>tqvPC4amQD{SkW*HL8{s~oQ%*ln4B@{F$75j zX>mIdU77NkaSdBX7@*~58aXhnPp8KMA1fL;^Z-TFOQQH59{hZ&jUIP!F(U9h_%PQ| zg)f+%HWq{6$lvtqk~l2$i~V+CMq}f%&7K(td2Ot>ss56K8cJu{N@p5>{kE%l zOhsg{E8dnuwsw<0n1*e_G=iP;;or_gn>xI56 z%P)HCnkEa4Y0(Vk-|I(%$H}S4bC&HncOTJ$xaCX4x&o6W{f^9A>Df|+r18B?#d<-IH|xuYhrqXtPXz}!RI0qhny?BPR1 zLqy{7gP+|#l5p!NW+=N_?v*m8q}MX<`_)t+HZNh%k5*Y z_d{2fiO}z%rHI?_txNygvX7u9eW9^QP0MrHdxx0E@=I#-*&q7{S4~Zgtk2K4e}5_r zs3~c|!9REi-l+}kCdH!S;*zDs;jt!k8&1$+T!p^@ghxhNT3SX%MoLOao#ZHRoB{Og z3RsFV)!r?HIGO?p%4E8Lz|+jtAMB^U2AwX3(^FQfiJp3#F_K0<)A&JiCyxUZz?4DA zzBJn5KXL=C)?Ifbq3FWE+`GY6y>-C0w4x3dZM<_FPOE3! z^{u>Ii_T61j?OxAmg+wyq49_>bJ8*Xg&EDdO?~1>-VQPzL~glc|Em~XY$8~$fL~Y) zTi|HjRDjH$4Cz#8J^H)%6h!IAEaa`4!p4?7921u?W9f~gPG;(TEAu#!zMsmNt?6dIIBjKvMC3<0&J# zLAOEM!hOQ)aIT?}2qxi+nLGf`0Q`!}#TB3odTNpXM*7oy8 zLkXkw+(TJMRk?sj0ohDd#?5N^zeWDQ-yVQ^k$vES5Nbd9D+6VsNoZE{O;sHrmGLjg zjTYjFICge^;j=*sC@n(%58J4E{!r>YmT9v9;PU%ox30h_qBl=u1hx3ACtk~L-y`3P zC`_*ScLK)Vr9q|OPnV}!u}p`QL*lKka(Nv5Ju~;$nG~T6n@_ug)ArA?uA%y>Md~)) zDa-b1gof;YHuOZ6G@sbtUmDTnT2x|*mR@fzJh}rv#&b3WJ>JHSG!2d(*;A3Ma$<1) zOthu01xN+?AcrEThXyQXY|+^n#E7ihN^F@2fht8bq^-N?bQnzn%2jUV_4$u6AWyIO zx^OhS|3fLai4$%8(7<#xEltR^i(0yXcE8 zSZYvd!+d%)kh8+P9&i{mydR)d>vB4Gdwbi~)&{6-?6*2v0g^N?uV-^JTbg3(zs8C{ zNCYTyetv=kGm>f_j8aL`E)_#Wrhwc&7o3w9fD8RbN2gJ(&u&)meut@D8t3i16UDR6 zDKC`J{(3$8Ft%W7i*R&h-|c*7G5s%$?xLoYNNplJVKl#9tLDdk1}run5+scf?#uwek%iL9)wm)C3X=qXw;d#vF&KQeK0|JL?o{jgtp2fbyD5^SbQpI=6cEWGz3Q8J}To~*^0xR3f+%ryps&A5N z?;`W-O-=J|pTwH|o>PZ3-Q(!TuwX|-=tWzi$A8zQ8^c-*O^ntbE2eYvyomb(2qv4J z{$_u_ao!rj$SZI=qsL`NWif6UMjaw82>rtcs#TbOUK$ZA%?jlxbx&|j*o4d>ze5Nj z=5Mk>D2}(&qb!JR$lk-dMrA6|_u8`;j|9%iDQvNG%t(>n+lR7Rk9$E+r z4m)tNLpbs%se#xdyVFr-4kJu04M&5BMoTKq4Eg{bLC1>wgMo=wrd*ZMiJN|g%kaDZ zsc?V@e}EF{RIJx$-w$OM0A!`BM8+8-u>f-90aKr}gT!|8gJ3=&Eh%d5xi%?YK}bWV zJ%ocx$00`V^4M)ie0ftkx@78f@>u@6TB>NT0Y__er5M7ep_}3G{<0Yr{~4K6Qm>%? z!oU%d{XpGr4G(pugoh8mJbmb8oc5$OvA(r6Po&%Iy>}i4`6TDQAVj~=w26ybi8r@| z&(Y{*S2e3;G26{)V-uahiy|2vY7PvO>gxVZ|B|KNfHmNcG)kw`?&Q1*kI0(K5`XrN zxRP8bY}sRKN+{!NX51j~f;8y0f4wW7OCYE%1=Oz4tZd%a^3=xf#(bw2J2z%pZNP~J z)Ycj&8;u-o-$&`d$rF%@HV7BZp91Zc7;t7lq#Gc512Xv609q1=6?yjl1X`wnEiwh@ zL!YmAfdSCb!9P-B#Oyc&9SEz1;Ou>1^QqktI>z@~NTzgt)U;#bDT4#Z5x1sL1uV!@8e9MZR26YxSyL;<7a0TZ=+zs$;yDIHkKbww!7)&N#En_QPXtx+yl|*Asl8J|Fsexwx`CUUvb~ZqZTOnkS zBlv^IVr$_6Uqg4lbE_A0cc+h9S0El>0iMaYqW~4?rr{&PZ$v#D5$ZJInbZE)CVAXv z4ismY(*VvGD3IVOv(1Eya<}d5%YQ=5YR){D9DkqCt)@% zAY7=2SDxdO^c_YVpX@gc7w8-d=(B$$z&Hb@3A=+a(7ouE%Q6@WQKh_fnl_jlff*V9 zH1cYgJf7U?WZA)p2)JTZB!+enu@F&TC#M9_0Q^q7{d5|1fQkrUL*Ci?WAB$0)w7x( z0lV_M8qLFg<@UiK)*{o;GIhX#`A8qxz zj4Jf}hIFaTM3rdOD+sTu#YE?JwqEW1b+u}!Df3Z*u8&yibr$9I=Z=9v0^13@u2A43 zi_j-4>-5IR6I$q(078iWky1+ zDF9)vc^3s5V3oAn?&`eoI!v07my{1r!(gWla_@dGD(Sx2JM6_Wi?Z^u=w>QtSPcv3wRtfD92X`GU&7g zt(>3?dII@DNFZowxdWZKvw(aD=;PX57Sw&cP3pw_YqBO~a@nt|$%=jS{C8a_JJ1qkPVl$mKbdHL2%#T=6>-*a;th%3x zq?toT2_E!hxnhToS{O(|Iitt7IAEYb(^ND2;AOjtP8r8z<pvd+d}_Vnd#Ge9!5+oJ z6D4doE^`Z&2dmECv8%PXjhxOFtoDzYvT#vOVz4jaU}9qWG6}^#e&8W;2?lzBI5UAr zrAdQk2Di0?w1D`b$OQ*G7%qWa)ga+~1HrY^=0xFxSS2wAK?55+a%vTZG0bG<&s*Ff zQ6a&wI`ki};S0|bZKG;=*r^DP2M-0su?4{k zFM~0ybZqsgMpP!+Aw=OFFeXhMhoUDsd=h@-qmd32chnV(HNzxrQWY3c0Mg5#3#co@>%8Qtd%_hYyOnnT-VL)#cF z&y*TCF*%nBeLPHDdwtcn><5Ex)gP*ny*+K_AMVDdj+y?nbhzeSUO|ib{JN}4`BUc* zn$eh{^Sf$th^nxwx2UQaM`ufCEx-3l>5Giv*8&&>h13Vfsfbl?f5OfhQC->B=ew3N z{-KO03finAj3ybEyMe*Buz}e3&Emj~Q{0FjNog$dq7b=b#RG{g2t+I?9p0mV&Xyak z8@A1Z6%sstMkEmVerV}!-YwJ0%^xqTh?^x z;sn6|7@r1+c82$N2W2dmhG|wI(CiGmMvZGpTB%4$cTc*4G$W@cGFVv#meUmxbXrYs z9~thF=T2_WRV^l`7(3mp9x^a%f1=*NssN%*aaDSXpFNl2g|p$}1*+wGjn<2ggqao- zS#&Aa*LYQQ+Qtd&GL+*Z@)|TDw5JiY>E&P%Y1C*5w6KCXj4b(|pE+7u;hot6P2P(g z=gFyc7SY6PP$qLGtZ1XyivMs=e0@GI;wLkO7BW7|~Hc#r=R5=w988oQcD5 zkBzb#L&3~^RoRhX8qOe^RL6*5t&Uav2zj%gt6(hIF&3CG&mL~%6DqIKZ_fvgr%MO4tTBp3b1+FTenh17F;W@1WE;!^X4`!c!%-3_V&(8VM>j95`=P~+yM#eH)ggp91nP5A)&|X6qfO4QZ&DuiAm5CRtpHv z23Q(UOe=aAEENX2fmqT=c$(-5QNsaohl1pQKCxhgGL{Rl3v0mb5Dl9fxC=VMN5bJm zNwyXX@d~JYY9JRdxhuuVWMx%F-MBlz{bBNXPSTJx5FM9AB&dIv+JO?9CrKj&&>)&h z1P%krJAZn*{V<&|oC^m46mBux6iKPK$05kog9AJzz z2ov88SxJuK8>}Krm8eWZ0hrKBzk`Flr^&zWis4UV{Ok4=_;QjiEhpJy62UG zG71Z`;6S+rHXlv)q%8!u6sfYspw7MJ?y*^H`tzf|qTBmn@7G7nw$0er-Q~Ve8u9%? zcB{eX;OcwvOBmKRt-!{-M@8w2o1Cka=6+1G!#ZLcAmA|{*Vkqj;I4OgcnBzafc|A4TU%RiZ~k<7MQLe&7g!Vl zGIH{&T@uc0MFr{b{kxx?l%%AJREb)5RX1))FgwcOXk?ty?c(sFjMT?HpNWve=8E{l z_?OtYyHv?2taGdFZVr4d9@|Bu>4%ub=+tHqkZ*(3;^;CzYY1x)oLW8NJn>>mRCft~ z6|?4x(#lLrPmRc{P{|IWb*WLw%O^w>lXYo{7pd-z!p^c7Z4o`jix9~jEAbn6yL`N2 z(lgr4r^LL3P;1Z|T?-FPuJ8^{k(zS!7dPC$(p z)Byx4+Mbqt8=VXz>YbR_yOo-#Qyn|SfW_QE^j?9))&I2s0BmTkm_d*&92rgi`!qT_ zy5WRo;|}RgE-iW9l6{2agR(=?ildMuGl=VcFqdSNOT zr*AY2vULqSWls(^{zxoRkpv{`UO)E&H&JHa(M%dWU82Iy^~j7B8-sw=QDr5to76`m z8yXt!?_C&E&(F{K>^HcTl%}t*uK_NOCIE~EV%2U&8jGhyMH(J)o zR~|rg}1>mo}(P6OC&_gC08gbY>cnyAut^E>~i2tkG zpEeXuBO=bKaICDauD{rt8EuLp0y)8R91V&p-U9+dQ&5msW~f*g%PToin5f2jG9klN z^)JWaf>;$;1b$O2qdMyu|^H#Qf)xF7#_F!=#;|n`IEY)T~*nNmU?4r0l)kAt1PXG z!J=Z1WYOvb7Gpm}Ebb+7h3IAneb!oj_s7vr8$qFl%W;#C=2%R2nD1 zCCtZ0L^WMk(vdSf+>e%kFE$oa{yIC4%LU5n+uFQ<^1^R`J+{eKTTKlk0L?TyI5=3i zv`&k@xVTsyXx?@WOQqKyxZ^eQE!3e+mE(!Uj0lAN5o9kG)@!c4FKq|8DS0?N>q>Qp zyWi+B`tFnbYY&~Qv4Q{BZ41XamW7!GqYl5r+I`j$8}!v{?`xu^?02b$6t+-PvsVnuQA;M*t+Szz(2f@kkcHXtGW! z<0XsJt5%qz?rJa;8(J=gB7V~$+T`>5yy%dK8m1~{^+K<}rfOfWl&mz`DUy~K2S5A5 zsI!ustif|C#0B-Etx}z&rBN(DR7WT^_T(6+)zVxFg6<_LaOVj4nIrAH|IYFZ$1P)Z5LJw!)#exF+Q?88BAG6!j(b{rj zMl#$MEGFc@vM>T$2U=0AVi7C@Hd(S0V{`dH@DW;zKWjT9i+KtB{U4J~Q{lO|;khLq zM2gWK0)&m|FO`p|Xap%WqFM_88|;UsQY@&5krW89og2TJ*pP`PwheS^PYx%Y`b6JD zCZ!fb%bWQK{|;#;nTynGd6B;(;C?>~gZR{9BtrIv0K+QoOB$7;I9#R%7paOL!Q!ny)pH@XXX0l+d-6@O= zK2z>Dzq{8p17DA&Mc=Q)7A+s< z*zNlwMiV%&iLc$Fk5AjM4yb*^&O3~HVBJY=PyX%BtljfNu7S>3K^ z1a+2Ch*SBk_6~r)BuOCq6bh=2J}N~TW-0uRBOM_p=W4!0q1F3k@Agm*_>VT*)r9@w zbA0?bYKnpXRNO_Xun|>obH-xwwjg}`Nc~vjb(S>CxZ2%@2AEYjorY7jL$3;+x|43} z6Rpnw?L^1j_m8&T7qk8U}7?G4=?%VZ0-%0cZ2kxf5qaR?F&fL-q38+wG=+c=x=sqm8UN; z7s}&WH{(uo5a(uPU;I07G99hlY=vD^ zjq6qU`J`x8BXef((^ e;?Lw>-6`BikAok=T^KmL|DA)2W>ec#ex8&K@aH2^q1yE zYZP=VOVn^J2zW1H7HwM}o!@a!DlhI+DE$3hHbjHmf`)SZj|*>z>ZB8I(C7%WPPsfq z3dC%~hWY;f9yxH73>Q-u7Y*s!NhWHSDGm-vhJ}X4;;W9v?6E@X+qRV!WMRaH|a7p9T4OB)P{S`ijE-#3bs)s__uS9>*Mb zq}Rx`%4OrAVAt_gzIE9d6JJT#n1FbJoJ*Adb_g5j%Tz{)=*}?4N=n>qfQm-`^-J7143cWC*b{1qFG?**Hj9LiepY0~8b$ z5s;e!=@T*zbI;%nhw%W6kdP1%e7>_|*s3>m#~UMAtUSWZgs*EIHtr9~4JMXv(8~!O zJUFOGW%BzI4}%Ui{i9J>L>VoYvPvUL4Atw?rbe<8)jJD=^M(#=sRjHxWHC68lbyi$ zl>8ie*3pHR@T^SBN>G$j%}_Ysq^C84`?1Hgmp7o5Dv^|o3_%T#d`^K1d<<-+?j|#2 zE5-!OEnrYNU4=h7Hg+K2a4m>pvW^|XMwl}N&eRBfCd`^t{2bRK?K-?nbfjg!O6bac z#5#1`e}Qup&!2-p7dndp3$3S3l{PH8aM60fx>&NXz-nxJdwE!nWDPIG>1~PO>B`&p zc8F_5|Q4zDPC_w+0r&_1ox@!86P5$m?qcZti|> zkDK-Xy1MQrqvVvX7KsH^*-gAurGG<@m-YACj;AoJ*O|$go0rH_VW6NcLNL-MjzUBh z6&}FV3QTyPKR#p+LISsn=6@SB)hpQ<8T>9MI~^Sihljs-V%2F(NlE+u;`$2enXjZ5 z%*J1ku^b9hCFT=J+(kEUTZSHE;59Z^Z&!NW#Vv5zZvIG1Nx?!#-#D_=a^YsblvF*07~iE6@~`~0Yp7>(!5pgYJZ;%Xp%)GmyCYAA-p{PTK%2xBY3`E zS{?Nk?puCS;`)v4uiuZiFriN0^_zoCuDB_KzuTJWxe2y1@`^1khkKzL4{R3Gye=(Q z(wnvF70XeSa50iVHh<5o8Xcy;FiHs`RpRO&)$ef0tc*q%EjL#6$5Y(SSN9=zlP@ox zF$$9vOUF-0t_iA3(|wB&OLp z-8U!A>WrZqv|`>7yb=pfQdR{LB%OS%>O%Efl79=#uhOSODZec2{eHOLo;-q^Mg5U8 z|F_2ab9n8(Gt=pB77e$%?Rp5h1hPGW=iRH9=6Yey6t+Ggliw!B-A(**Y6-ZT<7Wy6A_<7Guf#X$>ZgjFp40h`dWAr6!u9zf8wfXpWrn)D$`ZU%-pE9O{h zHF{}Ztc(c!k^}l`feOso8AsdK`*M5xzw~m$!*Qx{L9_VX+7> zRDi!Fl@S{c4~>9;1}iEQnV1LzBiJU>OuKy(iH`?Esby@!oUNZ3z!QPp(!UuBfD`#} z*ccbbryPC#^OL_C!oo_|afEX7?fdm#pYGrvpOA4b*~T~oSPGh0|2#M|4)@%7OAdjuL-;tabt!BWahMLmo_0~)%Dnd7mJ>g4jZ_}A7j~R# zBx<;pf+Qcmh^RCm8!=vagbKs~u7ir&|Bmzz?<0g{p>m?Xgnq>$K0BG!awcU%!%NMS%(Qej0!l+fa+fMk~i_66?Qz7A1= zSnTn4KwVcYJF~E;7#R_xOJB366faum6N7FFOOI3f$T|w&;x+d3rZZ@to6mMEc3-N1OXb%N zXx6N<^YctjC#7uqh{=itehSmGn8TZr5Rl&bvi|jk{PoQA-^R(c;>E`1;FP9MtY|cD zjXXlYlPy)Yu4%CW0`E#EwVTejRt^Xk_qH$GWmSvZU?ceF? z)!rVf?FzHfvGYxd#F`b*d!GlfJNZIB^&gQfguQ zb>yPGp0#V(`hAQiNJfyVk&puW@-Q%wFNqL*GKl zc0{7J?c(ZmwjX?cmk;xr&0X9-AI^4zpqnqY>MJ|EC(qQsllSAs(9z7cwV>bAmA%b*=TvOU)>UctWt>j;TiyQU2l20*uN>w*gw;SoeA2bp7Mg1t zi;#idMo1$FE(nX}MnQWUpN-Xz%KGz=nfsN8g2FpW`)vJc-EDqh_4>j~qhIGie`BSx zFOhY(w|w4Pc1Ly@5~)_zWr-VgYuQ*)pJbNVu^`74Xs}jTf(6af>Vcs4%MM=O0@-}aQg zUQ=^FKOBTUh5>Hj&j2Wz?B`FgAaWi#TH6;p$y$muqeZH3)oR}Y#Y7*VDn!cNnR0mXyT4#yN05l$r; z_cw3)SyvgCYl8+`5{@E^kr||%Z!KvzwglKwu%6Vn=17gb^7klYy8W)uNAP-*_87f- zj&3MFoRA>A1O5zLLhpu*oQpg4TJ=8#25^vE%y@!yQDiS#bL^wS@Nol?Dp}#;cEdkJ zguMyPnocIM1cv94tcUQUd3!DXsJ?o|-Qw|xV&Jg5?Bw|}`moJYZM6P8URw+;nO8ra zQYYq7{hcf1cRY1yvpli4q8yqa5u)4BAX^o$TbZSIhL5k9E7QJv;FI+o$p^) z_xAivL&fDyyMtdu$SXv91hXiS`=i;H&N!89IGc5Ivw)SIgO!aRU3AHX$I{YgL*pf` zy`6(@+gk3ui{P*Ay9=>@^?zfbnR0*@(*5h!ql8<5an|9?WLBoug;Wa~plAr+4lhKn zSQRpgvi^waPkBX!(9e!5>B;*n`4qF`$xQdNh4O*|vSL-MS}h=a2XIu-$j0Dd^jrR9 zv0pno-`a_*%8u9hb|a)- zx5@rHO?jT-Pc@fH)ha`mZeh;9-gUjHV;J)m6S4|&Pmj0?^%Fx1__3S>0*fwAhf96n zh}3tHPb-DShj7U=B12XjvJtCeT6P_)WEj+ovdOBXCYFt(_o&rI_+m^fX;^M-Cz@cU zg}l%t-^+ui@MOR3-$$NknH&u~UySZMl@w7^4yQ5jW^Sha#z9B5O8hoJL_{8jfVBS-BIx|^yr5_kn})G7#3h(MuQ)i_88@o-2;sYGxO(gY+wKX;7!-37 z3?2m?1hw!0ii--GOt$n^u*SX)B_Xc|59tnsvkGBIdYrr{(7Hz69;swbZ&=TpA>deZMy3SEwm&xcXe zc(LjioAq6lwjW(StrC1G4jatl)~cbamKDinu5{`2(iL!1ip07Z-Dl$ZyQAc~PxiTW zPEAHHYF>*jzN;AheYPKS1e<~KUh{n`gcWlZ7ALGGX6qW}KkVo~KOe9=vz3Ca58R)0 zx_z$2mNkia4LUu2a!CM}tn^E5{iRSU4PnfMBHAOmG-J3vrMeW@Mz%f^!TYPH)Uk73 z6L?FmOS8aR{&@v3(VpA{?SI`3MwKcoGiqj)ZM)StxsE=z&e!$PzZ$Yp$HL814y?_g znd}vW(5DXs-ya=S6t|CwiGS`7t;@-#&_76E0Hf_R{@=|9@ zO0}z0N%t+O)(Vh`F7v;S_A?CS2^+*nV&W2F;t&KcxrGHOqheylClPRQGM-gvD%l_t zuV~a$4d4ad_N1r5I!ab2a655 z1%U<+0zvPzigV=}TL*_~pwNA1r)Opc#c0#%zNKIUxiYv5^hGocd)M*jdns}5u?SiA zD&qo*R}g>Y_l)Hz^?I54i)&g04RhE9QV z1#?7TBCNsjhyMegjt>+2=7A)P&Y{FwmP!wDFanT3_s{<1J0V)kASXsfoZQ%UobW&M zf6FA73HK4-Ml33!%m$+_AXF4KG(;|{bmYv=(dG9PpqKpN)^i3*><~2>i7R-1ciXK8cK%wP$Rcv!haINF2n4PuyzVHJy+F8dkCd1k11M zPgjR&O{8(o({zkmLm?M|ui9fz&GmlGX(sQVokzCcXUm5=zQ^ch#$qL1YNaI_v0M67 zzU~ZYZMKMyKbx+vXz5^Fn6ct8=|2~oE|^s;66Bh$YP4Jf*{VSFW8?Z|YPJ8*|7!uX zwYA;a3GJb!>KlRXg5S^I8+B+CWq^65QK?tQ;CC0D{=Gp*!O}9kU(x2bw5cQa4qpI1 zGx@O}+0%^@1d2?y0)4W$q|_+JE%3O`R^;NOVx%Qqb%^%M4d~OWjsM%Pr7kVs;xriv zYxaxFpmV|dY3rpR0r4h+Q|X@(R6QdVr>GVMO_fG*10G_7202!g8eXd^!*^@UT^1vN zSE5QBWhqzH*Vp&FU&$Y#c{?rHUw5}vl9B85y&FoYS~qnnR;@~)J>dPp{3nnCjKuK} zK12_`RBhY?yxnrNZ!bX~7*{GbI4Wg;fG5I8UN$*&o(+qydcH!dlb=2^4%enGq?W#V ziPbvA#6?oW!W1WndFH`A7?m_UZNqTBgeD&{a*hsBQeV$o&28%0iVY}dN+QU`A>!kt zr(46zMIp>ZQLsu53WFi)>hjSK$6<9US|5qG2WHjB`w&PukgM&#CuMyxX7Dpk{G76YxDXg5JKXd zKZHW3zzNMQST2B8O-jp*b}(Rtt_>B|r`=1TXzc`8!)0Jm&0$bHB(%4W((?T!V0B^X zf0ArYkwt9UBf{6`W22J6g4`#H67Mct|Kd)xPdE`LdgqB)fgmLCP{6~6?RNV?5#D-e zA@@74X5WA3ACSz|md8R^1**K2ZAPH=Azi`PZ+#E7WIKE36*@P~)l>>x=GL|ZFKqo5Hdp87A6nY)jE>itx_vw!cC+_2nbg>`Y4}%bipzhVhtxxA zPG2xG>9DiJL^T9YQ!!u7Q<`I6`3XG_bEJQWDY|A?4 zhoEN}7)d`TXkA~6zcJ+3R3>HecsK;iMxv5Gwo*P8lS`EdruCcGgjRgg&U@njieXJo z*$e)7ydFw`NkbKW*kAPtR7#BaNTqPd)JA6ssFbw%#&-2qs- zBnkk&h%QmaloeKoxCf80#1>KJ-TwqsVjY((Kw1dCJ}^>FgY~%)6%;0lcff3iW4ta` zm^0YvWXc1n$&94cgF(G9-`v6P&+WDgYe9qB=PZNT$;=~yYW%jW zQ|l=YECnqQ*}CxtTOF9NU_Z0U=(__ei-$Ae|XM%(NY6HEgi4POXV>Ia~?^pQpm?;Jw9@9U1RWX zM!s%Bm3~sOF8?Ywxdg9(HmiU{8+Ybr3ysr!U0UA*EwuaeANn7Tj{hRzV<-)TIMB0cca}d16N!yh^}l#b25_shBbwN{udZGx$^KM)NJyR6$7&b}YCAk7Ze68J z#kN=dvlsB3alAD4H2GK>daXLnbk}QD_Bz#@Z7sRfoc?FW-O)dMt3D|D7yh}qL#j>z+xF+8kAF+O z6Pd?nr8%X-q%ObTSFaB?V^*8{vGsS8%Lo(oilr%I?U$WT##yYZovy0tT>Ufer<2^T zjkjq4*mEb|vb6JgC?#$;SD4Ocr<0Vbu&UB2R4)&KHG)c1DMqErVDn0ugGHQ7Tj*zA zTUa=dOP$_)-&+d`a~~V4V5OE{``zAUsyRCwO1}KpU^A^Dn>7Wg^CkOrUeB?E>z3M%$)RgW z$?>ve9a5)rE^SWU1&$<9+WTy|1w5X9YY&0MB!0K0i*lf+GdqbxkZcYQ%RV+L4tThQ zM<8n2nEvgDZofxO`u!hiM!@4#2C@#WuOAjmaC!uQg6HP|drW}_2@MIEcL0OUnL*^g zHY404d_(?)?L$MM5wWlZQG(K1M7I2r4 zLDUDT%nXisRhSbl&ff{e zTT4ONHMp0+i3j#ktU7zEM-+e8BV$p;F`7nQwNs>m3+8veawK?=caYe-m}ubZ!}&gk zleiFeDga6hmlkcedhYjb;=fh6X{a9^A1Z3MF?()h71h=@3}OJw;}3PS5)tEeO}F>v zY2o@=Me0AT+!o)zKVLB1R8s6!VvQcT2jAr<&$Nf^#!Z^4W0|y4wSF+)oOHE@Juy~p z)}L5D{IRik^1i$6i|bSpyccxvdAfcg$xIr!{xy1QR05AU-x!&hu`{C_wl}^S zig!o%zcU%=om~08_lIe2`+V)3)@Kq{aZPhwu61yJ8>35z;`jJr0vp9FHDJS@(bLld zyhB5cz`(%z`uhoE*)^yVNl0nfoZnv`Y*HEZJFMo1>Mb%$r$-XT0_DyBN7Fe5*V(pR zICdI0X5%!r+1O4R+fHLNwr$(CZQHi3e)sdvd^4Gy?7w^Goa?^Mwbrq0OmCkYkJIOd zi-80MY?jL~ru=(1_-ghJtN!5|gNMXw7Mjek=~QZm!QsXI@i!G!t0`@6FR{_FRY!6M z&Bc(vbRBE9$4!HTZCU>w=5_z=7yJAh_W5#jQCojKQi}cayM%JZjBSJ!E^I07r%Bin zFbw{qCs>h1j9AhkX$}$JYex>}DlR4p$G_Wb)p_3~oI+bzOlR>kdmW+M5>B(8t7da; zS~Uj7vnh~7cn;Wz7U!Dz&sxFP*JsF9B~U3lM5gu5Eq;4>`BB8NwGBuXU z2Pj1mkkXk6cD@giI#b3t+@2n%|&+?&&l z&<@{$c}lPTpg(&&I#TE*gdc}hAVe36V+44g9~doeISMjiOys;jH{=_v{vIK%FPG%7 z`6JYl(NQG1tgRlRXy)j|d_^<;UeRX}8~5u@c8rZUs(^d}4EGU1yr==i+uc540KBQ;yQO}jaj_SUv}UQUa< zzpA@GFZsW|<_GVS`zBQzm8s!i_a3-9Wo%h+IXa_EAOjPQ5j$k%l(-7DgcTAdO&o!O zVnGy(NG)=tOfK5;;UQG{0w#WDd!VCKmB_#5~dAX^+sFDxULaL2LIPqxTVb~H`5Lasec>wB-!Ch*D5+?3Mbje^xR`|5$mUHaP8nPzb7?8) z<27ly{ZMTW_Sif|J>o9Qxx&CAgJWiLa&mlpy}y5ac$k}#l8BUa1hCy~Z?m(oh?FM$ zNWe>^W*~i-I(fvam{FI{MY!pZ|4qJ-2m@nRgB&K=^ySNA#K=Xn!+{f%xj<|WEySh} zuaGKY60&Fk`LZ_;NeWpE75a7H#V8M32k}Q-B%|k+|5f%6##B3K2d2&o{J3a8G0w+G z0!YA_KH(V;3e-*UJR{Ij7G;v~T`&@KrU3mkB2Hdb@6jI>@fX4Y?8G&oA=$ zUJVD(bf_s3?SKhkkoqA|3D|@HNFkG62fzD)Izc`bBSL|*+Nn?)5f;psE`P6c4%)ma zmIM-xf$dGh7c*OWq-T`=UmGVJ;M`M5=9hoANJ zm&|jtQbj{*-|5?&Tkl*qmm<%Z*eY?G-4$NOQl*V`9Bz+p$$m5aIh0xHwBFmg)Hn>} zR2iIqN}ejA(e3DV{WDnw8BC+Pq+;E&(D9rO9Gn;48*6XIrpNwORl$|`&s$Ait84bv zji0^iOCH%Z7rG>Q-rq*Z^$@o{4X^tN+X$bX_|C1oR-dkZd7OtoMVV%9PHzD!Fj6P| z*TU<|V&@S2@EtC-T4tHH&(+Hk^RQZmxz^@F&D+3iBQS<-c115+l|QPpGJE4@=07`{ zj|bnklCM2OU7B&lAg+@1Xp{HF-9Q5Q|wVgsO7Qi3cSZX3Gl< zBw~6t_xj)^?`%BniLJE~B=JWa!a{1Bthw)ja?U5tE`VbP=&J~DL-u$roU8J}ki9CO zG`~d5hKTomxX&xp0RD3{hoUSl$EKEs0i%Ufgu7aWu?yI?vbxvhbXi?=z+5N+N$aa^i?T#yf$*#VS4N96}b5gu&8N%$igt!v+6pk$s zM$tl1Tb5x9R+e#xjH!_t_pn3rDS=Z2>a_3~H#PLBk6|Qsxy8d*52UN@>gf=LEV@r^ ztkIJV$ReK?n_=Dda(MQLV@}%P^Z>2`;ZL-U@`f;z1rem!QGat$eTF$z-0T!|UN=dT zse_1wh1!r*vR?RI>Lg`p4$cw(?#{=1ujeTd}k0G_13y5WN) z3%G*@3T9?7wfr&P;aZxoMBxQMz^tE05MJ8r{R4fOP$+I-2kdXYi)4u!)YS8RRD~B1lA!+v`z~3fGT(!%k!_FOE(egj~SU+bYO{ z9Y^B#1GyH=fm!GarjlF?>ckL~NE%OpI3!LGAY)>uAz>>VdGe7eKoo~Lf-H*;qB<*& zkPqkx6d8p)#d~_-&`l(gId^9 zV<{|hvXMF6=r@)+qgGS9*3ndGyXY(JtlZu@x$=C;eU`AjR?;u9UH@!~61&W#wZ<2s zq`7@Xu@(Wj+WvdtVr$df%y)9-y0v**SN~{ix;~#(MZw?U^L5PM^>sEHNF(DhwE*;J zw0GrNxM?5Gy@At26KJj2nVpvApHHz{ce@ql9qRNi)6+M2`_z};@BapA^zhIDsr$`+ z#m1Jr#XDtTO2q2D`%DFi0IVeb5FRFc>-lt*RX+N=9=Q zoLWWf?2Nc(-tG=7HCfd<%8|v1*Q(#CUpM#nWb2Oe^Jq&Iy0dn7Ck>E?qUo{e#fsN1ucu| z%g5J0S6ZBfx0*H(ae;Lwo6l$3U}JEUm-nZtjyLEepf++A&W|jhhAqQPWG zHdu)MPy)(2529@^y&mm+6oCx_X7aRFP)iHKHM8CU5hiAAx|FcQ+P~NPRRE1MJG&$w zDlR;3CK|a(T5XD@n!hxnVv#CIJ3r@uUmS&x%Vzynu%hScCM@o`R}$_OdA&N*U5)I9KY1}R27 zJz?!0ahW76i!bkfYQKFWWQmBQw6qwz-tKfbdiaYGP9dFXl$~Xqo~EC{ILpM|-{t+) zg2uW|xMkDg{MZv%gdZ8ad_^@;wZZA7JKIp_H|lX$|9oJ2y_uz?%FxLK+o`D=5DAL*H^Z0d)6dS;rqghyD8Y=Q z=z)#A9SrY}#852NPV@UV_~j~@Oisi8A=YHzF{;CSv+tKDiMSV2aQx%WCG@p~}kOF#J+o%W6{E!k~#%d4okSDo@-KQIA} z95GIOfvb@-Zuvx5BV2i^1fxQ9l=4usHBDibr%+!7u90-@#Ube6x8GJQVPR1DQTyhIh4Q74$ji7ZCn*dF zSE)S41{RurlQsy^H89v^R1)9AsTgK_b_9BdmVuEH^ykCnuoe_H?4^vq-L5?yY?ZF-n zQtkYGqlNc+)?j%9VDRPj#3hgi1@5j6zS&>*?#ZZgDon%r3`?MveY*vu;S`RjBdk%9 zm)qKgk3B5n7>nAJ8A@>l3+0a*_P>(8--HeFMSr1mu>PEYqJ>;J+fYUOAx#$vgVYS3 zaLb-!9tMN6f}BeVqYO#uFM@U@w?Xcz%M;a2M)23w@3fP24#LLr0^>%ZrxhhBk`Ni5 zJ4<>CrVY-F+sOUy2Tb_ieQ;}rGpCI29ug6kb{8l9;2&N?FRszphli|lUMIf2z?3oJ zJl^I9+iLT78@``So|{%`GI<+tWhYL_$uOCSGNmUOZFBjYqz_|WZ*e#k)$WY+E{Z+T zmThuZw;3IE<(Xq}7pY#Pv{jp}0dEcil>#1007Rc3cJO$TjZP{b_jrSi{aj=?bhkz8 zi;lo0<|e+}`g&GFr^j2>au zwlSHbbGPFb(FyrLOnUKvenhGhd6!GvHy@zP|E4alh+2*04>^ z3D(2nL65ttG8MQ4nq{s|U)tImKZVtPtBH+Q;x6JYnFRe7?(4r4It^Wv&Sq@gb=~Y5 z>l~%J1^hdR#c4@ZT8XKtt<`xI4!Wy_wO>%TLcpNBtiWWRiz&lFL+Zs=z!xj)^HM z(`JmGI+r&z|NoD>d92e7>Wh?QHMOeO(~zRQfrCgjH6 z9w#m+CSO?!1PX_XEJ$(EG1e2d9?U+>HL)Ib;!s}^aLQZFk6FO~hb837NJWhrLXn1B zLvS6)pTvw$j>AHPn=Mg-r)~oCNg?WBfF(8>V}&;QJKsQX>f_(pkwZ-I?O@#2@~ zBZy|sk`@G!ctF7E#f->RCZ2Ot3ef>oS(khp7){;YbaaOKc}VyrTrO|wt5>vvZsAK+ z6JvP8lj8NV5r^ayX)e~94<~P-YSGi1tqLCZ_ha+H%d8i=3hgd}&Z8H=sdb=QYk0PM z2ie|ym|&IaWV9U@=7(K=ELxd{*6MQ{R$e^5-TCo>lsOH|!R+E!Mdzc2<$Cx(DkGN$ z-s>~Zx7_p5;3|*HZ7px7&bHg0vbv5@=%=Yl>QqIQjMi==&tLkI08*io+ri?Q*2}eh z_b{LNx~p|{@ku@)hTi3eKMqbI3OM@3J!_4Y*ekZVQA;Sv>a{;bX=woADf zo61aJ*-mH0F*pweaE2dMPL9)5^WvqZ9HEiUI9X_o7Sft)1|nb zkDp`GW%BymPApDWlNOU>Pm-q!rD%ibqf5hWL>g-}YLOp!Gpvn_-1N-k_|D{H9(vgD zd#C6sTQvL%5MOjx;*d#C6v}aG5yTX9gbHGZTU8XoSDdah37Z=?)FlM#Ya70Wrv?l#iz)7eK{{|de%%zZYQ`0(kMD^?j~v$jXpG4!!>5WIxr|^ zYE&eX#YFXknU>MKf_K8IJ{=IqhD{4_WHO4EVJL~Sy_UB74GY@eL#Fx8>7~~mpYCq3 zu(3|)9V1TAL;c9&fFi6SS9kRm7N@PZX2mpbq>hlQ=yCsrOuWELuSH!HxUKRs(QmY@kCFi{m5hfrPp0_4bH0 zl!I)9?txzXC`hbvFojLWsuc_vWdf-~*u_=9M(CZ2K|Br0q5V40J9mvi$IaA*L}S;H zGP23QvXAQ_46D83VB~0I#liRm+m}5%kUGIb9V4<<&%d?VVVCIbcIT6^ z(M!`aHvDoed%NepPqO=`j@x@?W} zRp7KCZL|K5jU@FJmP##em0hLvp_YwY?*jKSlIQbcV-&j!pA+BL4B3EkW4Fh`>MaC1 zuE^G^*vjJTgO`|;?eFn*+b&O6AVB$cx0i=eu4YQFnbG0!=m(3YgebZ;KW-gSt>z^C zGNvMhE4P%*<#9V2p3H1Aar2CuuL=u}rFT@Xmv-Q(q5?PHf zK}^10w|UOYEHF*+6p>uj6ghB=cBy93av6`Kh2KkPV*^qNKCJn=v_h-Z#_(+bk8FIj zAwv8+wGvE!Afo$J&hg&5E4+TW3s;+=z(h4GVgIy3 z+0Hm-)0FyvSDsIWFN}*ll((oU1P(^odi{ohjbwXu{dqNao@B^QXY2EjbFl6rmer`d zeEB;ob|5%}*EnH8k7XWCRG7+46cI^R(n9Dcz#fevayo;-=3)g4xw@etAs~PQ$cY1b zbIdt#)dI-u(Rin91_O5V^hk1Y&wy#y)xE9XniduE2j@VpwwG0inBlk6LXmIGRT>vf zutxq``>!#e5AIVY^)Y1FbD&r>@G4mZ9QVA2=85F>Ord^( z**>Jl$dFnoa`y`AJ&@1AQSwAd%&fll!zM*qle~hC=Gxup65)=7Pr?k>`pSYi`cey- z+`9R3TifA#&qS%9-VUuYmO%eS-erZ^$2Oba(QrOB<1DbZo4wgj;H<-43TMoJ#ri zN)hoxcT$e1QHi!zt!@vioo`~x%S#VueA~vnh9@YRo1>Y4a04RlW%c!p9>FfR=GUmd!9jo>x(@8L2Q%E_ z4fm}yH3_J{eYDu;mQn#g@!t)0!2e1h&w>#;d1A;RQ>+%9G7LU|m}9M5HA@S+^%o}` z=odRds)86HYOx}+iyvn6ks?8}ch6L;RHUTBH${NMFju!YEhD3t%B0)YZR{*@9lC(z zn!+MM{cU9urg{rCrME*BNxfmAZ$|B4rL1ACVy)y)JLYs_<~;aSS5bnhA~s0;mYZU=S{-5j2P#B=I5GOx{3%%rtva~0;O+=dr*}c)e#M&#j*{R zx=BsOGDBIH_hAmEm0BsOsW>LhH9TVHu2GBW6-h9antdf=6u&It*d|KLC(5~FJg!wA ztLn($O$*n|BUy;#i<0j2-M4zigoNC94eQeZnH>-VjbyPXT9o4U_xAGRH@c6O#2p9LQ>I;GnqtH-<#K+D3 z6bESf5Vp|j6c(_2kpmQn_)ysb$evd3Fm?OioKOXt?$3n0^MK6!mu zE%o0QL_c|9x|ws%JRuOjzxyD9iZP^$;Gi}q6c8+HWjG>z;7HvwSYWZI% z3JwXpE35p_d3&KX!Y)h7KoN|*<~qQ4mKPAAT1(17%3+s~9K0N&@BjAn=yZ?8q*pR* z_bk(jtEqW~$EB>Q*k*P|IzAzxKVD2`GHhRNO0LbPaQ84ZYy10*aC^h&(n)`QH*)y7 zx@x`oV`gg*TJm@~VRF6Ixv#1NmbKmFYMZl=hrZtG{-ra0j^^IsPv!JRtM^{7_PC99 zrMZvCvDb8c(~{UfrTFcB%lE0J%IdY$`eueo_v?aB<5lkaxMeyd`c0OqCYE>k(-&~= zcsfGeg?sD$?vI$%gC&gAOEL!>VZ`B)F-X=zktFymF5yf@ofRGfZNdD z4-88*e19;a?;VH$TE`>1jQ0r#MXDQej{YY(tS2EEmOoKn4~gG12^=d=Akn_aSdSx&wBagI zIJ8c9yqE_kxr#wAQ3HO=WyeqK$RS`$c`@og1)o832jg8#v_@)+ldzQnX2*TnT7g0-`MVb~#2WIO6$lr)SQg#ZElSv^j%*Z_5r+=iWCuoHOStD6R<3ejQn zUE)}AVK9HsPfxFnAS6e^E3TSsdC0n&HvdD6>1+NHPWc-5$Ai)MeoT5v9R>=jxw5RZ zSntz=RSFlmZg2OetI4zSW4I`MEzc5%tJHi;q{K=78cQ4J(TOqqd1^RE>Lyb)t8C@d zmdi1j@(s3H151O79Y6kNo18W0VV%qU zJ_Q{MQW0gKv8K;91LIe1c+peswKNrtTnSG4s}x;Goal!EG$J<2y2_08K!cE>LTSKg z4PeCIL9b(%A&=h?R4zY|B(~@m{1_Dc+r=2m7O7~!lsd!vcZs7=F*PP8COzHbXf9Cc zcnZ&!%lT|075J-SyUzUVB2}f4m7UL4Rw^_>>VqmWBX=>%GR4#xs_%|yC+4~#;CO); z7G-PjcYl{x%jLAK1;3}tqns_$zlUUcpSSz=?61aq-7angm6*iuXeKkimEB8&3^XzY zZEH?A@-_QMFmM9n6yaO(Bf$C0#0aaErN*uQcmYYRwU&WXW{3Y&X7PyH)kwgCIAmHN zox(9?w($NMdAi+ApO*=RM8E-H3{ZXq{n#Ac^a^NhRuk}@5rYy!Oz7PfFIDCWk}5fH z;0&Ph(>hp|m4q?E712X^gVM|ZNt*&={3gy2b?kOG9LN-;4WFuk;2!RmyJ-U*I^?QL zO4VB=lY^Fn#19)9-e-=S3m%bPvY4~Wp?|kS5%UR482r=Un{a_SLpOx~y9_+l4f-!H z02jUD{fRG)?JDz9H)tT#>I=eKfXb7q{^mOi;*>+Jpb(OSFbZ~o)icH*WP;@`48*i# z=1uBXZJG^LS(c3E*kE@dX&^W`RAD-PAZKu>3mk-I2VBtBT%=0}WuMPN4Sek$lduqe zx2;PAPadB3yM$>A3y6Ub{gmMMQzT0q6UmDqTGkiVf=0S~BsgSqwe!JD7LRZJ(z^r< z^y%!A^pxr?c7k_9jY?t7)giTaqYAMyh=+1lY%ZOhZufIl>&t(%xzlxH(!GoH4JWVM z-ldLV*y8-C4qr8l*U1yCCs*2yJx_z|4}UX_H5*;5F;xAubugR^qOT@&|J-v>dmg{a zs)o>R-%pj-yl`Eee^pU?AHIpv1$TLV7mL2aFWv6eQ?pUN#c^CcN;%t`SgT8YuDWz} zv-NpDm+GuU+HU5*w!jQ=l$(y{|F^sTyh$I>%VK-g)CkCB?sJRx4dutD>+CMT#{b`V zcGuU;;@#QltL5=Ce%YFQo3-q0(J3S@K=Ebc^O>K(e}%tmnpm&**xb64!C)PvNJrZ8 zvfH&j@29s}u-#;#;SEiMdR(6ClZNe$7gqAM3P9n`ufO;5r6(XRi5!Pg2N8i&BuCyK0vfgOil`~)vb1UlR5R@()z~d-pkUX1bKeSoG5Vn)3H5p z1*eIaUu66_eC8U({=pNJqFQQPA(1eC5a@_Oi|Apd3?-L~E zy}v=h%mCZ*9bA}%9tqh5J&C=75iLL1Rc`v96DfovPsnEmpf?wMIJ#!0A3@NN4pc9gZLu#P1N;i13 zMWm6uQ8QE!Sr45%Zvx#A0}|OB=54n>K8ounLrTz#B%?A8vL^`HH~$4|n2i((gJwod z(Hs~E?6q&2jC%e#6A84TF#HHa3Bf_+lpE@-}BBf_m<=fr1c7IHADhq3LvTNI`i`qzkD3fh;a6Qbe`Zv=Nx;wq! zsJS2!q%KWfmZxEjtj}kMGoT`0cD=pWd=`DX44T4$YI%Q5e|M_YZfp5_gkSGr!OzY7 zcF7(gbeEjn<^FmxHBV^M?e=-HnO?2)#c0&+=5;-NZR6!^YT-_q-}uw2M*lwabgcaN zE!)faqgYMt>(N&Cb6mH}=l<>%X?xrKX>Vyg`?}l9@!z6Ukw3$}v*+W<=J~L#4xi`i zMQ^n2^}mO!-uvrntyfQr>yoZc#_}qQ_9~v*d^T2kT8DWYLD{#mySRY6xl8DxcHrU1 z=klo-DO=0^=A@5ZSNDJVHs$g8)s`%qqWhtvipR4Boh~g{*;b-NN+AYZ?kK(-0T-h(NW83vIraDf8*6{w!53M#yamY)lMKm_?#U|v{3G7t3ZEDV38YfkShS+d|b z=~KXhsRl#^3$fPFqfUkf#h*x@M8M`P2J~@oTV?+V#*c-Dyg#^(D^} z2`M3QPrC!(%?_yho8VMtJ$c|xWn?D=Mz&~SY-Yyr!cENQO0$u^0(MC0=W_q**{VgL zw}LF2o9tF+x83gp{1hkoWKk+U{ z2~H=lY^3llHn+B8W-6mEEseUM&-VYYlRcd7b32E6yh+Lup0?T>Kdo2Ob$GcQPnNew zRDJI8&EG#q2gY7^x4-IsJxz9hyiWC(8&VXNO--_TyO}<1-qZNFJ>MJy9>b3-fWh%~ zI=ODE)9v=LH@SISZR`DfiAkTe?f(2UD`(s7`3_f@-}N@0Zu=jCV`pl%pZPMg(ydWt z^sUUA6(jU;FkQ(2!?Le~#GfbZeyN$oh;_*{n}hM=;dRp1r{(c(GQYa3_3oy(SdJj` z{V83lxeDLHb}C-{6|X9qFdC8&{BAZBCEi8=ZRh8G3)`J)&-l*SUyD!}v>Ks~zeKDd zm?DC*Bly&bW9#ed%gf9BlpIvnV%kcMns487)pyR$@NyI+$)v-`AT-F+#D4~`2M+I3 zFT$Cs6%Sa$8hVIMXK~ki7?~+u3ucsl*0?%5vqN);eQ z5Bo(DnsO^DIpCS=yFdJB%&bogM$AsaL`vf!rmtYLx3r>C{zJ7oRIB}uv-HGUBrZG9 zZSUshhLt5lE;zJ+>}YLn-sSnqWVUo7<*UlX7nE1Z$EULu#3TnrfsC1eOb!hOgNK0L z=I^Qe!AUO!ehx+lIv-L5f@7d>C`KYGbz&3M2=hLIpvOHUFoPL{0A*xDO%!-_0a4VW zWrZ9KP5d+JKG{{?f5o~YEJqLK)~Q9VXV0DlV&mU9tRcz~W)fnVWyEq!kODu>2?8(X z1;$@Ib@&+sdA9FzAZa*}T$CXa;Q0)wC$KqfB_GAgV}U|L&ftZEF$QQviIT6LeDNK) zczEBx7payb*2+7KWkLTQ4#R>b;zN2TIn9W{83&oC^3KS?mPMK|O_UVW1tWD?{41-?L9j@ z+S8&5SDCxo^<8wGrL>>)Tr}dVNEUSCQt>?8Z9Zlvm7c5c-#(Q89T&SJ$(a`qk3T&e zM?0BD{xOdFbAe?cab+ouWhQY}6@FeFj&HuorJg-gD2H`D&hJrhe^I+d&zJo&zhBSa z-T8hW9o^HY+v)n?ApzmI)%kh^oEq0U8=jy2gKGR*uJ0Fj(e$<-BL@`#e)BMSI-Ae) z>0|bsUAN2Y`LNvOIlHqh(3P*q_&waCI(yUS{$VS<_<8Hg?)o71inm_{u`Qu&j`r>B z^6_m!J1||TDR7`_uOj+Ehj4OBr6#wOEvcjVLLuP9NI?!SEoMv^DAc=a z*JI<#lhxkt;p*zDq%@z1+Z>g}#og-jb`dxY6$GV$rwe?kA*68FA5RI(&r%C%T78&z z5G3B>>UIxjB`*WC;KH9SSDROO=^7ZxM?*M~h8W0ow0&Jl%(&%X8 z=ElCmsjFjz-Dz_sfo*B&>fT0oqrv3aDJit9_D&i`nz2>xw{{N$Mrt9_Lr)DT5(B8I z$|Uh{B0^Dw$%FciZr)(A43z5l*)^pV9pb;0Vmq0=_KTcx4VFl4BFjrCfnF`N@W7|1 zrk-=)(5bCqsISory8$w#D{FKvPFjCSmbbRDe64ha@%h-+G0}Jkme<#D%`>prkxO!Q z85l6Z=!iUYo@r_f1BL#!IM2)tcB`d>d{TJ9cs&<{pMu zS6g+xTTs@&sx-&OBqMn}oc6XF^QXJMF3wCnrY0IEWKN&HVMae5MLiisJDW0M$H}a} zYsR;o?X^9o2jMg$EDS#`3`M&fWmLm4ECd={ta>;!sm30g1=A)wuDQTFMCWRPu zn#gU+smTax`q0X2VjR-pGn>k*mt4PiwMEy}FxN2_H6vhI~i5yz;oY zk#+kOiYv8uFuE_nYLF`WQ$MWk?bROLfhrHz&9kXiEI>l?piU!8wQX;ao=}?StD?P@ zgG<`b*wnOcqfdmEnQHV;H%IaN*_e^cEH&u3Dp?q+M1XX!4Z-mE@cia{M0)+#_Zb3%yH_a><;qi4`vqdgc2x5~lX&OL9!G=MW)_bA<>A zLeWAXmk5wv;nMI3SX=d~d+57%Y8A*!rp#z2DwCUPib)oLl}1o)^dC8Pcy(eatoKKb z>$|nIr_pH`HJRn6$LCKn-S2%ol=5~0^+T(jm+?OuKRXj2-!|&v7La{(OcWf> zGQ6D5Pa4Dfv$IY(8r0fdT3j7!?CSV2OE$N&=GIeYeq(aW6RxYZw-&S6l#n^sb?>b3 zZO)dq)r)c2YNftCmBZ6#Zwp}#12dvFP0;OrdjcrJJ|C~Q;c6~juTNvoa<*M=?+1hR zV%55Q-p@~??aN51Hn7vSod#_on;u_&RFA_VM*r+S%b|<;xEUGNGPl(UmJ4JmmdQ_O zut%y^Fw~T>;=2ruwKBM*joaN2X*dNHlxhnb8I`J~Dk~=`>150*re~Lp5|XSctJV}0 zvJ@4v=H|3YDrJ#i7hwXl_zB?gz8{2S1l-@aZ)Lk)fkLQ5Uf_aKxb`1+QU_d+!~$Ul zLR-GssMt}WmS{{-)f0C2aIsdLn`2Svjmy3%wXM0dk6v18;t*D;C!AXJD10Di) z2624k62O`#~_*!oqIXSJQl*jsG4h{?ypMck%v~BaHTN&A+%U zjNL>W+_g}nZ$4DqmE`A3-XAux_e8|dNcDW1v`?R#Qz~!x)h>De=cwQi(}b}FeSfq)= zI!?Ur`Yhp)KK%Xe(slMgyjfaH9{u|d4$z}Oa^(d(* zJW2ECx2NRBg(R7%h9{Q|lV!@i_StUW9aT@unpIV;7SHF$%HziVSkIf!KeA#^%0RNN zMT~_l3?1c#l|AI>v6i9lN`MDHxN{QQ_6frlcvHBLA zKWjFX&Ck!s7@Lx0{}p~-%-4>Eirr~0X%(74uNE?ZN}$_w1iu1C z989klPR0|c_%j~9)te8lP`wJdG6D`C9~aoj_1qrSb*leOBP!G)jvoacE!eEIx~<=n zUIJurfll~FE->s516VntgBO@Vp4j3Zk5SFTFn#MW|M~sxP0ok@WXI~R)YrT4eM}^2 zHjKgGFs;@pJSyEEN%b7wU3mPue@CYI1zP`nmM!2*47S6SH5_ufl>(;4SIAWD&B{xB zpb5p+$<7W$kzTW51c)W}&4`(-0yC6M-`v#HR9pMUNo)7$$PWVhTQH>1zTwH&pusEA z+xJ}^&o07__5iV+K2JVfYgegW{ZPyJH$jn<4o_-~{m{c(*OTSI5Z+vQaUr-4znvZ6 zb^>J<#3-=B3Km$)LxlBvNIolsc?OM{N*WjE8v(<9i??Bvv@-sGj*6l288?*hVkwce z5&n&DRCnFR{CO)F$~Ki941ovswbGVIDpfCS)4ihf1n45uPM*o6F z^sO^6>O0pDDhj*2zB4`S1@qomfi#Fc$5t!h8XRc9oJ%Gt=-=sN**~=!^l~N1X=z6B zFKn^!frr#;!V6k!%eB>Yosx2KZG38p&AO|z;^M3Al+UBxTKM92If627E~Qpe2E%`L zPY)wgvr`4JQJ3w%(cW>J9u{q`mWL4+DI!>`&n+c+8cdf@g%KS+9*2<{w%!e%9-o(e zyzQ@x)pVJh#dS7(9-nsa)t%gF&;9=Ga@o20%52WovP7byT(*KL znudN$ODR_UcV}mwnWLzp*@eY!ncg*Jq*#HwhID|VNnBZxXT46kvSyrohoxmATc>2Y zhIV|QkILEvwRMqda%K4>EP^8Tnk#drBmx;hs^8i}%a?G?S1>cNi=Ujn9b(#$K`lT^ z)>|7NhgUFgc=9X=v_+1|k&a=PVzvdRLOR)i(1s`6M zI0MWq+21!c}NR4l4CriBlV z`;QsZSjVF&kn2blyL0poizd&Rn3V4C>g(&7=jRmf?(fsn(*Zm=@cz~Fiz3_eZp-7E zR;$JCc5m?L=twG=u95BL+;}``b!BB`eZ3ur4^UmZf})#yq0f(pS^Pv`5G9vUWqZ%f zCTM!;fQpO@uq=5W6n?=bD38bc`}?P-r~7;Gd$OG33CyqxqLd#WfzpCTsaie|IRbz5 z*ojZ8iHMHuI3g+xU$9d0$Qfcn2L_@dWVol$uaNCLKfff#Qe$4e5izj| z$xqlTI(dzJmgLA@1Ed@re@(#(w%h)=AjnX3pHl#MtRf!LvP=N>$Ts>&)(am)^P7!4oOLet7O+v9d{pAFfqw>|JmK11@nREOXj^6T+2jBPg>^=KO8zWPI3nP?o z?&IS_NJz*rtcSpYgZNk!D_MvW2~d^kQ69KBRlW^QI{e;NF{$n_VCy3EY7 zcevlkz|z$K@D`7|cN~hs=Xt;h7Cr4JBy?q_tj7Mph6)K)%0gZ1dya!KhHW43;z9}mNFNy-oN7^lO=bCVQW8d`1}+8)N|V?7QdU+L0BZpV zH>Rehl*@!(4=D3>4{9U8DN{G16}zIRT3ApC|?dTBT_&j#s_jf&A<--R0Wq3t2LOh)@4bHPj-0k*-sor+v8y*JE} zpu0TPa@HUu*0(_CJ_!J13k?nZqdag<#a9<5-uFTvQDP?ne4I^{mJ)SpTlW`72nTW) zR4$B=$R;RPtDkVvJffplcw>W-3fMj##8FQXsw5KRy_ zk)+P*@T8(7<}k&fWTBgAWAn(M%9(KMI52SG!}~xvubi9}x^UWpkEOc1c@agB!dDqZ&byL-rItbhDKLK$}Q>146j0$ef z_1l}bT~mH7kK4VY`(>A`uC{-Blkv;8-EQ}QvtgUx_4#A#|7g0V;K;hJ9ou-5iEZ1- zB$?Q@ZQC{{P9{z!wkNi2+qVDnUHnz6`l2tos=N2zXYFS_n64rGVFk+aGqC&jw)Z3k zq|e*MZnQb_R;S;~aSO7ZkNe@;@jH?%yK7@nGn-A#^5A*-UgP0JcV<*bW)y_4tnh0! z;_8q5b@T&mBZ#aeC*uO2PS)(IFi@aYErqJOpxJd#Y zfBPf(GQT0l#pDH(7%eaUDo}awQ3OTBrl-->tX$4gl-3-5-}nRl&OCk+}bgWnzVXuct<3 zApFRXpu(&r2O}h2*6uT>E&@x@Awy$%P$xmP1OrEFu^XElUs(FBu5u+MyWVBk-wxo$ zfTt3WNHuCwFE8*~YrhlN=OZGn0}ny}hI_5aJRR@C^gU_oy^+f`PLVYDN7eswV-XVW1CnSQ@A{ zpoKzU);o{iWHAXMAfz%2Z+IXtgYC1z*eSPEo-2uUhAREsdA72q6eleDH_VqMx{_OAb{&l}yq-1m9eq7@%&jv)>(O0PZrL%l zT~Z=n)RpQf1pQ6j%pAO;{I!y3Y_nKgD@e!{|Fo+%vGV_OQn%?8Xi`hl)BK~OnW$AU z{YpB5gb2U$_R6BFgHW8T_;XJXdetCkNW}7=I`BXTvSKzj@!L)X1OzZe+0o*>+Ly&F_p}-vd_0`3%*?g9S#DnUgWELu^2U@H&CJXn2nY|-e5p^7Cq(A|s3IZB z&|oD;SEw=Dv%>AzoWSUUSb`sw9f(2Mh_VtA0bdIIEWgo^2Ce+A6*DW(_=X3Rn$l1e=al`MkNo^nq}p$U#2Ya~mGCaO1qX|qU@ zw7&`w1_q>!;t*d5;R<0HE?uChW8gNSS)>B}BzX-;w+H~Q2t&N{(BW8Lo*$1KHuv;u z)6&WWu4pE=B=GR8yx!W=E9tK7XS&{$Uc=&H*}-Yo(}sP z{kW7h`Wx?quYu0P+DA{8=0oG9VQ>^)^+O%*F|I{dcB^9%WQefAvf3RF+FCT6h)pGg zn>B*Yt)6x@Uk|r&@9s#QUXJ^d)+I%c=UC5M|5`uK!YlN*SNwM!jvraQw|u-mH|O8C z{ar7^?Q6RIMjIvk-`}=4^?koy+iq_+Q>t9cCfT)l0dj2l9*vaon3NICILCR@`q{&% zm#vcQ;Zk6y?;Gls)C1u6Se_~Vl-w$ z)CstmG;8=|4^+zN8(h@ABxGvzKKKZoKF7)Au#LmT$>MUbsQ%knS)G5ncPMRXNv*?> zb?XqZVg##Bv%i}wGo?-yO4G!}rEywg78>g1+FY{L$+M+Xx4CJQUmQ6)OyNi9S8vm6 zgkBdtTI<&zKP{)jz5Kg#YIYiA)rKRjAJfUhNHFj>DGI9{dELaa{7(Pwov3h1HxC`1 z$>y7?_8wp=(a69JxDz!0tEea}D4^rx+vx2bU0C=CMovGIBlQ2c1#aY(RaL+@sNb^Ln3Fqo%H7*@*YN#H$tLKKmm&3~(iMX3|gRUuA@DPd;`y=tJnfK_ID;m?-* zAhH;az5TOECwDh(L*wp+HM5MejKP9mYD-Ji(SmgdH^>Xt$T4ehRLH9<}deXLP zBC8_uqL;QZpUBRl(db^_XyPubF77C@ zDQD~IW%|p?bTIC$JO%)#Qxx<01hlE{`elDEk%ZQK@nZ8|QzFur$6^WRe9|QPK zGNruOuU~Zq+zxEEv#E|7e_!5D9tumE%x63u4e;*qgL#LF(6Le-^V_93>q-CSq z+jyM@-UZB2e@nGVOe9Ktnm7r3jbefcxk=g>>{~g>hW}X4<8Y+qN7Wrqjwxq zL~mkc(y=(QFwasz2zW4g?b<9?rvwUY+0msU=Q93|z+`FbmZ?r<0;OVUThlL5f`Wjo z)@tyYFG){Nf3#lyRioL-;-xw;l^wIDrR(QcEml}puVrR**A+SX{@;K9NvF~=v$ATN zy=Z7^uCA_ndU&+{5V*R!(hIYqq3egH5k$3GXofr?`aoTp>N!Y{>pzJWLy|<36rvB* zbkV<|gyGT?DOWL!(IGSMH$cG%YQ*s`Bt-N{!Is=lxM>u+rjVylT=PWdqA`{VZzvQ; zl7~b9FCnh#@r6@ni)Y6rEOMlDt!ID>?bGNBt73t2#5-V2h$Zx6>_@MD#XVsgqQF5^ zE~(^ zxsm*X=mFwwKLNl3nT7&sz?2NQG@1AK^K3v06T67fU_JO4q7Q>>UD|ZUj^Af*`ZVNz zX7XZlo{|mGlRJitbRIEbvT|MhVW=jEdx{&+-n8*qv74%vL$G3O_Lv^%Gm7lgprWN6 z6?F2L&d=!GCH|b~ic3AJjBDOY>LZKIR@O~&y?z^wHXrKxK3iD4Cq0gHCCHd#PSJvP zrhI1^ZdY<^vBkHFxvtpUP$v{z_*bRe-BxGh3*5TfM(dN`8^xa%vbkowE&0sG=ab$2L1cJuXQ@*7zW8=5S@I@tX6<)u=u z^KB+ygi$1E5TPetsIG{ug1wB>FhN zZ)?SpEtm6C-$tUba6Zb1ZplqDttT9&e*WG#hMy9*ddZFQ-xts?KeT-3fVsjtio>(g z{!hdoG^rW;!syEA4ZkP|89ryo0*qM}COkbl9K5&~#rk31VA4@x2lyCrFURj5Z*LwQ zpZDLS$b)7Q0$i;NjX5ecTkK?k_K9BGXt`R~7Da@ky|oqCDLyy7V64g&zu+emNR4f6 zZSC!^FD@?5&dvZl>gvi)$c9riY^Qj~Asx==W&q4Wf#AP+CJzi1a2EJ~S>fyuZbKoz z6R>LI&SflM=)fn*HYnHZ5b6zXBlrTd!Q|jx#0U}ih#^*mYzwM~vVEdJ)!zW_{oEKEpVrcJWn;gps+sho95wa8?(=B2^tpPPuZ!J#|Na&L zn8KgcrsFWLw{tpL1bzSUn*QUr{L9=m9I*B&8|fP>gCGfvk;)>=gM&LtplRY|7N%tv zVqA-x)I!eh2G?+NT{SI9GS2MtMTNtNwx|p_>GuBl*+ZrgEJM6r@H{EnieH;~K zBsFzpKjTVD8i5)L!*6;!z`1nmWN4}*Zs?@1X|pwVmR7S~pX%D$yJfySXti_sTToNs zpsuN;`Af?55y{rIq?$szX1%Ops+{IqS~++ z_t(jZMTX3On3yRE33;;?=_?2X$d5%#V-TvpCCKoQ#Pby#+H?TNI&5rgEUf3#(p;pN z3vQo>g=6*VCuD>gZ9>xjq(R?k{PVR)m8?ajnuLJ8F~aqNg?Cb=*g-q^#M=z%>s9o) zHQ3t~wsP>ukQFp>&rZl@$BcUo+wIeQxwKW6`TLSUM_Y&^IMS!&IWT1UF%4b>+*EP* z3s+6tX0_F9K5Q`&mDq6iCos5}n3_U>hX+RbB_$<%&(E?>)V96m`*n#S|mDtA@ z8Hxpi6hiqCdytlw2Qn8&tuI!k78U}r%XaK&g4b4unGb_95t5s1)MJ=%q|2Oe?&)~w z;yG#uaAuIg5BK+h+x4W`yO(E&r$>8h8*f`HPird=7x#LNLv3A?cC$@JN@(aJC1IA| zORte&b!}7CZi94qDYDx&K{+4S=EiJ&LltpDqk*#uN)4aj=~YUD{??xkch~Dhc;8aw zbF<-lFy)+yyUj9^^r#{Qt z=$vNhatwY-8h#_=LO&aGNwfQN#$@pp{B8D6cKcoIWYhY2Ma%MU`*~HeU8~b%l{j~C`t@35^re>2z7pw;tESJXP#^xhrMAhrx4>h2LzsfAL1_G3y(O3l4B z4!ryxu;pcCNlxOhU%{(&OQshLEM0?x;C8gtTTGi>%cwAxqUQKY`>ezL9 z(OWJ(tljmG+4uHD!SiX!09AbFs&C&Bz}bB@|Bx`t1L+{2rl5gRC7#v0=s-?6uw#Ky z1RzmvvR)1g2?3ZT^m_kZ_TvS=P734yqt`Mql(1+7fZC>}Um&>^6%{QloM=CHO@9@U z)@jAu#_nSG!$)ZjnLoi7N)55Og9j$FOvWQ(|DcaR`T)~r3-%jSo&ZM)!Xz|B zU1TMw6>=i9+Fx~!A!|bn;uxSrnqf4}L~D4d=&Kb>ks-?p(heR>2wd!RLa3xJWEeUT zg1=wkke>-o`l>AA`TlnQ6L#Ly#jiaK>&D`17%~{#aTH4K5*UDL0OxxNGC~IjoUXhAuH{=vq88#U? zj;mE=K`xEOB{c>0G)?8?lKIOS%lV3m`LVI)wBL3Wm0S7tBeP3pDZeQ(G3?h>|Ez7O zEzRj^>SZYFDr;!!rf1_|VPQc72jnkRiWtK+kIY(+EeLvWnV%3N-x3AfK$A3YUend; z=4{|lR8TLbzdo}$pPQ_$pr_YmIZv^`fd(UrBTJMvo;;orpy*`T0~uQYFC)pzkv3@D z@Z#sxBYwK6uzMyF8o2XRE)(V#uzRx39P8JQ^Ejp7(LOCaU&yjEY` zI>G*S@i-r!mbYE??L&ST>ATgt)}8Wx-+`YU7$cTHGxFuMqPHmBZpEjm;;dno@p8rD z+0M?+&CSio$jHgbNo_5YzW(-LG?u^73mx0R$o~jfT3TAHWic{tF~Hvq>h(}L-1Z^GUyOglYK8EigaqfOwLd71X&FZdEN>SY?34c zB6T1{Sx}7FvOO6A#83sujz?jrw92mt;o`*$A;JPv(R2xQszh8A3t|Xd`P`8-0e;3$ zvP`kg!%SdTY6w3+K2>1`D5T;R%X;}{2=n~_?g+;)Zo=i|{?+Lr&{x6$1D&S&mKJ>= z0ju3)b(k*C}p=;3HHG59Csqf5extdmh38@aPG=@VcF*l!HwH48M?7@qge>YAJ3J|khU zFAu2wCw63BF6~SLKlh_rH<56&L>|v(8rwqp+DgKzO!~}b?8I*T(u&%`cEYlH+Rkdi z%6fBkA$@BtX>m1ieKBKsGi7^Qoliim)4$x$ti;%0Xo`=wljyWO;jQSf_FG9}Zep2BYyYaeDx6Ayhuv z%?MW##C#D`fIfQI7itmO5gHc7y3k`chz7unjWv}p3+#jSA<{!uLP%ypRxP{BWezZ6 z96E}+!C)h-+}0o$(PXZN9>}aCaZS!o7gVr}I7LA|$rv!4r=F?4HR$*I09zfJfo03@ zi(fE>LK31P1`!`wRS+b4EYM>zYK+YZ)JSWN-28Ezg_8aib?Ssuj*a}AC`>_$|DyEg znGucZ-iiU=%vE&U55dGTB6!f}yt+XWd^|`q=8>MLfG_=cg{TAv9XMk`>M8g>U;qo` ze8M0sFd2fAfL2G|j`mfI9x)Z_+7r4n+H(R`qF&UI+%OJ@EN`x^Zhmg+rk3g^O^+|& z;Xj)+m}->B=Xu`Twt7km{VXHv7K?P&t_A0{4$rDwpavDegBw-j+x)$SHQ!Pbv)Rew zv@5#5aCLE-{{d8|FRwVS8x!O=0$mnx{u5eB{sGSax^6eC+SXrK>Z*ss>tP^4 z`2?HNN~vfY9#&?jadF;+MV7`*4FT~4DJkjfEUh9nsB2fcRXYi2BWmq`dCfvS_YbD9 zzgQ^7BrfoO?5!>~KGrbGeSd!cd#>^Cy1l=zxc;;C_3rQe{tWos@17@v;}7B%F5+_5 zAj2rZhv-DA}+pu@9Zq< zSQBvc*VHhkjhki`)UB#CK*9(QWE`OC{Po;eU0H>x?4>874!FrYVGShZfV3&N_T=K7 zo-x`dqn)pU5Di-Ftu{b1$kcI6ST@8Z^6amX*q!FG$wLf#EE<_dO?pOiK(;3iL=z?B zE8sG1|6>AX$rlI?l@*p#2+rYVpVUc~{0eV^`+h4#7{CRgy0f;EA3zp!8+hGAw8I`M zh%4?QM3o1f6Xi6K98Yb1`@95ojjfA+0^Hi!6v){`72t?)yK%0g8zp$OVCIXONtY7# zh8^q4(q|x$uz3eD`{gl+A_(|L?oGVfqy{4{gH?j+m2H|C^?P>TUcs6=eK&5WXBg(T zMpw7yoKBT!waqDOic^sY{c2ZSMp@oXOWHf$| zRn|;+IUOJLpEqza#%{E;IT-wNFl%-2qVl&Qaxb8?F5hi*3 z)Yg6-_D4}^2grffk6-#okarZd05!R+FA@yZ*P@vZ*)0!;;O1nzg9WGH>dvo zm7=AUXRH}xsF_$*O|7b+FPp`(kJ4>op=qoK%-&1H3Srq;o9^!J`pyF#sd{jT3BOT` zN=$Eb67Qi+qCDpZoVtYiup~-K%o+9Ggf9s#nij$ak4%fM`CKd*c)XhO|3HloF8(At zVun2t{`!~T17if5A4tiI| z-0ypNb+-}-NfY5Vr4ofvQ#in}Gfl!osZN+iO+wTtQUXD1_|S312T7kKfeIjHP|@&^ zneAr+7%&{5OH2+44IKoSzT)E1q6Nj$X$8-(1;3*6jI=d00BRB!4-bGI5wSpcGXH_{ zFN}|mugRC@zk#IT$eo5>9vb|)N@vs?!Uf_egmx?buZS&~=+6!&Rs3K~ek>hTKA&1( z0~Rl2w;09my4If)_^8=K9^w?xUrff~lnS^zNERjeAbhz)OQA9yw_PJWGpnC|%MzPx zsoiy{b=hE~5XK;mVRWEIDm#2cd*8U@6bt=-2~E)Xa3KCu!Ep5yqL0)BZ+-O<6y`Bt z3*-es{lKV|xJXH_VU8n3!N286crrZMfeWaPM-u9O^B)v4M{`DT78d4{M<&ldK9HB{o0@FmlJY&`iqY(yXrZ)kuCe`%;hR5--F#x@ufJ ztIQ;$aJ<&mxZb>!yxQWd^TmYzjV80=;{r^t9@-zN#?H#n$Otj93-L&2Yguq-)^~F) zHJgoM^F@=uobBW}UQYMj=H%@d9MI|^#b1M2$v>IJHEwCpMWf)3e`pPL_$_X8`qC#rvi;2NZ?4blCe{yH*2FW_`!n-FrKn zw>MDt9UXV#VYFsQZ1_AYV}J!!ecV&_QAy0v(FU-(_0yZ|!hxe4XyL7tX~)oUaq1u6 zCV~p8QdD_)J09QK>#No|0n(0krx`F-50fj^?euEO$=RGMmcG0IegdAo661+D^~8Xe zXY_!8ZU1>|N$gwrP1Z&t6v+@kN;KavUwqi%mXac2vX_#0{v=C)x7B(4Ql~sW&w6@l z>D2an*c?sY5&bsA_+^mEu1(*;p*G;0@{oH%2J?G$Tyuj>O%)#Hl@>lNx>21`v0Be7tmZ#pv~hphSe|lkU~ZvWMyTwwzj6FtpGas^_7)Mjk>c)dSDgU&sX{pWDij?ti4L9Vj>4(9HhL!ser2p z5EqNq0Kus8A)^;`T*}q7peH}%Rj4dtN_YBdcH!0Ukxv-Muyl4dM5XM}9}>M0LkBn@ zhy=2QQJ!N>%rdz9j0#&CexUmlpb*y_84UZJc&gg7T_GW;@{H$GI^wH1#e~YWNl}y-?ogu$+1IQ8Ss-U1)PPsbz4dWTk3d9 z>dZvkjqeP+q0%2U?60n-Dtn(|fa)|J^mfBSe#Sz6!a#mXML_-?8}mChRy8JGRbKAo z>9Pu+u;S{R-pX>S5)eI9$XeP>*;HoO7m{JaeniQVo9u zE$I0=zm;GRt3{4}!!59N1waTIeHeD8bF0O|DoJw???R5CkBdrIJ(uqA=97Id$&dw# zHte6GG|;n#AEFYn>!tU7h6*FlL@6pT#u!k?XVgrH;Uz-T_kOk`$lFQ(GDl)1R;T$3CnYE*LUIIgogQFuO zK)AklwsUr5(79n0+V4bZ{thgHjI6b+bRQc-v#a4JDjJE-o70Pp-o!ssnWM8|OJPA` zx_)kBC6Ba={FCI{8@!&!V++filwDklelGPsZbcSmD+(b+yw3k-rJRW~pOwV|yq=%2+}1R6fcNOCrs!y96jex4(?nI2 zOI@Cn|1F==ZXqUNoA7tOc&pca`#XXy4jmtwo1U4W$;Hjh)lpg7sI_-=6b8y0#VJXK zrmwG$f@fS*a=IPNeuUj^Ka}2Q7Cm6pBvFJGslxYXVmO=-J(-E6{(5EOkbO4N53e{U zR$J9{bDmJITDL=w2t`3DNT{d(1dda^^hb^-8P2L$M1PgSy{LLR(@+{olDS$Yal#Ecx zgI$Y-q&#rg*a|x_8u`Uyf-~^$9xBEJ)*^@q*H|(tFQAn!SrWi1*XD)hK|HZwJSc_hYuQkoLliKR%PqU;c& zp@oe3P*K6GLK~sFzL4*S6!>Cv1i?cRQb%y?;5q}L8US4cFi_^_-`w2L(b3J>+|=zv zkgdeW&p11`Bucv-oZSu?{&TKckw(|P^1ANt)%&)Jq zPjCN$C#$}Tx#9nrBM{6ZydLM~RQI=-u8yYEGAkW3e^QmXuHvh$Iob&BC1Mzhsq zzP>+|r4OGDCY?e(9?zP18{m_g%~w8phx_{x*O=pnLoq`VDK64E133?#w+(1TqhX|k zN(PKd6zX*t%*!KQ-U)f#Y;2qu!x@ zo)t${lt8r^_Qs1@^yQILels3%osTDfU;DQ^yOa-X4w(dwiW7EzZ|#Lr5O&%3-8b;~ z`kbsYGN%1k)Y{Hn%dN-Krf|uqTu!!t9hgYISRWvy>LKdzP=53Gq;?0TB+1G_!NX*r zymlr9P|OKc3w~Ji7MMx{lUv)Wsw#SV`bk8{*F1fI44P2u>+8#n2WVHI)<7)4Fm|va zIPyX;(2P-f;UzYbHRxx>`qbKAFd$-ySt6R5ZON!NG@APm2Ne~`z?S+Z{9h13$Pq&< zxDxFO+Cii&4ux!mAmRwy_9134zQx5Lcg0jpfq?9nAcJ6+i35p&Q;-fvJ`|Az1*wvt z>ElAX0tqq}4!Lg2RZ;9jS1?Mh4|}p@uql|?5o+YnE`%i=)06&kxBgP?+iKM@{7taG1rPbEQF<)D;%*h5$PCMOKMFY~F1cm~Zz!=QI zIm%a*N1#5I3=P!>#05X#v9)N0tF4L&rPuT4?9=@|k$T_c+|E|{hOO9M7Wz- z7ni_KWh;}Wp_Q(km7$fDPFGv6)$D5B7nlJs$`=906+QtiZKcLy#oP>RTs(Xdf~&Ic z`LtmMKOTqk=t$`0XMzoFcIE_khos#F<4@|&s@skZH@u8;0p4Y{mKrNF`OyuP)xgp6 zHtNldugnH#SxU19=VVO$x7PWFc6s?`{G6)Xj5z}C6(FMJy3Du}-P;BK@)fcDK+HF) z+RM6Aps9kjyOY1Wnju*c0MotK+}W3oRZ=OJm#-I2-7qkQG1Dm6TGX1FmqjZVZeA)s zJ~sCDbamnkMvcT?U&9GGIkA|aewPKqFFSx98$L4nqv=g#^@!YgkBH^9=rD+bV}!_H zU}5FHf9&lV50@fOg^7!gq}2E9fOI8bq5X$PKv1qU?z779XY0wQD_pb>^WKvsQG+-Q zu9dD>w8yC>Ix@-M&*^4xS-iWARWXzBKTM-ew_;ai+l5EzOTlg)Zx8*P2;;-yd(6ns zB9=gnJ`Z+JpZ^|fVB=xdP#U~0+yC|uHR%v9K~RyZhrPW+-*|vQLsL3CkN=8J-P!I7 zjRuI#sSLVS#>T-Q0+f`L(9q$Sv}!LeFCI92u^z9hVaW9cBRQrr(uxugrSW90W9kFA zoXA;37CR)#Fw!96*I1*dc`YGQF76hf6ZyW1RFL@`Cz%Jx0uki>eZMPV;>iOGZ?`0^ zp+*Ojh&)4>Fh~&Rh22cIn8CFp823OTag21^SzLac!p-DCP(}zk#uGj78;u>_ZIg%v z;77cH{3l&(M1=rR2{D-<1tQa<{~?NktU)wJKY95|{04Jy(4;Na-$>g?hS{^G1-Xbyfd zwxy|Qol99$Rc!w-Aw4tm>r8)tMPA-X-)lxBf7Sa_Q(XL#+HYIh(QT#d7Snm0M+yJI zCTZ{P@4Jc5tam}dO-~;+e}jJ>P8P=&_FCe;9}enIgUXx8)mQHyCd-Lsna1<%^XNbl z!};*r9rQY@mepQE^O#W~Kjpi-9@pmgYDVCF>AO7PIgdx4p~>IMVs2%Ce$#Fvt!!&$ zY^wz<>?-z_VsiN!`I@T96T4|z+E`lZxTqhA zX%$LkN^`93Z*S1zVWes-zvKqcs)c*u5mQPjs-~slCr9NZ3=@p_? zsrKG(eLg+9(5M9g^9oG-W;b6C6&DGMbbo^c8loOSCMKqc*AU=h%&2J;HYXR2mBpZM z*I~2jq^w-B@OXDPo|ByoGNY%bXJ=;zv?&9Xy=94?2!aGVAVqW7b`o|$hTy`W0Vf54 z1!&96Vj@KFi&6vcFkP^42o6Pxfe3Li`()#lYH(i>Tmdm47eZ#`| z-+$4AR!uk%sT`r;M28S3$hcw3h5MAwkO@CaVD?BIPIs8XyC7<)Y8Qg~q}C34DSi zBgM$q;vl7BnF_GXE#5=GP*1w$T5b3udOU+Hz-ugLL}PG6l`-H#4IAL#Sn`9zmwsaE z8|pgz#aNc`;)LT#j_mU>U{2@qQEPP}i^mS;N*f181b0tQqNFN>ge5JE3hP3DE-o)^ zZ7=C^bT4deGQ#BDn&V2OEB|AxcW^gGL~4qOYm%31jE!BqCaAo+rmtBvGbyQ#-NtD3 zm%qQPXmGE=_wae{!8-Ofr-(Lx{x9~~{F#Fiu)EL|;D4FiEPSrM;B_zBe+g_ihRzy# zk1mf|Ix2xGp&Uy#dg-Va7U18wdCl0Jo<_*!-fHm|-d_AuShHHbNOAJGerBEY-T~*$ z3!iz$V)a9nOtoTjb|#^4+1}b_Wp=Kws8rpOmAAtRE_&V*3^|1*uegn$lG6UwNn2Uj z+1uM2Be|i@a1CK?MPq%9q0}F6oIpZ)0`4jD)a0!=L$n^~$NuQ8z`^b0fqo-kjI@Gc z_#-ORkqfVcHeH7zDdG^$(W6z2*cjFm2`#ZdOto?av9GZxA^ReIBfE8?a%EDRggsC= zGNeiYW&kWsi6#lIb&H{yCQ*K)J>d>N3rAWhYn&x|Zh!d~MD(f;u{3I>4lUZdqO*j5 zEFT|<#bf5kBd%JN7CHttUGkU*Trn9Cdq_kSF^*bU>+X5o`Ml--{RwzXlLN!Yy z0mTU82LVfJB5EZAyU4;f{eLcibj!R(D+r26b%wk4seB%#C1X0WZ}1bC2bp%zyr?ky z0}4l0Y=#g5ALaqfuO}2l0gL5`co6&n)j@^?sbKJ|G)bZTEPd3hSHgNs1|*KSVB&^n z_;Dy|F#;k?cJ?qWIQ(7+CYUa)IY}ZSAqXadFA+IVINZ|4fKi-6)=w$RD;O!_<$t#U zV9%JblqaY^H;^OO9#AGacz`W6O~RuuWXifC2~`j409v^-4s%*)2uhJ)_|q8a##&%I zJ`A;}dM7GzKom)G#v#FlAuZP5rnx3OJgaaYjv;N*h?#&M(9*lRtHV&(*)h1$(*5(* zQRAZ1|94>Q?Cd;Go(eCZW7O`^CQN;G@^_t+orz_`;Y7h+U;dY3Z)$2u&;>p&8V9s% z6Q)3$|3y~#u$|72HmB<21LDsIi_rn0-md()hVTvo9sZkxqx@*fck|&2XrBAKc~Ugv zkkPum?B4-b?U(9u?%UmbPp5UgtD_}>R|U;s6RATFOCnGs2PCSxDsmaH}Mo=tP`ax2|jj}3Af*J)n zx=14^Fg-c>tN8aAS(i`qWHWvF*3?9)KH*FE*Z5@j_vfPjcMIXw#-FSW?JWITxm|nO zG-nkW(A?pqaWZ1iKs3a)Ntk5RB$`f1e@UVujHXaA z2l2*fD%Q%Yy=vZEm$&0NpE7RRwu>*mubKUz_T!wNH_b1bmi4^-oF^IS8dj~Egxj88 zeR`}fW+YbeW-T!E#1-tHcp(P@$-qbulq6?jkOQ#SLO~c22tYykb3{aB_n?TfDj{=v z{4^GDisXFK2ngS0p3K{M=peM99=m2I0y@E>6&sON#sBHq=MFg1;W(hMhQ#flL7Wun z8&`=*{|ACv#?y+*;o8Gj^bdVQAd>7NXr&vDbmcbMf@LNu=o>^k;znea94`<<2=Xi< zDY+J8BitaU8!%E<$7#EOFgaK(n#l3si;6ZnW|B%6yy>+U8WdXri6u4=v}`s9NKgiD za{{E;ItfM}Cj0D|>Y#Zd&*D#{BU}geYoOs>@ZMte$cT(~QNnF?{ITnoE*&{H4?K7r zRceSuVPr;3Coy83qb5vQv1ZY7_6j2hK9RrmF(k>@7y0a}8mm)tCCIMySp1*=KsVcI zw)w7)Rb{2oXLB0P2Hh6gTjuh0S-*?G>v`Yq96rl;K8|(W%WwGK?evj$9AB;Tyr1+- zPv!dEyf$dZUuxDH9;REOYY!vIPi8DN7?^eQQnXZdz8@`5+55f?oY^8ztTwtG`O;Eu zci8lur6ey^X8KH*OVX;#XtWzV6fxW8R9yvj&aS%0=(IVl?fpVOp2qF4I-F>8kJatk zn^G)<(y(neB(>9OcqGWi#O|4rHBZd-PhQpr5iZx;=W~B4$ zvK9+xAX0@_&I(eJ43dlbG9{n6)}f87sXKOzf!b1 ziy4dBFyTZCzP;$yAjvdATUYXj>JW~UxDwVnVUhOE!m^Iis;W-rl(;wW>ZiDp>Z_%r z)S&T0Dl^tpC$7ULcAxwN#{b}f=xG(2R0&bIP?^$s4LXV!Z2G|wl+yWAr?%`te;DKE zSDzvy(z`$njv4fsfS^!OMNnFZoB+N)J0cdz7BZ}a12`#Bl}Nx5`viG}^x&esDY$zAd4IWIT7umXg>9-V^ii{`p`)#fB32yt092{o~>|Y`RCk z-L#$o8=b>lEP#8j*D?NkP+=$91lHjiMP!CW43l@k;MuEt``lqgr~-7ACkN{L(W`3G zOp%J*DYVBxC6k^f_$Os@d3nVPo?MQSAxx++sThKf!F*Kmu>0j|r`=~eWWzPK=k(aR zUDllc$4TlZGNbQt)4u&bkCR2f)FfNe_iUyBeEk^D*W=bWTphf|T;4Xv`#moO-fp$g z>}>3{-(1!vhr9V^q#9D(Z9=>0VCh{gX1n&N+4WgQx5;KNDbyH?5zqg*0Ct`dz*D@y z2pqKw&7bf|(-=E!zy8%ZU*q^bZ@SazdZ~MR6Q{&Y}4G3L7W>4r9<5E_OR>y{m{S4sjsn_iflR16f_1`swP-jdU^1L*!^+!+Wmd_ zO5D%$`BR(ZN1UiILp(1|{A+NR2Me0ChcT=@3%-QuM_myqHZxS=n#0D-LbkQF{l$fq z<+X*C&6t^Uqzgsr)Bs?zojqyh%A>2QswycdsfyW^$71ZHp_E0sb z9pX@lY82|Jko}NFVJ~VrJ)19?-`#kxr3sghUiYtjTPQ>- z99gD(l>%RgBJf{{8OIGLqe=t-Of6|FLswzQ!`L3qorz_7Gu$&oW>`4RCGW}Di{xkLcG8s-juNrowEM_7v) z<+=o!Nw<-!r?s~a@PP~q<5Tfa5SCbMjO&G70g*VEwZN`tS6-aHWXnK+3I-CEAVl;4 zoH7QdO0I0a0zoWxwV-8{4zSgzP_0;$YSJp3{d=QNg#rJf6gr`yN}MFw1pnUzuba{H z!@9UYt>NyT=l+$Zfa&AiX!3BA9PW0L|8P``9*^s3tnqQ~%E!a1ELQHSo5}WGviG$f zbA!8Z%kxriBI;)le{Ay~sN<8~3~gx2D}8p$^LEP$bvdm%myL2$boHwAc8l4U3|6s; zbZ)EOK5AOE$%~6PYu62JJN#O+$-OpbbGdA$wQFZck-Ax9iWpqM*;BWaR40!QttvU< zlv`1nE>Y6omZC~28YL*>DQGED`LlnE_{#LkILa`*QU+`ka38dCwk+zr`RuZ$uMxud zdLuYdo?b||gch)5AdFz`NeH5TWdtI(2LF_&B8WOnJ{7PRcwhF1TfIPE$qfz^rOUJ% zIYN-S{R=9)?fdY50E|I%zVy?_?{TU)rIj41Odt^mjIOde&w`j0bv_w91I zZFYw_or#CSzH}xYjxa7nX1y2>1w&r1&k>C=xiB4Fxu%xHz(HMwhGZ-rY;4L67|^e) zt1A!)$>qw*%JQ0;DlWISuCAuGwwlM|%48C)RxK8bksxC*7|dofsI<{&bQG(FAa?`( zM^vxd?M8SXFc)w`7(o=67NdwAMzLAIHymOlH2`y=`xETqO(fC^X&bLFy~tpr1U*Et z(FYX6gSHOn0Dw}B5&TNu0tB=Bj|*YBfL-3XH*`#R@t%fK8%mVI!Q(yNb zMrnP4TZP(!CkpEdTY>y2ilhN(;^b^L%Wj|SK@mw~a3o@`kc$AT1C-!`Ma7~9;xbSY zZ31)IuOB821|5P7lym~$OeV#ao&o4Y^C`FmDhIF|PDt8A2TKIp2s9JyPz>b+(Zt~F z5U;T=0e0hv-|zMLJT8~Rn9OFQQLoo)bvlh!t7cLJ^;)e~ ztT#|}%SLcIFwmgd6v z$+sn$5=&B^fUngv#zvu()bpw(GNDv1lF3CeuFoE=p7#f%+JY%+W0BZr(iGhH*Mt7;mEJhPMXi(8{WKjaR(e3M!OB^>( z?n(?I&V>8|a|IIx$VNI0^mm*IHqF+uF+{*|BJ4z;k@11QBBhAT32vDpvZ0e8PXt>c zAcY;I+v9ZrwNZG)Y|&e+2CL0Tx;A{0Mx!3_e^#4;A!YRV}}+mxUF$a ze``mJE0;316x_L_Et{|o=uT|eG=JB&#WSY%n>BODf_b+tS~y|aZ9|8TXdiiV_mpWP z48khN=u-##OE=d6aA)3ZbRWe0Vq`nM;0 z+R|-JsfJ7}7VFiaA}LK**oXr~2R#`&Yc)#Qrcp*(b0+$5Vc{ z*OX5C3t5lNP`!5ft$+WQ7Y}ZqVw0EGb2x$$j;Nd?ui;D>mU!dBjz4|5_kPb)uv3SVkwly~8x_jE2nsY6!g#iOQJG+{~QCDMAuF#N4rDGnCOD>mIR#ujk zmDSYLak;eu0Z%Fw%Zu@jYPHf}&{-_Zu8caJ&SWw{j|OA|*ZSl%;;kWC+6P1F9sx1n zF*uomE-+9;#R%r`LV^8J`X4Ac#n%!H(S-oneMTDu7MCFX7hS>^0nltDq2qK3cAL~U zATP-&7#xVGKovkCbpYN`pc%Uu6LND1MiYqyg7%Pn4~E(YrrE!eZ9|(_mjL=`-2mQA z!ww)NDG3h_H-go}HI_|qNm>B`8JHtNVo_Ep7K>02G~GY?LFSIuEI5Mg(Ha^W5{U#B zFMhw@<#G|&;VQuEY&L!4dxgiwxZu;wUqLGLA)n8K z&bW$2Ah2PL$z-6d53Dw$*`kMnX*6k}oapshK(@hvd^eR`$&)LX-Llmxy-*`QzJ2!8*Ys0;F+&*>il6kj0dFr7zUpjo@$<3z@FFk#D z@!Z=QMh~)&9NFaeDH;mC{=NB@rbsGjzisN^IdeuWUO0Brgx--Ons2?ObL7pPW5y0# zecz(<7f${B^H=B2oyg~-{ra`tbW@L7CH1)NViAv1QOy;JGoL?q`;(`pKXZ2B+0%=^zVgV|R}Ovl;jU+& znE&dtTOL2UV#A7Y<45G0v*uJ#Ur5@!nj(dUWGL))x*c9$ARLJWqme+=AB-{48o%}L z#;NsNXEOQgen%o1j>UZOsMBkgcQ$(-*}vlVUtf6T%&PT^I~Gn4Y*^9o*pW$B-rsuR ziF+p95_h_+UY|3QO@zX}aKxXFwz1Zf$7HU<0t0mL|X7 zE0am8tE($2DypliQ6xkt|f&i?u#Skj{gO?pB2`PX~1?duOAnr5ZK!3m`^ar+Xz(!R< zXLPSm<7}lKt+81)x&&y(?Zd4_9m9oaEsimy=sln_7X27}oR2QCVVeD!gdGGRL2&{) z!@6KpVVTernuS!wZVDs+Ygs7La0x?!AW*S^O@OxRpmt5f2O!dOB`C+j1WysBDVNJN zH#bA4Cq)dGqaZ&7T@>r^F;I(p1JuGFlF#RnutY6iUqdl<fcx9zkT7_=Hn6Z0yJ#_5wjy=29Jh)-rz00SqSUl;DX@fVczWwCk``PX#y zIk;=yZR2utrnf${b!kImAQrc0bAhJjSbIlu`iz@r&Kfau#;~ztx_Wz(9i538GjBa` zXzL5Fo_pnu=gyuzIdbHn*>}zuKkgQTUZs$W>uM{jDoa&5Engy#$b@FA%486W_#B0p z$-l>28%Lo7Ym$(1d z&(Hqpi=$WG-Tdw4-9LSK^qb3vUpl{W%esjZZ%MV~w0@r^mG?3Ie*kX52r+1Wf=zoD9Cq?l6W6q6aZwvSc@2f{-13K;PKd%Ki*8j>QLT z0FF>^aWZ}-V@Ys|xe6;n>h?93P2mvm{t=P_y!r?TfI?a<&^?p*07VSrf?J}v4m@}) zql)p=VJHl+5X4@o1}^C#D6fUbKnF4Biff!0;FZ<{6t|1Xib()7P#m=g_JC(^N|{bG zd;S8u5yePRiHIJ-jsy^(DUB2Oi-AI543wE5 zW6i1+)7RZQYxRohOBaosJ!8oH8N+sOTJY5I2cLUl`_hHCOq<-bX6@|Gu4Hpdw6Q6A z^QeAz&K^I1!Q@*;ceJ(yZywn;Z~mlh+t)mK?$}GOT{!dP@ohUdEnYP5wy6_y*<=Za z!>y~bnDvzvC2p5ZsaEI>Dx*=VR#eDE9G8hRsM9!qM#IAo4nDMN8&d!|J%3czq`EctB4YPzXjQuY{BIYq>>H6 zKq4ASC*v8tTH|q8LniZx&d%{e2lQ{vX2L#;+F(>Va?#FYDw;?}!V!OQW5z@#nWS!q>mEmtTMi$o$ZlhDZUYpqso zH0rHZGvPI}t+UMriU+?U5E=Eaf#Beec*)stLpXwkHVGOy6Jr&PGO5LQ(ISxuvdpk5 zCG7(3ut_?5oXJ{HgKV2Yj1mY%Rs@y?HijUZkdc}qR3U?bdm&y748{0hQI79YNH~;h zXwc*yBW?>8h`-WB+5JZkfn6k0LtUWZ?ehVPdj$KlZ3cT8LH$RUFox(VSynU)+jb4I z37hbNLi(_x2ZED&TlBW!sl{-IWN@(lqE4`l4CEMkTDTdq5I`%k96(s~m@^>C!N93V@gC$hB#j$i2MZ>d`^HhqWSE^>!{H!7b~qeN zr4mq(kou1ZMSwEgl_a^Kj1}*Zim*Dr1;_+n8*JZ73YW$3J#V;3!$e*4T(Lx(ixbB=N22QFKF`;nvDp1t_k zx$`IY?BBX-?XtOx=G-)Bu+#1+;c)mou2do_E9Gc4Dy2fEl8ZD-fks|#(Q>+*RQD`s zJ-%zq;|C|~-PV84)_!}p4m`Yb_+tkqoO@)(h2wWVdt&xG&#!&<(RGa}ZxyGaic=*l zDR)b&cCVcB=kFi;`on$izr5+amp6ZQ>A(+PocjKYQ(s;_dg-k_%N7l3$msGZYiD~p zpN}(9C1D?4xqtfezXjRRc*yN_rPA3%GV5~s6Y)$wpJyBu{%F7*G-}LdtvwZQY|M4X zB8{OyE)euYqJd~En9jrt4VjkKhMwMz?w(bg5U4YX0wnf=&vA^^zH+~a20j} zI(Rn$4#5##d|c(a+l<-e2X~DDM1?$b4=j*^^I#0fGNFA8EQ|rhjnv>iNKLszoZ5 z%IEV$%Nb|X!(D2yj5C!S({LD;G83OQzpm?K0a5(%Z# z$!mp@iy?y$WKi1=IugdvZnt_ojBpR333W(Nw+{kKFz9!?ogNRfLscN)v)ip^v(e$O z`2%jR&q+J^I-C}#%j)*ntyVK5n_vS3iwV-UR;#vJ?Ix4OU|_0jBg{aj(@7*UUY&u* zRn=71M}nSvR?a;BPC9=+}Ti*x^YW&NLjzxU&}?>+O# zlmlBw9ojbT@qKrmJF@8fktJ_Fci++73)K>C8K+KCtx?v9WgO1t1>-(>v z-Bk=CibNt_uh-}E0T%Ht#9}du#Rd_BX3B=eK1w&iC|E6^761)c!DkRdBpKn=2BZSA z(HQ_ADJrp83^BOZxzRQMKcOTMSl}Rzqksf(kQhAyF^C|cFjD03YadjlRXCuWu#as~ z`sBReSCC6c)mX2PW`L$(=}BWj&q6qj19`@b0FYz7qil@ZANqbGsYwk@OiyV>=qIrqtUS2?R2>u zzPi3ju2FD#b-el- zufrncRm&Z;j#$co$&)#?WljCo{x$phg_r3Sh&dYB+{OQ{} zF1>O8Pv0K+;^Te4`}&a|KHvZP3-?W*6b}dZEv*r6z#fgqg5gjg#6;*bQ!y0Iq_WX) zESz$LlFn$_AC7sw0cSiBN@rpLzbhCEWOB(^GUN-oVsVBeGfy_ksBN^yqRGQ#iY3C> zH71>jCz27L-{ti=qp={;7h75jgKz5B+pi;)jz(jFTt3;`+ndd1^?H4Ic{zu};qiDf znXI@5;t7R(xm*fPZ7}GpRx_TdrC2Z>Ry-K=)5L%-hs+7Eiee?mAeb7_Ow439>Ver2 zb^sX>c1v#ip1w3QC5;R-s-fz6%qG&osgqH^1NOy-j=%U43^{RrYMQ#(^edT)h9iED z*Ab5RTiY6k3?10h+tJ&vv%RA^Ur1+j$;PH!Lt{3bi5J&BDuF;yU0q#QS0@&WWyS5j zR4N6mECAYKF}Yk0s?+OsJ42xW`T&B0X@Dv;SjJtSiavy+0agG9^r{0H@heaR5CdLv zMb3or2|{`K{N;~B5oW?x8Lul+o$${Ff@{E>j-Pdc0$5x z;&@-k{-;!;4^RTii76A%U{2#WxG*`~AS=^Bw7@3pq%a^>1Oy+kbOfvbZuAh}#cF`+ z4pOt!VVu?nvSD@5TeQZOWzc8%Cox?RdxUadkS_qlLq+ZEuSxxN>pW~wH!{l!C<&~)UdOUA2@tq)3PO#=gb;1WqjMv zfzjau5`(%T{riQ30ZCU^aLt-o$4_p%_~Pkjo;$gH*V;8}@1DPK#-N)zZFW76U&H6u zi$nrGpDz&B)p4r?qWa3}GL>3v)bYh!PJ7nAZdv~L-kT5X9CZBP=#`5*tQt-=hf~EV zSCz)8{Yj+qz*;d-tGxVac>xuDo&h&tIST`ybD~ z{nEC9UBQUY6paOvsYoOmV2WHvLd9^MAhW;^#hjj?FBFYLlU`rQ?+Zu5$#5W!tPSkz znoPzSUjkDd`x;!bXCNkXS9e>XA>;KqZFW;48R^%*tGlN?m5vP?KDev94b;1(wV|uK zEt!hy4eGM8veMGh%F0R}k0&lxOqCZm(#7(~WHMNbN*7j6!Jr@RWvkWfayh(Sw};tJ zhRLp?^ayrjY9tc!csy(($zF70flqEB?8io;Fa!bcO1J?D?g?Z=p%D3j0Mn#5;sf+X zGy-{=FplI40(yKPqz3PXB7qK|wQ!i(ixSB-L|x$;#bY8n0X~b>13@qaN1#8{KE+uh znvlR9#(-=Xk!~O?-6p%D9(xr+W`?W+u8Z4bj|Mu%u8D+pa893LA^0X&#IG!y=mW?v z5Dl??eSB`1zQ4t?;a($Yg^-bg1&KK0iU`aAnBrvs{zCSpa1P2z!Pikl8*PR{0qlYX zG{l0Dz?wdwCxqJ2QXs`pnoKOllwN}>2k&_ z1g=C%4n+a7s2?7y4{C|e=fSAL_vrI^yk0l%4)TbjxVxCmW|I-PcWHX8N# zuhVJNYNb*s2XM<|61`C-l`+*#MM9ZSAgkw!_8JnsFCSk0-&cPA;^f;G@B7`A6OSHRTpnjE5st-^sZ2W0WUoYHaeqrowx_eDkWDmXGx2aJ91O)G z@lYVhI2f^W?sZ`V)*Us0bGeK^;Eu&ZsdOxzi6cj*|A6l9p7!?kR^(xIb#-)gbp!%F zi9}Sxq@Ht$UrVLZVmy!1YPCYGwij!o!}QwiR=3-U(hIbMCpkWKxhd!g$RJI3v^uS;zb+=FYA^+MzYmG=Nl zlO{uhOb-IZa-re$g={uU1*oz4GSD1haK8oFgp63@(`l492>F8M9EG*v(x9Rc5dJC4 zCg`U!rzo9F3s{hSGCTy?Y0Zozkjt>B6tU(ZCj)y^ou5e%U=JerTcwIA@6j>&A z$W1&RWiM%IVGAV$d(+?`bRn!2NUwCc99TX(op!t3YAL!OLBz0;jYgwFCJrbYCAI5x z8kJgXFfu`7N~KyPl=13C)m7Zml1hi!e%Bo{&pdYM@zc8&ExdK~sN96H4Fh|;O?lJQ ziCrs~PuaC&<&$R*96P#m!Gha|5ASC*Y50QL+PVsvT*RcF*Von5R0)NAiI^vm3KU9- z$)peqI95Gp{*1!$-BTXhJ@LSUL(UwSaAenrL%T-q-ZE_N?a9S=HEvvyJom_qpFex@ zyALj&*!jS?fn8P^-zcg#3f01rI(d~uQ>&=w)W}K%QKP3VnBBB^`Im1zfAyCSum1AV zzkdJ3vbh7QOE}z0j)kY@b2x4(=hE|=e!9Hxlh?NV@4vjgVa23G+#CuRv)M2cb(e_6 z5>dOymdM6ZDPJUNZ78^g4a-cst$W^_A-7NKH)2S-H6Kkze5q(C8IAcoerEHdOgs_~ zVA>E~XEG_!h)~!UPlTJA^S%8#d;4{^wKui3H}&*(K&fkPZftBU*zMNx@=^|mQ(s>v zlgWfap;*l9(kPe9B@&57qj5SJ&jcJ2h{Ok#cDWpw)wEp^E!Qw5=w%_600plPj0+5ZFhm+|{{E4nkf2FSw z-)D1hh!UhqlMTSv$u;s`YXqfQVVPD~X5{J%uE@rPw}1cs<5&Ov-49;g zdh;NgQN^)JD?_Hbm9zT)c|n0 z$wDj<(gfVRAp<=-w@!ZP`L(ZHT>JQmMf-P5yLEU&L&}i~JF|&sI2dB$k+KPY$W6p0 znT!)%h{Yl|4H?kV+E8f7boaCm9Ms#^-jvBEQt4QGdwZc!aJgK3KEJfMeGHe&t*@`= zvv$!%qN>4Quv(eOdY8)qn+?A-Ih^sU&*!0H$@i()Dll8=)mIubH5HF*Y*2LsUJW_;4*^$fN1e} zl-!bR8VhvBwMbS5(I&`dFA-9y1nv$n4Sn#st1t-93?@1rZLwZ0D|1 z`9;JCg0&GbVl?Wt8lzAs=J9w61rt)DQYnh?EmufPm1VUqr+xX7yY}yWVCS|~+a6ke z_xy=-ZXbB-h;0Av@Q?wy?)Hq+suA&Pl~R$z;ox$)rKKFPSg26QxZGMEzt(8d0qN>OIg*63B0YDuY9R&JM@>Np%_C1+f3`qP&V zUcLI^mAAKTSkbj+WzUnR7XR|?6JNb|__Npde)GZ6_g>!m%kQ4rxNdqZqK!rDsbqwy zSe;3DBc5m>l=Mo+4NINeH}{9n5B|?Tp8ETrPXG1CQ@{WG@cxJA4(%U~`ZW1eBo&J? zQM##kFzjQ)G=h;b8O9NvOhubp3O&6Yon5WDd@7NQG&Sc34(d%NlNO7ms;Y{^;Z#;u zGL-|=YJot25D}CIu@pBVDB?8}rs*oy|8f-l%uucov5L8YmjZ8PEEb`O!JbjUpdT>_ z1c(IFga~W_0p&2+Roe($h=dZRP^t)YVEXks#}DGB;Bf-11GV9Yq=*76 znY~`O^|}+%WHPALN}J7sv>JqzsICVjDCByR(e7}#OeT|BBUh@Va)nsTkYYWDQ&m${ z+rOuM-d$54+_?Psk)01cuyXdy0TV_yO&ZfNs5foW2!z~9wOpc*i0kU=L?V&2sK!c* zNqS0^R3zp}C48kqtW(Q03hwCP+5KC_@7d6La%anov`ltP1)BNuYy{8EibRb5@n=msJ&pT||nqzaLQUsI+mQNe}(}$=2^3Cc0_~R45`)T`kU+?(gvqK-hzWcjNr+@$1*-Ni&|K`e} z7oXqL(c($O?CDh0dmVr|MmOxfBW5IAHTZx%Xc6A<;z1qezfPO zZyuXDwK?b(=M%nkoC$M|#v}0z^U!GqCX?|(A=lQ{(%s$J(b>}3)r#!%bS93l5UC zhnY+(yy6=arFa9p-U!eJxr3(;unx_d9jA=Hf{=o}Qd9}SAAp+_TN29Q_yN9S36J;< z!gq?kz?;Q}TA(37jVuIxk*p3WNH7UF$X3{?79)9FVI;^@`2GHCsWe2c zF&h9eG$#Nkz)hT)N+l525sNVixY=wPc!Y{bu~-CkpNsZC2Br+Y355ZgAnim>N&+~h z$KwK|g4Lob6H0cFW0O=o&=BA_E(DVU1V{WItO7t8`7c<+!T*c(2*w)iKuKi#13`hI z|G*N!EQLY=>~(+@089l^A5k_0n~fpM5qqJLbCL{6G#W+3B=9 zis2%(e8v%QG-xIeMo~%|T$@U>>Wc-WOvO#eP-t5!74!M^Dy2>+U<$~|Hkzg3eIboz2Bs+wvWqjr|973?0_Lr>6@k1+A^kt*y--kBi6S zayXpY+G=jGXsTE&#Q115Dm(>^MrAbWokd@RNkU@nnCLJGupBi{{mfq<~I-y>2V*$Z~S z78Hy=!Ugabss-AiL>0V!kWE-@`J&n%5-ccim;X3p;)-U5+JPQw;IRLL06&c!XN?tu^RZl zAREwzaELznkfdfnEC#`3hh3v&5`Yq99C3TVWi05R008002apfVopUFf&vUFq2792nxjxrc#MM7MN%VQF!RiFbouv*T<5ma3ukw>4mi0t+7}nm&-(>VWd7Hq6^#8Ach1=h}Y}Jeq-=7+U-_*F$&O9%z<<> zC6w(p8gv@q)~%a;>n)uI9bYc35sB*s!a9jmpwTj0$%w^5nM}eos8{j1RR($Wpcd2d z9b=z8KIQGF?>@F={KaEyPw!gv$t(N*@Ws)KXYYFD{PNeH-kfnO6}$?yuv#mr)64i; znLs7wE5yuyrHrqT@)S~@N-of<#5%P^tq>|@e2GXb5!Q-oIYx1%Q(8N`;Cb(^QHA~zPRzzOZz{0|KPiC?D_talN(lzkNDN8R45n@g`<&pG7<{A zV^+!hN&P;5fC5l~h+(*45SUcwFE$ zM1Q@WDZ7Zp5P~w{Lw38J*uV(W1KJlRGcu~6V&lcZJONmP7C@`SnvYh!n2?ydK!5N- z>^_VtOCXgbt)lQA_VY!G2Ss6nv4R)(aZ3WiD6Eix3_t^>OksAUcN3u|ehS3Io|8EL zdX+aOzZ&30!V8)u1O!oKBN}cBsEv~ek!dwR+64>@Qb|b*1@33FSrYDvKBK4;7&7u*26t zKe4ko)MT`S7LZO7iG)xosj;z8DC9s=NKXJ$K$>4VorFX~qB-F*#c>0&iTJZE3O>Wj zkMl`mA+3gX6oa*=6(7!|iraWGh@O)xl`K{`97Gm7^blGuV3%Qh9q%4W`r&=UPtt9$ zwm{?XM#3NEblMR-1JNHTaNzzRWmrvHt!As$Y_nPH#aJ;yaC0%89Y59AWB!!I4a@0Q zfj}UUFg{7KSj^#Y%F4>(@#yT?cbq!$@DpeDoI17T;fGgj+<51fEsGW`7;Cc%YHCZR zGM-i^Q>r9#g;=eTBW=fQG;yoSbh45e<6@8QAOFnpnGY==T5yS~IUE6p)9hCr+Bos! zmp6Rz{@!H^MwfFqlKL{0xJIWE>eV8ZTp$v1`MjEXZWXt>f?Hj|tF038>SQ9mTr7}@ z_);NHr_nOlEv|BEg$7=^naf!zMLm$4q<%2i2eD~QS-+zAM(wjTqcwy5A zuWtG7@`bY*=)K{$Q24X2q}O>5*D3QP*6mpqJA{NRda;-vSQkN{8 zl{R zW#yG6<&`BROdV2Ad09zSWqD0?Wo=DWO?72;RfR$#wis0gjnJeN==jz8TF%U2{_o$s z|NBpl{N=}UfBpSS|M}NTSO4wG|MSb6fBfRi2hVT*`ol+_dHjK7#1IO(Qkk?b;Lqfe z@kAgI2|Enxs9Qg{Epq4hp4Icm&l)qZG2(QY)jp@St*NnJPj4cT@cNv|bfBpv(b8II zZENW1Z67$Or>(s)nTq7{$$tGibGeMoW~r{OwcwCSi;n;^q1eMt#%3)p=ZM+xgfS;J> zv@oZ&CLu4NjnYyG_2>m54hwXnhzlZ~fGW84z|)BcBOaM@xZ$e=Yeq#`U?Nd?+C7K* zNdg6s9ih#5h2eXoZV(!x!+p>efngqxhja{L(=Z-%<75EP2LLWRoRMrBF3s*LzKfRG z7!9`pj^OKP5T&8X159R&7942s8e|g?6MF^kh9w7Nq*6?j8{h_FMYfo(&1SMhV@W@W z$D^27WCk#w0G*`gvY`--;3x5G03zfO9Ar00cnvTm(gD!K`G9XseL`wzOxT|+m&;+s zlZ%yJA!;FBEbWv|C$q)MQ`A*5D&XnJlSHo|A3^=6b}$IAl!1WH>9ix45{qS@&jTj` z^b;78V9*b8?e}{TIs&=VUEIvqUZmI#hYkPj*98+`H`EeDY8wnXg$KCpAw;``R#wr%@@Nt1_oeY%=jjzYmT zo7G}beLc5Ytx^bhLajpNckmusJM6`$?|S0sw3~Z8ib_s>ZCN#kBPro5n&^Gz$k->3 z&G5Oo0x?&w5v$c=nT%J@tFEZzl$3GGDmdjeW!05cHC5GhHMQ4wJ*=szs;;iAsxB`R z@vDWr3aOyhst~yqHB$$AKD&6&@2@=m_n%&W=EU|zGbY@7*Npcr9KZUfcYk{Ck?$^_ zcY;4Ne9cCVnTUl9NSy?U+@FWruzqsRimj?4p^P{RnS7!h z#ip*+9wE|)_a87yl#>9CLi9);0Z+_kv+%}KZB8sqsfY*hWi0C1ES1z z5DkzAB^q{ujjBXHk&sFC|A^ZXWV79XAmGS*Bn^kqpU5o1F>b971k+v6dWBrL7%LzN zK{n2(abV*w#){4a%Z4^fjo^#)T2;cyM^NzOmHP+T0$&> z9|?o$aMZW$z(7ZnQeRl7SOT@ngQ7;_-7~*sFWy7<6>HH@ykcFyEUgTf($fLFrjmT6UDy;>m^ z^7Lwru%cyj zQHtb}`g(3vRb@#vtmJ=Q7$#` zIKv96OXn8<;}0+GUVo=u#`yjuC1p{)WdFU>{`TRCKYV%S*(V;%B`toxJ&{Tl97=`!t@&ik=Z*$_ZLQ4>O}S($8t^l}wzm|94jC}`rk?h$#-5(8=H^C_ zm6n#K#>RrhVk#-&R8>`!mzVPS^@z_Ai5P#Z*=)oPjZi=EEZ|JW3+4BF;Vz~~Axs0% zBTRBA(LivLN656JUKl1rAmC%am1u;$94xYj1R$?ZC@8Zbvh@_|4`X-| z!Fi#219>r1*^o{173fL&3EKsVKfw)%d4Q!E!k)l5sJD2RK#Iv1N~le58dV)3Jp}zM z)_o0O9f0sGh}~!qcY&|Kz#w4~v3-$9sOTUK+U-_^U?YS81zMqv!b1fun+UblYQ_*6)6J&8AKBwryKF>-L*n4kfpiqt{5SCati()~wfvYO8Wl+tJ+%oDJz^4_Z}o;$NRWG;8exKcr_psuQ}vb3(MoL67N zNGrumpL$-6P*g9G3Zyb7E=4TiOQZssTx8K}xHYAGLA6XOmT+suWt^L`^3R`J`LAD} zo;)m8&*7NG61!9?;&3Lmo4$W>{l9$s)X9S@a!HHNXN$&Tu|(X*q?r4&*?caO^*HRY zpf8;W2ZEkLW4@`Q#qPI6Qh{tf(%O_7*sp!ipstSYmWI|myf1BSEsc!@v)Nc$%E%yc zxl}Hfip4^SM5IzF)M}-wxPy$tVKbYJ(5w*HgKaz!Mg^xa(qS;MDIOHliNr~ImB=-M zX+tqulp6^GL9w|6{p4q27dj@X6tN;e4H8lzQUhX0YJmJ22n4_=K}gvs3=|{kN-_dT z)dZkynn?zOh%KQZ&c|`6G}IYV7~nD`%Ee}&^hT5R4VYtVLFfq<*04RaM8Kc0k{}tH z9e_x*m->mG1GsT5w(S8-lj9Mi9SVimNlXOI7;WkU8@@@{`ITh@jDX98o>WB)Xv=1= zZ2f_hZUpe*>zPa{pU)!GJ6SWd_}YN0cTFYCo~^O_?IA~la0aXLGeVK2}~fCz|m+J1R1-LA*~q$=w`N+Vyb3495#fJfOf%4NoejY zmRbg^lXzmYSxhE_UaxgH%{skOt`KRoa;wc?wHZ`uDPK@4;>v_vQB6gu!>ZY_ZS8BX zJh}Cudk!7gvU}Hxo!ghLyKnY{u>*WAeN8#1zPj9^*GNV6dbuR#F+aF^>gBh$Tzuw^ zGmlMt>#Y@+&d(#q*m&W|MIXQS&^I3*?oF92mF42PYJOFDeMPB|TcebUbSkAv zp_ECab=*q6pjIjq$Q2^FLZncN)f$;rr?48d3MtQG)ibpNOG=bAoN0r7fBks-kC(RW zSTo8ZWh%7_Ih>fb^4Qv&|NPGSKYo4o;mvoZV@9vn8i_?SxvVeXPNf-I6ODutkziX> zArTKnV!=XZquOE2wkJ9UGbdSdc?F*Ucn1PTlh%fhHKg75J z-}H(h1__FGAmGCbMbsOF3E}*Bvr?%PV$mQnc#Hpl-GsjY8W0yi3F><|olcL(gJ=_i zX@V7ks(;F|X^R}_FbI>tHaD3}2K1S#nt*J=kWl3fATs$*iNX_=CZY=PEpBlYrPy<} zg@{I@=no`g!eTUzI|5@vz(z0_WJ5W@G{%jMq-0uPA%Ms*8^qtyPmDH(Iv5P5iV816 z7-{K%K9lvL8-yp82>Ugb4GjU)2!O?=t3X3wF&HBFBbo}qXSnq+SrLWe^}5kF;3HuxB2`Epq2s|IQ!bfq3K4|YgIF2chKWe7m2f!h zcDvbmT&UOH(9nR;dRk+Wy8sa*h!4R_0ym@2=Se2x6crA^5xX1^#l|2Y03e^wVz&gi zr=T^Vej8=Yz#EBoI~)!=iurQ*tFu`1FBXd+$j@G^Kte>@V9@#fURyEC#&kWG9r6gm z{;b7-6TMz5m5QOp3Pp?@A(g1ADtSVI?9Mx9J@f3N`wl*E`qYk14=lX@{=4qKfA;9n zt!7ibfX7iQ_*$)+Ut1Y8N_O5m{_S&%-@iEjsS{J*du8LxPc6Ot=KZfdyY$6#3qN}6 z{xn@s%KRn?zPT2`|N$~ z>$h^jtwVp<0SSH#>O&69nTC_SqAvl7W@ zEz5oHcdoGDBi2e)rr`{H&SX7-`g5f`lGmNa2qB-NEr3>|#kt@pUQ7m5HI&d;&p01E@dV}^?V1~`uw_KesRsKg~o0*b>kB^j^hthg} zAJFWYiZbI#iF0>vZfb5$pBe@lT@@7w(i|rB%9a0_CX;fIoe+jEYarEz5<$w_`_ z`;mGpzy!~G`AH!PV{VdJUs#Q=xkM$w2J$!17%IVGn;u90LxYzRVnPTQhP?;ZjRaGZ z&O(V8fZGi>McW}++ZBeR^0Wct8(j-2M$8AVnNt!I9K0*|0yBq-*^|dW5GjKU0(+GS zvJYf`%-Q9ddof~({8*|xgBX0$Vo04is%J)W%+UI#>rBRxKOEGhXLV?pageEVd8$Ylv$LH4?4lNh-cJQ2_i9oTcO-Dj{k5+Q@ zR0-|G{Vphb)pCJ;lVFQ<@Nt2`^U!aQ!7`nY;AE@KV8xJ0coNv;@bb{g#1(KRTr{gF z9bSE=YIc!axWC3QW2`^IFmHNoXGB?K zt=}YWQ7tJ`qxr5F-A7rT$=!WY6kQ4O_P(^i#nJb59z(P|>hbo!sl>hXKMPB75Db_Z zaj+Nib9C1Yr^ZdycEgC@Ja<|p;^J5HR;F&@MV3q&v`x*Dr%O_?X~_WWNd}BrPRy;{ zw5hU3y}sqJCF%}n^NqY;NIeDI9DXW+)?O!CMm}FR6Z4p_-d}E~Nrbmb zm~!y>Sx%bAg2|LPGH5tBSRWc7gXFou>l7__cOr#*izf&F@n`b$>4u{axGp4sBgd`* z0?MiH0LvvTJVt^XsMi=64;Gh}BBN#DxZ-;MKn2>iqUkZga?t-BNiT!%O691%mR+C% z*gOt?kD@<>Yb-a*1eqVyGRGGwkMbpntECYdx%jp*Y-r*U3voOS zcabz0Xz#{~DNS@_wc`}5p*|iduE;b&k40^4N92q&Q;P%JYT4u?Wy->(jqtB5UGAhU zx4aFOGcOm%zEeW5WF1x@6qMB;EVD(a;mSDH!Jh#5qy$b6iA4~!Wyg5Ai$Dz9ZbyF^ zDstw;waJx%WKg?q(TEo<CNPHN<4@L^q_M)?KhtXObdY@%d0 z@?43`#r4plOnIlrwrxL01GB=B0Nta>jk37u-_n+%*@Sv6WC4G>dUa{uJVRzvI_t6j z=%9Bg0P~hL+t7`D$JK3ecia}Ve#_ANL{(9A^!+&qBjc&)rk|ZPBFJ0@A(z{hd11nR zHhH+Y3DAwWt57Ncno@78nC=QzC(TCfHyzO$lop2dqX}tPp#nOe(EJEae2tG;Mbnqa z@PDRw5W8JPE11*?OJt9+(xSgf9jir1!Suswg7>VF8m{5XjUgjNlUl*+!X+hI!q-R8 zM74+Mf>^#WDQv*eZl3S-C;hN2(|#Nbq%~K9^zC})fXuJ!+kOaj1N$ybgU9`{VKoe9 zy~82S030xgK8t>VPecBtldw<5e#ZsWP2OX(a;Z@uLGqM4Oqj}&})Fv0$&c0pv`k_ zSu~;>RWDUcSrkdDmM_VL7JC1w`m3j=VnBfr1%q<_bsKHTWv|s_`c@&OcM?Z5 z!R=tcVIonqS+J|&LhinqPqorWo%(qb4T-Bb<8u@iTPy5y#Z5x={u137@cG(i*xl** zkk(TBx$Xn%4sbjgPTWK`iH$VXNQ)2%m!Kp>8f>zTm@Z_~NxyJAw}_rFLHtLAUMhIm zWKQ^4CB>0nZ?QN3o;Abpah_vm=-YJAQA_-KTC|YY6>uK?gc{)Ta*V1O_jP%vChYrp z?4e1V!`n{3n|zeCrN@Q-3ra1+jFQmSc9iOOq6FLTsqgFmvR)sqzVVddc3}1{%x+AE zMh@<&1O<+~2q$;JyP9db{oNeAnYDMTgl%r;oKY>8sTM=vWUZn zphOD~WuXkBtb>3NOCON$O{ax|AVY(A5the*;m1?D0VD3U7zYzJOEj*Y`D%YE_kMk@ zn0or?>fBd7*>ag#v%K=?@yYX>-ozl%ZM9op{`~CT+3EYZp{E!gmbBQ7m4o`8JWSz^ zm!R9Lr)#0fvI?#kmW-@;I);Hm(8{3njHk80_MI@Qh2NP%`bZ54S^O5RH7Oy80D_$SQAgb`N0JDq7<2Ptv5@j4$Lp$xni z=mccLKf%Z%LCk8SqJgMp>8s7pGp<~?fh%OzkX{^2G)bF>npS_xU0eh@k z6pvF$K_I~gK7~JGL@3~JJg88*9X1hvS-X=UhC`|5w8Itp?L0RsZGz{&UuilDigEFA zS44Suctiw*k)O!ONJtl(9S%>In=?Ms3tKObD<4yq!jBnBhCUatTi4Sbox6+115UURtxFKIPPR&0FO7LJZoLrV0#{jDvWP5k}24E1PI=GVfa>eu>+ z%7a{RB&TWP?AvZfr%}5fuAl6C4h!;pPYUujZ-72j&s(Z+$3^(lhW9{6cfi$1_uB<3 z$aydCbGutf$nl9<=0>#*#oFCS^VqmvSBs&wtykk&C&37iLkxIlMXjLb!K@Z81GyAcG zZ52mq*BK1Kab8m61oO<_N8{xKnf4mY_?(*FwpFa{ObRiI^03@&l0_s#6Z%MmrA+?0 z7Hjdzc;Kv2m*7-MNKEc>*lp<(VzyzOSu2R(h@lV-J43$W7GPVywoKuPrG9j$8wNek zD$Qb!|4d7jJ@*C2^qL85#Gp!74xSa>T)7 zTv0LZ&X~^sX4SO?Dj`YO(&A5{`t2+jG^)|l=htKeE1Qqqj+pGK2(-SHZ5@5T` z>*MWXJyDX@b^jypbx=z9Vax{fmb=n@VaM#Vkmdh&z#MS8P$QI*`%NePlz#*7<9#IH z>qz){W6IF~P8f7OZ3B7@9*WB8_-l**anSho*LF>7^>gUVzge`X4Keni9eu(3BLH^R3rx4 zGGOlae?aCFW{vRwRmn;ibanY{UO)%MSstD+5&_ka4wbJ1kT-kfR*^>$+l|tKslabb%p(MP=nnX4Hj;Rc8ZDfaU!dt3#w!D*82gBr(k6qfPSr_VX@np zw-Yt~fLXzVC)0{X$6Wh8s~dPF$>mCc^=*@9uNCQ=Ba2YZ&InUu65fk2v#|3!g}F-^ zdJ3gk>J9|PdW{C-ZR{lXWEq?tDLTuABEEB9=f4m-MB=HT#jixI{D!P#zGp=m>o|y& z{yc^)QqCZF-b8ufEhHsCDXhO^T)mNgbwR(VB?x6x3xo5?9@2Y4>t)FMo*5{5F85)Mj^;$~cw5nCHEc)Z?-O5Sh+GJl+@9?OQ)nRst@+llZSBeO6d;e~|7^l$ zy1rt+{AZ-PecpT=dUmQkwr;xv{I>5vufv9VcZHReYJLZ*_IAzwV^IUJE7lVeZSGCk ztGk1Xn7I0m=g*1a5i2XGP0OfF|0*AJ{JcCpJ=XyMxW#_6!{h35vtx$utSUD*H{%$D zWwtpNaXePON(eKC>UQbv@MvC9GMK*9917=XF-X z#`fX&PLquP2Ig0LqI*8p6f>Mgp38DG}ZqVjtNEO zIWd(46Afugv=n1%SFW{pBJ}*=z+58>PO23w0&6#a@77g&+yZO^_~pKQEg=IqvJhk~ z*qb{iHtkrZf-b!;WsD|{Oakh25lEHWk);(R-Cp^+ewWBD!HV^66rn2^byN3 z2&z+^uBN&foI#NvW48Q`y-z_bf3B?lS+Xrlq^(oWeF-HW79SpfTM6k?aq0&*BUfe9 z_XcFVX>3YVjgzqD#8bJ$s3`|C^>Gqq%(vxSrPV9U*zOK)cZY|;_pnW{+<*MlK@Ntg zXbaMRB$*iLvr$#`l%3y5K2}sxnx2_ytEJAHQ6=ReAz90mothrR-eA8mAn-q6XA$J) zX6NG*V5y5YJUTj}qCT{+oX5n(q$rw`%!(S@@q6>Q+Gw@|)f9AfiCY2!ectz6w_4TrP*22SVGXNI0{+`_(BL?mr@haMY#cX_^F>kglncD3D41Od-`KA`)( zH$(TYsUEL4VS%T=Jzp0c-LJ5q_M0V8+X1q0=i3G7<*?M>88jkvO&ve|WS6nlK<{!n z*qh2IMX%fa;t}v()FI?M!??2LwcrNoeqjc^{KGZWW3)G$r&coP{QHl`eWyUo{jch@ zfz!~?8Ej@mT#cdsP&r~ekv)f|M#Vw%!{KYtvKUvh&rDqIGw9`}r@OoR=H><%OxM>Z zn&xt2x3G}3W(yPheNIAwBMO}ZJXK_4Kz?Ye3381|6+LQzV~wEy6mwNH1{=qwFM>3@ z_|{646Gdeb3i^l@{JRlUS>LTGxtnsidViR*saHqDN>If@oJ5M7N`Atg&<1jCRzVJ0 zB(0z6=&kuRu9uOEP3zgD^9F^W-l= z_WmK#Ym_KnqWZI0C!A`@8oTPc7Y$u+2d!fd?Eb&vza{IgGeiM=R|`?-o*DQ_EU?IX z;y$5baQS2WDg?i6f(eo(qNY3@S(OAFjgawlbZvCa(bJGp@k2_YCpmD%*Xv>RAd1sT znbb{e$3D}esV{UZtFQG?-e68zVK#~r62+PE5v%g-)#>D>EQrJg;kETZF?4})vKjs+ zGY{U_!Ksca>N3B<9-gVea+ZwP7H!A#p&QmG;aZAS8)d^+H&idh$hbKc$&EynK+xd+dB&hva|EE@^bQV3Ucvt^8%lRSOs_%g;#q# z%#7-eHtg1C)^CoJ0IoB$(CtvqNAyb9<97$ofoQ|KOkBOYe<0tb%G|f&N)!gg3!XN% zCrf~G|Mk3O__ckBy7ii(`L$`8`}NY}JFVIMeA{8~J@VA^a0Bb`(qFw|_*Uc)aO&gX zcMXKimr~*9#jnqkv;fDe(yt?sgWqvM2g&P9z;j<0N$b&a%a+ST$7RPs`_<;>NuJ-4 zDeA_1kW%NvkGmrW{C^E4?PupFjJmn1dF?xL%-wr7EARK+@n8Gv0Y00${$Exd$rJL# zg6`YBlGR&!49u1q6+}y@&n5vsIZhuCMb8St;EM=;aG@)hN~qfeSed{bT)(x^F(l zG1(3wqeb#aqao%G5WN3ga4l(&vLWBXA=t@C1jdtPqX)AP`VtJsarf(I3ai5ii$o0iI>dd zJ3Ley9UV=Ss?e}B)Qgt>4D2fYV4h;U<@53M#ViS8FC^voM{yV(I_x!pey$(+Ea5$6 z3DeD*-xXo?4j^fCtHTRmcjE8cmaG#5(9fXNRIgos7aO;AjxtGrG{I&`94L_#gzrf~(DH<6M>uHsHyGU4$d*eD6v?kWvmcJJ=G5NMO1#toCI z{ZxvyQEYT487CP)jMy0~pKDvhk`@$VMKVy5kCRu7ot{*bpNRoJ$Hbr@AzzXZ6aMSA z8)5#MUvp_(nDHG}+j=Zr>AadT`1*~j|M7k#^vIoim!9@c(gJ%EzS|Dx(6CA#K-dm{QLT;?;YfKFQ~fAj$Jw*UIN{ZoGiwNQC|CIEmj;jmPIi z*Gl(C=0vXh$+ao!!~5y?4*S3eb>1kO^epe zW>X@a`Kaj-^8F+nNq@9z_DhiO7kn-t;awZKXN9cm!^Aov2=R5MID*Ldh`X^i#?;f- z9954UJy{)<5JqW2%_38%Vb)eD$Ld@2Z=sMc~uA|n{2u0}m1 z7pbaO9#yGTI3OwU&*w!%#jr#8FEi!fDurz27*pDyw@_g+4KzQU5 zg3=mjDE%|?=g$aLsU*cBF)<;q4?#T+M{!%ZcDfM}uiRV}GoFWgxo?w|xgV9l)+)yA z`JAM$@j7t%IzE{3e=mO=_x(CJdx`IU@c4RrTM@qB`*NER?)n&J?mV5Y?LLt5@O##6 z>3UoLdarT#+{@dzKj7Z*S%?6A{<5@uwB2kmpV(s54JTxSd2HGHviU*7*ZVWLqy{Dun?6wiqrwm_{y^=*7|YWB zT@<}0)^uLNjqoibBmzUGW^*_C65u}IV9Q{^t<@l7{Oza+M-K{wI*AG;3!72?$pq(u z)n6FEHlf0RgNuV>_Mrz)Cwko{QKz&&R4582l29l@`^}Tuj2ew=l0C4xux*y1Yr&z7 z8HQPmVlwO?{&Ds}=G(qzRM90u+L(7O8^=R22M!L-XcyY}^*p>r>B-RvyQCR-A+;;p zAXSYhHkkbaX-!u;?+yzT89``aGFlkL(Yn>*x0`5FEi;PA7*yftPEuny)k_p+l3Of3 zG-@>R0Qu0cRN!Dp7WFxjiazo(c<;!yOZjmR>`M|t(xP7=WYlSsFduNY!)9_ao0W-1 z5J5l`@XQN?Pqi}H%(p=s_E%aP`65*-kD9aH5#GXf4?w+~mse96Xsb?GurILholM$x zCyX5)S{_lAEU7J+vNvKDOZ1+VpVXgZl<}D})EpAyN$eB=aj%OV3U!%`({fQ^s!w{;{72o;kd*X5*`tcdx$oz9;9zst5G z6yOULRf;o4Tzp_4gfJP%#2e;-F>aY!Q2s=U5*@}$7iQWD)0A0|NtSq7m(9x{gB7BM_@9YCN$yH2jWt%o1v?Y+B~skPx+i*Ot}C{HHOeZ4K1I62w* z!RK;wquf=1`X??98F-M8pRTqVKi=&u^I9INqJlmVm$PP`Qz{Lv&oq0kp_Tlm8%dt_ zE1A7FlHv>+wyLJ$8D}p2hE11+z7kj7--Eu63Ig6n^0uD1JwUI0{Px~6)rLNIE8W*X zsQXa(x_=S&JXw&dywiG z6A<9xY!Kw4r!=kiz=D{L#t+f9U3~0mWMM;^^TW723x-*0p;@E_|Q3mkF z4OGFc#@fx2NbW4ie6r9$VsUS*3ub5FhCb}+K}MIh6AA|jLJpEbe2n}%VTXlr-2E?o z8|Hvl0WJJ^S?W}rGzKf_nl~#;X-cVaD}AE$E)2Lx2}E7&{mHUqEiGQoCeNYpFK))_ zPu8L`76%v4M}cSXUi#}(P`4%LsSLR0o~~?al571p4tnkiEx#Te1V1!$y-zEs4IG!s zL*l#3y5`cEOJ0|8BK+^lM}&PgZF=sedS0L2YQA>#^WNfNd!Cs+{LbH6dY+CzU6)$~ zwJ-CA0%wRMU9XjSAF(8xFT+3_`+Vzu`P*Udd-ZhrTnTIcwGr$a>N@4Z+w8j6I3bpP;h5eo_t0)Va`9(-H1d9qWtrzGPwIZi^`YEBuF ziY(Z@+)eVa>>7J;iC}(^RE$iEW>lN4S$04n?N#mUm6)lr{ByKD^hI9UugYPskYswa<$SZRZje1B=z(`N7{hWZ=mHkDEf12@0~!e$AcKiDEz;*T3K}p-7eB z57zj|KvAZNt>yjnKV{YbK0A`$QMRN3sQOT{;!~-zX1BGYo&#(8Z+7_ixoN)d=WB`x z?<)(SoP?!MH@4S{nJqC0v>Ow#P4iO9{&p5A`Ji zew~NBdM!HoI_UU3ertK3`udzh{`%NX^Z(qO`2dPi;d^02uVdlv=f*3)ThQg(s#5pe zSU}HLt^a*>&u5Fz=cOg+;}jC~+^Z>k*N)nA&|+{~m4sVcB3HgSbUz*YIC)c4ty8UB zo)VYcx;;N4@cKMv8i7(v#J5P7ayO;nX4j=nhYbt+l!yDZ-sbW&JFBduGy^nCsHvz9 zkB)%vRMgaWFUM}e!!+5}S&F5jYV1z$94oe$=?QSxu@96D5=|cLW(#msy^OwqtV?+^ zaU>}`(O+JQk05RCzm2xDrEf&ZBJiF6soxr?CKmS} z{3kFvE2OuJsCi+PbPg*7w!wi4R+%!{a4X{#o`75lsWqg0okLK$M2DDbaq&{Qg6Gbo zy2F3Y*e$w2tt3}SvGZd;F6y|?T(a0QlbC_(0ZZeYg@Y;*d{>%}VI8_go#5YaAC5=Yz6P$z zp*t)GH=2sESy7}mrjs52FOr=LV@ZD1?ed^?&_3;=c@D0 z{lS*e@<=h4=X$YJ|Fb{s^OQZ;r7tPheS0pxhN!2`*R{*BF4ZRO@O16upXb$BN}HuY z!)HIW{%xP|XAXhz+h?uc;U@RTX7iWphZ~U0Bcg6SaJTp!h`0E@{3Gaj&PDw=k^8!S z(G+;A7|GQUT$HXYhQS%XTXL^XVJ=RsD0gpcb!v6me=ZonHT1mSzbV2c(HEYrQosFQ zsj0(+f_$}(a}mGxZ+(3o)DvK2WMyV%W^HZl?Ck97>gw)};}})B(O{c8c7Wq}TD;gl z2zNoSK3=42WFhp;c4DIy;cAm12)o^kl=6`o3hk;(%Rr( z+=3E_0$`P7!d}LK1Lmyxbw2kt>OZD+O0vw&mPs>xQv>rCs-N}70rw((BF4y07ODJS z?R@M=VBGxAf}08SWJ5?nFSlLD@Jv9z1&SJ04AhB7Gt$?4jmFmIa8@oVKgNcF=PFqY z*1kw!i+$Oam?9bWvsf%uSTCkTf~a&{n$?T_r_ zuQ~{-`LN#hPQAmF`F#=w+sL%-iJgX4`cdPR3~H#@jU9+f-!PMo6Rw!Hbp0G-985my+%h8%?(^LsceW!{~?v=qnWwm zsnGu%ik8!bBI&Hm^}ahf87n#1op-KRpFX-hS$uc3_UFsWGGzFn%k(qoh1@L409Jro zn}!MN7b0atW7~_KkRU&|Oxu&~JJ-|83opv^5mv9?8{kr959;zc+TQ+rd1)Jn;Lg2G zHuT!MtMOiDXZE?pWcHi{(!uzZI1)M%ZASYhX9B6z%<8bAT`i{Op7d{4SXA*ExJ(9& z`d(%SzXnn!xKf$5bp>>0s?&~6U&>R$ZfxBPwX*5c77lL3%9FJX=$bO=31HVRmQsKg z1yk2~p<0?jQ~SRPjY=CESd=P~IK{vJy6ynL0ucGw7``I}3*JnOS?nhD@#=+9)Z^gH z*V{9P%L!)4Qvs9ALID<*cT!SP z@MwQgj%+B7{b7Lvr`9MWutF>g4VOFG6E7=*%0JMJjtlJ4~Ir>i`JVKzM}^(Phl)nxO7Z3t`Jv|+driu7HF156zNre4(umLlyotu%|&t$p0m-~s_*J8~0 zuJ`S7Q*_4`UBt?Zb8mi+x)lD^$(riP7MxO>wi`+RVr@JdX2rj9?3D*=7C&nYvde)# zJlIyJR%$fL$z`bi>{cDCt*Ig8?ew1;!fn#Di9M8cRUhqpSXx^0?Op|<67UK@2khd6 zx2M+OskgWLc=36MMmq=N?fYIQDwvo%|0=~!hflgQ_VoxHernyx8STU?X*L4*5CY}=a*JEfq z1X4(u*l}E3T(2x}@xVdH@2kdo4zMf(Xi#l1EPWQ797g&Z9FSmXgJ301q@eSB8`r?7%ug2?@sAEXq_r}z`UDQ7b<9rF~$VxXpwVB%6y&b z-%wIkQT0XoHOce%{_dn%J7JI_e1TO5gn?KN`wffggy4hva;)%HOXwnd-*nz9PNpa4 z31*5dJORU3-sGY}R{=5Jurpi1-C9!qh4|(&@dxjmyWCyc_|;$g-v%i+ZOMN#KoyZP zeCH2+sjgyZ(LqL7g7>WFYdjq?As&Tc2F3?vO|^5HY2~zG74Yg6n5&vCkeSWQ%ox|4 zr*eFUmS;9odl7@}mhnqqg$+JBw6L%&EvL*-nqe?g+accvx(iI4LvQ^HCyV?0o^(vQ zha4Simp?ZFRtLZPeYW4Dw$J0aY^fRnEFEs1R=~!8)HVL|W7NVsgP65^w}X`^ALFL+ z*?cNp`>W$O6eUHlhy;}x4;I$dTrD~|KN%HT(kyjSG9G0sv@>dJCs$GzmP%f%88@vg zvZ}=zwQaegZER8~q;#ki3H9_VHEmS1rHfRe)nv*O6BBuKyX;nKwt$T?z;2;dzLuDH zoL?z#k-Hg^4TG6i&@O_^0E4OuM6u=N%qc2u=<{DIHa~wJ?*OKi9h--e; zV$T%9BUi{o*bTrW*7qTKzKh&3{M|At(EH=j7a%f32(27xm|VXT1SZO-G^(f#=PAqY zigbs2bNwBRDIxQiw}($&bgeW!PlRd|e-gPX?kBzy5l<4Nkl!W6MYLOK8c9km-`s^$ z6DgH>h`pLBjCS~sLJ|fu04L!?o}WUKzbsrP4=*Ug`4zAVHo_7Xy&}&dsJ;;c6(wSj zja?J;jRm2M<8h#)uT`?gvXLsRPgHUceVvk(m9nazkUI)1m3;l;FbLAdM6fSH$jID0 zVYV|aB02JGfQc^fS;HU;kBm_~%ieK@VX}n15eOw*+=etv45`jT zL$*wLf3R|L{P*^Xz;61*GSAx5e_v#*MJ@V59Rm^Dm2YTlF8RM+ElbN%DX9ov*AC!d z17mOjgnP>Th<;)y#HQI4w@EQqtLJ?lQpt02r!vp6Zz-PtHIyF3z}@NNIdOg`wm(rk z40D8znz=lWPo?MC^WqtLsVG8|3nf`|MYh_#evVGv=0t-(VB6?rcIR|w;6XgXIs%nD zp71B5CQi{^ZPvrkkXS$fz#Y`}7-F^}!CU195CASNHXsB7eO@7<@%~=lcPjbQg_}P8 znKTL?7=f|Y^^3<>Z;7ojh9su^^GVyR!@=F|Ba3u?6w$gjjbn1WIooA2z8dj<&loE* zw4k2&Eq~Yqa6VV~hrp~N9foxm1JcEvVS6rui2UUrfyW%gV2MIW5pFqocZxwj znJC(^jXCA{2h8scd%=;%d?I7!AEEe{y+RexVOS-3X>z1Yb|TRz-~wM<5O43t2VrR& zK@^znvG>>HJ0kCu6&MC5MnA_r-XQL0?F0u;kk5?8a%vVz9o^)VjZ8h@*4UJ>hV*`s zOcu6={E?e48o&@w5sUN|mZX0wIE%zCPL1E&Xn_qi{C_Th7z0{hL4#E2T4lr`aE+MV>!%RtYwU$%`RdW4Mq9j;b*bc zb+ial)OlTh{8}IPte57uB8m^?enDVufK|aH@#Y4abikF+)zt<0_NL~d)-1a-+n2H@l|{`I zgZ9!84K#S#U!Unwg)S>%D{BNCUy3xDJDU7X$`4CQmlX}>yN^B3`b}d8q|PGZ7P;b< zx#N~m2^mN>%4`XBcs(7>?d-~z=(xW{$4a`+Yt*ObWfQ{I`gl)+0O0lA?r0Vhg@KTO zAmbN^l)@k>(bAGuinccn-e#e6)!YGC~qP-2PufW*pt=jP~W#sWVR22VgIrN z4DUw90noq1PR?5m(4$uwF$Ra!wCmDxnK+qJ3dwjOtPPnwZN?vN!Xq4;Z^+_PNiPMp zacOLA7n7od70%oB=}eOI%JD)4V&m#y!PA^)qi4j?WPdVI#D`kpge5g~B7Mm;!j0k~ z1gUcCl&foH2WbJX>{&oXM-GKHhH3({+hG3Rc@MQK*cvOlf&Z|s8$&647+8L76@yx~ z6oz(NJ#l2!?w|@3?r(-QZ}M+oMNTlC=ZV8Z_qVD+2T~QUtD2zRN|0sRjHlIdT0l3KMR zweDA^HLF;{H4L;U)H*fWX)MQRLg(TeEN70|_8jF9s$eAF;2cFf>ez6x#g8cUhgAFL zfAS_NfBzQzTLj~;ybfV$N-xiuvOx_~q9isKlR ziFkSFUdgeh{=qT-eEM)V9HZ;MEUJ~+d-A6WwP70}2g&yWjvQQ36bLK^J%72cv zrRUqiyj1hbE{^cqcRkI^8^;uopd$x>X^om&QHo6S6;k{8zLY|@AOO?y7HSyo9w$XI z@uZ2esBrb9sZOi`tj7-Lt(Q@?Lqp>|_B+#KPsQ7#6WV-%swn<*!UCur%AZ{|P+mgz z0JI0VU&^zobM#{zW)2oyT-aNo;^<{c)zH5iMs_Qes;NkRXP@CM0n(77qJcM32^s!FVWNcX_j@d`!A>@eT2@8!VexlP&`tZQ5j<#+MCWcd`_j()l}=yYe*v?{nB}w|jdmQ#F6eB`Puv zIhmB_!_4{4&&@5q99hnQ>{2ZqC9~xDiof0poQy?Q)NL9RraC=&D#81ICqDKq4 z2qZ#6FqK*TnVthC6WR~uo;91l(R(SQBR;Dx8>fzfX!gbg-R%*J@Eq>6KtfDu|LY$_ zSitVMRPcG-d$=xIB+;FyZxKDh8pnA8fxg7jM<_Hp5}_?e%YwE)Wz!Dpdu%qF&+<;z zj!9-EIgSe0xX~};oNNwxDlIBPNbixaFs2-A-4Lt{6mY~OSxpsM24i#ck~u38z;R?* z>^qK{6^4L3T)RO~yi*?=8Y(bSy)?} ze0_d)y}3VKffjlko@(^xSXH~$yo+tssa(-u->|7y^45Tr38u1QK55-$Oj;mbX(5k z&du#ajU~1%npyi>+xmXp-%~olFb&$}8FwRk&!wD_)0-OM*QLxHrKP48rexdV$ipVW z@6WA>}ok{Sr4*%agd zF^aPiG>lX@T5<*p{xo5llsOhScv6l&x-vc$u?_tRzrJ5=f1XC@la;q=S>I>BKFe)@ z7_8UX-U-k+7a`(HxF~mHXh?*cIKV+;x+tvGSmpWPlO*~!zw#p=AE-e*oaQvG*bqsf zvN$5wRjOpw$mndK`X0#Qs7-J>Q#mQ=@GoW=S{Rs^me1Tcq7q_xqUlw3mB~EWn?TA` zLurRN;P%mDIJk&Q)+N{^@Nx}d**y5v+2kNy2%0Haz0_1$fG6b+^DwN}r{_#T_TZib zt-DJ5#<{^oJsmFNaHPHOD?{3w4^W+{_9$euCETv~PZH%V{JDg7Q~K@D1X40f5bAn* zu7D8Ef7R*Y4P5Q@MV41vfi+R z`tScr(TmNkm6nbck2e5%0dSbh^%ibt_B$7bZ%I!HYM9B&&)JHl>={U~OpS%3!5AF) z$3fuv7-W^dDMI#=-Bs-OFHu9BZW2P%Lc{Kk+edk%9Ca#eS|HW^4Tb<#{% zkuY5oD`$mpN1Jr-Pyj>!b2V|`Ou+=*V%D$qcg@y$n$vR%6M$Slk!<@N1F1~9fb zF^0eUFgZJHk&Q_xRde+A99@6n!g@SQO8yU36QfsHsMRIJ+=bvW=EEFbMm?IZ=o^f+=TRD*# z2;mCo1+H(dv;eA}E}#-U|0T!&c)r%`ah3Z&Yjg5nYV;1<| zw@15=55M<+>m9({)tU9?N)IC=5CAp+I)rOJ2sW-(w8#LiEHX{;>0cF6(=VY|5$lNm zfqit9Nd@b6nVc55U6zXYv<*uTGLSK}Y(u!^79!?ZInQ{kfFB=MU@Pwv&YBr3QvSI3 znZ(Gx5!Ytisf;PlV79Q2&t=J*pL*OTkSG$`waqaNK@}O3{7(BILy5q($EnaaaGgdr z&0}COf&hWU<<##F$5SkOZLF?3V9C7)mPrbs^%z1iHxNbnE3-ZlkL8De&9MVmJsMXV z>$_wdtAS-UD!~7GmVYp)Pe0NdX%%Wp@)7a5#t;(cks1tqz$eqyH`HH$k*e!Ib+$&S75o`-hjnhBIp_F zZ1M0>nt3_O^>GJ&0LSp4CpY)51rUFkO3lO(33hd@dt7dyf3E^~xQ&*$=|B}XxlXHX zI;dN`t2vrA$7WB8Gv~tJQpE*L_Y<4Lg3?nmh$f!<9;Un$s55Wi$G4=0s2=PZ2 zHrPhr|3Xv+^2`+aNxS`>%uXkhs|IRyU-oBLAwF0fwwHimexBEtG|X) zBIbDmZ@kQx(tDs1E4Dyc6ybc8Gg>F`H&Xn}v&%PhYjJj?f1_KT#mtOoALx=9Eps*5 z)Pte!&J>`0OT4T?iG~V_yHNb9nwkda=_RrJSR~FLoPV+oMydWQnXzaJI((juvToG& zc;iQNXsn9+?axZDFb~-~BomsIK3ez<)-j_%gfHh70wu5TIr9u$qLufj$taH|#1q!f z1iFmO%=Fyc?95C&5)z{L%ASY_*z#?vYF3uI+MXT<&39`&5iia6xO9NZ4#Z3kD=Q;M z$AExNKPOvTGZPbAPtSy6gs9|~%eSui6D(+!^Yc zFXN8vf*`I6#Y4gV7 zIPs5P%&{AHmeV+O-b1O8`R)-w??fo?0veCsmYktA!IwK_Jb6K8euSJ-+Hj&78_+M> zQS8#lHjfaEguz8&DGbyNwZDz>Qj~6|jhJk4h0!q{ui+4N{`fG&+E4FLk`h3Lmfe!7 zqKQ#1W-*J8=0+Q4Nau#Kmye7{0rzBhIE>K-+I7@3^fe^p+v}_Q6$m8E(+aeMNUVei z9au>SH>-M<~@Wo3;WHJ-TsTI8K6aSU#j>eU&IqX$(kx)zpL5KGIOYS#T& zP7B4W#zJPbjGZ_6s?&c!`wq3MvgvqbI65tc=3$Azi1?aLriqZBS*#}?V+tSrxd2-p z@3!ok!a>g?rfg%Mvut()hW4JA8@VF(TURrIr6qFow{W*5sl6ITfrLT7_pGu?I*3~i z63V!)-|yHT3MvPxdd{x4Det<@ak-bUp2;;xXwFL=GohHeGU1k-$@sj0nN+;kbL zY$3t!Kgea2dwQEn8)eY*55bj#raI^i4q0-KEeQv}&A z^b5qWW`LDkwsitzPDEk1&w$Qwb5hlCZ8lr-no1HHu6e@N$qC4;$?d|O>4w!{fVjoo ztUBT_%j_YD%$!jX6~Z@7k*_52!V^&`*ieEs;}P|X z@Lv# z-z33>Y-v7)A9w|;9wEGVAU3$?^I6#U?CkW^)C7ekkmbqAabTT93eY?;G3L@}bYN`! zk{$N)kQkvSbP~@IF5x0H+?bH1)+2~H?x_h?k4!`&?EaxH$l0`LDN?`&-! zup%oL;;pTgER#p3UY?pZ$^`56$b2kEft6GJ&2fFKDz{n<&O)+OIX=g3fu=w`2sH&K z7XMLOlF7{D)OpVqNXkhj`FxfIK$fzL#e6!QA_#B|kp4h~L0(eZ^Ye4SJr#kFZcrO0 z&YKun-sCtcPoOoVAk;t_d>KYFlqy%NRWlXjg(cD03C0Ezp(=W4@Q%e2mmj&ydo9I< zRcW-LvSF*}n*q2EgOs3_%m>ZEjtPYZ3fMfDNF%~cNQUSMl{38V%RV?#-2nQGeW~+d z)i6Mbnef?=ROF=*pJ*`#oy17FIDsBuaih^_wOa688s}Y(bQ_E_x>bybh4=>EiJ21? zXz~D}cj4+9jRrmvlmlnwm)N_IjbnCDazv^>)vi!Pg5KuzFT+2-`^nv(5%{WRE4F zrYh?jL)$|kLX$gi-~gv+!hIk$Y>`NWA>DqSIX4aA1(a*Gl@K?{cmRK#d0nY2QTb1> zf>jg4@`?t@5e_Dw&vWV)Q0|7BLg8UAUJ7+cu7R_J0oF2n| z8R|YOmFQ3ua@Jvr99C|)0CoerEL5`mC}?t2I*;qt+eHK)he4K{r;zKQXipr^X0vm1 zb2BqDR9mu?&8gNbkYF=H8+t40Lj#HSzzA@MiICDt&5UaK06O5dA#SQPw@ALEY#})U z8Np3}Re~AvDeOgJD9%D$P*hSV#B)3X-3D!q2C!|ms7PFJHevQ70a!~*ORKA^oE9xy zs;f8v{2VG5=AcDA91;hMgO&6Ov*NFUHRsT_+ie(|p}Z5pKx~{;C&l9+5+H7X3%Nw? z88|;VFL!lywcTz@>O=O;Wy)NbQbdUfWl(?vj}sw{B!r-_CwykSC?o<$fzcl{0f{ko zQ)j1NaUi{d{Sn(%tC42nH_!=GGgiCK*$5DGus;60jGcsO?$E1*u7fzv_)$fSzggyN zlScdw>3Y4&4l!!iNGY&296G6~pusxrg9i_;uCBTWsVY;)!=e*TjJJ#G(D)DpFH3j` zaMOYi_a7oayj?E0z=9sQ1})`EG+u@9DL@RC{BWa+4j6#~gO5y*1943WjJ9R40K|y{ z;b>aOrBFuA6ypx*Jg%3zK#n)ryep3pkvs{LDwL^M2@V9CuVCz|7P$*<7qWRp1_6Q9 z;w*c{w7nFednQBDnZd%Ov{G;c%b_+dglu3pOii-PxU{s?Y&Nmg@U$7A3e|Ntgkhf> z(|H{I*}OYfZ4|GWak|Q60pc3G%ud}1l(53Z%)XH_)}9Dk(ITk~ngE7U0)WYcxNp>m z@uH0;TS7afZ@!RMo-VG@&&1GBa@j7x-Dos~QMoF80}vRjag3-9tRozx2hq`eB3_#U z%9u(`Oy47tdcB=z5*eCbCgzd(rK^A}9rMf?C&Jbs@(7vM646rL$J2Cfh}#d+Df+o zIoimJuvF+`u_$?WZgiyhNfbyovw23lH=Y@?^;mX{6i4EHY37~K6&?!f!QX112*C@; zQ#(5rKNt#-9Rjx8%MfZU(uS?mTNByHkO~&)Fpncu4GMc`5s1&|HveRel!yn|rM%CS zh|Wx;Cc{Hb9)I;sX{?R{+-%oGYgx&#rb31rFo|Up)fGQN8PI{L$2d7Cm8_y${&ahM zqm@d@X&k)*{?IzGo+CRF#*F;cI;|RAg{=d5@(k#au#Q!mxT9B6Zx`WF3Ar%5%p5en z2VR`bW*@0PG%h}(oUYa~w6LG*t;1wQtb(G(#wcbR!l98sFwq3U&;eMm5);BIl?rw1 ze8Z#wBYs0Cp{u<0CS00g2N1K5c!f(I7rIGo7J+ja(n|~(tW$ur5H2rs0qxTnnKjBF zt5Aiy;8URt8UdbOel)KN+;C=yK@A_6_&6b0kXHiqpownWx)x-oi=cB1EP*UxM_pS3 zDZnhB7_w|q6EY54<{L6-*=*M1E&)pU7ec{#eKWae2;v@#kck)D%x4ioxveQ58)SvUSEZRVtO5%_d7V*=!aA!(T!kS*QdEfJ;{G&>XOj{$Lb_jG{(p z(g{RBOUVQ1PJ};|d(l!w_OvX7Y)@B%6;O8vx;0$rjeiGD7KE#_CtEdGLx`$XvKokxN?Y
jHm&l3`OjvDZ_{@;8D0CI!P#%Y5K$&bd3uJRT4-|%XU$~xz zorHYK_Q5rv-+cyLuemaPIuf-@gU3z)1^$ZJ10tc_N=FjT*pZqhg4G)Jmr5m8?4hny zdaz0#K2en;e=VAWw&)Mn=rHspT!UmlA7dcQO-RKI6^P&{)-z-foWFLUP_)-}OL3V@w4_N0Uf_g+2D!%mtyn)q7op&BItZ_K!{2 zyg~)I5wC%4gD)Z5AhCO>QZfPS$BXbY43bP=kecvMXa$Rho2fUb z&3Mhag!kePp!q(6FT?Y#@PDBOLLK7u%mNyM`eHNG5xE4yWHH@bW^&UKAhU3wISYf$ zW;2t?EH5v!Xa-)uBn*lXuVjjtJtUaSS_m&fLt+;U*YH;%+l(1{3tf=tgtw@Zp&c<^ zmz{jH!eQXTlenyPVBlf>A8ndP0#+0tEz=pfs`BxJgbZz@&-_(fqqkfj1@>|Lm0N^G zFqFNb&U_3>cj93`sZ_aD%I$ z27?1CV}BDRF+*{qOro z3FPJN4+^SxH7tOvf!DE~MQer(nKjt%)1%YZAjYFrFb8qnTjw?B7_b!@mXS0XQ920VuGON0Ba8za z9$(V9b`oZ6uzYe9EP&96-C$WM-cNt#TsAmJ>`xgYy@EXAV*oXfj?^j|Ae&=b2l4?C zu!Q*OIZ_8Sjx)&R76@-4=7<_K3cqpbBW`(#o$*XG^28aKaxsxjI>KLpaxMmZ!%2ZP zb9gU~L7EH%hq&Bbc!*9AG_`{A0QaR*ab;z>(Wo^V9R&cpS65fr5Fm`=)l4!XSi!NI z4yt&W<^=MRB_MBrlLr04aqxwEMI~DBZR={3xZ`QsT#3D4u~?~2)O(q9=8lJgGKoq9 z&0e=b3yc?b7Ah4Z0>nw#v*53duDc9i|U4lK7<8zCS%}(mr=xP|{IKTKLyTMZ!i`DuD zI<&)#Gy6V^N#tclT+ehH6!Ju-gNyme6FZQNdF$#ED#gtJ8DmqA?YGu~GeO;vRJmMU zU0tOZKCEiM3vs9jVXp)SPoVKHFP9sQ+Ujac(i&!pV^An~ubgXXX(^k{LMwO*eOp*q zNEi=x!epR2A=fsW;Spja?D!QGXDkSij1Vt%m93Dva=(uf#-m6I5+8(SiE}=mC#%c6 zI#^EY?q>Eoq~0|N7kN+%a^EpXEmBTStYFRx4%re>n zRw9jrU7_c)c!&#-*Jw06H%gO1O1NjFL{~{?VUs)#lVPIqKmxIRB7}ReSSQ32&7J{j z3AORpcDoII)BZ6)DlYU-0!>(iDz!8uB{Se|GM3}Qr3Hg#FcD0!=Nw06T0aCM5eB5g zD2m16!oq^07HzR;XkQ|cV*dpzX3*%LUm1v%nluvDYm4=C44uI!Sm#VksNzNP49zd) z*J3dTD9YKHQ*2X9*KaXi#9pmdJCLm$(Uow(dPwy^x6DXni*yK$MCih(y>~F0gh6fy z`cN?QA=PT7(Wtdr4Rgl=1WXneg2%)55IRQ#^YT4bieUYluT;Gd9~Ox7lmwZ~5~h)W z%B?`OJ)qq0wKsKw>4ffSLbY10-EOa~tqIvml4@cCd=0|@D9m>Q-;{sQL!VA-aT2Bg zjV1p;+9duQWnHAMv>%Hos>i3A$aB@1EO08sEY}<86@P-Whu?5xH)GRzQ5O0tA)tG} zH1OSBHi)7+FXJ<7j0iJyy^MmnK>mCVx4LMeAwa0%W&lE-h$hpN`WbFRjR)u*(FZNa z?x|yX4%JvyF$2Ib4IlXxMZ!@rc3*6!(V+l5ln$BYr;-F?=TGvO?$DyI2}$AX&=DvO z&Ju;B;=;Mm_DN1M3w8#jyLyzSGsZanuGe(-y0XUX032uYau# z=lnJ7t@XI-hJRH9oi%3}CxJ*2Aju!@^?N>q^5+}GNSP@m%O*xTi3QOI$E!A|5YReA z;8TGBM(daMUVuYC@G#+;wE{(PNeHl>Y34dSWW&H*P>?qIbVWb_!Ac_!Qg8^Gekve8 zBvg&>X&*#J^-(^o8sT7Lp+$wNV^SzYB~%dd9>3_l4rI#_v|E~0{`|`9#Ia$tC6$Ff z1CdygQKCPgMsehkh2fgMfcdht!1WG1&TK}@uxw?dnq_ld1s*LBL%Qu1?c+}T6L=jj zHAk)j#L;2ITsxXTRKj}4c$ksi>W~zdHKy83Tz|3QKr59_}A;g4h{c^7EQ4%G_ zLcBsbeC(wn)v#G13HE1Nlcx|{FyjcHS?(?)6`6g_+kxm>)RqvxcnTvjLC2TIk=m?X z=3kD$pA_!T?}(H!`*!{U#WPWuY6i03K?eF@_YpNMJDzTyQmF*-&n z@(`9$n9r9g1|Q7kJBf+qtw1ID|F7$qMTWzMF$P4D{xI$@)x!%sG z<+IEptuZ?10RC&eo!&Je1RNLwamdo%gxu(xJyhpV7fjShDvq)vymo03)Q*v{vs@{O zfU=Quw+Px&Kjs%@aF{XJMJyZ63(p0MT{#4i!(Z_qiJv%NyGNp&dUF(vLGkE#_=^mR zpbD=LKl;p&P0UV^6vCD;2UhAzk+8^UOhY$71j1(shtq_DVN0IonP(TS0>qWI9 zmSXr7t>ShDi?-3ME}>L4yaZ%(oDh~@C=@u8meybabW%$;4ad+lT>-S4H;51< z&Ll)YuE7WSmd=(aP*|)-Q^iexl`NY9U`FKBT)@($$nHuem$B=TrASfRiW>PH(}%LL zw&AO6c}mP@&zu;+GnxKF8-XOIP(qAC z6Uz)oTw@4rO8i<{TH=XjqJ;=%1gi;z9914O7l1pl4*Q1a7~S@9LN*Cc{BFHoeNi9;Tnm~VZ(Qy`eAg2cDP;-P4SEE)b%v)I?}Q&fMZ`s?x5Bp%^Ts#Fs_y{B%STi*Uv@dzQ24 z_GWaTOBkjG2(+QbDgeLQbNb9*<=5!5;zhBw4rRzWO`M!3;;_{-VKUt7QxYHaZ6Z4c z$oF=}yX?GwLLds<4l^$xFUcr4a>BPIh!^buXr^S520w`ac!~#OF>68-*Dx<44C6vL z24@PE#`#rIFlwELEHgZ_#TjQdHQUq2LgC*i3Jz626s3>U#bFE#3~?Ap@}$iY5A}&s zN@J@~m8D~32F+OmDAbL>zWD~#OgJ9oC99(Us)9XKzV1;5LoEy87I#bXJ(ZqFjEEsj z7O7zdo+SJ9-d-SHb0wh9rF2;3x)zLdg{cv}(gja|OesogOW)^1V zL8am{(1)~12uWgx9gynE)aXq3ER`9HjqmLcM4VPI@bC!_TYf|nxDDus)Q9HgC}dF# zhu+#%7O5zv#wBaZUXT8$hhd_F=hkX9UKM7ZM7FL3l#=-1Od*PpU#m;Pob4b$+@9-U zN|mQ5I4@?rU^I<;3I#$7#eya{i8ykKLkfigUD~|-$V0=P6Mygxj)!~szC(z*#~gVh z?I=oeuybp2R%Hzl|3S9El8wJ03uXLlhG-5Rl1Y=LQvdGH8(7qttgzO zjG2H2$PIz(|H29xPGl9D!XiKJMH$SqV`%dC5O(R6p3Dd@>tgL2(4Bt%sPZlr?#FeBb<7PW=`7(z~hsmh2rAR8L&w$rsiol{|N?_tH&CDna zn>4)(SLH4X7QrLSC*m_eqFF;e%%zb~B5{f6*lWY?8{Ra=Q3NhC+F_1i5|b#7DJ$}8KhteP%1pPFpYn$*XylT%Vl{6NDooY&=rY><}Jkt6oCFPcD@lhX%kU| zhAg6mAGiyzDb3<8THsH%lUPeo!O#R-7BP^d->bdy)==P@QrHtjq5K^<-)nRRD=;=; z-5coxmw}c{kc0ENP<2^z#nT)DiwT&vai%&0po+p;Yz2j*3+MoNkCIE8!@P9B3n zSllS+xQfVuA@zEdQi1O4+oN(Nr-wF~IT9>5Ub>4|i3SW0(EzcGU!4_7O<@_*V(xV)!J^wiQQQGi2{lF1H{;sq`ox^R@XWl2`tkA2ZH~cr*)%r~&dv zVrY)!S`xr~Nx?#GfflI@bXCb~y;za;0EWhBG9wKwlP8kZO_+LUhko{nBoOdk@_GuH zRU0%1b&7uq*QeJ}u{HjnB=rjPpWKC@lQ03eBo!mvD5hX#cAoYbGSiCW!^bJu(|zrJ z;<;SVwXEoGn>EC5P?8XXc$ST*MNFB}pyzOT`tK-wBK->g%4hwGlck4KwbWsrD2#+1 zGg0ZI5uo}bh%sI%xyuilF!RW8kN{DjB6Sp9VR!!Dfo%9Ai+dPSca12Le&~ga2OXia z8?&A$=1n9tIOo${$ZoNV_r%+=(@9A>i_%k^ltGqdXcT33Ih*2wlQWYBm_ZE5_&?iXG}U-!M8*&tk98)Kz!`XDzlH zOO<(r80qrZQaZUH2EG}x>8dtm)Z(BB4$!D-wc2jCTdfvOi$h#hIl5|>5-rdrAztY8 zF4{4)=SrpIWqi-iP|uM+&2Ijg7^bcwY)2tDePVPCxMD^K>lSX6|1&y#o)dUgUI1SlSKeVb#!8&Ix(F0c7 z345Jv9*O!UNCb%Bnjs)!O>UeVKxmzf9<+(g2u6ez8X>V8@&d9+^9gMVF=T4$0UzAy zpnoE4Hy7!ts_Y(2fOTMUQH21+Spmj~dD;WfNpwh1b}bHPDeDwNxj>dD?L}RfJf=VV z20vtahpil}2U3kk`wWMkCjz4`&_|G+P&Fd`u<|c7IaC&8362wr&a`sIb!j{l*J7v< zCr_3WSi``9FkuuVO|WdSiJpYB50bk5HI$f&|z5Hj5G8==rW3cz~kHh7Tyz!=3% zo)SdnLOIZRv$A@3Lv30PnI+GKF4%`KeP^D7S?EAEaMOk9Xa^VetXNTcmhZwB5hY~g ziGYUxBx@gRSy8zyITFlcJL3qLASRz%ilnu)@9B9_>-cMcfYtl~&O z*~G69FiK9M+@(I(9@n3>{FkynMR|*pun00E+?LaJxkvJbeM#3M&g5`P?(5U zk{FJHi^V?lKTLySESf#l%A^O~TLfeqJ&5=$=q1FMh_MpAV!Vn}I95Y8e@H-^(niz5 zo^OWiu7*dOT|=AVF8}I>kV?`w{19n2rC@0*R4|MB#7f>%+6Z^01L~3 zJq*Eh2D%kyZy7u^AK3ME9wtc)oYfnA3_S5N^%} zn#Cis3N9)lAG&AI5cloOi4mYye_*hpPHQc+>5Mp+j918}h0qgl2qLcy!$TAOIE0XH zC%_1}RD-o-r^dnzsuuu=xJF{x%nSj*Cj$KRvvK=5Zt{U68H==KRAEGw1gCsZqq;KI<7_#b}fKKT@ z#UV(E5gEMFN!U!-atPT%GZDF&<#1-b*AQp(=oAZ&!)b-ercYw*PAH8_WvrW|KWICm zqn3&Ah@N0~PHP9U&2?h)*iZc8sLlZnW&`zaJOHCrgF(PB;>IkoTi4kv(o)w=*D^?X zx8F-Hcoy@7`Z9%Tq&kfrK)3Y)-PamK=~OAdF@dftu^33*1vH#Aw*cp0!wj{$PGR96X_}kH<28WzmC4=1?NAOgKTH8?hY5iTbe^dsa^eW5O_h;FqavLsSg+=Z z3lvcpLWcT{N-%MuKEw(d)lhGKZE?7+D}Kd{;bE03S_twCAL`VH2^>UW2|Q*47_rSt zXM+r(oX!zOuBlV#rg7Rhz2aAWDtC#t+{Kr%VMk}Pm>$8E#;ZP^%9B7tmTV+UUnmNm z$j~$jpU%YTTs6`VJH$9gBqDP?CZ?KU`vx?)JtmrNU}!c=SNT)oCx{2S`7+Dv6w zCvM~6(CEK#thPw2Ju^h?HW+dUq2uv0E@X3uo%h55y;1N{$V@>3k>S)p_8BF>(D2_# z?=)n~e_423S}Mi0Vx8BWSkEh;)i|X9v6@CN7z}f}{K`A4JoK6B-S`y&@gm@+w-bc( zp|+9ARMwygj*hexDO3{fycde_2Y#(zi4#fD879W#rdF**^QDM#L(>S1&IECSAOn%% z9D@k>9zZ{YY$BU5+pF~A%E%RrA6V2f#cnkQX|To{*3Z!&iY()dM|2LK^(59Wni#3q ztBpo5YsojGI-|5T*oQk)6w2AZaujC*~N4&Vxqd zp;sVam}f89p<3Jd_4&qi4Rnl1E9_7NOeo4BCmANtBJWDpM;_ttdSXTjRJ^ae+rxhu^50G zH!;Vw7OoTvQhZPqut3mtl3C?!KwltMz*1N3k5qEC?vh;&gd| zFP=~47=G{-Vt5W|CLg>K!5Y~ZZ4e3J&k~7+Za$|3{SQl7v1E!nQFPKZ`FviuL8~F% z7#qr|31MTQ>kXk<-$)Cl=#cH*>y1J^Zin)ngv)F-^p?Jm< zqB*&EdZHnVXbJD@a-6Y9n3q6r>5l{9L%6_z+%yCg8;w$)LOBZjNRS=&(3WZ37Id*n zH8ckubLbD4HT|DK2`w;EO)Q*i#I9EZmw0zDpG~=F+F&N(LgJMgq4Cls%nbEZ+(Nk(neB4fnx2v$T z&P=q%-;L{+sC+Q+HyzPs!JVRPeuY6pMS*Ye9r*CAviu6gj$hGoW>&~CPtHAh0|YBW zrUX8P{xM#EZdT1uO~c7b%$F?)7A9?|@C)SzT!wX-F+_GCn^_C=DPrgff#pQ9MhQ6P zSDwo)%n{#{3;}k-@56Lc*q}SJoL^c%Lk)nZHf&2ClUTM`}*dHfa{}kqbcwH|o(}>-md!gDm5JZFo zL_<&>)z#b4veHno1(Q$+k^uV$LsWwaxCJ~Zr-;11H{w~v7?jhwL`JEOK(pfor98*jR9>%3QE=h zUyBfcY~a;cI|13Ewg3Tk2-)Hb@Z|C%<=gST&{CWw=)4-j@#6NvvmoRP=7>Vd!^9v@ zH9nNTFcE%mI&Iv0!^`}v>k1cL$!LcwmPQx=nFK9Ji#=>hhyWV8$?&sLj@}L|##J~w z{FO;j^8VHIh`AB}goO~~VNM|=sl5nC9MSwl0cxD}z9{NuXkcD|b=eFT)07j(1o5EF zKZOQ+h`_C94~o z>7UG5N!)Ra86 zh$&VI*}6f;7As9>8AmD?V!hTb4TN0^^v3Bxupv25hv0K>2u7~Q(%WjaVv0Obh=S*1 zmmU4ruoJO}8sPHsCD05fHolP-< zn&it1oOeEW`jYe?)J7|uM3F+@!-#~QN74|6g9Y(KfjBfP?fsD;o56-EijB*)>8kw{ zyLBG?i4MEm7v>G<9s?IiY2QDEe+{R@r+8!HLnr|y&w?4EQ&0>fjEcD4K7=hx-gUjs zivqD_wIcLzw#M~3Ej7nfxFS8B7;#NJY?@ZR|3OLKwSsfS)5c>LN?PtZ)3eYjr)iQVjjvi{45=&WgVe;m_%ZPUtM^BU&kj4 zMsE>IfOt&UBjSU`YGy1UN&uA-8`V5{hJ%xMufZO^+gcy91#rVq|4aB&*t*|xa$bnTo+pZcDzc?xPgzPA~*El z7&jK_AS|aU$PB2^BP@FLsV#||zeQLYa$65cFbIDAr8~I*r>E7>ncEeaw++33)?wQw z_Sr9y9aVs-Sw|+%`ldDKskw>GiFX1MJKfo3ppxg0LSmDf_S zrTkOv1A}| z`FVs4i*8#9WGeGYJp@_#;|;om53e`*3=@^(&W34hsV4y8n6C&KAcD^oBqO-`HzC_5 zOZJ|w5%2Eq*!SSx2Hg=mz#w-jS&4Jk8e}0dZV7@-IVB4LU%q_to|6{=hr{7`JfhYK z2^cjS6RGJVk~|>54^Q*eK&%US44+wQ5*ib_sUc!3I5;jWHo3tdVj@OLq#pWf2Z7zE zr>A^P#vteXA&k0ZpJ(0N;58f;-BqEctE*!@&zP9rxPe{s3jdKIG7JYR1Nf!~b!2yp z*!}(e1+uepsv5;;+B2Mq@1$u)oF>XZBx*bR%^=%FaStePke7{5dbHxiJIE4s`?bUji#0%|QlD%eSKbpDUj|FO2Jc8$3eSB2 zB3y+*btP7!7N9TuB8TyF{7VVhU%<;%JbB`;r5H55GX4S({c^{~m6wwr&ZElwF;=FZ zDZz%mdUCC2_GXs>O0RAiDIgfUcH0-{v#ns1fwGShXv2`;UIVHsI)Xyt%qjSetk7vg zQBMyEor47*ugYOgjaMNkw@6bnw0ek}(aTur;g|+A&sJs>Rc{&`4u=b5=LD!wPIsmq ztB-`jf_RPHglr0x?6(!kS4i!l8z4Ua0Mv@$Y(p#NDwyS%t87-0ZlH5(i;rbv3-s6S zDsFlOo#P}uHX)u0ILsylIic7#WLvJn;yD%G2iXRSp1M!vLxJ-7$X|BKJYkjRGaJ-4 zscaTzQaa+C6=l${nu=yQc_LyudkI5utUVV&gbO}00ILnXP@qY9?qET#DNG(Rjo;Q$9T9Zcp4VXKTJ_;ggyUg*z-;NnXv?U*3y_2hH zWOBWnv{2%P3D@%eG(o*$#slZtN-YCqaZ_ULI?-umSRAgF%(rL za;R*j9?mYIxZ2JK$_sz4BJ1X!k`iV=Ke$y@iidB4az3E>$cH1ei89CoWGw&rJsKY4 zLmpd5n*RW(t3_eLP-p^-&?V!{3L1Gki$$T0R;EqnaHcV%;BL(0<0H4A(`Vbd-GuYt zFYB;$p0>8~lt5-j?5RPpZ4v}F_Y*8DRSCZAoY=hT&VZx_VucS3sIKZf3LT53`tF?g zIW;pU+yN1mk9u6fk~406U4LO6k7=K{?8YUhM!c@vwddG2Qkkq~j~jV*Km<>iPFl$J z89pxIeW%8UJ@|HD?T3h=d>kVoo2^@S354wB&e*9d41i%J*RwnJSH#gGk@0V;a^+~y zI7`rMVhqh2t=Mn@=n=Tht~bOCvbooq+Sq2v&T9S7KmRnR3sTd0;DGGPKp6^G-<(bT za@d#i&2l%d^HR@|N-H@fs9E>)L4vk#f)xi0t0STzDi)aIbJe*u;V|i;8%o~S5{c9a zkR?6>#Np2ANk?@`do5Bpf`Az6*ufFC*=w>$Ggh{haQV!fL5dnoO9m%#jEe~y;uW33 zVK*prSQ++e#5J#AbdsULgwJ1({^(c+K>*ba&-x4K)*vpaCzswlZh%Xg_K-M}NLr-1 zF;T5QsC0#F7oiY9GmjGI4&AtDt>r^{#(c{&%R0&!+hHP031OPybVs5HFXY8>cDG#; z!uRH6_AAko$J7#_{V~}Q#m;DT8X9|NC@Y!ju%Ll#Hmg!wLV$dNqr3oN^pwP(v-OYJ z7-6E~r6HeTKR+XQswujObw`%oks+Yf@pw!RS0Ou9DQp-CAQ%3`U&!`4F(i8HG7qzId2_g&esW9IfT{X&Btaww{@QNTtDk&H1t{pI~r! zmPArq%n!=mO4?CR}zB9QVKLpzQM{S?!$w;yXY?LwQ| zgM^X=l=tXC88FdYcSP}wjc;x}D?>j`dJeq-MZ5~BJrt4i{$VnGVuU>nAv^Kr zwKv?D1Jvm%+iWvMl9O>a^B928^00KDcegbd$Q0Jr*V%Xx581z{1beTCx6YMXuOUd@p)A>J8!^OTbHJG7MTSFzb(PZ>y5_T++`|z5*yzt0 z-LgV0I{6C+KfQxuN#Z2QPkM7RK!H?+mE@pY$HrB*^X|jL!(}g9AT}2%44%89=OBwa zAugIkZSe@(Rum6iVS?rf&{#~)`MblH?{2$i?M_90al%D6Px$fZ9*^sBgRvl6_{*iV z7|o`N52d^%PHyJ4465u-j!o8p)kVV9%t7BPureX^IZc>b$e3YoeZD^Mm-&&jh|K+4 z_wG}Vr}&{SY}H?ShgU?2^<#miDN)TmG`p;Di@|6J*$E1yoW)EX`ZvRcdwjC>{Q2Jp zy)u|yP{SGj;&7z|IZSoo8v=Y%RT#oakq%&DhlI7Tzixx1=+DD&CL#F%HhIC$Vw~HC zZb|dozO4PpKzfw8mgr_!+`;exIGsn{?^74lW+phH5*f!ri(kHc8TAk@%g5xGpJ{AI zNE?RFD-s^vaoviH_g8Dlj4JXulMqi_hBMX<0mJR9g}nF2hig!1Dnb;~IY9sASXnf@ zuCje2CYKE7i_pujxBU6%zyJBqfBfSg|HF>}kVct3crPb$9Hw8{2D{mNnL%pe)E-*5 ztvWgn1mK&6MaqNsrpkaj}VeIe!=*Y?+Gu#DTB9P;S0TlP|L*4(JSO9R)`)w*h(4+=_Pfz>O9( zpfKHLjI1I@K~540BbQaSknOS&aPjw5foy(WZdFYx^#KiAazE1~Yg1wj89JitU ze-}}mtdC}S_6H!Fw&@HU;g3@?v+}i@IblyBlwsr;W(GBf+yr79M=%AxKLN7M-6HI` zrDDyKta?tvkAm!S!$YB82oT+@I?EOm?u)W_g-CE~|mQ>>ze= zRXudjsG6TNM89jnG&j<3AUnS?vaEmq1v=C()dDn&%<12Ro)Ow|QlgW{3)ya)ph`zm z)doFA7GbQ6v6#uvOo+BBM5iN7L)>=EJj+Pup%Wf4w4n)?VBx@<8NWYdXAx#!=wN-P z`-fNAR;dA`R4fTGNFXzqRYlG*>8-uUu{)3E<(>hLtGnoCLCyCoj>jW!Kl-$v6`S|F z$^=*3ra|IPzVf5D^fW;bI3{E1%h=O#0yDL2qLbhqo8#uWP>UfUn>`sUj(>%0uo4qQ z$#HQ6#p}^G`9%Gme3o zz{mx%{XQxfDi*uB={HV!pWChHlqX*?W)DRx?p|`Grc4+D3{RiQW*SfLVUEbFj4@KP zm}o0HZ%@`W$q)mz-dO7e*!(X#8lAa`;J+01Gk2qux zU8I)C_@o|{VAS%Uutspm=K74i=yBo57V(+n2S@n zY)7-9w(xVv60+G>;kjx3w`(~%R<}&Y%ML1&8i=s#ae4xY*zsHe&}D65 z&h*n~34B(bD-|Av%5m2&zbWeV(Dn9XE_hw@vYPYVLf_~9G01j_if1DbrPNFK&GR%3ryT`}F`PVW}YZ9-$ zvxk z3ZR%{A!0@3P&z>1HM>L4&(D~4)a;$sXM~b?rP16_X5r8MMuvbpv3~57yvngK!HP&p zyajnl3{luJUv*n0IfbyItvaGPUr06gE|5J!FnH%CsgKz$#Ob_iXoEYq{@^%@*p3*g^3L!hkRN*YowCkmbbDld(aKIDK zI#Q#bMvp|*;)oS_xwEn{!k~)6A#wd?5St`GHZB6|E@okRv7dYb1jM5pF#~N+=p^xC zJdiOcNY-D@s!h~bO&YJGIjeB#%tO3d<)nMi6sk!-dZivuIkcRTUmn6gclNi2?DRi} zCOUq30MX^@kFB!Flku-%q>6-W9grAD)>Bk6*+Mcivgf_s%SV9O%RU_ZCNSN-d_O>_ zqJ|5YE~3|u4P3IoR(fLfx=yFm!6V-8s}!D31sW4 zhKfkYCW4G0PmX(^6X(4~VgDqjE2j$Avlv1q=MOT_%Oi)tS)5a>d4+xxz&IFTFXKoI zM%=;DobxUkP-yx&F5)t?Z^qvt~(OC*9UsHMzIj{`aq zG@-lDqfBwifpaNReWxFr_6Lv7kIh^jxYl{9Nk7qS7ffUMpeKj6sw}m6V9jYK$6YCI zqCP*LzS{@l2+FD7DbTZM*1Avt$4;5{C2writgE!eP_`O%a;d?SC%MYT83vAQ_bx6< zEGzL^H_UEiJj7w0WH}F0R78olyA6(=^-Ehqw&PN3f8v%;wp@QmET7f$UZM}}fu~Ly zWM6hhI1rS(UCrIA0o^eye-@UjQw_)x8enrHV;h zgdG6g+#|-%{Hr-Ju2iiarmzEG27o5p!0PxVKB_8>%A`}AN(WN-ChdrzO`lDL)U1=E zT5bkX(!RF7@q=Va7U4)0k+0IcrFHpAZ1`Cvp%rGVs)syGEGRfoCqzvispRV7{XM36 z=*=cxus=SY7Gy+{JC;B;rYUd6j(kYXNsqpH)`!?!Y5L=8b`asStEa1+gzV)3^OFUF z16UUV;(*c9pU`~z&?9_(b6k`!0!cP`1YaG{ToFpb*Yi=#*y4$}Q7aq0%27_HJu0H2 zWX6`5iJ?Dbh=w?+-R#%(S7|n&%~xR9VR6eQ!3g>XARBlUxZR2!K?IItU!hN!PI{wX zt0qJ=dpDL4Va<7~T5&moe)R|90-ml!HWYJby6r8`7(n?&(EMj0 z+wsl871K=&ieefQpg)Dk*;zd|&URMd&b&=e#!#ELs1>YzLiF+R@v@gK=%^jl zmmRqCkI@K)`D``vG(Y3xX}50ef5CHwKr<(pe?*q@Cp+v^>0Gj+`uqe{X;o{Qevs|n3&t8)xdcrBKt2Uc3QF+R?MJOQJicq85b!z4S zI)z%->6)fH7OebqMt{^JWD5lh2hGzcw-Cv_hld9ZIk@70tsu-IGhY+B!QfsXTewV! zL3=*r#1i`hAscgA7fPzDcyAx<9#iE8WHSL+LTbneCXGTjXDoXgGDw1*eil&zIxrh@ zJBXy(lTT3ODTT!^FBC?MgF|y8 zU_-WL9v=_JBv+Qem(j!4jfecag9(ZyL;@@L1bs%{ z)g|`nMc&o_vN<%t60>B|XT3MMnMIT@V%8k~_*W-uv&mG$0i4MljIwKHz}Jl|^2}OC z6iKzo-$@vsk!+s&{uj7GI{yMy8S^m$8DVL|2uBSrq4YD|Q`qXxTs2CHQGmz* zkr^Cj6jae8bHKFM;UX9mQCP@Mo!Dg-Wc%K`2;5gV9*;R{>A&$oA&`w%DD>Ot?6PLu zgzU>bL-sWCA%V4Bjz7edB80pm2(HhE_)C3`rG3M14|7B}zGS96&Gm|~X0RAG(H1|E zKQk|{co+c){Vc+<-%04_ej+tzd7HRS(Oytj{#p4-s`I8B8UIuZ-{w_X@C|Y%9H$DY z<1md}=}hsYM>ptN4U>lqbQUD9kfhF{t#dp_)vUi>pN)wJcAIJB(4d@{tIo7%5F(yrRkF#WhUX7JQ5Vi9AL$;Bz`{suU zVGQ$B(q>FXiCC@vRUr*i6?8@3F-pEc)`V&Uqia)jGb4F4=dU6?S+mXl^>LI-rb_th~Dgm{1n~77%Rz8Vb8rl$rWzMXq=2|yC zMKIH3D+H>di;4UdvIS-F+7~E1B_Spj;V12XIsgD507*naR4vLP5EH@OW)Y7p@7#M) zUMo4|^v9?{?1${M=rS<-o^(arL&0b#QQq!6L^)-X!(0QLtBh5#F=8{fb&MvZZM3@q zVVY3q+0R014@Xlcjy14K*v4_05lTWRwyHK)aQ4EUCW@_IzKo$uE9Hs)5G5jPiUKiw zi^DH5=^hXB(L~7RaYMhD=#wg|kR6-aCm+){d>%Q;r~9BAmjXmdyfb0YLt8HzHg5mA zOfGZicWVouEB|SNjGj1BInQxcuh>vxAj}X4$S%lHd2(oIwq!EYb`!1qi)32&6dqn6 zJFxi8#~%{5lFkfHx{%sKF*jGW0hE{XV)TqK6$~YyFC5^E=9IVFWDl(r!;>@f`U(jv z6#iABPGYsB zb#f$TF`1dmY#F;_tqKGc2OV(Wa9FfO0PE1gU#@0M@&joM_cGR}r()<=_7}+B-k8#K28SJgw~yUH#)^ZY|3D;% zMvOz}T@IZ^DqYo#yid%;@hV;$8Tp#iSvIS+)N=^}(zDbMG zMF@`e1Wp}_)Tz_9LcElam{2bGa9y_EWh0&HXgKT%PS0S6F_xZK;M?KLuW4jutRmjFMyPw_h6yOC) zu4>NJC_!)(eAS!georbA>|z|v;J8t81}$fNf=E3@FplF6RrYibWUuBSO0Z~(Is?&> zD`Y1ki&j3CBuBzDDniUHA^{qA;fT3j1F|uaW1KSC)f`3LNaap(cH5w2+qXLFfrras zjhu(H-TzlVi*U$`&=7=Gq!|3tHXf!P+innQ&~6Er-5F%7C$a3T>doR>1WyP~dREfP zAfS^odGk;VHKem9z^Dm1i)8XE-_)Rcaxh9STzZ$PJWMB3o0wG_BR=^9WY6&0_@h5H zr^WFsk_3ldgQ4(k>r`Z|86ss?iCJY4le7Xoq#5kfGM~tZ+KhW@aEZ;HQgv2~F0sLP zZ!=yj9WIv?$X8uxZnZ9Ol7j0O=rV8Gcs~oOAlf&l+@)X~q@>g}nQ8QMnL?t0xJxFrO zu1Q>9STD#HxeBR0EMp$dV2k^WM$_j{?MZ1UyiW8_kcIw#$ToU2!Z=q}Wnhz5Pv#13 zvu+j3Qp~YaV9@iCkga2OQ|u^0=W)!XLy37veR4=!XyG7F$@%?X!)+b%}EKotw@rJv-oF^ zE~{)YdX)gsy+wKc;lWFRvjO7HHDfvc;_~D!FmE`)Pq2-BF!bkXfM>}{Yke_ScGB4U0}hwo@~)`W`&%k z@T4rN7606Ham?AYc)zG0W zqQ=Qq@?BVg+LoD;c$J4qr=FzA+6r%_@*X|aotuY+)ZP|L-}cZmD9msfE0by@_Sj09 zn;k5HnV-(VUbE+#)UyHsKBRInWrP*QY;GuoRCg^rWjAepcH{JdJHYK;3Qw4*JSU!U zN}%=1r1oxb;|L&_7l;%79G z%n*FSDjTD?p#zS`Na%kN=2;PH$bNa1;Mr_7t{lr&9;%^;GN;9Cn{+kzFda)eQxHB) zD1MMS?}@3fh}4;M)iCC`AVo|EO5x7Kw3Re!-}RT~*iGM7m4FDGDl|_wl14Lwr4?b+ znE;$x)tNC-^Wxs+15yszLM-Rw-!z(b-Dh_Tg=aH_KaEO&YoJxB6`FId%6!Oxum?ru zVonrx)dGsK`qZwTAfGxD@eMfg2E&k6p|M+#Ozx?UQ=KwC@p1#QeO_BA-+*j)EeK8i zwRydcr9%h{&F~G1d`)D-&w=dn!MWN|NkadNFawIPZT2exQ~?`)2xOx+og6viS)Gy4 zt0K%@_#uDKPKfJkUhYt!h*IleLJzj!hypVQO8@LoLq(`|KY<1eL2tAbvc;)f4wo~j znZeSE&4o^ub!u4cxM#z|H;^4~;)KXT=50Ok6vqT#m)Hnsu?R{aM-zd?)a5C1tt4d2 z1nk&_NGzuB3E6&8Ln|hjj#Vpf8ya)ldY{wjK}gKKX@`uPnQ1W_`W#e0R*mZDs5r8sz7o^Vo*FB0TkhKn5ZEC1jiPcxx!iuKw!)gufQ#N&zP)6VvLbeO}e5ul~GB)E- zIc6oGWRAU)>KH=|sm=0B$<=|k$tsbRkWjKJyuqyQcxY+a%_U-&9}kQ7?oNyDnF%Xr zB-A|mFY4h&F3n2Md+n;Q2r;^dS)4@^9Pm*J>eD550vw)auYr=}L;Dt=oi%Ob6ydsI{ah1)8IPObYUVg*VQc8dB z@9*7f*7LMmt@L)RYu=jC`O&%@d&IWM^YgQN*+Sw^5s4tHv>q6&oP=F3ueQz26ElD? z>2&gW?lL*h3fBanyrIWQXAYX@-|R)w4CMGXWsF^Z^Lh zS%~G|6i#~99TW;B?DlHKR$^;9>G(c9J-xoZzP!BHkf)X5WUv3jAluz! zW6i#SC=8YvDaGJ$R^dAP3n4p)IcYmmM0GQptkNcdXHn>35oON90jV!V;LB zck0q&(kYyD$|Q{s%UGQLg;TEDUm;a7PBA%oR>&SBfc3l*LIYP4>6>(pBTPeDgQ(l& zkNwL14U(`Rd!vrBr_kfojOH@!70wxPj{pr<{~D9)bJ>YvKSL9OjlV>b4*1t)tgGyq z54Afniq#m@VHy&zQwHYeud-Li$=x?oa3qXjCW=gn)GxETDc@9EGq?Vtxz=rhwwYZ3 zdV%Sy&XhMzDab5Z=uy~`&QnP%Aj(+nDJETpgfK6V)2kUyscj^5gHxk6b!HF{%fAWJ zduT?-!7>vn8unL+EI-TPy2vov>FO$NWD>`HD>Bd0Jl#kiz-9WCbxprOa3%>NZv;$! zG}qKpO#P8?Zpc7UN2NKNSZHIhC)Veb_QAPM9+sGgt9hIc2`M=eDzAEz@A6HKO5_xwKoJSGNm~-c z$6KaZV7b=z7MAa2aFaty!+0Ywd~gm$x`%p`ObNlu|N zkykfX&HVsV$BG!E>VCRDq^m*|`x`>G{Yr(oO3fg+{$-T0h^iDzx**kv=_F_<8knE8 z$~L_#4yB*73fEbbJH2^-LfBE>G`1F~7c`d-d8q08`}-RkBf?_hb?zyPl_fC4#B|X~ zCWT939qLaJiaAJ$9d4fQ|(VuG^;y<&yJR){^ zr_TMBEOpyj5+bJN><%2kE88Y54&IbZg^4@*poWpqV!0<@!u}$eMs+neMn+p7%gLT5 zfTj<2imO2P!4tKWF?q-b`)dT!qNoR6zr4I;5Rw)ID`GD%FYb&Bi+Je7kgIIn&|!$u zFVnS%y+)f^VW5DTszbArCW3Hz1pLfqeK{kA=u0#J(AkF8XD!nefO@bBWsW zX@V91nm0}ooJ#$vA*aU-ed^h!Gu%nfS~-?QWZRKe*t(TdM3zeGDKQUICTUm4MW8>6 zgjRFA*H<$V`t3+IBwz6j0qD1mop{-Nl^$;lu8PUD0<~p`kO4=aS;gB{Nmh39i^#q} zBajGXc$1m5wssP4h(3m{I&b}UpylNn_Dv>1@hEXCAf#*S4`-m*uZVS(1$k-$%!{7oTSv>gd?7LWzF z6L6hZXq(~4FmV=bHlMAsX}JII7<4!@4Kw)}-wZS7$Y%LPlq|^_2jQUouGtP)-+w^%0|Nk_4^L@S8&R4BA{K zk5CKj!cU+#y(&!q1(0n9o8snN5lX^08%oSW1&Sz;jYFHBmb$J!W_Epp1`X_!JU>6$ zk<3xB9s|iw-}0!0@=<1$dvvBuTeQ1JV$Bv!chDSWb026OgwI7 zxGb%n3c&@1mZwlfVY*YSIeS58xqhXyaP%Q(J6e%Q(uvUqHlycWxs{&Cy9(JF&9U%R zET?B27P5V+`glA7**w>HI2?F@B41Vsc9xk7e=T>@h5Kd^>HVE^C5(4=#D zoAgX`$|OCL7veF>5I#OWrVmALL;R|6W`@D7WJ0aY(+Y!XTBOg`Mh<+{)!5ut5_*+Z zbUQUHhAyjVmc#BftFQ<)V2A?P_?w@F^V9o4_Uc+s|BINJPz(Wqqo8EgT)ujWPyo%P zR&zHA)s~+d4Uwdwt@H=J!y$hp(sSsVZ~Dofk> zvVMX7lOTHrsR_GD&*b0BHwnN><0y2F1hFIOp+^}xBG-a+=F){oJvvjZEHH<#^edot zIYp?sh-&EBYVM)S=bwaZ?GD7{#-ksHdU|?D$ToL}hHn^_ToDM#6am3j4;7dZZ;Zu( z@*-Mk*2FfUN)&Dja~8?$pm>y+%TVg)NT4m<&gP>(LN=zk5#>5G<=ti(jc&*bnigqU z#4i1s#Vui!6*Ow;n&~aF3(8vOp)!3)0hfB5On1OEu3!BF^YS*WE~mM50o`_$Gf;m1mPy zErh33>tK6IqS|`6r>#oP3H>pv?6muqegoMHUSBpwvH;$;>Z1`9;8lF`}z6tcs%_$lUuioC#TJE=^`{VBP`|wrg2$1 zYkre2PL+P`ZWAMnZp#}V9b*+nE15<~PO5bS7kEu*oB1QS2(`p8G1Oh@jfeA0IUK_) zSLM1b7Gu}fDg3CDlBwtU`5Cb0HG2BxTH7v&o+^J4e^|;Gc!kjN{{`;F`V>jAcYmE$1t)S(k^Wirc>MMI>0?* zvucEF%~@Xt7X6G!dSa|z+q>aui%As|rdrwd_(fo#`# zp0&h;W;I|j;aJagJL{r6(Mk9;Nyr{i`#%h_XHaf*M&d&tJJT*{Q)kRAJb_OX`tmTu&{$MwA{MDB`0ayVQF4$&f7)=>YLDdh&}f;6*3~pSl%~N_gW?#}bIQ z(`$kqYfgJ9~y*6Zu*w{PE^!*)V8CU7iKRcA0XLTcqyq~7Lw?Lg z&ha+Xv8qZB^^=s?hU^?5A^;*2)osW&P+Ii%Kn|Y{v%E7=H4AvEs~Dz|F+# zT422JvH49x-!Pveu|Ye!)m*-WO5i9jzX!xE>3Obd$wRPdy!5#_ z<)lSu##h=yd24~p2sG$G_EDxXp5@sRFv@4l5d&o65vfO(FTAM$jwKLzBh*lT zDrCEM7I0^gQeY=!&-4^hd+1owP^dM^Wfw6A$s2$++)3!C!<;%t+EUDGz1&x^Bc)LO z=y_WCzXsWsbP>h`zWAjWoDYX=6&B%?qXXrb9zvKWnFiUm{IBLW4~#x0LvF9Kv3`Z@1*5+t!M)2u z-UP}SU69RT;&meI7_S-jZI}~n2@1m*vA8_7ws0=Pf$7nlF6FR|v|{fibTWr?q$`!J z-q8~{mGO#=n&HeKdnP~Qo49`yVI1}o8474OaBE4s2ZFI{!#OvvY*&R> zU!`H#GAX~nD9(Nwb@TH@vVUaw4B3OWGkpUPI}FGCBOEUzweR`jM}J91lr-(;_`t zwYVxjs+BW?Y*YV}2^>qKKujUj%|qjm3O82SLY}6xp~!O6uFZ>>H7uka54|;q!cjno zw980l+!ChqZ1SN^j3P!!I7G&02XQ8SE z1QIB+grQa9HN>a~&dba5`8SGB?+N8+(Zv0PIE_MFAlpy10omt$7>|2gR}K@0+zi-TWWwKqK)R@%<^PIo?+4!l5Sk2 zLcalmaALapD{ti&0c69>2-rdFS{F0If+|9{Y3SJzX9Or7<}-D3jpZ8G2mTVW`F1>y z{fY0nD&?bz>`z>OVI45aJ!|F!AIEl;t&6F2KTY!tK?X(WRLoe@L_-RwYL#&NrL3$9 zClmP^Ih~PEpom%OIFQ&XE2YHYA6E^0A1CEmf@!x19WKI|-%B}b!y?S`^G^5qdmy~8 z_KFZ|ubZsxS(@u`wcuprG6ctvASOsQ)*b4W}7; z*las|JOB6IIF!6G84O++3J^E5#eNmBt*3-H4qZzXv7w(+IdHB&1lF7Nl_j6F9WO$F zQn&=_P_ZI(6~4o5jmD2>2><{K=t)FDRG`OJZh1dEEI-$aE8sGJ;ru3$jq6TUZiw5Z z8S&o=*-Y2efT&d4d08QqNgfh6@p`tfbwTtwkZqv~c?CW2KM=Cj?+yc9){~tCF;`gs zXM~bPsK;&MAA@Y{j>?NuhnZJqSEiG6HS|z{okStEhbk<>M9mJ0gMS}nC(ckrHMdz= z5GkK@wKB*MwXi#Hxm-Wf=3e%J1+1%SVDXnjw*6!Z`BkfI-6+Bk7h$HtcOYvpa@0!$ zhci8ZtVo)NHc3JUW`rwxYa>xcL!SWIs}2aMoW-|o$i`=bkPWkI&_1D|p~P-ox=9En zH&^u7y{YggAv^VFualp2d1drwM7B+OCO_kg(M6=rq>XbrJYI}a7ps+3g;{kyD--$Z zq(}0LD779UrVwiCLW2E&i#|FI!6AixIG(}JV ze;aL0MBDlu8CHUtE|Ag(S073ykz%IcuZ3)JM+6a_vruI!UxWdv?v&We%S&P+Mv=*Y z?5EYA{;$$Aoe8ge$Z30HM2khJUxnzAUqm{&Cjyx~KSzHUWaswCdn;=x>jw+A2nvUu zX6Uk@lCI_+dJl=B_M711m7Xlb0NK7H0~7+ZiPS|m67N1PsI?DxwgK6!_q9`cmX7tm zh5$oaX}RGTd84nNMJP~&=?mXh!Y&52lEa_$h8|$Z^)H9Yzn4g(&{_OiS=K)Mg3RsP zkE7a!v%bnsqrwM^-$W2-1x6x;$L^#R=y84hV;du>S+Bl*`N(%!@Or{8)$sIZ9H#t3#(7*5A`Io8kB!nAB9)Ld%SQ-tzGB;L3r<%iqF zz_&7YJXmtQ{Rko}&0{46(|IU#zLzMdH5T}%1G=02`SRt9=1Pz9MSK)wSHy1~I&w(b z&DG4f`Rxdo$?9>T?Lv~JqIP!@OX{xto0a+bkS)G!uPzlE3H+yH&>O4rJY_7z1vxhf zgQh?DFTaSH!i4Fh^^=D7OLIl!RKzKo%8IFamuyw{iRsW} zcVMEEme6)&M&!aA0LeltTAy@&gHX7Le3)+)R}0^KZ{`Zw{9La92W0yjzNr*i=zK3x zt{4s?_1i-BY*cC_JX9Wz-TWxX=1Z`dg0HWy-@kv??oJ{#6rIKSs~}sndM{MXgw{VKwQFT#d9iC+cTTub33 zwRsb=sb%}S-9g1hg8l1!uG+1R@m}2uWXl?eL-s*n6{!n?No56Kd7#Q7F27z+J!`Z-$BLQb7&rM<12>zUsdT5w6!zumT-k!^buFbOv0v4X~ zMd*LY+i)lGQF>#CqfufWDqn;Sz*l}oC||_)$$w?eL-oT^n`+=F zUmcXMo+4D}<_sDf-y+msM2U@u$ZOrYC}L~~rye-*a3(K5t1RyUX5Ez!d8nQuQYLBC z=7SYrw>Xx&3tzu}6#(z=ug_(l_Da_N--2unh_I2Fk=M!aOXZ#KuG9?M}j6(qlt7VssHRdHE`*(8QmtJ7q>fJw=R?ax^45 zyUG^L{JxU__*0OrUc1MA&(tohH?H|7bs~0CPdSqci4mcMu8%14pc?|&FzFfz z4;_Fa6eyw|s?(nlRmokNr}9!*hgL{6RIExu`66cW*3wQQ)$VNav0{ZaGv#8RU<7LK zkL-ryyHk6(Uo0(m<`8v7s8W8%_@*^-ND`PHjYu zP(lmYqu4COH4+|vth|Y6A;ED8AciVABeK6^j+XvWi5=vW@?u003KWrx);u*@EJG>0 zK_`49ZIgnqa@#}O%2C5Ap;!^6$F{TnD!-E`a~^64j@tfjLiYIU0lrw6Xpq%p!YeQ< z?Nz?bi&zydW};9nsB!!0=}CP1amW^PjRo^k@{>-J^3&I%m7$@KJ<}tfhN+DJ5lZMh zTXaSI=3zzO!;OaN19YZNE=zrWHnnX-o6ta$(VuFrd=XkKd9k1fA)^Q}rLbH5MO5>j zKP(6|X9ih3$;=0Nr)C}IZL;Dd`+E0pG{EjPq*>u5&U zu!#4{^9Y%1ZT6+z6#(=;2D0@`BrReCQWL+VZN3fJ%5Uh$H$n+*tC6UP-#oPAMa&wK z1dc(z5kuaPLl&y502HQ7CF^SP>6QMJ29vdjnY=|?#Husni{Of>zX%0(66J=6HZQDE zpokf?siz1Bs0h`zM5(=bs39b^GV7NLY3S&yrwA4PugL79pe-F@hi*c4K`G(b;1r zuUhQ7F(Q9Ppirn%KOBdIY1VNfDEIgG3e1R|DYem@Q|S+x!Ip@%#6rg9Oxl%c!b$i- zc@Z=p|2ie8pNrpgqiCu(m!;_s!dCcbQA7GX61Fmo=U!h-L zk1sE$uXw+_JiopkUtcdWXE8zS4WYv`0*ksj6DvfsvpP(}H@43Q@D=kBj^yVQSPrN# z<$1e`Q^j}OiLicZ*Z!KE6PZ(Z4Y+T_JU^d4X+Zq_od4tFK_(-`sdKJ6)ayiAcN8`V z)d`sNy*!=2!RDYt@1B?#l)W?gfHh0UGiNGpbyDx{z;JSa~iDq>p_%s2-+@v z2xJ?<8UV-X>FJ5-qy)x8hbKo`ro`9~PR-lN{1C{tW(Gpn-Vl~9TptM#J4S-yFCegZ zkQY$i7>fhtix4TwvC)l%^FGMdvG)>-xmO(CXzm1NND~KXD8fp>Pb<*L{||y}(k~&K z{beCrpy!8cXZ0dKgIPJVdWgKuL6uynRjZP>VG+5~s#{Q{0m%{Br2% zo>Kk}M8HKrf+Bzs5NTeMfTF&5VaNsj@1t))xA}O$PY9qt@1eawnBInd4y*k8!Q<01 zoW=ir{WT2;>NiVraCPU`_9L@IIB)#u%J&^(5940~^IS-A{lU4Cas3tn#&2({m`i%S z_F6f6P4rS7mudzS(~<-plMnv7WEB;yD@RSQmzpl)jpjVkGZuW}kwH&lyZ0|xhczx-wl`&kam!RS zFm;um<=Zo_vqb%L7ZL8if^vL90lCuAJV)fu`|b5c-)JuCfg7)UUmsmpyEr5#b>-;I zo|ToJpz;?FBAEhDsz%4*H{~LXFb^Zq6gmQ6f2fh9^7IlYp^pjpOqC}XS84WiEqBWl@>n0qcY4XXCvnoYF!)WeQMy8ZIEitmmQK5SJ*h}pC zs*JGHkW=Pl${+Uov#H3$g%1OEx_HXVXV{>hcqF%kn6GIrdfg%X>)1*O?qb!N)0EX! z81!utjn#oC-0t#Kq(O80GLFU?6ujv+hV%ZJ?mX-H8{!Z%P6h&);WP+G6~)DWsYxqG z*(Jg*#fn9M4jUBMtp*B%%sD(M%1zIQNJ-TZdlL;5a3IIna0G==x`4kQz0q&3w_&(R z!JU=v__9T7GtP>>&BRzW#1K(W|w zAtBNEEf$le4iB_^^nCoJZty%a#qjC6fuQP71769FL5198)Dp;uvx9h8s2XG1<^tWX zCh3NkU%t_zH&TZJGyao@R-8jsRorgN%&8#ZWFsS-C>`C1;GG$)joD5NpI-eNZaV~pM z&Wtt7Ckk+rv6{S^x1tNugqkuVRaB07Ms`3H)Nru*HiEi6@#@-!9{fv3ziuRVAP#Vv z&!&HhC_-wYKVoxL**I>*Afo5|nN7Xdnio*`+5?ugVQ+qPl_jN_%E0A+5|T>)s!CF^ z{g^nu-<@#;i>iwWmL6ojbTXL=r_o|(QO%H7Tn7oS2gNObes z<~>8`EXHTwErPT&$`toZhnLtm?7iPg@%J#d0T476 zKbsl2amXs<%~nmkd~=n2KSqZ79TDk0-fAbG8`3lr`tihxtRzhx2dL+v7cTlX?^kCF z^)jNScFIo*l})kQBo#k+1Ej*ZM5sb`%*NX@)s0y)@v=3GqpN!7i#|;}I^s;QbsOkH z;jM_KeV{%~9V^IO1pUbU1NA+ir@6%J{`>250&wZnAhBtvd$gCfwsw=HX>A<7brc`+ zg;}Kzku3=_$XXV9@p*w$(l0Szr+UM`>nx(mNtkQDweyD)Pgh`4l{8?HEJ&TiN^ay) zw*zsAgQHzM#Ok%`80Gnya%(KK+ahGUAD*@+WAkZJYm0IQb%)`4iBWBzW$3o%;0R^d zK@7hfJs-F)HblKpcwrnCZ-T&sHvATu;d4}vz09hA*Ocitf4nhf8cgPt>SO7Axulhb zk;XI3>$14ay4}{;IR1_5{tEVe(1jUuJOYvmsE>#0w`5^%`u#We*%Sc+K#j&k^2L}G z@`!JTtLeIHlb6VS(#-}gSaLy>pM9}(dSwp8C)z*t5eVNu!)&AdT|KxOe9KKJj}Sxx z!Y9SiEqFBMn2|nw)_BPN=OFk1O@JF%ElYRBD4=Tvj!)A-yF~$0LmC^Z={1MBsFV^= z`z<$dxIO(XFi71WpT~9B8oR=hR7&aUQWJrnexV+?db$dRef1)dT^MB`A=H^5woVej3nqXRvHtswDFP_PJsB;%K1);hT?M2Hm z`p%RgN)715jA+2iC|F1hmK0S>mI$T6Lp1KwI5cs^E5TEgHL7Re&Ep%L7zYd+o|ych z%Z_#1tH@HF@D)+aU{cjU(Sr3yvxqZ2NY&@%?2ROwP(WGQ&${K*%WCMk)=6>N7^5{a zokz0~E)1y355`R=M!c*MhX#*HD)1m!{TJm)Kwc$Dc`ht5;m@obvsVrHn4o@%2;0}{ zv)KA`k#q z?~kXZ3RBCg4%0_*t#s;k`Y(UT`1^ds%SN*nDWjT-85QX--8x6mGy%c1P34+a(Dw@R zI`V%hL9PEhXX0C4n689cSE5Dzw`>P;#EV|g#lkBgZJOpi)Pw&h#gqPdJ{a>x@Pajd zVK2!1KjuraP;nkfza}yjqJipG#J2w^S^j;_yPl)mfnnL?lm9sANY3|rwtcZu)Zj_%M`nSvOQ)p zrbOU&pukI)*Fxm^bBPQ8 z3PN_#qGwOu0ygdVW|F>Jn-3~Q?tSPKhe@r$*+w7@2ICc=Mi>d$eC7RH&kD>zxXnurB6QoS!yhF zieKzI3V!$|RFH8uJ#GqNkMBuyo>DoKaaX^U`wrh?fTmBAP)1uj{WKEMlYkd+dIr%j zE$s`Rj%3WW@F09o<6IRcJR+hR3%4euY$#}(KrDt5L%QxF) z%*80hsA;FGtYpM$cBi2uhl5@-Y%S6L6*b z*Bt65_}&h!fz&sRWQKtSPn|+fl(a7!ra{|83J^v{ili72hK!qDZfIBaz?6M<^>e!Wh`9ME@?hZCN z+I<`zbT0eBYvc>bOP=zeRHacLyMZ%mW^fb9sHYZZ5AC(a3IM_y2hu4lYmX{<$f!?y z9P&F*urq%&0`@nO*hfTziW<^X19-zH4GlG@w}m-@ zOGZYwq~1P&Y-{-`OV&^Ka-2VMZJSK z^iroRr9V~nzMO|vtSd2H6qHjg=k@mRx82;IUwMgnrSXrieB)@!J4_}UQTk2a2aaFZ zn(-OxS~)7x;~Z!4azO{7KI>L?F+gAHFFrtf4A>~V3Uh^_DRiGeNP#V}?)%_p-Y z!Tzlnx-{ziJS`d+>qYl3_N;*qeuhI1KvK2wX!IQVFNNPK(U{V$+84NLVkQOG>dpg+Hy|o2T9W+gEHomnTn| zCd+X~$$8Q=2m~!r9Y334eC?_5w02dDO9AsZ^Se=(r$z_e^T=SfZ@Y<2} z6L7S%FQu2Lt9DvrpA$~KBFnq0dWp$WbUEn3lm5wd6yAc%ks>#eZs8OZsWsk1F)7@Ux!oX5v+diCU?w_MC@lElv`8X%d9- zGZX6IyUBCn6hAm^1MRYIZ?DYEugbC1Z3-*TT2zL(;U9GIJzgZ)-Pa?$S@M4k8udL= zMv?tQ&k&x1-#q6CG7q7g$}wCu{c0eRbc-S+i(d8g9XGjlE`rnLKF zJ-q_V5bEbJlE8v5#J*jt(tI=F< z8F1SQD19;eH7w{>zAQmSuABc9xH{w1{?s{yr6(18X|t)d841#~ZyEe`5IJT4dMSFC z-~40&g>7#MZVhIn08KZhh-dH`#j>)4j?(5;^~i4Dh(&}jOWe!gkpM_u`)I@MdB1to zCwCM7_)0r6&azle&_x26PW%}X>|;xc2th(jICewIakV4EUqOfe6I7o5!YqkSIR2r^ z99!N2DX3t&A1<-)*>;j@>16F%5JkD&mMs-Iw_nVkY_*#u4FvCYdN~Z$(xji?^C1{! zhAN>5&1N>{%A4vuhpgUAaZr2madFNJxNZ|e@to@~HZUG(TL-vvf?3a@duw=l&( z+fnu3Kz%XSBioYbx(VL7N>h${&5M=4oBaQxl6hN4Ac$6fl~>P=|CmMvQPR-hJXf_5 z!y4FF=d;fh{y-%M^7RO`>7NO0f#vW$!N)2Jpp4)iDS2mq&hD>v+k?7TiR#yx#E z-l46^R`=&4+RFbvLN6aLbSiNDlho(`;!h;LKP99#(!9Ap$EsQ5KSx|PUN`~W{3F3Q_`n)& z97mTA$;+CHNXFOzW3#ao0`&A03{6r0todIC3VS;LSrYIoKUo>YWA1fK8uTM({PEmu zyPc6GXarFdm@&vC1N7J;F-L%03*mnlDEv_T&piXhBU$7WWJEwl2wh#)iMKf58{kgH zbQ-Mjbo^CC5w4(V8wQsk(m!kbmjP3`!T&_AX`2b#{J$!)0eSL4Y9GVv_^7?KB9P#R zr4XtE^s4ANxse~&_#Xp$4>qC!dZTD!9pG1XGHk6UAV5RcG2Kpm+m8q4ti}7Cd^t4s zTU{dU5I`@b7sVR*9N~W$6gd_DXYOiwGVg5l{jV6nXM@ex~5mZi~RhrGDkc?ccazZo|IuDoP^&3=g;XWHu^>`$6 zXuk1}9(wwA81KeBQxC?rE$o^2D(QFdlIA~#-OIRT6??8N>;pj#P&v1>-nVCuLBOFo z;XgJA;E_nE(OmOVwd0aB5>Ml&!*w-m&B1X+zk!{rJI6Z{!mo#(Swocz=ge}}mCgID zcMm|4#Y+R%(r|ZK|!r;Xc#!^$q4<~Ky@(RDS_JwzP zvDH(;&$bDr82^eq5)&xij)vvcVGNLlL;C*_bjq~OZQeu^#y{qHm<1{qxN*X}HX@#a z7U|M9(7_8Ij^Rlsan^8RcQgU3VnjJI)WSf6Ke`jfBN2xH>BZfHzetWb6$Kw|{zNP+ z_VW95fAgYDgoD$l5{m2Tab3^d!?NfUQ2EHXq>!VwaSIWDf%JDb&2iP%&pzdq#PzSk zAxjlnW4rETSGXCY3F%QjR=@%2oZ);C;AU@JF>&4_{$lk8ep$1csl6=eCZ@ty#HE60 ziG=va?rFg=0Z6kWd4uY?Pe<65dOdPg1KTQ6`Dy2kn+F zU0cdnH>~thGstYC7ML;rYMo84JNu3z7gSNPcj5)x4~6@y`{+NMELs;s)@C@7%nj^~ zS>sPWT`6Yz-31ZVR8)-A{5EDlM7(*`J#+S^?Z-%V5*&{`|8;1ymiudT5J?b`pl&({ zM1n|`hkbS&Gb&+I8V3}dMPY#|rBfkO65kPpKXZ;}r>ES8=(d5Q9jm=v?wNTMj(d{C zt@L6|!+|=FkNOmUZ`qE_8~?c<3!ir!6>`h$Gq>Q7+6}F5BxTxv*`!}0lRoC+AQK7MyIa2SCHd$`uRWC`rR9F@Y1AgVFm7`8w+|d{%`oVl7htjFY zSjC}p6w#Y8`VJ*(J7Zeu;Hb)-ReUfvQZN~QNKkhOIDIAWyh-?7cG6KPP*KW7vc@lC zA1n7or;!;X}lbkI~MOrWj>YHnk@ zdDkZEO`ic-%!Wsj_y{f{O%7?Lo9ef|p1kjkNY9`YhG>u=BPHaXKkbx#`HQV5Ni~6T zq?AeAM8;;vYCf=F(UaX7`J=y$V;11K807-{w+D7p2eIpjPB%117Dl%oNLJQaTsdBl zn#N%%nl=q*l&RjodMeqFBESVy!p+VcU&Ur2yi$o3+#Px0J5)l82y&%4hC@bC1GOKRQ=Bq+G9b}}XUH?nq=2C- zNLe%Py-$DdOsW2}e!6FrCb{^t)bmQ<;=Ao`exy^M@`e>X-0(=ZAYL{hBcfI;rYix|SbtX=X zRNh9a-r$`&BG7esb{>%F3964YkqSd;C=qiN^Va#YV05pO;-YYC{>s1gfZUT889Y==dflo(fL| z_Dw>ml6Qef--*+ieX^cQ%()fP zZOe{}s@WH8-YQ12Td#D5A2N3PM%a#b=@+r*9VglvdbxTe?rFJC7dK!q1P>45snx00 zNN5!BBBw!3DUjUx2Sf6FNNoB-ifvOEkNJFiHDg8_+L%@{g%kczhfmu8zMVC`o8Ur=~5xevJ^5l!%2Oy@I5mP!%~QTOc#XQ9xfP+2I`rq zzISpyQfxMn3Fpemy!l0oZW9MK=rIoYI_sG>TGFer#q!7@jJCT=DV+Fwh*&~a_kN$s z<&-ab^pBOa7j#?~C)J+9Xg+UE|Ad1eW)YKDm@waOKV7&YpG<%HZP3xdHi1G!+3LRM zuBeh|r^_@`(RP{&WBbru%w9a{$-=POhV>L{g(0U2MiV|-XLYS3RDdB8nt}yX*J(hP z4{gZ>`Edoe%Oe6z*Hg_Ote#@l6?ePk*=KVkq}^WYv?1X-*pDiOiM_6gJ4>nQuJO7( z$gcf7IxA#d7V#t%e3d$3UAFVBSTjr0H4)ajfG7f7|G@!q<@Ax2ExlKz=S(D_%{ zHRy`g6?%A9X6$U-<^?AblGR!6h;ES&-^V(zAjoH#(JPAcD4~ zzV2KpM!Jg+Yw_cE2q1DmP~&+#S6=g#C%N1$O({q0Hm-n>77}+k<92OYiYh{~EScJR zZL|#BJr9E(eay+$I4RA3$%~eYvoRDjxUzvd^zip@J{>&yHCaHf@?y#(=i#*eOwD`& zjirN-m$Y1Uihpu^YL`AIxtS1jnVH7^siN`p#lqHilr7O)7FcDZE!-Wcb&X z)9Rev#+R{QO-eyY3Abf>)HAj{xB~*U6&0y3N}G*0Llc|RS~E-3dEIY(Iz~|QNmXv# zW;=6XKHF?{i17IGwVilYhV{0X@;SX(y>BcT>2|ssT4lZ2yxF95RhFpg)HTfUYPZOV zf*-NLY#%=n1}dlhhXnv3A%Yg0IEHy&51Hg2j5+0~lpbrsJVksLl$MLnHLfj-AV5!| zH|~M>4GB^v5=&I!Rd!%;;Cr8xr;{Y+d>Y+OX!LRZ#jn|hHSnxhaPv}Em&Ro#-&?}d zcv3`$MKDDeGXTy{_D<-mhDZ{vOtR9}FcVt<$L}l(NWCh@W=ly&X2=rXmwip2I=Z-#qyt zZVIV>xS3@>n9C?G+FQI#=O)ixD32RYx`3`Wa5I{Cf0j8oRE)Z>-?;D@Ju!a1zhY~S z{}Mitkj_lHQq2BSNpyIzN96-vMw4~Q`jqgCkTxuDSg`)q!Yqw0Nz=xp@XAtzoIg~2VH`#j@2iakJWpYRCB~zJT0YYi{L1?bU++aPvjf96{=LTuJi5;N$h99t;6%` zTCvg_QouCWsuNBd{(9wW-0|Ls5XITF?rvQJ;Vn>=szp+0J#f|$qF!rcSZ>BhwVdU| znEI4-%32;Z_KgLj?bFByp42zOlq`LxVEHVE_YL*90VBz<*XVbdgVrfQ1;|H z&4LlE0W>EC>|~vu6Jk_)Uwd_=Aykh!@A4=hag_(zE}MTY=KR9y)Vy>9cgmEdy6AbA z(FdgK^#|7n2AB15H!Q=G3!4lFZY99xe%lI@N0;)WEro03?!4y^96j;xTIzRV<;qU8 z=DOT;&B#N>lcUhBJ&Yg_F<@ux*V$wzVzEx6)K?o^!qARYT~4cwIx9|m6YE4z!8JH! z^@3>Ipc78~no)}dP)lUsQ6#68YY}xEn&0rif-Q1}wdcKS%g8?lBHeh0dI+Lu4G@X1 z{BlY|)tVn=?!IzvCy(E2mLFXiT$EK*z{Y@^GbC?J;m7uwo&Wi_ifs1=JF?}5RC41< zpu*K({Yj}o*l}s38I^(dLOQCvLM~ZDCi%tPB-7Dwvw&J`BHG0VM9Hxx-27VA*t-^i zF-^_63!jt*(JlA5sa@&yhN;B4{Y{Fz%8E>Hc!?vrO8<;>VCy+Hjf!@X4X3QoL4v#M zinUrVPhPRfD2}ZY->QilPfh7m-hdPoED;XWB=%ra2G`!X4 z*NQSxSu1=!?XP{d!IkRj@0Bh6mtd2g(B)^2msh-8WNtBZFy9OFC4y z5~XJS_aQJTobtN-tQC#zI4T?9?vHg+L-`NB)fvWqh-<3yb1BQZfNcNfZu8 z@dom}l#XSZhOowbnvM*TcE6JBY;jp!Z8G1AAgVAlf4|kc1iqo0>xxULP?0TH38S)K zaZ?_%tFB-Iyue398+Mkd7V*s!uMzIeFKvVMx&0UZUEV=Q0G{YM7DLdTm6;Fq;c$Cy zCDgr#0U2dxJ@w)`st$nxZq6ED%fdjtO1&0UM8&Y%mMp_e$wlhSwA;9!DBS6jb5l<< z2@S+ew;2jwMlZGAH6%@^rvPFHImZ^c<=Dzvl9se0oInCp-hiXA6(WeGfwIR3=H#G= zD05?r@z&(IA`OElmIz}DKc@ulgt~5S0kIanWrPu98y#c1X|H%7JSnw`7aAc2r-nI3 z@op~}vrWBKt~c~(;*V1{@007Rdiza~hg|l-;PkYYZUHI@0co=y;$JZJ&J{<+sFAK5 z5jIT*>XBW2$~{r`l0wA#RT*}$kc%^8nZ^|5(yvDN1{I!6&K-={ZE9;<9gYA+n|Kpe z<}oFr_Y-LTKLap>8FN}xk z<&lGG_HDJr_rZPb{a99d)F9sc_8YTA=NC$&td7faZd8-Q#-hH(8oWykz(JfIdr2&_ z27j^rTj6uN%~l$DTTN02n@L(pMG+Rc!MonGZ((X2rP2Bv$Awh7OokYBg6ZV)N8I zbyJAPG9HmEOHYb2PTZP~3huOij{fxDG_;DI2n$sg9K^|Zc71gr|@D@_&{Xk z&{Z&^s5O8E7X8V7N7oXs>ul5T;_mC-$v<-*htl)2J26jqn_~kp&V}A2;~P>@1hv-i zDQ8R(!`xtQB`n1SL4ebpwxX4rD7f{rH-?X8@6}0Ns4@VMyO5$NTBAkf`y05m$XIwR zG5hf3vSI4ROMNr_h0#VEZvW;_d?Ewi`H?EjVlQQOKW`@BqQKr%;iHjba=b26_ zEGPT^E3P6DC6JlO(lp(?a5@4DQBOvyOud@hz*LCT5stRuosna1L3Zu2o59Ke&Lxf8 zJ@cC3fq*&PzBOd4) z>qL+rcDdB(7QNi}B?uLzVbXY|z#@90DZEU0nN4tFHAgqtr`eOcl#k<}Y|rg@9=WhB z>e#W~IPv{xW0s6_Myd4QBCpFk(&EeT?hOg$v+C1rguKfY*l((uBL=Qtf!PCVS}`hW zc_hj0yc80O^V3YHM)b}oHRR{|ZD*^XwCf&keq7k{M|c-&Q8TLu&{d8JbYPOFCJh=a zA8+!{JoO!#>iqf3_jtnW#dmDqfX*%ZN15kc!7MyD7lVx=Ss>{;?jQm}Qux%|$0FLl zii0*06yZbzRk7TAh8V{OegMN}?9xna%u?O+#uB09Z1@N6^fnW-Mxb#8dw4v46KSWn zgaI!kJmRd8L!k2#FHu;h)1qt~tf>wH8YJs9@fIY{_8L~D{A{mz#nrOM-I2ocvM>u9 zN!Coag?ac*5xr+y9C}{bz7X|x=leK~kQ>?TN|J3cqUcWW73lcP6C(+S;gS6kJh|mS ziC&i8^|QCMwFDS!ELE<*16>Rb#KK5i)u=P2Gw$ibu4VbO@TYB<&EtWFohd5lR6P%S zbjT*N#8rd(&P7xzIY;{-{&s$qGiA!-hpvg=CUAu@m9|b4P3W=59hUU_y&dq|#?^E# zkjMc6ARq{G#iA1qYpV(jytNF~WozDzNR|K8l){y0A=X``I_DwW_m)Cp4qu-l3TP$N ziU0Tdz}vsCxBPv5JWpzCJ0Fs@uP=->#$(OUC`1Ufs!V;s8zi!}pA62zi?y@2zVBN| zM5ORE82x(vS;@TAxR~xc6Ff^DMMFo~u6=FB!zgxCLAZ}y6h43meB1x{Ew6InM)V87 zTHFoe9UFYiIX~H%ZBK_oXso`7&s_QzFT}dX)`YtGjpz{y3l&pBHV}YCT7Y)mL#IUK zr)}8e#>U_^aX#j6Z|^|^jfb^B*-UP}ua!BfywkfTd5Lo)AF{NkpYcR7PIz?T37YGl zwitfUAhkHT_^6(FV(z8*^)!K->+w2AUhZq@S#e|#P&li2Qz5{$8G0z%xt4Nt=9NU9 zZW)dv477X>$b$-*OCG|$G(os>c1z2hb&MZzVE#y!r%$#F4r$Ms^ngN3NoLGZ;sFJ~~v%w6%fLe;p`WzGlF!o7&WIT0M z&u&tib~d{MGxtcUYn~94CN2^mOQJrW;UC=)p%Z^g0`#)lB=hYu2hk?69s3`D{3nLr zASb)w^btmVMnE%lS={~VX@SHbP(Lb~3Z=lYJ9Wap+-mf$fYIhBL91cBd6xVh?~wl$-UOAyYcENX*`M7 zW+>nM`NJ4R+#Y<26(aZZtYMK@fkE3n_BAOrjXZEtpkNTy3=8grN+!h=D~pc0Ugl{e zg?zZq)BMCs8ZoUKty9tLi%7%6LK6BK?{esEp=*aRfpDrO-*{EkVffd_egH%mY;uoO z7&V5+nR5ur0QMO4h+NKC?kgPSPjY_$Z(r-ui1JAUEWV^^h+ zy9nk{0llRKnu)xQLj?_qeoMQ4mm6cH<ezf!K@ogBF$myO2MmXk6$PV#UC3K&%(YynI2i41;>GN8S)BNL3k%0_ESWLd z`2@8gN5nC2Ky|b2*D^yCO#F2ZJm|MNl?x(iaUox8J%yVmE4>bnco|{wz{!F>gUU@@ zdzLY;6{PWD#qcmH;HM5wEgNZG#*~FG-J@#-n=^?i4k#00MF_Lk1N92$$4nC{SAZROujI~fO&5qp^ z;C*A;G{e^0)+&ExE#daN2{=rRrL6n#xLy6ea>?40%AJAXBe4LDut{nN+;rin>!07@ z)c&t!Z-D==f3+QT{=T(0kg^;DV%EivH!FVsJX}#r_%~KwU!SaBtpxn@`0VbmIY|HD z?PGkP!4IluKT{sbQn0s{P@dYzBGVn4y!-0j=nh%7VC^uj?WjFj3NEPkY#M%0qo&R} zF+1E)kaE!-@{P{A>Od23_a$0HYCi=4Tj_yIR&pEPCPL3MepclOZ!v||o5;u+-;%^6 z1EW9twOu+QzFZRi_t#k~_p-a_hW=-x&jaq)seNY@gCrhyRUx4oSayKQP@l#7n&-~r zJg8Mwu(IJj>vwKma+vvguv3RtBZ-))<|P5N{lhlDEHX)e4U5~G56*62V$vU)F%~ai zqaEzSFlT)aqbr||ozYP5lGo#TzsiJ}cP2?6$FsiudhOq}OHd)BKEgfd z-nC+}y#68lGaiD9h9$6`=h5q57N0BegLR6dUTdx=@zsO>*^s_o z>d9TK#j(rKx0V^H0Q&OBZS1@o(@RKJD1aEvJ?@iYR{Q-{mUA|yfl8$oV_6&$fCM#V z1y<5artY!SG@?{dk$D+u`f2*Yr`V*cw?_7*P@{a&Q&+5_^KVfli7V(A=*Q^@vydi2 zoEi-(P3}a>{<6K4wFMR0-@6ntiBxX3YrF25X3C?VygQ8LvazcR>A2|1<5a7jdgC8E z4k>71?h!;v^gd1~ZDm|PtK8`&AWMr7p&vuYn0T3(TVfaX+mHg|>0rOa^ac%V*F~Tt zZ4uyEWsFkyBsof2hb4~PYOHCfV?CV1ZYkBqHmdLspats?2S6AY2bczAm1KA_Mq)P+ z@RMMF6o%J~$4UIQ)jeO2lc*0)j&FPY`@B@*#NS3G#Kx)f?w4qB9dp#m@5^S-8P@(9 zB_|c63-#A)_+VH>w-|whWnE?gk8^I`_;x{;`snkPUss~4bQ3}nhcFG2iYX-`L3tm)(ofeSE*?62u4gSIZ;ndICQ58WRa=Lnf__8AHwicT3J)50_uUaq6oSm3)e(7cnH@ z*Q=IBTF2}Cah`a3Kc26^&j2HPxNPo9$>6QV>Sh2!v=ko6gMq!R47)S&Il#atYC@C; z0HfT%D;~p$Ad}zsqpRV~!oF>|$%d)D_D`RVK58uvG&V&xMbM5*<^Iu&7%YWq&?I#J~V}d5YF$QMTMwCzCki6|PJ@FJR>Nm!d zianoP678uI@{Q6@B*Glm<+MZ;61cp&>B;C)V3lhD2)`js4xvAydoBxy1Uf;Sj%D z%sbknq0dp1r@yjybJVCItV8T>6#`@2v+$A4Pf2#kr;-We{Hj9oXHFrtbM_;cNss_- z_l@F)2y<2qNc`{PwO~zyIS;@?rm*j1o!(rZyeCvrxMP=u09zG|o1dir)RHK;%1GL) zH@RK>6NmYYYFjLE<$Mp#1it?7Mw|O89|}&@k{q_a4&O;O&3ChNkyE?%Bif7o4bPgBns(DqZnF!qp81g{j!Zl$p25*qXDu zhBX?8av|T#b_SG~oPx{7!*QtLZCQs#5E=FBWjob?%E~#e z(uM&L5NJ>lZ%GAz@=(8rNAqqGWlXGirvwufrva0+!0n%Cz@^o8!hOg0Vtr3PfMrkj z)a&hpAQ0=6O2@qR2)4w>+}>mhpgv(rp6x5m`A7rIfdbHik&Y+N%Fue_!YiIRnkm?&@d(eeT&s*5zn47Jk;&-1gjgLFyASp}cX;i~_)G=4kh- z>^; zxmqPRmJpElwajbEsBfwwV%ap@-RU)37^i-oKC7x>KA4B!?)kL6z%;Bqdn}>GMdJyUce1_@BD>c{8Xn@pt&H)hs5RHcpX$d zAl&!Syk@@Sdv@d!J7|H#Ekg>l$OvcNGb_xcg~okri?~XUn^%RbNWHAsIWBfa3PaJN z?e^`t^G(j>qPxEty5VhSCHKD3W6=OIZ%e7bSds5nk@Uh_>xVAv1`$4l!MEoKgq_t$ zq{LJ{X)2dX_D6-!85!Yu!(qArFau3J58()~ev2cKr@H!tGNzT^v<~`F5g+fM8_+|-4yr}hai%-p*JpfN!HeZ)a2f8&S$)hqtK91(&!V?CT*$DgFy+Yz+8dXX7 zDj5pAwR4qb;RYu609+JEra2Yr<;X@5rziU*t0!Px13)z`p{TOkjC>m2;Bemvyl3c!;Za$4za z8E+&$>Tk1tx|BIe;`d41E8efwu@<+#Iic z0TN>%HumEQ{d2t@cMy?7Qh+Pt0NQbn?7IN=I943D3436H772jgvJX$~@}Ip-dpmP> z1B`lMP4LAxU0~_uLs%ST^AvK5*jl+C+L^a=BqN)CVM?AgWcZ_7=?niZ6dH1Fx9fFv%o$pvI^oM_e3}zayw0%P;zJ?BAtYs;QUS z;8?sm5l66V9P{4*8GzwTD6%&-TYRpmJwsbnIQNoPe7Zb!?;k*-UA|nDs6zQtNWxJ^ zz{AB{@N5^<55AT~FEQdKD^NQ;jknOC)tzg2%=0U@f z;ND{@4e%u&c>W8<@aNYIN~X1Q(F)`DjO8b+D_K7}l%GtOJ}rz7#ITg--|pyNpWs*i zgETHz{^q!}?DU)uQ(JrH!p8_1M{`2B$7)QcDd2~UdhZ*c4Ya*L^&#N<)vvX)8~P?Q zh|Z^J(c_Yq<)f?Cn&J9(L(a1#DvWw@Fc%U0zfmBDr;H-bv6lG?`PY(S#nyZ3z>uDp zAb^Oi&{@#}Y5*Ddipi9>R2HFgO9j|1-Z+!ZzaAQBg6xdFmy`==^I7_X?Qs;8#{B+)C>`^fcJBkwy?C z%Aqqv{nlM=4E!w!pJ#8OB1rt`TK>1d-5U6_5T~D$`fP4xUO}F8tn$ab9i|FN>2^p1 zOhc^_nDQ7>yS{;w?P<;l;1Pa#z&7E@pi7Tm&~~(TubE?;p!E6r=41ueY~)c4QdH2J zFW|u2kdx0p?C`h=BwVE*UHK&Ldpy`c_N{g5q`bk+?s$9a#~za+psK-9bg~Hb`}x6D zz5*&jKbv6H8D?g^RXex8>rVUYg=Lu?*`D*(rtHNVNZ#(tqCd$GAB1x(0>Uw%TT1Ohmc<{wVLR74#!k`$UbFkWzg9GLudvyIF8W(J&W?#Cgw0&XBRh^FOsr$GfKJ`Bs?zTh&Zt#4G% z3%&pc$nS%_s!cc55%4Yr@uZZ2`vR7VQLonC|kSdVTkz`R3y9z#KR;9k~c zv5~f3>Xwv;XD1(kEqE$pmRD@AYq>2%L`wiZpbEM;M*)T;`$~Wz3(QcU(w+`RoZ<0H zs}MZv*q6VQYVY4t=#0|ptazFRU8Mn+#Rlr-Mbxo%5O zcY`3^jUe42-5f#$M3L_9Zjf$}E&)M8X^`%&Z=HMJ=Z)_de-3-?y<)BzV~n|(VgNJ+ zph11MVByi!EK#q&Ut7_hpwSzq<;oWV;wvcN_t8hq%jlM@JwJ?ULL?kxoZ+-ZG+N5z zqw25=Kwc7%!J(s#%ZEQKz3032&%eF$Xnp?1Wa28C3Hlg4HqM}~LmbtYu%Ox?&iO`! zc~;(=?nO2Mm`4fl^qsb641Vo~mgsdy69c}oId!ZFM8(97fnAZ{e<+t-J74q~e9Y@K zMGyW%wT@8kQ|PA0NNzgNdNY}x1Pi7G?zNH^>x2zt!w z!^o5{(3$3>tnP_qR2tsknSl#Rpr-JJElA>ouDZ8S^x!-JoZPC+>Nl!v;#K0&c)E&i zvR^O=TQcI8aPkw5@IU|Ar$8se9y2JPAh4%QN}Q*M=NE(0+hCDuSd`JIzCPXJZ(DtKUwOVRDlCLp5b}~8aJUW9&Cx#|9)JSry6twb3dJ_nF6`i zE<$CPpl*~wL-Cz%CORer($a5c9tS0bPpMuKhinPF&hwN`0__1J234>h^BVVNsB$^n-Fr3Ri(#N9jLK znEF&wC6rKceNI7+QjQ1PD#B(#|F69Ur^0$%R~PAhzpa`U3hcrMZTvTZ)8H`;4)5mh zyB80(W}14gFH_F}u%5^qT5tOA$YFOR?eb;~N|RxkxXuqbf{W%e~oPq2Zm!-)G*OyJXF-oy&_**Ie`} zt&n5Sbktv3E9AAfF%iN>SF8OKBH&TNGDZJ?pGSt4R)}hEPB{e#$s=L$@3+ZXT?I47 zx9ie3V|Nx0v=cWUmzI^Yjd#4jQ${fS+gd(?v={2i1Lw61|G)3X9=5-N9>DebkI{3i z5X&Cwr341sSLCXY&Sl6nJ-A036$G={otTC7r&}YwA1eO!?|Qog2X{tIfo%Bx_$=*Y znl0>&?Pk_1+)s*$gG_V-ZyB+o=2A#Wi#$qXI$qmjB(1|pl?>sm918rb%OV&jiwaBU zSv|k;!#pY?+n{g|I~|)9CX1?l)w^%ya)msP1=K^};VuKkBn!rw#6h^#XIU!#;r3&Y zhEv4`r#;u*2PU|?c)h-ZY^Gu+q4?4ip;ytN>~|@X z57pgG=m?3gyU5O7)S1_OW_iY`XZjN!RDhMB2slw5B2#u_@e7ut7IC)yVfZ4%x&-8?eEC$rvA?@m%r+Y9lPF zjxMez)+ZRAD7RfRk27v1E|ji#Be?bv*WuW`BC&*_Me^z2jXZ#l07^+WC@YU0pB%vQ zSC>Jj<43$x2(9x~Aj+|7^0kXE+C_{~J)aT>+=YO#e#po=cJBW0Aj}X5E#F2{W^ofNqo%wp@Lh9Lmh{F91; z9Jb?8DCz`^$^U=H9L$;YOCO;ViSJ!Lh&{!vtk57|z@icQqL^eMx0vjAsK5}71XuQ2 zykWzF1YCCNy{bWOhlYx!6e=d7SbR}FRobXYIw*XRpSvb=Ch4B%fcHAyt;;vxXG^4N#yMYpAuy1chnq=90fZUxXDvo ziluTl!Q6oCK`g7Om?g2FLjd3n{2`TtqpGa_$Xtn#kNFWsBjwmr{H8ANRTcXJ>;=fh z_M>l;lmGndYLo+L8P#M68`Q@0NWia{VbY|~(=py~!L+Kgs15l-Lu2rTFi?Ij0tPF@ zO|-U3W3q_e3-`z6ApX*MOz7&e@;xPc=!i6ofVgo6%AibFEe5!QNd)H&Ft zkT1R1D>;*jNud+r+1@URIzR0*Za=EHfeX^)>Nzn$2JA_Qi^BOmc#_!xQ{bcx90m8l z9^6X!CiE9!lwFdP#VTlLBuIk!L0u7G2$-uYqP-`B=fx9Num0t^@@wLt&gGDX)p3Ar zh_Va6i#Kgd0j{DA>cG1@DnpQr>aGNi#2!ottpT#r3sy|Yz_8b<UFO2|_r(7~HJ z*-VAN8tp^fAxu@>9(Nee)irhmF9yXTQ7x@+4kUUaN15UAI;Kj~$BjHQEZdtqZk$FN z)s9M=9Tk8(V@wNuGrsFL_V7T~=pAt1=3vnjnlM*b4M;=5)P>K4jaQZK35GsQBG&=u zlwCjM93;6uQ>nwZXKr!ZGhKz)$ifA=Q-a;TwDN)jdhvQd9Yth@SF3`7txnE_aKiX> z>f~n!SF)FJj+^)h_F>NT=U%;K>bUi>ShdYarXSUJ#Lk)|?F!h=tUtfLO@1%mEkU3FgPsy=!tgxc?ty220M{CSTJ4t=Y6`@Z(@tFw< z_FtKfsh*(EAS^_5CQ|qf!WTkH{v~dISM`w$}a!!qX4q5;1^w1 z;H&_7K`U<2UM?FZ;LYCThaRb>e6$NY?52hO0@UiE1I1sCY_$jLWzqOSgMydY)gSj@ z4tw7G`-^Mn{0H9NNAz2H(J5Jcf6JIPbNrGi&go!MqzM7~3>Y|n=%JkQpKtSI-;4WL z^}j#4Nef~0iXlB~Eq9dEsOuM#I#42d20fhO5PxYilt6g%I@5}HEcU(VT--`YIG7^7 zKo|(czDKKo*ds_7{Jkq7IYyuZzA*F*#TyQbgO3Ghe!#z94*|Z;N*L$wSf>j#M_I7J z?1g>UpR5o*U487#k~doHTEZg6z$X0spZ8bArrv}OCX-q(Rs#i2gdBx&KKUd%Id9G4 zMGfS=8acZmC7Nw;n78ozLV;WF-Dm2Br3ZJ(r6Q#|GL8*hGqz0%%l{~z%=h&9_K3v~ z382nd{&pu+jv6(*Jo_ifqNNofsig&K7B}$A(s6^$w5cpWu>n&uW>aS6!5{0EhN*@; zT1PCm2_AtPPWasU^?&UZ?tv&=xfWjiCWg<1e*h8Zqg~x$3kLlq-gWub-9uu&%KzA`EQ3F$*vakWSJ>=dG(W_7SLJIOyfZy9dfey3YaqRM zI_o@@EsDPfa{(%MZ$E8_XzpJ4{HOrL1OeWQ9KTFHPW>;*^gmb#D72*Nd|s@W>*Y&8 zCXoWg-y>KD#y)LT{wN}!83yS*Ahmrz8NrBR*tAt$rx+L}EMcV4e>xCN9GG}ZS(7pEf6q>gKSI_-bH z|DrD9>Rj7_~&PrRYf!K;ly}2myQWBiNa$f*NnyZ6!cn2Mx7YJXGq+7i%WWl%!C! zO(P6-^1{d6CEIyMW(?^>IIiyV18@IHX3%ZK048maI4STGh@SR8X^4rV%~-+cHWZ`f zvp9WBzusbAT_EQ)*#&qr04zDfqQ$(VnMB#`eY1h~qQcvx4lvN*FTxSfOvR14;avXa zom*>#BZ4~`1{%zNo9_Y3*J8LUX(|=Cq5t=d+Oaec4@e&1*Z=6+{e_qR#T&}y`}-zzRK{4E&=%!pfU%lsgWR&(Jv-c*l6zZH3rQpn8NOjym$VQ5Z)KZ4&2I&AY%pv zAOkWmrVcGTw-3cWNU4(>4z2NRs}$ie7s=7V37>Y!>0Jhb6zv5<#!WjZN4ib@!G#n{ zKd#UxjsllKsC1nc)LN#oJlmDbA(4j^<9Ak#_t7dstXu1aJ(DdxH8tXs%DwB9>@j;K zAY0-BxtOBu8V#%B3*M8GQX<%TFt9?A=!7RF^8ZQhIW({rV}-DaL#%COPM;Gw7~bcO z!d$G5jl_;kW|HMC3B%8jcWTqU=rR8(%LT+5o_+ries!l5Z2N9*RiotZG>7igJ9b^_ zQf-ydYpa1zEj@3`^b|Zb6I(Y9}{Zr&!JxT>}$xB z2&%QJ6EaQMpW!0!Vp{a!;9Kl#%ZS9*1PiI;vErlpMu!nRu2E&(WFDYPF|gik1RJLz zswsS2qt5gkd*v-=CJfO3fX|jl_!HtMOh(6gNzQT# zkMzv1$oo#Sl$XGdErkcQH;5zwKx)5bode?7~#eXVBQSFp)d$rmiW*n&tc!_4w)@gcf7F3PhF{$6E zKc7N_?LnK7>8_1Z_=!W1&Ze7u`->}ulm79Au4A3`qPA_rbUSf698cryP&}c!#7pVu`MqEi zc)`caEWBt;^clCu(#Qq#9i%T{3arv&*W+WIUJlrK34$a|0pgTs@92W5me#nyU}-6w zLRe7C28&Vqpw%tPZrw=#KS?GRS6~pU>XRqr&qh1BVy?|nRhn5o_t+OXX?Lfr!)3z> zC=WTy%QZ!=^9W~<2c0JpBnOgiE4Rq4@BTJmg!?SL6?hVwd@AMg?=nKO6vJ)JC0Hsq zgF0_H1t!wOmDq+gfy7PWTaP^Lo^K>YD}!h_x+V(xIdaU;NG&0=MDZo%vF(9V8a8C5 zR_}Lvg+-jD>HAf3MJ?YmN_(aMvl#{$X;%d!=Z@X{5ww3zXnDRRDFy!$%+T|VpWIrsMzJA+APYa}c|-m4RBrsA z-W#Y43(Bk#8a4~gZ&J<(L*Gu}s7e?dI}9|JfXku&f}fds73GJ5c@X@vu8YBIM3?_F zyUg}B%-lAQO?@-6;@@RYcXjjG`v^cr?t?^7=F%x*F&6osWp1UzW^(UL{re&26NWPJ z{ujc9`5*U^QM&fLvHzWcvp!R676kl+SesdDE{jyeXk8XKe72h-^+I5o{8O`DK0Rc<)dVw$ zZ8}@@LK0P{iXC{K*8jCU)?Rf4G}%;Tgfyfjc&0bl(e1|bzktGt*D$>k)vjjKS+nSk z2Y!jTvc-+zg>2L1F7>^fVJ%ILbosG?IjbAw{2OXThw3(&2ss?XJeJV}gS~ zkI#(FX>n9K?xn?#Wty>r8G-gT0<{d z`9&}xB}Ab5_U}?hhQjb*rM`T2FU8SmVhv9|f*iNnO<~zoPh9_~qRU+C$h!X! z{|!gNT{}{hYM>LidQ7aRlybqBOuI);R|EH%W5U8Yftg2>WyV30paz?PJKrNbCBf4uGGSlNbDLH$W}PNOYR_ zY)r%R&p)8<;PUF0H1UGtiM_=>Lfub3d``H*d6Frv@b`K0?1Myqm3*>O_74hUK&6C9 z|M@323g-Rs7u{CyWqlKh38mter4|piI|U@m6LwqNxUAz#K5H(`=a1P&0SI%(lvp7< zGxV{uQlBqAOe@&QO6uCbzVgK|tb_ z>V2E#1dTy@b8z2-Kk}Vi6g4yhVTGMTxjM4Rx$wxIqh>4jOCU=m;jXlQ>>Vy9G^SDT z!3zDO8uK)D$LweLwB;vU-VG8882&iiiTR>ca|#WXLN9;q@u8GAI5=!FSw+7l&<@(T zm!t(^kgFnh{>>S`qRwJGiuc7$(A%P`kq~#m+P`fLW-5H{QI~eX?5QC@2Yez zVw1i;{)J)C(v$oKxaoi8nzZ-Et$VG{y8o^*$c|A%(p-<;hGTrQ@2yQhnktt{+#D6} zvHGKVh+Jy;Q~^9OeuPLDIyUQ;N(QvLZ+;K{-LHX~qpAXB9n3`zHHHJqemW3o+s>RH z)*5euQOq?r__@dUTS$i_o9N?_1JU<5PAQAk_POmg>Vp>Wx0@_k-Wttpdkdy-d9VLq z6COAI*>5Dw`@y>i`?7+mW(960Y-jMoN2^SEm(#g>@5Bpx5=#4}D=>H$*{cSD|yug8PL6oz+;x+u1n->Si#o~cu)> zadVZm)y#nXCsccc4OB{7Wn6CgyQUD9A%Ue(3%mm*4QEy$3xJyCJq6&&z2DYZv30Rw zTUA&rMonj+HX4a7R}>_ZpJ_94o=A4uUorAj*4eXNP+pDE6URRYxBjEcgNnWAg`m@Ue_}Q?(c)+QhPTNP3A}@L(KKPruU8;X7!RW;8VLcaCM* zTP<$B3y!->8%59edaC`jhEpE^;NtYkIagWB08#z7$e_jjBpZm1_)T_uU9U$S31JWM zM=gPhw#lY_OFhwR<@^2c+d*mEI7>o-)pdeb#`J58PCj~B-W=l#oDCuX=Un#2SOmlC zJ=FRJsJn$8Pj*oG=PDZJp>1s3^5w8U)=;i4e6$OWc&0&a*yR%Ie_Q>sGge8n|7sU) z0{6rhCR>zKUGzPrg{EK!M%jn3sFw zgtx5PCg6$k^7T6f+jNq2In;qxa^!aOtl4Z%RzPwS;uDR9U?~|$TygK&P^$F?inXM%S~gw`+dptxMJp2|5{E_xmYeT|L!)r$-t0`eJ+{Yiu)U1&KYY1G zWHYxmI!|=5O091myvp6#Brd>9A^P4#!A04RWQ!`D@a^nByHb?IV-z8Pda7C1Pf>Ap zo#)C_`IW^Y$V@EN5XIy&0JTvO++xBPa`toj=Rrlu7jxWBRVTi099-@FtUJXfx|odm9bp^kd~ zwUO%}!9?9H8kJZ?U<77C@9E7UaH^6cXWW%k(B1nmjp!PrjTG9vZzQp6z+0!# zhTaQ%1#4mcsB^RJ4F^#3s>bRK&9skXNKqU4E+yCs|6WN*fPyZrdHx+ zcGxFj`wt1leLxd#tQZsbQ(zj}sFMcPU%5^mKHxQ(7Q3}vm|!g7UFYB?k~`}_l?-3v zheLzom;99mpNd2cj)5fRh`~M6+9%Q4I>aicFK`#ATw?Fv$tWC0*$RwHvA$Hzi$(0U z5v04aMk%_p%S(lZ7T{<<<-W8!%vR^0v%)sW3+csTD$#E6P3ep}N7EmbyVrF4v(3oq{id@; zq4r2uXXSH(AsXOBXT#N2uSEthjslIX3UQPU#Yuf9A{NQI=&e%nwA?YK2xR;sDa(hYtg52bfmdMJtj*P5j-uA`n=Ml zK&)?FT9_0$=*d!&?HH~{bmk}ewET1z;BuTKQ^vfS@$PiheB)8|l3F4UNZPy-hrq>! zp}p8v`6D6Aqa?XJrkZ*%B4MkiyR&)^PdAGE!bXYyxauP_MMJaxDtXcpp;s{|8;_oh znxqM*4kAt90X4YP-BKtApIpZ@EbQ>YVrz8 zjXkZ$LWXMO`&z5c!`OE8PfSuIJlCJsu1hfjd+;E;ax;E9O^)-@l92n0q6BxH1(K~C zd2iwA45L=XBSsxL{ShUGxn$Gs%OxcfF|^&|h4_V{HCU%tP^nPG;W4Z$Rv`-{%8nAHo>CR0Wr+pe96lufI6Xul(nWx+{$x{i9v z-pR^kc--rJEZb{YemL}eqjvvz)p^u%c-8qNBKGR(ChKW_^eXx^;C>)rWA z#MKINBHstV5h+jN_6t2Vk8dvS)tke);jK!>^(Rw}@~EPt*f z$HdV>gVbd}`HYun(mlg3RlcWBQRm?M>JW+lVvH7|ZMwr zG&y46RziHyj`}H&y@dC>C3s1cb+jzRA_lZtGS$B{sYIuKwdRJb<#W~(Jw5nyJ-WRn zVVPTa^DHK}Vt|HRT6cKTIm5$z`Ka*>@2#y&jOJ#UCNH~LGkzRRs3y)`%#y;EhTeC* zBA<_Pz1nGH!~Q5DAVW|IG$O%1?Hr;KX`BX~5Inv41Cw@y@9ny@SzUKq8kV^+ts5NW z960Po8$u;FWt%WJ`O^`B9~0TExo zgJ63uqtX`b`k%qgH8(djPgJe-vzrYr%FnrkB3F5ECAQrKuf=-`-UF@=fWl#C8`_i_ zrr!?I7ccEm^O=qqm2xj6Wj%g+Uc)9zQ&8GP-9O-Oeo%|H%qZc~CuI3Hx9@I}7XM$B zM68V7S>JNRyHOIi{pUuB&UAm@!Ek+LZ2hVc%ej*P>rJIC{>xh-)JXzvuihaf1-J5f zDso(47l1?<+K?Kh-xl+=S;xw?uU@0CfZP6bh|}R!JS^aeT_OPtFmw6vsbSX0CT^X|puI<75-#->QpxVVl70h>3k_WD?-9Rz zfJ4*;n$8J@mxQ~$?~Ctc+m*J1{H~uD5 zFeB8RQ-!SaFbQI7oYD#TjHird$nOsAFssQCzoaJ-ul8(x{?&Bjh1H0RrlDAUn!^Ef zR>dZwR{+9Ivd9l55A+p_lg3?g@|k?JdyZP5_xt;Qp9z5cAs&X@)A@PQvOePs_MwIF z%z9(Lo#wWD5hTK+yd7MuG5t68&-Uh6kBRRfOzbL~&EQF=gFcr$z{&Awlf+7JY27bs zm7Z!1J7Q0#zR&`&x6N*stvs!T0-t+$<^qnz+~f_56PKgco&orUh@5y zS*}wmx`!>wO1srA3H%w#9Y!oMgG?bY1(?iqtAejkoczX6`q+_TF`lL8`f|RkoT*uOx*)gQ&s-(NTZv(9Fk8Z$>I+3%#iw(R#j5 zS|v;yw0NAjysqzdDGZ=jb?m0<3G}!XAv}}~rj&aI*btezEN^`owhMn=0EJGUsgZjO z-KSHPRz4=&E$H&oc6UD4d;=8R=HkM%i{J$6uYYXN8pxcze5@o7@>0fQYxb}D>GO3z zKQ7-F*`qW>ThjkwKsVSl6Z>8`W2@(%nF`=h5g8cgxf7;wi|cXD&#^UdLI&*&*N zQp-%sz@Y7;ekA|6(OT!sIoIg@Yyx#2Q7-3I&q$L!F8wuEyW}0d9sg^p4q80o)lcNG zH5oV8exf$pxuhkUw{C)rQ|kubwF^GyR<|CHPkwP82&FC5#7udqPJW|p&Ssu1+KzpJ z)+fep-g>0fDiG8a96j{)3>gMeooeW4UbVwloT9cp@AYl}jj{Z0uOvHj3~KDaH8Y3W z&UK<9B0P>xs&g|7f?-wC!Vkq74`p|!&balo4C%Sv4>~GrE8BgOM#aK4QKD{=%$EdFWPnU`D;1OhUtR zoZfjG{>p+uN$eZygP}<)|7NlHZQo@E`M;|f2fng@QbH-UfgVp|wOLNi;1kIZPKt~z zeS_PTs?~vzGm3eCqq#cnC$DURr3Ey&rJSA_`W4L1wP1f4h9Mc40{Fic?O+Q7(YzEk z?>)cHcSHP1NIo^H$gBd)YtIol``h4`%Vz1b;dbyAJ^kZ0RP5HFjd z%cXJ9X7qrXEQ7qDCGexGG?-50SweQ%nYr5i6h)9_;r>>SiN=?skI zmtNSXgiJ5e%ttnU8qPXuke}U2u=)Zj@VPJaKsMl=u%rwlQN0JUKU>%<@9l{DDRz6= zmW&~Ki0?$<5+T;(e0zBmzXl4>Hbm2jci%vlho?UAVg#A&qj2b{^2<$36&06`xZ6Ps zHos*jBm0{w>AD%>IDbf<3{vx=99!&jriY6$vD%0t0Vm-LJ2X z@1~8!C2v^{Rl%u#iVeRfvu!D9<~fdcHSXlaG7Ul$Jw!|&bZAx)D~`fSDfR;?tlZ&! zWt5q)*TmVP!qa;~4;eBT?_VnKni=|Rb9_oo&j-y*bx~;nN$@0pJ$_M;tAuVrO!rQJ3uOiDL=*qPAo$&3uEZwYzc z=;vQ2+h;eRcb47DLO*kKH;-S0m+R{y<1z1k$|jLg(AXoad1D2oIASEpMeJHPjHTDD z7qH&+q!Rz#s5ox5_wY3SYpD#-e57BTo65u^HEJ)^-OhbSeI)_T+P7j~ENh~J=w)m? zo50jP_K~}pHVv}#ayeEzhj<;ot(4`i+4*!9g0Ow2i`8Dz)QR{4@Ejfxys(O+@FpZu z6kn!mpvylGNY&X?aTkccJ@#=^!*A8wjWy<^*!{%$xM`^z7jx>da2U}r3T=ogHegD+ z#1y?Azn`rM1$Z2E*?Ht7T}9`ci{YZlmlY5QE^5S5Rw}dl4k5CECa5<6*6)}Woq83c zjdINj89$xMsWV3!=~}MJ-|V_{y%F2vo+~)O?F8Rt zL;XciLuN;{^zOQyF7v2PkU>sJT}oeP7e1X#6Djx9@ArIe6}d6@=K0obiXV{_Z703Hu5=h=cJ5*S5!ejl<$Ia0+3+W+`eG3{c*Rr%mTjMxAE^u zpecd>8+W%annCA!A$}lbfT$QKE((x6@E1d2u9#!^tr%+L{^jR%oFW%4Qk2;mhdYJF zZw{S3$o!rcGwfB|6k|bNWmpY;&P5@=;~#hUECt%?X?*dUJovj_q|M(G+3S!A-q+h! zie*4byn$Oa%i$aB=ii~l6Add$jfoQ+9C7HvbJ)$vd4gLXAgRE5?7-TI+9i)ft4V>JAOgkb1|Ifq&SOWjICQUS-7+hINSYY|h2i#{ZQ*u?2BTX9 z8Tmswx1#${tELhjr=~sAx3t+_-JtdgZDWWSJD{MO37!>d-a zvST*AdYQNoSI}rFPt{>D@yhLt6-T<{ikV>G-LX19r@3u9=ZFgTB2lOJXYRNjiRF<^ z$)*GcAc%50s2=t_&gmrq0{@|8_SGU{?Zd|_9VR)WudZ7Pap@Ne`V8hcLL$~ai+byV zTtgbQV{-ZlT~Ag=`rpWgYRVswPEbxzkl@j7aSR-dXY3|l)!ABW&*cAtsd~*-{LJzp zKU~d(PuX;;KFOr_I-!}_GecCJ0Ut+w$xk%8B)Y(LzU5$&<%3Oa6P--)iQ|@@VyX^G z6XFB|7iF1GHvV)&Wf+>2DKi0AeUqCG|Lh8moYJ%qX^A# z(h!x0K&@II(6-P=HHI zROm#+*sB=LY&;VtJ4})uyw15Sy>^BIMr6}cB-I5JpZ8~%+psdQSrharc*pMg0p>^E zfS&)skdISN=pjMjqD+JdAyIWbLGH4N6b$He-Stg=-rnNcOE`Co^TEY{&&ELTy60raE}Lc195F+s z<9ob+m8Gu=9PCi>!o22TRp?k(Gt|g)hh05l=++lrE$D0{8pkKyCo$1sDoQ{CWf3A@ zi{=sX;~+QfwH&_6bn`XGS@@ts{~ot;yf1NO8e9BA{B!Pq_Xrr2g|H)!n&ExE+V6aL z({kEzouypVFi)(=J20=}ado%Q8GYVGY3R{)cHx6lkK0djF%-!(tnirj?oDnNW3fsu zqn#q%m&sxkD^&R=K|K8rDv~fisb5@l|042U?+L1X@Xrc)2)vS#`u)DKw3KR}zUpqT zLbz+yrMbSMqKjwrD|qN5@&9_Lc%Epucu3q3756S)zigj;lTwvTy^Xhs|I zr)^U)@Mm{zpFZ!dtWu>5R>KWPCgN7AOK)Gr1;scd>-)k^aa3zQ=;PXS`?+)PV&O8h zFRh%)QP#Qodh@b()k!de%EjrqXO%v7fvr~bDLwifNHN|Uv269?80-9P`NZK1aU!PW zT&8xWyNiiw@A;LmG@Hh#hI1J=0x58IkLv0!p4dfW{cbFPP~B5xKALGswR`5%zHu>j z+oambGz_rT9C9g{P_5afV(2(sSE$;j<|bXe>^k#NJIzeNsbd zCbrIu+uEbd30v56F8{6UO?xrc>;i+-?38Tsj!=b#Ji-E!d&@K<`(cNAV~fnnWGL=$ zSb2o6Cq(e1;iN0$nGvyK+VRWTTOUl(c6-s>gvo9k(7cc3F-R1}0&iEw$(l2cPrQz) z$g>^@FNloJaIdtSxMY6(v26ozt$b>BasJwWz`8hkEn2Y>RCqcjntz(f^f)lXf}f)f%Uo#X#LMbPCi?>~jO7wqIJ6TJH9}-?r;xnUNSJ<$w7iEhY z3p9l&-VS}K@odd77Yi=ID)jr1)j)YC0D6rIv+q(XnCmu`GU@r@P}csDiLE%Hug>DN z{a`n|ewB_i?G#3uT~@m5#GgK4)$y94oGc2tVTtO&zf+79GlryJ^U|B#q^>pYrEyCQ z%k{u*|M~F#Hx2T0Gl}JwjQegzIW;XZ_+@HYKc5?X?q)E!ag?vbwE^pL%=POjcC!hQ zk(MY`^@cXry;@o| z?UQ5zal`Q_q){?M*C`fiu*qm~UIjvhRU4ffNu2F&<_9y#8!9cYdNTk?aF$TI26U~u zF8h#oaqp%{$v1EB(9Qg!2l_IsLy%2H8OVY(qJ07k!QTwM)rH!60iq(&iS0P@gSD?X z(vXEN#VEdA_;RWl`aye|p6xRtr9gQ7Y3}06*iF!ub6_17*J$or`rRsNsj$dOehm*x zKph-5%qz}UL9r*Cucjk%MAd~hke?EEsWw^TIF@*`D1XP8SZdn&IoO!r{tT(v^lMxU zx-wgs%7R&UkAEX!yvVT|S4NcsP?pU!R|#A%FDMs}l{ELmp1&u&h=~)Fe}P#G=UM)P z@Inn6!;5N%qBxZRdZE6?k=e0k0K^gz;n zbKSQL>lV6&L@JQ{`f;bWrH6fKh@T>1Z+QCR0YS=*uQ1u+`7^9rX~trMHm zK(}&;EC?_|E#PH9N3NG6dUidCbALKj3k9k0#4Mpcr4u5BlB!=PPZ>+k!`-w}_)CU!Uao1B7% z%JIwTBRiiJGC$pND}hA7kMAW=uM)!EhY-q$|4i{tP^=-puv^Px8tgM5 zQLvmrMqH4CG|9+Z?xe58ka)^MaD6YYcYnRzB`Hz7HzfB%e|>P1AX=Gm8{ua3+GLdj z1z4(JL-s0Sj_HBO?0SxvX|=3E8z<2>nI@>Ik(ql={BDKMEM;gK2EWTh&h1$&AAdGZ zzSi)$NVpJHyZ#*Ot`2_Q^|)zn?!@#7ikDH%`qr5&zl#@eAdz6^6EcNVJV6NPqL=)H zuz8}vId&rqVSx>oi-~-W_xUsQRXYmNg=j9QbV`oFYUIY5uOUs0Vfm!3V>Cpu=!W41 zHZwAC7Be!rCac}hH+}X_Uz*3XFzTfP9P+?~B82X&4ZB+tQJ{%XJAhqewC$6&iawalZOm!4Cp;|T59 zf6c|5|Cj-M^1?KYWtxkoK2Mp=vtOA6(BUT53e~dIs>?o*(%OAXnGVB7owNOoLHI|Y zv_v?c`lPIgUw>UU(hU9@p4`Pwf7jMh`JNw;T>@16DYnqFPGiiTPP~LOlz(MyJoyS{ zR3{YG?MaQfjeK~&bow;K*viz=AX80l^aBLFdiZ%l%}b7T(`$G*?7ML&nm(K!GSBk2 z$I_;XCm4kF{P!EA!}T4ut_gd)#e2RFenVE5=IJzcE(B6QD~F_oNi^YqwX|rD#LP|I zsTrnQISj{1I3A|p*st9L0VZ_)ME0@}ZeX3`VLAcxPXn5^>2_S)d|_oAATtKoylG?g zjkq;uWAl)IX08*%0DMm>)m8IXVhBCqqSU;c{Z8!BP8=@qLE~y;Rd9!jlbbH6oXHJ+ zFr^wvOrQ9_ow|<^_Qn*tMqxI7_AE^Qk59nuog-6@^Y-3`($UDA!DG}6)~Al=>FC5%g6QAm2D{!(=dT?tdRwRxc!yyS8GMR*p=cn2!NIdElMp6hGS5-5NW<_ zlRVAPjOh!k=yqLuQ-1{NrAA1Z4{NVAxv;YhT3}YF;0$n%qQ$Tp``q?yf7yCXdf|W{4yweXI#_$J_xP{IB&iAv0`(eQ^ zv=A~ds!^kbkKAAGT67qZAgwt=1bU4a?B33@dw=<7*-|Ngf8J56ox6^6$JdBPe7);c zB_(*X(Vt7@?b6hR^q7Fv14gL6KZ2}y^!{;6%$Dq$KSP$%F`{?fE{;jEa0AV^^1*4K z63q06kJv^NY%A|Uq<8#+LCWa%dBlNOr^=8BrX?H_*axEmE2_zdkKX*Pk0LtIn8m0Y zz&+A7-?nJIbAb{pgq8Dqk=hkXa1M8|$ZfE|XW6U$FMNxY8D_ank3C_wmF0+Xzu$AMW5wwV%k_y*_I7 z3>X2)m2AlicW~{Ic@wQDPr*7Phd0Yyj8U%6eLswr{L-)WO_f)lL6qV^u99LVD9MOF zV^ZwwEBl_1$Wu3}Pf3Y6_RC(^9dOK?xTbWy1u9I?JW->vAdK5174%P*>%+|&T+-D6 z(y`CDka*}j^Hk59)5k!;J|F(^%c%F-q}b`#MeFH0=bqv>?*wc=P_?4E8yJO^#DS?4 z`7QGK^<}8<#A6(dxJpg)`Djv(4P)j{MR>JWeiYqkeIWwNqWY7RWH%GxYoY{KQelt6 zMbV=k$~wCv`L(-#p1QdoP12$)Z+BAxx)xC{q#DDZ4`Vq!Nz1&X;8+z!9m_mcww*2$cb=HOi zxU}v1MZMN;93KYGgxZf`dCo?!9hPwx=n^Fxs^Qp3f&|bYG$u&(6L2g=QM_p&h+@wi zxtU@7LKtr228^RwNzwHA1^0w7x*%nWnKrnSZ?cWJP}#`f;)*FgAxRf#QnT#kzSzC) z1BDmK5%9sQ@#a68!$k-ROnn!hQH$;Lo^zEuc_EeNtXunYC{W<_J&B+lV;HC3yNK&{ zM#<*oD~~ZP`S_`Qj^J_p`Hk0?Wb6Q$aT7EVFCuf5!`W1 zfr?`|Ng1+DLmF@pYy>@Nigaw23hWgQx~zMJ{1y!eWj(mN97D|GJsa=#SYdvM{w*gJ zp*)bc$Er?uIs}ws?tuJIAS3SCZ9bU4Hn05gK@0BYVB3|qdh+W2eHUC_nFF47B*42K<9IvV0aK%FjmU!usi$BHlv&pPOzCjYHC6%In9 zRn&_D(o4vEZe~<`X&sGauO_C>Y|>QOLnZ$c*k`GjCW+7-*_ul4&>^cmBk!c4?&>CQ z4orDLxp<)5c~D@q?2lHn*Y&iCAh0mkKt3MHUXo^tPS=<643YidDk0~MvIY8iM zYdDL)TBxRfw;x1IJO~y%8WjB~2Nd9S*|hJUse1jNYC=mDhh{#ArX<9;k*o{)=Zk#l z^QX;e|2z`rOSc@TdytVdiiT=n8d*oe2$;amzjricuIaIwup=?pYjRvsHX9(IF(lj7o zn{1h1F_h=K?3qKDMB_qcH;Iw~+=Zw>Eo3gAF2ru6fo9P2Sr4v_*ji7H+=tiqY!7uQ zlCKun-)m*70pDb%Q#|zKE07O9^0A0c>P7BEUc?b&hi**=+6lV+x2%PR<5E@Te7Io6 zb$(eGK?RXk+i;CHklvf$lQqy**h5B?x_Mm}uDIwm;7w0|s?C`xie7sizA}WPgMgSt zK>IpKlgpPIbB#D|pc>p>gs+!!PU4&D(7XspHh}{D{ozft*fqLkb*AT?Y2wA|(P%_# zaV8Xmk7Kg1l|U$9(xuu}@D|h@+Cvj(w3gDqf|yJ%FpKJ4-*xP?mj9#6FwNqnP)dO* z>%uqj*l)`&!b-XljpBf32$sp&^LI^XxGE2cT(poyTrv|4yI*fYAuQ4L?n1Buy3qJ+ z$HH-5H9MsJMh-y#WfpHeqqg&T@D`&jo=>z;^b@h*P~X34BvPlUi`mZz@fL8Y@73Lc?;-$pu`*vQ$``wNAW7wwr zc#HLWMsRePpicbDTLkg!9Gbt19yF!}oF^pYCzlUgJ2w3M(!FG z*@L^Xaq{jT`C6;ENxwO$RS$UFUKNtEHXTdV;R@-Iz!jlS6pgA0ASB2rlqH;eU`SRM zTERpUu)ycvXZ5`kzstdQ+CUE^JukqDQ^>@MryHg~KlwPJWt~V$kntq_yx=5V3#SvG zb=W!Z8Hj;lfG1f$bS^ECl#QeEGc1ZW|8*+1Loevn(@-&1DJG=H1$TpN&M*(Gh#z#G zRW=~cZ!Dq4QWp|}X3%o+afnKfGmi}1q37p-!{OQ9@Cl9%7NX7oW~+MmAHinz3tPI$=G(peGJ6#RQ$t+yVz=C!CqV+bF$Vo*B&BEl+ z1wvh|QfBNCE!)8_G<6h6^KQ1ibL^N8Kb5d7$Xj9%DW=eFpuoU$A729R(GEkhj$e)Q zo&zTV>Gj>p4iE5#EFXdoS-^*M97itx@?o})v{y_!L%?oYNLe^2dBcQAp9C&LeN_uG zSKa)yRc?E%Jzk|!LG1?U@?_xB3APl?w|`VwrmCQJN@CwBw)ds%^X1cOi2P>hzeobefUG1Vv=bQ#qH_OL6KASoScWZo` zeK!-kAW;rTa=U(t`(U;o`i9MkR^-LIv7%^&%mmdHIupYH{=03!Cr}Q|=4>%d<#?e_ zASE>)Vf6HV!cX6v51a!`^2&hgUzQL}Vf~NrDBj70QE0X&Om#>g+JG=|?nXq;!j|v; zr8{@V)%~M&z0e@=mn98udbgbu!+%6ETqtX{^lM%OMj99AE&Il9$_-Y0n;bq^2=*Lc zdssg$+UL$FZdt#L?=!{^NSZJ1_{lk$6rXtVor?#-8p?H1f3+In;L^HS&LQSd()tKa z=N7yhYLB158!>^cn z&=oHz-x-W>egZ38W$f7uG!TF5-25iG7r4Wgk3r6bM)&9>Y_XD(5`Ttufs}z0p`ROX z?v-XnU6%rKB#nUH6=#=p9X$0lq2W-qK(;WhIjciP`s?U+heKq>QBxDLvxv6TPUi0r zvuA}T!HY(d2AMa0TuN<7jI#m#u8*Y(7o*q!Ew4Ww3x- zk&8I*`+s_5{fK+)c9Y}2lyGT7eifcc2*HuD&Mq^x{4}!d(8w{KWw9Xu&O|$R7AjNE zJbdQC$oq@}aH1`Sy+`7%L6Tb8?cc4&;2Y|UZCrq^NZzueZQWcVQH*f(3?KGbf=M*^ zmal;i&T5$ny&l5*p$DJq<)^o5A)Nm2psf)TKtj#lGKX8q4(~h!Jg`9cRuXKNImQhr zL{|WgR+h5NeE427L>tXXTkVFb+1C|I|aq<|Cq*iEI4%k*kk);+@{a!o`$a06uwP|G2cHrgZ_KW zy~YCz$xAfiUEn{;$mbV$TA?eKZL&(OK_do6*YC?6);+ACzjog|4dVo!MTbC%fNOHP z9s@aVa)I#1{$(dcT4Ntbd;eD8ymdb>+1xDAxBb#xBw#N+0L=>Cy?V{J@JNTt zAlwIrGIO+f(b_CeY)uFftC3r)U=&03p98>1a0*8eoHq;8U*E%6^n6mT8B)Kxg!@Q< z65N%u09!IOCj-w$DS6OZL~S=8!$up^zYi+J#=ky~nJCm2>zCcUG4(!T;~U$_u?C zK@EiY5%nmh;CN*i-ekilr=QJy<~r4EMUXE^<*R4PdJ2!QFF|HwFZ^gZ-dBhY*{^$3 zYURU;)f=D&jL>yqxVqanm3>C7Vfu>bVO;k;WEc85<2fKf!!HBVIfS(~Jud>aNVTBa@#4sT08avgO;@Nfgx@zAN?#fuogROU;< zMCb>2Z(A)JmSo_p;8xB;M$(Grs>RlRKdUm)GrpOU=uy@`31Kocg2+!UHXJqJiA?lA zGA#7et!6McjCpmT)FqVtd=0E_bLj0;E68;Awb)PuL-%Xn{%L_3t#9n<^ZFG_9XQBj zrS_jPJ_r`E0b_=y&Id_!HWy^}E#f2V-|CLbKKvj0Ex&n3u=KK*r_Czwq)P0sZOlZN z_{pjP51BR_|0AnI716(%Q>X#0m(_QgzEcL@YsV!M9-Ut~H{QQ*{=*CK7WZC5*)EwG z^m;6)UF?+5ckI?|iM{N>^{?XO^_vDLZt~_2z5T>gCF1bciwD>*mmGKrJvQe=4Gj6` zsl?7Z(Po$+iTXU`Q-SFLpE>f*6FN^m;CYJq#sj-nPx^zuMm$E8@h2{VSs5Vlb)Y2j zpt`*EJObQ?w7UODP1OL!&$%C~f(1t?dBvXl$X~csKxEPgGujPxD#RLh^G%2Pwju7e`QX z*kuB;%}?fw|2f65|Bu>e^Opv%Em51$c9Tx)B3q8Nb;jdE;xxZL0u4R@e=IF2iA8)r z=)$_#$!t^j?_vg7S@NGvkV}J1Z$Vb8->LkP-0hnqbW_ugA0|0ER_edEhJou4Se=I- zfK(MrTRaFa$nw+8U*kZ3`cM+Bmq?}bb zc9S9zxxe)U7Zhr0ei~#HPvqo*OOJp?TUMY>xv9i>83VqUrgBOTvSW*-mfdd?cmV)! z2&`6RnV9lKl`5YcmDarLcgi1tR1=q1`Q58}5BQO%Yty!!rTnTxbStKBJ^4KEn{_IP z!lS#5mYA&1Yv}np6x$QGTWjOrW4shx#T2&weAi%{3)BN%!biq_bORWyvZKrWi$fa$ z>_Ta%_>CK~L?`wK_~eHBjJ77c@TT(LCu1r5U6^_|-F*WC8Y;h`n2xSJK1Eyyx#}() zI(JbFP3yGU8%Vzz*uPZF2d$AKnm&38I}rP`j!H#qpZ&eK*T(0^_ev#$EVZkMP>v5? zD8VnYm9=Ts@nTN&!&IIOm0ff1uowZD4T{hn^^8?$_LI(b;xORlOvYh%7#C&8!CCz}lB zBqhFgzl@ucqsM`Mpx%*{PB`taO59E- z0^(=3_aiUutcOruMV7tjst(8-xx5R`2g4w*lCVrUnA}ueHN~7%JW~^kQq4xVdeP#h zWDQWtPoz<`B_9vmF%(ogF&*@2RPa-h?To5dm>TB~nO-zh0ZhVFcnHXOJ4d{C1HF`=r4@L*M2I zg2=a<#?$m%jpR&?UmNBR7egUHafX#71dsVGvOXapBiLshGX zNx*l~JjugsOD+@wsMh4u-4nPo!KmjBDE=P<)I<^s`X!m1M^4MSzigG6v#Gp(3trrrf4}fTPcAE6 zWnhc>I=D$nYouF~@^tCmuXblde&ayWIs#b$vrl?E^kn0{FSBU&0bf>*A)ZaEwY#G zYKn%IK6t)7#-wA^5cekBagh?l^|pl3y*YWGlkW!+47K34G7hZhioE(`8-B>k=o^f; zvi*pu1U8^|2>p~N6HqO|73AjFp*2cj=F&o5H%*%}s52zaEB*KW868Q3(2Vx^X$dsN z-C`O$uMrLBCCv(F6eZ&@Fv{Q)e`2~k+&Go7%~_q*3wg~=waitj3I%#%Tf7{MR_lC( zqA9p|XY8rr7*{kwr{;tJeuNi+eZVStc4odUwY0z==g}R*yDYP*IPY+1C(P&Xu}NY z^&GcG^`9AZDNHfLtIK7NCqvBU)7v1|l2n(IS5no`_UTHs7vu!6(E|iKAHFht$)A>+ za9M73)8iLuR2xVyv6%_(Z5S!PV0&UgPju0!iXFhwwSL5NZg)u0NmJ=UqvD?E;poyI zMC{^KY^2cRKav%hZHbyMJb>G{TJXk||v z9!?ku&^B%^wNS1Qpighewd*cQ(PBm*En9Omer8roH69Iop*maX#PPVSH8;P}=fLnO z+kBnB2=%DBdbXP#m!E`C7lnF*n$eMpd;N=n=Wc8cCV;H`wc1JcI~ANxw|JIGw4Y9_ z{AS4P5*_LaeoF=q^GBG1vhWmE>U9eG^3Kemb6`P~l-$=yN1w!l@`V6P!vXqL`@3!% zJ1gdi_CQvp8-|MU5F4Syv~ZQZhSl%LX#A}^j&BMfJb%REZcefj@)Xj-H22>lhP^Uw zax41WGRpei&|u(ZBSp6YCB zYB5q+<#o3jJ>6{GE@fPvL;XUEMSSM)FYOBJCsT1qtPzoP4kZiuW+XLoh?xUwzrQ1Hk!f=J zj1dlZVuJ zp&+-c{sPa`0*K34@}H#VFR8k7l%UlEuT@HMXC0za$dZ0m6){CUB`_6#lH;7wW59~Q zyPx~s9Q3OAZ8ZbQ0!5+Y15B~pKq?L*v7$Kjn38M@7N$*;^e?K36BUnvd}K3$w-Hgz z-Da!ykILN{`H$WAz%Xq%zY^)CP?SP`*Wf5U_PP_pDN?2>ri0o|D9iktXZnH1bQWKz zB}}e~!CJ>kH*3kT;!)QsCgxOwTcbDq1^dt2gpqk`d#*1Gu#B>STR96ZPIKJk?A$Qp zRwHTl0h5%*!{H6l1ZmW;es$He$JgXD@b2R`QFrWdlD%<>wY7fCFb&sR7_L#wW@{}) zHW{@^YJ^yG?!R|y(~wA|(!8t1yhg=qRc~>3%Xqw`PNx(~5S>lgW(4E8= zz#kbZ{8M`?9`&KKTQ2kse;`FsFII27+bMg>l4*9L>;iO`c#*2uKw(GNF-(SqD6fZB zYPvooUDbTY*Ppx8PutR0S%d~pWF8saxbf;!v$chA8{Klwb2xZs;9z;S2~p=KBnJiV zy`(qfo<`*UEn#NG(13a#rItt6A^qi}V4sdfLQZV-%xRognpK`zB%3StERL)f&~&2l zrQ2$P$>HKL7?jAop?ybbH=UU}rY zKl%JpK(K2vWS0FC%=uR2kOZf@hAKX!b89PUPsBDdR-gcy9|mH-tDN>3Ep%3Usa$9z z1#4Z39<>}^qtPDOHj+uofxe*Lfkb*A1T{4?)HvbwWBT+ybg68il2OLpttaU$8&8a0 zHeG|&@j)#4S|_=V4A(m6BTda2!xLPP_F8Ia9ZeoE_BNjmD`t+otDtKU#5St@+8CEJ ztGjseh5OOSb*w}DZQ*jY3xt&nt-+9qw?S{JVnt=&7tUK|7}8tpc|1yw9mqKo1mUBZ zTeitwuRi$c#U@nsHBvk?!Xq^R1W{4B+Ew%?ducEA${KEPNi)AGKTyh&pnFgvRIT-3 zN1w8}ELcMs*lY9-fnxe>)HM=J|G>F(r%pyONSBErd&sil9(SM(zqfy*L2G83%~Y_A zq1!rPMI}fzQ9Jq-W1+r$9{|@?!Ho(>PR+RZ(5|8?7>B;|jhV7b7Zg!IhM|_!T}6>= zXp|fXvA9=I*Dnaxmdx4Q^@UP0hzS}W^~|996_-Vi^=+wRoB%EKUB$?wtrt0upI}Pa z64FINI<1#UXRP(B_ol?}ZNTA}s`hG0U>zL}KQZI?YJOWco$=UHY%H!<&GovhUZq*& zcW3(9MhmEOSZ_*zm~dlp^QR_Snl987eyI8ce>Jxsps6`Ys8I`uTI4cs(PTsg-yVaD zQ0QkB?rJ~V&~oXIT7ua$h)U z_rj8lL>gya9Xs|OR;l=8Xs}SoPxc;D1~B6xtNRxnR1~<<_rL3o4+99QkbTk8dzH)Dwnd`nS2-O`oZis-z0-tTIC;#i+3vw7zGwcDEpd%TlW5_d5MQCOQF;cUbh*^zbgq08@NpLkz$s zwww)4O)c+OA>U{+)R{J#4YnN5qW`#3dJRe56dQUSS=*RMsJo-h&6%-<+Pmw#CDSOg zx4zCJ6+v54@mi4q^rwz{PpNYS!%KC^AXQY;sLS%cWR|onSWO4TU^? z`)aPqlffp_D(1!qp|1kJjA$es$;g|Ub9}MZ%tgIA^S2ygZJVB|S~nUEQVVXMi6bm@ z(PMpiJhi;DgmnSi(9=5qli_V^QjNSf%6rAGLXCmd?{3`~e+mz5pf|@x$N}R7Fnv1R zOloVpa%UvAq18$3op+(~Z_sGoDmv-t(G5c+|K~4Q(wK9QsVafS=G!sKC zSbiY3jw0Hb-29TEP<&(IP+ajk4y&kCD&#=5ekk7>XT3MCCYY6Oq6t}k(yYKyR|xz(3PhPv4SXE;h%VX4w?8uE z2HT~aCcYFF*sEO`!?LSfFYJza{=h)3sbQ4t`i?ZRsYK*6)%zx3 z^ofB1S#>>TZ+MO{|8s5dFP_ayNE?b-%KLMCAV_aWjpo}a&AiM^7`-mKo?{H$yKO1W z=6A+bU%Ky{e97t3l$!W}qr3LoyoUp(LYg9Sho`7sWu!$kS4ryjI{{@*7z4tE2sI;q z#<;kbzlYZvQNbbB*W`8+FI##mQmxQ_giF`ZxqAxQ3-dYllhusiGWQ;kHCk@D_h(s`yrWdB@Nyh3Aj|-aBm9bk+u273i7NLCi-_Zm@ za{~3~YVVtbk>13>yg^`4x}ZS(<0GM%o;`jOjYhKdK}!u_InnnKz1y3?#cemMtBjT0k_egm+L7esixAaXL|*)9}*K67aL=|=y4-Qd@yxVk7XvZ-kaD& z=;}%fx!gLJ$4SG)0ynRGX~Li$G{`&TG0~auiB)k+cygeM%~Dr}&CsKtsa%XN^u?Es zD3jEZGw(JxjZ9i%Z;G{3R}eLG`!%MTfxUY2mAKaetT8ZI`_tGTf-LgP z9{cSLXap#UFgW;@&WX;vgaH-J=25KoeaR>l3Ym^&kknj|*}?(GQ{-Eel^b@vgfH3Y zsS${nopEZ7In3+lp|`QCX*J6PxU5#%^d!En{?Qzv?)O&a2o@7_FQ_v0n-qIBKvUqR z{C@WBrClwvM_@O=ih0W=^!16QchUSxg4rH#pcwh8pZ9234RE3XI=SUW$WxaXGT|!D zs}?%AUu&-EtTLeqRT623K&C0?z!kCx1@pFLQ=d$!j$Ql4zI(Ho37Ol*pr4AF;3^8nL`+ox>J@nQayp;7d> zAaH9D(Rh+lp3+^!P8Xylv=s+9p6-vFQ&|4^9*y#(%pY4vp?gcyEZ&&5Y*KW9vJ!&? zLJyO9(duUqXP7*pILM;uh_~%+l@-HR&PV!y<5goIl6wO?ebsXQh)?nQ3#GTfiInv1 z%H)i}c9Upgu`vg54uqmpo#u;(c{RMr>E2%!52?J0cjZvm)$R})_Qc!bmI&STbySMH z%QM854ee5;8(Eo~x^zcY%&F|=t4emDdD{|A@+UFTs#SQib@_OfapjI<|M0nSeDHp~ z>*&1MEQBvxa2da~brME=$doXfU-83nLW!TPXx{&*F6wnhS}<`Bd-ZTi_*rdx=v4Yk ztXJur-u}YRhvXT$@A32OY1}ho1CGoon0n}f~+ zAg*Rz+D~qB_%DAW=w=cDvwU{(E}yEpCU8E@U_pu`{bF8Kh_cE{f^t)j$;cZtlM1~= z_Q5@y7B!*t2f=3uRbssRn3UfB#=1wu+|$nCAJ16 zZy4T9iTvJlm78D#4iz&~^0P_8xMw`N0~ydi{I?w(W<}1bmX9fyl7Qp9illaD>; z14bdtLxc#3k=gK5li7i8(_`t#3oKiU8;-Kw_f}Y%V3V1r75PfaMhylW08S>I-lSKK z1|rPLsi?$RIj_zr$6pIOldTY=xCB7K_G-Zu4gvsllnPzGoMpf^wCwVefxqYl0(h#_-sD2e4*&* zTR&BIoa%rbkP!ilYl*Qe#pU~#-lj_~b*wO$=lR=)K#-XZXs^@f0r%kPRKoaiJIV|o zyW3#fvp59KbN`N1>#eK?zQ{8{hi$XLy6R-&HYh-8WT8y+eoM%0^R9jCsHa7tnw46D;~V1nFI zA{>yIRMxTrxp1oR6i3*==a{YzfZ~`fkRnvMspwQqX(c$4?E4dl zjTf#D!elWGzVQFBH%O=A{-760cB4<$=F{%%opfW%nJ0iBKZX}7$C1Zs7?UU0phn6P z=8`kV0ikQiWbPYqh243fcmDQ$oSnO=z-!%$Yd^X|1iVZA;eND}YX|7yqJ9eRl`kJV zlc3;ANp_EIUGX+kt6od~DjK*PEO~1=0PCxFW0tn7kac=`>uE6S&y4rddduvE8Sv6~ zq*YDw__85&u|rE7{MesgHX%u&QwzxT*7Ni9rTbW>@7q zne$t#p09y_6u9>27^x<^A6Z8ZVPUb#_w7W9If?INWzYZwnX-?sAK98gs2U?fvm1}j zzY>9TMdv;}uzVTB5-x1)z^K(j`Cg6wHpt7|j7Z=a;~V}W4E1Byr*nq4Y{VB0s&oyv zt=%JtSr5&><-jyAjTowf(344$Y_Z!l(dB#ltC$XKGwE#9AiK4Q8wCBOf!W7jZ+J1n zDk44UKTNo`(*3Y$5&T$DWv&5{NG2e9{`TmJl!RQ$Xq;D?)~N2x#iC`<662eJFq zH9nXJ4V+`9X0jKE0b)JBV!xr@X_kgTXm% zi@gwb*1<)VQKY=F2e1f)*Ahkdp00Dltn1O9Gwp=*)y~A)1>lRuu7o=Uv;KK}%cJi|!*At}ft%OH#Fd7}uF9P4nEB`@rC z4S${t!m^kX*laW6nj5r%gsopC`tmE&G_eKp|rwcV$Whb zyZ5OG0@1C8Zu(LZWN+~3@)OJ;NG#VlMP=62m%4%yzDZuDyPW1Q4aMD@{$g%$YrFmq zGHUUH7KUW~zTU^)n`2&ojGJDTd02q&1>4LmfY?UFBpoZF9I{W^H zc*~Y^V{_9gY%7w;r`2BPzQ!V&;4_p`e1M0FiraF$eWOy$-O34#ylv6~?G@Rt)8c3? zrU6${4jgl8`^x0}1+Z%$^tXVlZXPd9;BgJoE7;aLzpd$bG+nQ8lueU z*@#Sj>yam3y&`9L1_SL6i~2Q$rix664hHr!i-$st{Hs4t%YRjs(kzvN@9J8_MtgU?71qTiVm6f>f)lzJ)tPZX zL02}u-}UqAH_gMjLuZR+?PErdMy|>_8UDr}@y&lcH28MO$lE@3T&J*s$q6x1 z6}>wKf2{g)wvde>NooU{0lMcv34dK|6Z|wpnO{FAvohsULc5yCGPK;MeYo(Jz8Xxb zLA0lqLOlsu~|XKAli5zdl7zCPj?ww<_29nN}<-QzSQylB(|sKaBB0Y z34|`WqLzv=`7+CWMTMh~iYBO;gQnNuvl9uZ;RK*RR_6u{0!LUb)}vXXW4*-D`l`vw zA3{fq@%&!mHy}QL+BcTYtxA3M2b*H|Q*hIR!$SC_b(oFoZ8zGZYs_7dN_K2TA!7HU z7#ZI+K))_BjI=DjNq>`Q<$^c6I()V(sSe`p=8sf&jGeWoWBIC*iq=m#zt-wW)>@rw zF?ysH6z{w9l8xSPUeQTOxwS2PbYBkCr}Q`s2DzJP~>Y4t`=0|hMtZQZ)rd}-Tafi7ag8G`z#k~DSJ^*;RLmm z455ioxz@}=&GIoBBgRZbHq1VtvC*(kNm7ut18GdQ@_ilVz3YF>kq-_nV=VW3gPgtd zr+d!nkwi9mZ7=4MEIRch*SCLT-+q$K(O2gkX7T^9esf%w{W7vegQBU&==3pJ z`W5`fV+g`jvZx}Ie3h1=d15p<5n$xeduY!Dtd~5;?B4I(bau+8OVfrNJRZm{=^JdT zxR+Re`X{9cTy>n)vl<>Gd4BRJ)vng8ugZk00n(lGZClSSk@Qu!F2!5ESE_I;O8v2W z+2ez~A7B;Rf0F&k`z{#R;c+%)G$e}j^;1W)hbT>tlV8UHB_p;FdPIDvJ7?LL%A1)b zLj))F0+1(sm}p?yK7KLSD@-GEB{j*2tK($lsnf+ig<0@wLL$?yY9LI95qK=>XlIQ^ z``kG#r*XCrrG|QdmGb)V2!b_MopF#8S_F8*eK(b*xsrAqf?|2C&uFVcUR+H~YrLvI zC7j~me}Ph!^OB&PjTw(9^S~}i-;L(q-dG?3P_YX-3Y_uB z;7d=w4)KEG*A4d#YakNvd8L7TaV7qn(Ai)u5-f#RIT$|D@7sx`FAVtP;;_d8v#v=%1RXUIyZR z$}PCKZG5k#Iri5p+-~IulDj$T^r73nYdt+#3&d8lihhZxd$N%9X>55noW+xG5kCGG z9bWT#Zt*9qwR^jjZO3LXh>Kqg z!5#7_1585~LNBtCo>j%VUn91swMfb>g z?sW?Ig*^Y}y6scf@59Z~TYcxZj%9=Ne!uc&_XEEu*i^uk738^CS*4X{Xj?L-Q{<)kb{V0d}`NsO#_<^86Js$;}lwb>7RV@ z2Hxmx(P`ntu5&ZFs=JvSQ$)Rx7Kc9v2(w6)a+S{&!GFdmSCT`ui&yGJK5>yDcd{|5 zIgM^RG}&?(heveif07b9cdX&twa_8rb3ki3!o&VWZ+7|3GkIIgs)quJK`8G#IQEZK z9~)&l7C*VPE%UeJ)lK50F@kcL-a}ef|8f6e(EMm!-xc*;hjvP zGHS1qQszx+(l=-5G-IQ-_j^YXrW64%AOC%|eH^VF9=9=*q|bW+S&o`VFlkGh(W9V% z@AMtx$3t`4mXQ>R$(8;Q>AG37Q!tRv><8f=d`-OrgvCUyT?3^O`X(nSTeoUgci#ox zSBfnp&{>#&Y$)G{NP7s@Fm8N?%>OlQzKDwMfB(yB9r{|9ZaC2XYDnN2yk%KSTa~;> z&V7n}TjJg95Q_5AMfa)l@lU9#2Fu?Mk^Jz`SMZjEn*w4XmlM){9cU=a$#_i`S%T1F z-`D$sp|<9FqK4A7|8!h{5^|?>aSP3HW$&%0sdI|n9pmG0r@g-Gqe?#=0wv}4WobNGYeg> zFfzCKZy?b;#FCD(rQ+ViAd8gcKYxC%JV?M9umTtbPeT1qdqCtEAi1bnsAeAgcQC;( zVjd8iUoB(~`FB$SP&hCTHa-XLTF)jM|EH6_Br$IQThA=XJHP)vs?-7%(A8TG{X4$T z^V1gv+<6BvsRIA$64>Vqpn}AY>?Z%ydp$TKF%YBeEH0Dvp8?T>qr(9e4AQ@@83L31 zZ}Y03xd(XiD8~N#C@~yVu$dUCVe;Ru&OTFjyivsbcN0DLeozE31=tVv(6RofEF`}J z(5rrwVtBUyKH3B{9j1-OhKYFpGoSxI7&d<8m64}^he$QBJs3qz#&B}mFr2S&z0~}` zr0kzTZ6|`;Ab_7D8!Q@iA29Do)MR`%-Gb?>6oq=lTZzRsTqGxG%P)3;|GH)N--UC+ zwH|*l`8Uk)C3@wN;SV?@I{U#o6DT7m?HVGJdjY62NI+Sj?nIX+EWn=UdXuE>TP)0&w!9Mqg9J;-2PnQ*K51Wk5iwrmW{C{rc z`X0_U!!xgseg1gJ8**P}4=sD&(^Hwx$2#glgE+oZSEG$XXP(Sa&!N{KAtewJCy&5@ z2nckZQ@zb!H&p!TdU1WcY3~Q|*VzvwZGjokC8ecFDyH{cdCw@fym$$NyCCcVY8(@w zRqh|l2^<@ftISf*Z;|qu=H=+}-)G7t2owiUB^2!BmW^A5jcnIkKys2*(@QZC8e=^a zJLb_D>?y9?8xP07M#)q5MQ;A%%@htU&}t%k&im*?<5o&cx);|1pbRo8pRv-O7m|MuQ{OY9Lu zY;9wdh}bboYj4`BtrWG@7Gl(>mDokm8nvs$Y^hdNRTZtRR;|+S@&0^%zdyc@$JbvG zM{>@6&VAq4>l)9i>UHvlcO5uy%&l$yh5(}o;8zu)xo<-;tRcX-DttIVaY;rB05B{q z-^ZtdM2D9#lFU>zK*mWa4-&o_C#rU*zLC(-%KbCaMgpwVbOFO+eIo|jW0 z$09N+YUpF`ScV?==^pDKL8wxF{n`Lr#qGy)3K6P1NAf#)00ja5=PnCLGx#kK=Z!f5 zZp&i~mZ9iDflc)*lA$I)_2Nv;w2S*dD9(U_bW+NOcAYcM1&P3oKar&2(S#H0#jL9( zk9EOr;DH|JVn8*)>xG@8FpRwdH;KizKx{?hvTxB%np$&`7L8F97iYs0+P+&hP_1_l+!o1Yn1enR1-V{NYpq*9wQ0y)DTFYIu8_ z6*pqvHpeK z?~d34Tf%t!-^#;L;E6achofc^j?W<3XIp@g?UOh$$+ufr>BoC(fdc)vOaKrI^%5Q3 zLx7>o>*h-Gbj*P}wA=ow@Gss{+Z!GTZ0XP{zI>ltBkcVkjr_rStjKUD`fe9V#&1IynS!-Zk1U{*TcwaMPRI#Y-cEkzYAZ(uHs~k-~K!NU;>0y z?klQ#Eh&jf z+FJjrv{IG$GoS)Kb(qh5HM2-NB7Imm921~?KUVr!yq|o%#>Eb;{a!BzeqI4dY4=TH zfegnmix4rbYunATrH`pz;FqoRE^sQ@ePxKkGq)AiV>h0n1pt~b2fomWzM4_X zHSaVo_ZY`9M4o6?{4KQLQ-O{?s3RTiR@-9a@>3W>+2~-iv3LLQX(}TPhMMW};&{>N z&TnytWuLa}M-h>iryd%@)_EmuUOX&fRb(gI>y1bWYtAq4W zLWeZe)cwET636#PLc69YSZdxZMG>>i0hnyN*_jkG?#|4-I%89#W8ebLmoig<_Gr;W zPS=G)z;K@jwH-VLbt--C(1 z@sC^XYXs7?$AC35-AfDZ?>9ifs!d3rPz77r*!(kOZeY?|H6?yg4gGyj;=Qb;GzfW zfXaC^U&e5}m$?Ten*S}gS(Qrmbf}&&pMIb}S<3*I5otZ@plcmWTL)Er4S3|6Z=NNQ zTwSibzjW$MPQrbbK1NM=n9M^-XXY{xGYqUoNui*&d9yG_RzKouuC(=Dq)FnrrScSS zuIFUHY}7Vlm$beuByu|cn-F-5>RcA!9`cONb04R!QSZ~Me#0d>%q0eTP`$}h2bP?n z{7NFsJsn_C;Yt>RdU1=|ASi3JmA(N7%dE6`PtLhmY3w#~PC!XSP}iDD=szB@z|m%X z&;*HOT7%GHE?fr2MIl-!PqK9_y3ZcIb8OTnjjg#D#re1I_g^Jz9Y00?bj}}`WkEI) z-QBBhEWQftyRVb}w-LImTn+=zeD=xmIDO>(Y)}p3H1bcWf6lX`)Ag#775bT(24pG@ zZn(_b=&x@q+`%xruoA^k+@LRR0|y$YVr?YNkL zgZswaq}8M1H0cz6zZ=@4ON;&rwv`KTz3 z7H!V_C=2~jNly3eqx#9k3MYEy^j> z>t*w3KlKK`wu`%H&0$zkm1+H2%_#pb6R@TkCD)pLMxQAP?C3`H5xrLf0?PpKq0(z5 zFt4cjHb8fziY6unuu%*${!v>vxc~P=KDFP37n#D@^*yj_?F82uy@p0fGF&|0r5!FV z#S2HPCHS=2R8x7noyMlQyE>zmH}j31EsIcsenho}6{_hIcE+uuJ%nw7zykz}pdQRFi^W}wNOW?+ zz1hkarqALNHe;n;FAljYu`f*_gVEhhtnrhHKBQ^l$T<7rHB%+$oC}YNx`*6rG86pK zQf?z?yY>qK;_TBB-$EKKZUQu%CU1&keP^ip4-g}!rpMthMm}K=s);T+KHnB`92_X1 zVl{u#iI#ZS&X0W(y84R6W+9Z2g6Z$K3`;)HL7Hq-%$$a(p(D$PZs7IrC#(Juj^5`K z6{?9kT#%4Q*FK79B1V1`r82C7tKLPBeRU5FQmG7l>a<=V=yUVI zi@m_!781y(cuWHK5jSsmK69`Yuld<`c@K zCf;3>cEuo;I~RWDL#gwThSBDbF`k4k7opdc+uB^?He2O`0}76GszNsBt4so zwbv)i_-C!~tuaZ)y-vY#gyO-wM`h{{2lem&5}6qNKo@tewFNH8R(n&qV=0O;t#&h*Qr3XITuUl7QQBRnGmNpNy8I zc;Q@(72pfHzA)aNxy{ot=k-5I4#b=v)@q#q2ZXakV$K~fZ`S{~)}UmcV){lYOQL@Q z8Ff@eZrN1zcuZmO|4Mfj;<@a{#-FR-{lW%mnLG!xleMLKa@cV1i3LqjH63op&6bbV z`UlVXZLLqvSop8= zF?1EmRxb!mP9G@4V@v-NkWu)9dxbO6%ks|tPO@uQ#G z`iz;@^5qufW&cp1d!Pyv>LHNZ*r<7UKygF;@%aI3+uPEQW4WrO6ldBo8<~dcPv%Gb zZsv{Y@D;cA5@ieP9tsc)oa+|xNcn+6RMul*Bo zsirkuHUJ@+4t0N8F6pEJ;18kFrYi^z5sBmt$w3CLH@F)>-d0S=51>%>!IMV4rE{(6 z0o5a?;6wPDene350)9pnGA^_^{!I0+-U>n6WWD%8zyb9{B1>aQ+9fp!OZ(v@T4&J> zb}BEq$m|fGY{PRD9a@YR>)kHx*)8Ma`z}`AFNlb!tu24)D6(43SlAV)yhdxZ zPg?wT5OVJ_!qRl$3n?PvlYLA|lSVf<=#Q=6V?dzw*@@&tuQvZe_YkzEsxwIR;Aaba zQQooYBRNXfQ8JQFBVI!5ZZMnC9${wii5GrGkKGi<9w_u(JaZZ=q~XVO;56gWHt&?i zzN^-Zjp&Xv6k;|T!L?{PgzKi7m2>S$NZ?{rXyDdwM*UVhyT0lBxpmkk2I zEP#g$2l{j$fij_CwB$@e&X%?NVIF^-2&VzDNgRI|EXxfnx_hM> zhgtef8cN*|>C$}N*78uSP_)C~C=pgn*~Lkh2aj{R1BdBfQ14~stSvvetu8(B_b z0VSmX(qKi_FO7k|Q%*_fTBJ(ppoA!^|?I^6e0`==pdRYv2zRU@gJnOYQV&H zT*?p2#}qbVCkCSUuQkstu>_~fHwyt|nT>hD(C1@Mn$2~`r)bF&lbInuN{L;;J}-Yf zy#6U@L2=@8UXU`Y)P8u}A}B@_5Xf>DzYgXsZ&|Ud^S7x1$u70E?ffzgW(D90#QnGn zw84-sDwe#^4@+VcCEgX@!auJ?3<%I7y!KQ()+Y<0tO?rU!_Wi7z^A49kNdle!biya zeas%ePqqoQmYG^HODW}a3e$3N{YP3T$!bb~l{4wY6lvvcg!bVUCKZ6xK~iR*jV+Mk zdtG4ZTAAsy@@oS=$^}Mw{Umj@LL~``K!*kL%=I=-<&BnZSaE;FVS>o(>kTKF=u%Fi zF+V#Q73SAdipU58@;x#5+Fy@+VonoXXzYzAn>TX251qHHs*&lNTil{Q_U&wj47R17 zeH)oHz>i!Kgf_9`0*iQT`;>VSbP`PI7Nbd+GEkR&v$j`8%c?sg9YjuF`jYG3?=>=Q z61wb8E_cMnfGSYoTUQGt^F;YU?A>XSBuW()3Qj^ zZ9Y_MKl3M&lZa6mns6^;C!5GE?bk!)>JDvyKb$))=2v?CmK}sgTZ3On!#(l``NE>X zYZ!wO0nG%bD2T%fx%l0J%CkSiJlb{;Rh(YO2M00$>y(t&JU6F_U-RAQWI%g32Pd8}IDLS3 za1V!nJ39Fz*U(&O-K5_2)tayQL=UG!8;qwJ567yQwK1UG<#* zypobrhj>vqdv+OS_{CK8=xBc!5)K!cXd28Bi>nc~sR~p@KH9#m;lfZ^+@(=AY@*7(9NZXGu=wGN6XtxE5ZFzxBmE$w7ZkvQ*wt z)#9ngm!sN)h|>lC2b#7jQ{No@x(S;Teu^}-6*0=05wAAuH1vXS&d?A2qBk{gU2!>W zW*^s$z=_h>TPbs}-pKlhMhmtrN_^%;#@QHjj8+~3pb{!TdIX2Nv~a3(Q<)tb=*v)< za|+;F4$1%C@e1s1-awh#VIV{0J) z;v#aHiakU@f*Lq2*J7Agm4SY>nZ#Ow=)h-*3fECv#+O;6+{VH6@|%7s(ja)2zk zN&hxTb2n&oTX3`|h%4l-Uo^oGw}n_qrA6HH1!`DAJYQp*>0xwF(USWE4sFh>?xt9K z4tl1{^_o1)PGOX)7nLGZTqnpdfomNS0iJAb?r?A_Yc#uUpbN`H6T6;m#{+p=jfNh- zCAz_7Mn6)eduIr6 zhPG4LWz+3Z|yuA?BCD z=aV=@05@W3G-*}1fw(TyD^!osfIvbG4Wl;d&41bLSgBPF*JtN6r! zvpQk2++;b2Og8+l_t3WthtTP}hew=e%R`CWL_T&j!R}O=McsU&NbwO(6D`UVbBHch z)VKett*5T!92JM~Ol$z8iNwSMYWFdE;mCHVW<%Jumn*zXf-!C(_!s%GJ=Qk+)LR#>8=$*X{p#EFr3>4T(Jw(wJ1;z{ zj}Q?FLLR4NBzL`5+^haKPOPIDxFW~~@JF@c?ItbfG9mvPw*;7YqiM7Tx%Xx~M(`~> z^RB`UX;UTlB~rFpoK8%4ZO&fJ{!+O6--VRe94I`xPcNxZy88A7VYCiLpK>z_540rl zb5lstx)QyH=&4r?BHiHAS>K#K!~#pDkKMA8r!04?0^*x^LW!>$uQ}>`b=wtHVUVx| z6PQg8^45u&{?|+ZT9cUITkhKk?J>t;Qe2?Bl_|)=J@L>5JRNIE{Jcr)HR-6Xij0ux z$@s3W4~!wCQU(B_^XrUBN|@^nKP!2vnV2EZ6E?@?tJO>}u>fAm`V^I?CIrnGh^H4;BtvbxyP zXX4#w(JC3I73PYUx^-Z4b}wW#P{zF3ti&yMY_$H$I)B?RE4?GN5`~!s@K`|SxQF~g z1tEprgTnGXW};~|wWvrM%933z=Rj*5d`2R^J!Ai5vNOcBYgsGW>;Yi< zVYM1F8ox!`6*|fT{}YRnkGOBtB#>rfyTca>Zg)tMuJ>uJH+iZC?xmF7FL%$-%W>?F z<`8BvKK0el(~5OJj=?YLM>y67f<3$HR{S64;*|4yZsF?1n`K{Uy|^S)&KkURP10H@ zQdcGUyKccdS#Lq}tKYrKBC3Dj7G|pYom8^dI-*iVMA^SxL|^m0zP@A(bqof^d2WO+ zxDfjR)(a~3eo1?yp4Aw?m4!n{4pwKpK?%uSJN|Vb845NP#gT=Y5r6&{+54c4x3=5= zeH#F;bK#|={;(y0SF~2+|T<44ij(%KH!amaCpbHs)oDcQqmuB zaO*kZ(eSEa7fZ|G<*6yoY5t$uB}>gyR=5S2~r zNeRxjf2YL3qVMGjtsnBYk&qB;2lScSoTM3mw`!ZOX;It1|I7vY5zv2I&xl_{`LfLc z@KfHFRI&jeWe`&>Fn#-HygW?KR<+ppq^996+GCZ<{qnzj1s!KPm+8w7>lT(d2b}(@ z&%i|8NXA0utK3>tgu>9^dy0Z>1DAE6$wevshVcD_SQtfG{Qe6XF@9qq_Kgi~(aY6ECpoB&F{U(a^_au@Z5EoE2AOe^WQ(X*UGq->FIk#@(Ok-5Lfoe@ zHwJwY0M`5JL;31!?wEs9TY!%~yT#dlE#GM2Xv|wP#~Rw0Vo@s@y*{;T%7d^~F~A@r zM5v(oS&O@E*Txd;S#nFq0!T?)p{uUMx94k^7i6=DZ{DKuIafx6Oiq)E{#_Xh?_HFz zQVa9*UA3nt``Q;}Ml5&y_4ee&vVU;e&5-oGdXV0Ho@1Pa3LKy$}YPh zqX?8r0WzPZ?>3C6BLqNb4&44Eu@jSbfUvNT?VHX>4bS2uGJz^|2_Pwfd7(*qN4G_n zW9#Ehpfs#0j4AWTNN^m{p081-(qJBxLt2@8FaRkj!ve`(EGndj7 zIj4vOdK^S+7cIsELup)TGQf%()1}<1xtQ^Ajy{)pzH;YnA;#k=tZSG?J)~cFrAd^;8$Q5{ z>kpTykC%t$N5nT`-jdl#SRpqH^DalXriEuXRC-sf-n{#z;G3Icldz=AJ2`pxskL`f zA}|uR17991ZM6Jhv5mU`cD7*k$-rO)6)Sw z<~sqMqe3RxTdwV2$a!5E$C~(ly}zY>?Hqo+R#MOld{hf0Spdd+r-*0s$=Ov4y5BpK zUg0RBtR}Ke9siG{yPp7JcVYEP=>XD;SEcVy!O@-#Ra+hk>#IWSxRgvvpX&>TJhu#T zIcqVr816axb zAhVUVkeoRizA5~|Kl{`D`7eJKFCBlc`V&7NbZr^rUIO~bx4m6Sl#-WOwQ``QlvY=m+NFwvx`0msX^W%fo5xv?`$v~a8IQ!|Mg!i!w_1c~dxW;| zw~!j-mmy^5x@smb^N13+oN&a(O*L55TXGK(D@9Q95VD;q_YfN56Gpkg+ z2BJ@?SCC6oi3g|XcQQeQ7ab@el#yJ0@?2B~`22zXHBm}BD(cCz_mYy782>;gm=1*= zXQdNSk`vU6NjhWZNz=>|sIHn1JwElRSl_hxR*!wIoIa5OJ+aL{H|Dym9NCsI!eOK} zx3CN*iNEV!DzJe8bw=b)G{DBQYk)@jexjrx#8l|RWqSY zGno8wEOKssw83F+q=zwbL{iW#X-hHZTX_axdC2%f7&)>7qg@Kwqyxb6lx8HNq{rvQ z!vU`PPD2u^+Nwcl+Ls?5h9qY4-E)jeHpId6%djG;w_S4_tvewvNOYsnYVwHXF>>p( zxP@8K!m>aut047;zT*RJcwM65Zek8VvoqXktuQ23l1^yl09CZV`1i%=xjvY#uDncf zr5ot5fu{uScAQm!;Lv(zx&ZJz%4Cm&7xW#32mTlG8T zQ9pONXiu)Vi}yygV}s~| za(JuOAEWEKF(35TDCJjURUT0dCnvPxcBkmPKIa3rqd8TgN*?<5q_Ysi&UI)qcmXw3j`*pH129`J9dF z8s2-b&&FzNvI|S9KCrHdLXgZ*@>PA`Q8{HDxJSZLw|PWU^g*KPGKHB!9T2X9?S>RksF1KT$7Et{LSXF|*ikr$**F)2N%dl&N3}|6yQ*VAP z=Ub+&L2v}|rG?(^PHDj2SC5;5P1_V14ZWK7JqD-8XO0K!g6cj061UK=vA=J86#Qqd zM6&aRMJ!kzCck*(r5yPdPP)i4ipiDW!~W5}nh&QNKD-_>%$oLpW&wIFF9iF!w3mTi zoJJDJGGK6{kIO;aW50zl1sjlMS;BH|<+AOg)D#gNv76pZ>kLdI^Ga?Uac1;I*0^C| z{;JTPRg~9|UM}3}IKCp#Q(!yKvUpi#t>W)9iDqF=J9l~v=zOVNo(xqRD{LCKwPj+< z{DJn9i9`@(y>&25j{djI@RSS{-A_CpSrieu5J-AtJ6JdsMmwu>PZH*edKJ7Ut>z5)uJPCU17T4h5)exKINgB{3Q)UN%}Igv>}GVs4K-n&|k z3oh?WH-Rh)-JO4JcZQXT;-GXy$BP9qVx(Ln%(GMBE4>m-i}cYlH)X|%Nyw-Sqk*_o zVCz}<%vMORI_1byBH-OuR9%la3#9Kv6ufScoX=Iu%f5QIp|4U!tl;AY>#9ZS)$deH zYaC5yfya94SFb^uASuVAB!4MH)PH{rq_vLdJQwEw??4a}yXy0@8y~KDxb+YLKl-}H KIt|*6G5-f@_XUjr literal 0 HcmV?d00001 diff --git a/lib/DFRobot_BMM350/resources/images/cal_pic1.jpg b/lib/DFRobot_BMM350/resources/images/cal_pic1.jpg new file mode 100644 index 0000000000000000000000000000000000000000..c47206f5e777ebd49486f171031962450ce1f521 GIT binary patch literal 33222 zcmeFYS6EZuw>BCD1f};5(v>Pm5kXKC5D*cN8XzhnC5F&zAS%+EfPjLKAH9RrP(mVI zKtyUJl#o!QlK?_!;qc$*Jo}typPT*deer!4du7e5HP>8oWR5xJJKizI+3&M?0GqLa zkpbYsg$saZ=Rd&NG~hmf=HkVF-RBqW`Ax?_M@LIbcZHt*5(Co}CML!!jEu}I9Bj-i z>@19oY&>l2oLt=8+)S*zd^}uy99-O7{~F{1&G|dDbeHMqE^{$6GIRYeUuWL{>oV#@a}ahgA;7x(5;d7F~QAfZ>=!EG@@lDzrC=iTKiJiL7T0#ed4 z*RIQ|s;O(-(!72Dfxdy^LnC9$r&iWBws!W;FI`@_y19G!`uPV01_g&iypN2Ej){#+ zP5YRhk@@L!R(?TYQE^FWS$SQ3Lt_)NxuvzUtGlPS?|c8i=-BwgB=+|djzC;kTw4CK zvbsjz+1>lQe?U1r`j=c605t!%SpP2Be~^p)T&|0>v^2Ez|B~y%#lZ7M!%j;lrhJLx zo;m$<-pqRh?! z_eCns05JPA06A{8wCI^8f^uKx43L*>bp}8yz$rbV|Nmb3T`fP(0G<50r%WL=r)2OM zp!eDt;Jpg`i0?1xn20?CB-ohh^DurHJ`qbh1N`bMKLg--FefjP|HIgRN$yJIVF`08^{qp3qBthV%7P|bTWn$1KF%aNWzEi zgsK18QfR+&goqB84k}j?1Uhy3!pp%SRTET1nE~ij_PXliN8p2`%47Z32hL*ZDsOxY zZI=AdaFQytDy#0}g$S{t+3B zvfleu>$JMh4mXf*0a*sJl|GNzKeyn>Hk%PLT@b;(8$r{ZPu$Roq?WPYzky(p@N9p& zy?jA%UZ|up-@IL*d^IUTq*D)VbCdtNfy!3e@o2zqKo2ivh&f} zZv#9X+Trt#HBTGCen{z6MNb3?a-hC}0Hv&}+WbW8knzc{;jf3IsXSw&gH(3L8s@dY zv~Re|6xAY^ChO1nJR6LCZ48m5PD7~z3FdF%Lx_gtL_hd@QQBg1O;qkd7gfF``fhxW zhW+u(TB_ssx=+QqQ+a)v61`7#ar{l`udMo?lu^l!{&j~f#=2kpw&60aN&%0R^4rb; z-=1P*YEG2*O}Te-i;nHq)N!IQC%&%pE*Od_;nV`6e$air!ud(MSXzH`+q=Q<*QHQC zTXcz?Ew;1ogaC6X< zkr3DjX>39t=yS|z1>0YfWO4DgL|<)wHt zKl0^1Tsm}?dlwx|9t4svHIhPhyXP)bzlkVkEr-e8(ds_n)MjJW+`8{LUC7=iA8CNU z_L-Y6%6f+GRmo;@a8b~oZ&@0#ClbX$o}&C~*PTmNZA2tQNon?d%IT15#k~xqnXHD} zH%Psv-n`I^S5@;g{gaNz9;Qm@2hFCo3Q2yzhW*)MX3u?ekg7N}MZ_ zLMAmHKNQ&s_}D`mI4bXb{Y5~2>4m3WfN$K(N70)V#CTnnHMCqbL3jE@s)&LH(GM$N zVt9`Y+$T4tC4T`Mn-dpY-7^2=s_=h$R=(}__#_r8#d`*L>oZMGb*d~Wxfv>rorRAo zAZ$iJx7HAi6WBLP5YqOGXEK6ZeGd`*~J40qF0BL2Ce z^X$iM&^X3D4E_z7D>kYfIv=k<-_4WDiy}WxXGyPaJk2fQE?*9X-`UJ_Th<#{4EAgT zc{#tkt||GYRgQWYxohND^=lMTTD5lqftt+PZBTddD>Vod>#+$X*_Le9)vnbO4nUI7 z*<_l>&F#Oos{HXt2Z^4G4#65vPIHwxRUiG}m;7+C`Ib!bby8s8HV+uXhH*U}Qt4NP zM;{GGs+qpnAG9RvPb?C|ZyctY%4clsqGY>^53~lG9);cmr!J)>G&E7IEkgDwqRShV z{qcWnlGx)Zm|@p2yG(Y4V+& zin(}SsL%DfcBFRqOo0s4kpx~)iq%mJitcfyvaR3Y?ZmMlOIK(tv+dkHtG5(fmA8|A z10&gQhz1ui@u_S+qe+pTZLK(|0^^b04ZC-7_D8VoP+;qUQ-vw3V}1)FRz#_lB>JxL zj!$3LQDz*pD&2b8aP)T6bbfshfN!W zZ6Y3xfbLK<_7T_`m=Wm++v`NzM9N5BXjl1TK2ihuJB&1AkD_ZVD8^_tr=X zP(Ai8Xjdr~)1aG-^8M#Th%B8(h)=#u;q4K*Jt|QuZvS=2@(cHAZcxhYjanFgg9Q*7o3;r#6xk?u7fmTN~Hqt0(V7j_{E&f=GU zWO5kr4}5)auU^IF>&+@SnDGoC1QuoW+l~&uEO3&m{HsQ-c?s)(zo__&LUG*n7cEn? z8w|nxHw7?1%at4Bs~W~zoDRTSZ72EEZ9U7!+Jj)30~|hVWY3iQ58`6DLUN+WMS+c0 z6E}gJ#?!gS-8;b%4x1DK`&O(_v2!=ZVzKrq6y*)Wa^(cc=qL5_)k@Z(!y>KhyP4((gVM>Xqq zNN#?yQ0*s=vY&g0ihhV-&=@E%j2>7V#yT|8-TD=b?-$SelqhG8=z zDhUB865qTjmS=!Tq|mSZyG#VW(4ePuX(sf5RiTLBto z^8Au%jlruna94N|T7d-ba@6P&NXW!+Qf0ts4XhuSb<^?TwBD+_S1-}MSB`1SCSLtMk-%?H#I`R$t@@I`cft)tw_515SI(j*SiHO@Tx% zUJ-6oJK3eWr7$Rb*r*X()DmGip(Ou2<67R$a;ZXDhbaHM3`?V%y?Rdr;| zZO83j$O2?KbsfJ0ZEVy@$wx!UC7Z4lF!@mw9I~KGGi^(0>k<$MN*a4K>feN_pV+X! z$Ej+g1mP@m8LPIWjR|S&`t5`_|w?5jxjopt)y;b-i zi}CHE{^F0^*AL#So-UFygnC;J)-*#rVI-Gk_#|cgn2>0r$u;>23|E zCG8nHFUaAeZ-RzJ<8%oZj}7;;IO6xMbzQ_)fYG}G_dNrjbFpH-TpDiqEg4&h_tCA(fWO4R7Ftlnt)fUXE{tB8N$M z$BYAKkI7vmaq|p7|Lf>y9H|YC6YS0vn8el#tg*MF&qa6GtL%VIn~Pm$UGO6I8!=UvmeM)Bp1*489*Of8NozW&<<4`u2cpDDDQ zW_)=?GEwqczeFzA?YtMr%Dxv;e65=HFzAsE5G*RIrK zJ;yp)KnX6>_m*9^hsGA5+QuF|Qz<&li&AE+BlR=Y*QwJmaV*H_pH`^>XX!i9n&T+i zESt_6PLC(<`vSXQaZ^36X1L=skqVGZcCq`sY4^^qjjNWclhljL`4E;x^MyGDr-{0GlGRyrH zIlc73Mt=02px2dep0{)~$NhEVbQ}EOOuUZc4Wd`vs6xr0iOdJ6)PY^|EO18LoM=P0 zwe5?0v`KT81)44v0b7@>7Uwf@HclBnn3-yglACZ>!}V}r*j69f+(`pWI1QYqOHTB! z2(#%%>yQ!xQXJfMxYC9v8iPFFK9~2JHIXop_u=Gcybg)>W-3*75T{OP;D+O1&q>pE zUrGBZ#AzraXlsnQ3Jc(%0a!X@8^WE+1&w0r`R01VgIGC zwt*14SVM(dS~It-Z<&K0*oXg`lO#b1D08&2Z)SMA~B6}d)|7oywH9jsLbYyXA7MPC?Az?QK z7lt`tDkMxiCjnB`Mky0(9i4}>J%m(l3h?Bbb=Q?^z-TI4sWOozd#o4W;8)unZpM)O zugLYHxXFXvff%0G+Vl%%boLbMW1A64tl#Gi|C&v9N$-cTs=PGcx~|*)#3|N{Y|4_gpSoz~s4J*OQ62WmN86EP;zS83T^3bV2KS@wB(!+YU{}i8 zfeEoj&_l(2ziC9DJ!{#p8C-L%p#{sBr@W;q8;aWsGdtGmx($Da1H~QK{~eBY zAyxI3*4pESAOgeQ-cs8i&8FV7q*hc);X|$^a0G1M@-gZPsG;cCKqdE}C5{ONif(0r zNMd!()HE;vTeb(`-ihwUCuhxJ2z|e*A)eaI3m9g~ahJVk?ek)fWNj7PEa;nas^FUx z)vsoZDj&#s-&6R5`j61{_C13?@$X&E07$OAOr`VViC^io;aYy&B`$M)!2fFVJ_GQg z1#Dq2DBv23mPK>c&uJ^Iho`@v7`hB=# z)eaXv15{y6M3uqtdYSml9)W}S22-1d@!bJbZIK(lHn$eDH?VBNDuVnF&m2oX{Rx+@ zf6}1ey{6=V)))qzt8?p4y5z|+)(9zbbWElE9vIF%%fHKwkC7G{N*9XymoI}Rsc_l2{KAiiBk z@OM<6HG8L`%AryqW!-U9427+Plw|+R;DjiANpbjIRG6gcmzanO%!GFZI?4V*O8|!oDEA3NB{8~nf5uLv2%n|KRrOJIX+yjk$|#<- zIq%DyeL@el8~PQ8QZPl~14otnB5D~*G$)D_ux}Z~_@HY)K!mwA>E4}*PByFtZ*lMC zf<&)4G5zQ7e)N35i?JFp>bcdt7kFZYAQZPMD1hZIH%cj%<0DMN<^EKiFT-W54sB4h z)j6b>{_2qtpfF!y5+A0wd|mVhUOHnxZhzqwUuA;epQ&$ui73}DcZ%ASJ8 zeTqAwLYE;Z-gMGG2V|5>sDV9(m|V^Bg0S@|_DjK3(>w!v_nsIX`@~HQwN_WmHc;JX z!-lulL&do)-W4|))udU&qi4s;mhl(Sf*x=tKPb1oM;gw-sGL$_jlHVw`GbeCq9jWV zGSKW*Nps-?t6m5;R&q4?PGbEN>zr9VSEzY?BR zZ!rH}Mt{lA*IADTx#%lBY;HUQ6pHoxN+Yb#_2fK=RCIG09*?LSj?s}kc}T{_%Ksf? zzPfhX^PQj3ZzH*mQg>wP?DgCmTzsGElm?E!+Ri_FWyXENNQorF&9Nu<7L+Iks-||@ zf@Kuv`=bq^tJ{#t&~bCMnFAGI=bCPy0K=p-t}SUjy3Q#Q)Q(Pd`yM|GZ`3&$esKIxc!g7RxM z!O$gf^C+p~>p_^#BWTApX@uT*UnEScl;Z021~d$CgKGb?i^EL){{CI!wM6B!R2~1C z%F-(7)54a%+o52ZX+RXFq zdc7;)jGI4?l4|MR$L)I=xshTv`={7bCWC#KK9tj(w8P);<+$$qlSE@(Q4wa7o_}kE z9p-S;_W~vFc9nT}h&%Rjz$Wb8$|2q566axEGb_b~hhJLTPqv8op&hBC%RP3A)4{+j zywrJ|j*zT)S`^N`2I5DvdxZ0jddfSuWf4bLfF5ns9@tk0!<+UqTy*a(V)m7vJY)*; zjP9D=x2L=<59;a;$#U0aJz*zIIrHis^CU5)pAm~nUO&B>cDVgCBBmzT^ZLYojnS~V@ySH{=xS+1ld_gCm*_8gOC zPm9nz>$Q_o5rv7K ziAw5A^$!MOaq?YCfJK+^L-~oVJ?o#QgE`v))W1@PMpWSxgzVDd>Pz$=9?V`k<-j!~ zd{~rG4f;Nphb)p^>0mcATuMP$Pv(Pp1FfRgR+kciK4mQ2Z=PKM?8#Jl+lbabZmfU- zDD@=jwsmbCh8*5l*j~HA+D2IMrueka*qsJLXBD<5 zV%ON%MtQ}w+LGU9?V)8(5shMjB@8;E_A?#j*HcZ$RI|LAKoW~x%nLH!W|{c7gWIxW zb?*LW08QPWkA^dMz}x1@OI*Rcn>3`Z?r@zpihpGg=vXn#tkX#{8K{1{eLUmqtbxLx z$h4nH*Nru{BUop@-s%$uza`sj^b>Oe_rocD^KQ^RzljqUqRHlqPIu|d4f1`p9~Suo zoeCZA@@Qqh{?xn!UTu|i-g26SQg-lXfQPY=*`9qQVF-G99U&PsyszDI9tYp;%j!*; zhewI1neh%}_Lm2(eK!fqbNpn@&twdd=6!M!E89KHA{Zop|7941_QfN3$1=$(VRBR6 zo`3ZDC!nGGWvIje^OD|MafjU|wJQaYd;l9){RjC)rlX;1(9~9t4_pUX$AG+C9`9c> zZ1xks1g>91Fj0HaSI4xiNHXSalY4*1U=oCBVWpni{`D=6#>*XnzqKFqYREp`(E+)4 z7Sl^I+Oux7Ex_rT5{Zty7Qd>sLH|(toUjUh$8E8r=b*uCd|Af@RWGkk_-J4i5wrAU zHL;S#aN?si>gSfp@EJflHSHK@GN#96VHAL*8h^2w#}7LWr^8&26)9tVXm(0`#hOMd z9j059XI((2Fe?nTE3EPpZtKnexvD)`#q8iM&z&iY9jBZ)hh_E}e>4lkQx)TrJh) z_tLS=_$}kh4EmHe!F?6xrfx*6$@Fp|g8Gq43g2=6izEy}Po;$DyTi1IvfwO{+IdG4 zqn4%yyZmvKQgv-p(>QnMMmkg?%I;aJN(sPVg%Bh5m@f$5tu&=!MLD8sPQtwWK#c3H z)VJV&fVL~XIwfF%X{WF{%`K@6KBnU$+wq>I(x=uJe)sQ$8R{F#9@jwS&H!EQ`>VeK zPjvzUL2*v)W*H~E$2ZoRa5>Z>-8bP}C$~Ps?gSR~(7)YVSqwcMjM-P+nZ5H-WxD$f z+t)r6@>9=jQ>j+Leh67Loc}aOUIH^}u}$deJo=Kb)8O-QOsYZp!dKqYg|e>T;3vWK zaYrI?ZPes5zy(N6ui1{hq-g{4Vg}U>{R|9@8=;L%W>hCr=beXMm2(R=anVsrlu!c1 zV8FY2+DvOLBq!(Nph8tWPF4IC-zTC?x@(#k%eWvFRJM|@vspDdyqq(3cqer%OzpYU zQ0QSz+AQp-eIKh2Riy}%#w;nW;03ovqfHqIv?nB^?KMRBlO!+4CH=5-*h7EyWeBGo zo?VAOC|5Mj9@LGwU{*9pWbo@9QM<$IkP8gGV=*|i>wJ3RJ@Ctf^D{qi;KPlSk8eM8 zVXqY-70?4lAyR{fZUgwNGk|*&)$5xe<9|0*@Q+4O z*GoW-4l4n*_iyFi^A>xU>)Il>WF+1hb?Z}k^q*Vy@QtB`DYVpYaEhBQt2P}0sLOcn z7a>WQ$Svuhe=;@<&OgE;KW~ZF?~=)AyLjo6-lEdv-qYsdmJqv|_H)R5i5ikU7f#mZHXjPP zR6qg~mAbci?J3E9mO)_S=3gkS(v>6AjJLtwzT8W*8(<-`NPb zqhE=WEf4>zrij8H-b{lZS)Ku+jmk=ni@$^bNk&SiQsH+5F@tEu)6B+G5MlV+ka(Cz zr;|DqFeO!8Mu2jf%B~7zpS}kkcAC`>?sm`DLEpY*nGx%#c7jf65MR|2%;KM{1)|xa zt;l9Eer9Z|)>$y@W%t+eSu@$1qTdJdt6B}}%9WvL=SLf&F6P$DGfS2gfrqmuyK!@; zO~2B)3i$kt@p5X18s`p0%Fds7-B;&^2HAa1wEKl5#pY9T*X@77%<{g~4+XjlZ$_4+ zOSKOMdn-p7xO0XuPuuGJNQ@HwuUV4`)u&bJXMiYFFo*-GyDrI#-oLS~`mVRGkL{a5;5^eOKn5M7 z-ScoChY9K7A@yJ$k*KXy1yd%&-W+@%$5B03h(o2c;2<25TUcB6X-AuCQh~v3qC# z&=G^(xu?(dT0^Y# z6n&l~ZBB)J)oPU++}6=`YdQm5@yysE!nETqsiQ-5gU5%PxWz0<$KAoEWJ zT8J`BXse0T;Uo{o{xy~B2ynVu+tik*1~I->V3;8$^HD18SpdzQw_--$s&YljO`A6k zK{YRe(~vp1!}HjD)*Y6(oijj;Zi8V2Rn!AbTi-gd*Pqsdd?5!cDD4t5@_Z4tDF?)ZD^*Wbtsm|~%d7L)8$S9aSi{0DV6=X*(-E}Jb z`nPP~O6|ZY3xfSRStT{T_ST>+LVHtW9U=0V%kkXky7blvLI93T``oPng%X<;pMjqo@*EUXG|2<<=U{hB9cG zSRVE`eElmv+IXrq9ae3e>hZ@?-y5gft+WY^%ata%?!(hh<4bJUL?OHNf5M8Yd0!1- z6!GAREYe687SU=0i1!7O&h5n)DTF_aqle#aaq;*k=V_z?Q&_CMJd*#Y1CSAKae(VXyPHz>My6 zLweor(q@&y)+6zi&KFO_Tr8GNDUV7I>r;LQ1rnnpV4z9|_uH)TehN@4WWu0YQcl@@ zZ*4aQy3g$K7c$IKwUX^E^Q@W63?V1&daJ^BxR*q3pBBIr2vD{a0haW#6{;jw>Eu4- zpE>u8kOq+Z*vX`e`^(tC8@~rGSn#GL#BFR*r6_t`Jzf;2^&WdEWNa}`Vx(yNIk0a= zrR})_YSHJ0CRgZ{CX1zz%^l=ngu9k5Xl(Dcu^cOv6Ty52IOiVS;hp!2;I3gc8=|j| zUx%CFV8e3#_%;#O&pWSw26`uu&uNS8E_){X%2q^-U)Ak9QZK^vx3*uz*vTW-e)N0_ zetv%R1l*ifLrAv4L1Unxqu;anbueY(ENd^$Vl7vA((g3%QNT;!tje0!CleMvdOZU} z@2tt9Yt3y&cCo7aSFYt3KL2mohySj9`TxBC1Z1c^X~RBktgz*zZd)YREWzI8jAmhx z4Uv7>l9udU;_6FK`prA9u_;BWA^u7F3rf(DY8{7Z2GZ!$+Jp>GPadrd6nW-54lP~N z_l{!d3rR$IZ{wS4PO^0qbeiBtc66a(K5)*L$Ocj+5{uSE5SAjp#H;;8GG&;Tm&kG$ zqM~fmO;mQ@_;6iXjF^tfwkn+hrT5MS1g_*ByP+SbRU&phVC_1YWy!JVI}~>*)Iyh& zQ1keSS8D48#-iCK$UhDNz|S==k2)Lh5%$aR^9s;;Y%B`m4=JDofTDPAho@9|)X4`} zA55`ohl5X2OeDpWGc48;E_uft9HK?R0Y|=T94D{IFl+X1*U%E=ulFW=g7F!*11>In z+3V3TBJtGLtOjIdd?sUhT9a}DIffy@?w2CvZyI#TuB?}^4cwz;^SW1K^@5|s6>KMc zx_RirLlwrs-*Omxo^Df`2e(?G)VX7-*RMI&D^oBYMoAN}f2cf5`UD)nQBY%Au6r+9bu!_IQR_UerO($I> zeLl>_F==TJpX4Mr&VeJE7~v)rE}3(UG);-WX!XXeeS25(AxO=H1ARx~6?$^m^e_dhSM14HMhL*Mcga8>^P;Hcl2JMrSe zk7RK`n^&-euEt3K`6Y*&s7R%vwrMd%WzD4R`yweaC#Gfc?@p7qyoSo1!SCTi4Ny_n z$cy4UyIfIfd+M3q#o%x`MCVc9rb0Q0l0~1Y*#HJ2Sd4-N`w+_Z++P*1%x}?pM`W$* z60C!=sqwsta1!hNGr$t$*0HwG-^A+H-Pbs9kUh@5_z3^tR)2+mJtzcoxQ8TqfiBc= zKB4pzM6FsTwi-&qHG`@hEhex1X|8?f$EmIS-PT|$;_*y*kI+Q}mfpVm zHt_#AJ0GHuhn2tNXzSE&*s;Vd!xW#RaCVbD%#YmH{Pv=k-TBw*RlNu#Eh2gVcH2wCyv7#zP1&*H-2*Ybm_Zjzy>bK z>yk3)!I}=^_+Dt04(<%FP!d<^>Cd0o{!v5OO}YI?p2?>L`p0zB9`(&fIR?{Px~TjnWAOmA&>`}wtZotDl3SL(a*d$uU>8Q@Kb=ovunJmK{` ze+GIa@1%B)wC}K<0n!`ht{ba=O!GXTwC(#VN(@HP<+f{|+|hu6;4Yx(KNl2gEmvat&GFz z8DQ>|w#J*@xZe0x!+3D1Qp-H)<+bc0(3hJ`$Gp+v4dkfCQnw@4P2tM*5cC&YCtLTi zpa3HAcg1U{it5;)wBVA~n+{@QjW%!DDy|w)?0DiwwrVOWJw&{y&r+b1Zr#E9<=P8t zDK!Rb-TSsUnOb8Z)UZ^T>L{6$Q8m?9p5VAKy0rFLyTTKT#?8K_dOn^Dw_ghXDWZYs z4T(;EltKYnMNM1A$i$<>UO%gwocc%4#AR_-{;urJ%ML!}3^@HzNAE1PQi`vjZY)|1 zziw1IbI;XnPV#oxSG(U|ZS&OkNuI%%X~3S6r8s)cRsSkqQ_@_vVnM|kPpcDx-CSyR zW02{g-MebX7#jI+EWwg2e~H+~RSyWl!l{ja-KC1-YaTRA2^gB5;OC}7;;MLx+|^Ed z5(1y}he8ER)at%7r4(c^{Al^kWKJ@3OiYTZ#7dZY+M4Tgy*ZDT0{(Y5S;qC+=Puqp zBmJ^nf)6dEW;Wk`xwaKF|8(zZzj{`Dy+BXFy#c+q=_%-)>t`LbeN?SOz z+{sNuXw*+@$O5E8T`;YUn=|QGd37Yt zC|6P}ADUhob{g|nVp5y!iTej6PLOU-z5KMUVwcA%>S^^uU4Lx@kt%*mlxE@K^vAM> za$^;X^p@OAcLiazWKG`CEu`ea=&IYkPXw~+W5EtkNT-n~$_+Cin{`Y>e7g@Ov;IU; zB|UWbS}HG!fqEK`HK5(P$xVtL<%4E z*A=VaUjeb~N^=?x6(6V{(lUdKKO8+A zcIWaS2vpwFb5Y4FWeekmoF;sVkp;G0fcFr|tU(H%Oy5go_(jzS5?SvRh>oeMY%mo$8n#D8O->&DWSlN; zY}4ES)x&=!W~=6_%9i$*i?=J_7YDM;rnbU4VHV^5nkaoRG5*wZ-I7E=jVmcE+Qbiu zpBU7>iFtP`g-e#8mufWEUYBik&QZe*OHbG+Z%g}$jsn8;=3~`Rl=fsYSn$zZ#?yR3 zg+I-bwS2vR?Zn%^Z{JL4xsJBZo=ja%^~EB$c2@X+lqhV{=H;N7f zrp%&`swS$_3)h`!&T$Ns!9CD?){X+SnLypxH+}*6C7CKkoSBhyb$^=ce&Kgp*Cw|~ zukIBkZD;od1qBohIn$Wb7w_rPK7qPZ;xWf(V(0l%-zMF0TflEn{JXgedj|bAtIv-$ z!{il38p&1#R*smEC*G6hP=o0|?pnD1HpNf}-p)*gDwm>tn~`A03a44WmE-OAw^6xQ zPYX_<<;L+`$hj+|p~3vH3B{ubwwu#ge@zhaA`JE9IEwK?uajs*kLN&qo>BQ-WY6dO zrEEO-)WREli$Z%f5+qf7#2eUs?EDwNv%B25jbYrfbl9`Ok19v zE?DJ45I+xukHB}HVqDJv$3jwPfHBCd-x;8RHBk*g>*mDKJOb6}Q9FoN4O1bY3e&<+ z2S!3=(e#2JQ&Qe(v4Nu~Wg-~zVDtQ^Go@y*W%+DG+bNHZ}MJSy5A@MOg5Dt$vH=fAmZcY!_QNY1-=MW z4{p;t&i3UE?z<&VajRy7Bl)h!D$6I~Z+SMa04l4TJABsR%rM9KSSmZr%v7%X2z4~E zII`v>#M!5cHSrnb*I3e{e*%#0gZczl4hx?sw~=S@iGi@&l#YCNr<;j3P9u9cz%J!! zr|-4FChC9MgPkE2eBzqiqJvM?25dFTxZjkImX=lAIY)1#68)lriAI5Vr+tWwUz&%* z&+}Z*qjNJt>D$`ThsT42(PA*Q32olz&Na3kyrNvH6{foPZzHCjIWk&x%SrV=DIe2Y zRZerq$2vddv(rlko))S>z=VU1l7+UmFza;-?D^s{|3u(^#&YeLEWLLB9&2UQqO?;A z*aO&nUV}4Lq4cyLsNo|-IT}YQ-K^(?%#a=;LO*j{>3_s~SezOwf0Xa}xv(tG{-&Hh zA4sX_=Ac{+0@+dSkXgGYEo^giw!-X>yN1*@9%T#tur$|~`uOETfu>qtj4fzC*gR34 zAU8Z$+>()~6rX=!Ke|0P(as}0@MYmT{z2PTRp9O_4m-Lj5)5HNT!Pt=>`<-+K^Dw( zSKG!K-2HBOD!7uSPa~JymOlQl*q4dB&OOt^`m;>>Tln@z3Yd5hr6Wn5#515JoPz$` z&w#x6V^cfU;Py9&(fxLCt4CDgVH%Vc zBAj9PI5P1T}l(pgeA)z!rM3;RBMpB>UOcKC?j}9P(j}u3)vsvF&tC7 z=ES2BHE_+Jm6hS;@gu$K+TZ*+9&^2f$PGK})fn7rRsAC)!*Bd_O~3!?JExtpm-*AP z1KLAs<MM*RBODt^DyE@)WqxPP?WtF@Qg|cGGykVrsN_@#KXzIjB;x2jYj@_8-I}L z;*nx0X7Y(kmjq`xyb1$!`6MQER4G1Ph7(i{*yAzr+VQHtwu*jXz`Mw1BZ6e_xyR_v zapQ4N$GneR`nZnJEcnPQmO!TO(v8;Mvta=G4;vi4g-hFWSnxSVx?S~St*@WXeuxhBeRn4WW zfJn6>WP$`QX|**h0GU5`1^f4$4@2F*`=2Uq{LdCa{+Ii`JNl_$FhCrA_ULBs$Sr!> z3MP?IFOQcv(;g2s@Oo{35buKF8?=l^Ytv_f5}zAda$GfYDhyKW)Ti~$H{q*A(07SD zDhxlt>8DjNXbtSvY3>P-sKn$UV}yM@IsjmL)%mgb;cUCbk`wNu6>+hH}oD+9PEkxJT{HDKUpr-RYS zxg$?k8L45!vt!51;>xczqcB!{c{6ys4d!2gtid$vYc(k9Et@owYUB#l$U(3C` zhjcfNi4BzPg;RaVGaZ_&$phdoqR|uWtclGp0rgvSb?TKCUta*u0LI#1gzl3D37N^^ zOfxVQ@(t2^s&wi!;WYWZT05(0d%ejzW6b4r7lSNYLb}Gy-fzYXhkW$>eUm?vtZs8W z@$yOgW4sE?QVAbwTjgu0DQ|-zANOgu5J!^+*0FPu*;|Le!?NH4U@xdqVLvaF6a}YU zv2WbZCW6?8iama5tJgXL`K!!_Uug&asgEC%~bc@%J>LJXb|;A}JCJHLSoO(H@JSz++3` zIYAH^wr~f0Zxs4WWvV9-qHV%qq@7|YVIaV^c!PFpx*6~YXVx(+5+v7iSg7 zE}#r{W1;_a1;5VJ$nq>v*=T-e=*^a*CvoVb{j%(t@fRA)&Lx!u_g?c6lTEo68R-I< zu$n;;mw_*i+Y=n=`f^nb$C%)ns*gaY_}W#0IYxA~Mn{`| z@$suh8vX~U9K#o6rg94T|vm4e)_Y9RfIK#MsH5geWGlcA9ckfQUP6S$N5 zz`>B@Th?$W_D9y`Re{5q%=UWgsBE=C2`6`VJ9eQd=%3@K25PT+cTALZ zocJA(9F(#BPovtR-o%pV&N(SEOCmv!6NFWbsWPqpa!i|)Ak~~?_sF|W>rlD>&9|_P z(w~#smSjZFoJbvM>+^g+jPbkxCrLz3<50s~?yuf?Zqa%%JsHoKfMPHO2)0hq74*9xOki?*Os+ zi*mqVUVKmngjF?S72jcyd?Tqm=^h_ zHC8Q0a&m;iAhWnzAc$UfU6P>}iS?bIb%OI%H{@!O>CjpH zwv>QdstYf^U86Hm%WLkC@a~@KpMTpE#2+cIJLz!kr>v|p)(;nl>CCN~J5>s;9s9WW zrLb|#>^MN<1iGv3ygxu`UqHOCB2gDQID20E#v8!CN zK89+b{o>O+f6SF2n~u~IZA_G=|L4j^lSHFDqb7GBNBfRQ8@l_(SnoFvZ&{@Y%_nUy zXmqvP^x`?GY#uzV9{813#R|B3^{}Kz?LEaDZN~IhbY0qU%}>lUwO?X~TMakb$pXXk zeX)CC#+?c#-8@G>lMCFG`+OOGzAaw6EU)6}+L>YVc_3AA$vlA!vP`e6eoFG~zU9R1 zD+3LFT$q1|`Ief2aaqsHl|albqHE#dn8cczaLW}|f$%W_!-y^Irz8rn8!a}1x~2y{ zT2A3EYaBy7OBs2OWFNeqq;3e8*1W;T+MX_;BThLeSv^`EL1_^XY?Nb*c++H?w&<=D zAaNA;=#XjKS6kNJvD#Wyeo=zspJ#|1>aCM2wFOHrw*?(MWN6)jZ(n;92%jBfSGEpv*=lO0~|5tPG8PsGSy?;ir z10uZ_1w=YXQwX3^Bhq_~igY1#A_Sr+9i#~e2t4!-QbSGXNS7|51OkHe1StVR-23<6 zce^t?yDxTjXOeeexchy+*SW6G(Jc2W8Yt?$6D~Ti9xcPASL%6RP(Pik`1g%g6ZvK9 zijYZh*em=t8<`HT%iDXVACc1|Z>8D5osqfy(h@u+y~s4rdG#TGn>VQY7UXghT{P}S z$Xyap6SYK;`K6u)cZL^E~-E$rul~ zf4!&tGC2h(eJ!Mb5>ha%FpHVx*zJ?^&#Hh`XCY6cYl<7uVc~=L{89W8>LeK@CR|@% zioPmYe-D%njwD9uO>C__ZrVRbL{wM z6h{d9#qV@2trUK+O?jn}vf31XTXS6GK+$dapxDmH16SfmG+VozOB}m@32FX$lh#9wsL`Z_C(&9XVcvnS`GhOv=tx3PsO|rg!J4 z=#D-#EWmOsMT3b<(ADviXq0BOut1B*;kXoId|oua=c?kjLW$o%85vT4C>6GIJz z*TnzRpvwPyzc+w#hSfI7$8g$4&JQqbyh0#aYvvz~yvPxOeV=HpQT9@0t7y9^`9ac; zE)uJfQVDl@{tu*=Bo5Wn`LpVG)pX*%=FrMuT)x-RlWnL#NC#T-q71A?^y&Bi2jV=u zcs}3t^U0FVRtCbqBn|BvX02%ol^4%;e4eVGqUZhYY-lx_qzDVk*x^x4uWS?a;&>Y5 znWw+7m-r0QB4sJxtce@@(5EAU8*gP7kPp+iOYL*t}h8T$>+|j@C5jH8V*6)xnJuKE#n60KpY{2mwa#ZTa|QtC*0p4Y<^hn zz(XKO!93N~$}S9f4o0Yx!b-l*<0(0K>cbc-pDd#x!|20)2Peh@Vs7k{Q0A^$?GWhK zj5AgD=(4HY$Ryo)2xJRrI4et5RoV@(J*Z@SzPDIemWtZlJ3E@@)d38Wl4K5`e+gNJ zlJDI1? zPUi=g%eUZ_uxlg*-C2qhDZ;X8++D8SO^v|v!7IOThgz}ITVq}j&f-IScZM1GgZ)&Q>%aJRmjwS!kM=hVij$EF-V9>t|Soalx zgW6XEr>xX{DxxokRG*Co;KlMU;)jTCB=hlh>6 z^V384qU8rVZ<}m9s$yNu2}4jVi*gHfhwz?X5BC+f?^QJ6k(!W=sjjouvKM(#zVYO9 zDU540v2TwV+#%Il6TO}v)i(|NTj#8`od(z`f_(fBBm>cuMrUee0=+%{8P%0E3N3P6 zfFMa>^oNpNn=L~a$Two}VVL)0o%=Vq?Sk(f6@G)i?%u&Or@t1lcHBMx%H`fCGv*5L zP~;ntv}CVUBn?TdeymnIKJ{G4dvn5J1aj)-k$Ao40U-@0ZXEmG2PI$Ah ze6kQ}b`?o7wel;9tL!AyQg(fJZ!@chukO;HdKW-C63RYy4E!osZz-MbZ7OYhu`4L* zIx~)L`O`2NR5iyHteZ%!>zu0I3?GaiS%t5Q)68Es_c%en=n$1S{I zLxk^%%db>ERrxQSjn0%Or9Zl7)$?y`NR2`OdF-@ew|o|r9UJ*bPr?S{FhqbsTcHx| zt;`o+RcLENL+DBD5Oyp=!6ESM@`j7(T-I>k zIkVmL=u@dY%3rwq`*dc;lbCQmX(%nJZUuP*zTc_Z5Fe@X!1@;^x=kU#%cTH{lVY{f zi2l`c2Ag9``YATiirOQtx3)CynY^p+rK8(CLv`{-ZI`(;&emFx#Ryyk>K`m>Fe$f! zrOb%I70X%v>oi(EHqyhyiFgH6_BfIeYxo6F*HC!aPA;osbve{Gm$&&ZY`z#)Qx6S8 zUOK`>Quqj_m`>b{qVhbKW5tx73Ha-dC&WcrywoS**B$fdWs^%Oo#53f!1M_v0ljDS z%urKhfua;aWx=Sn3# zp!x7knDetI(gDM`u!WYo$bdDpKiz}vQ&?P6H@$r4f+BP>sp9(gr9MA|fD;NbyoQOj zX_Bby{axis!xPHJ>e}m7rc9JJMI`GV=n&wo{8diw&7nbGCMor!ZxB-UJI8M7l)_uw zn%+8m>^i>2hFzkPIV~vRV`k%2^O>c}KoMD&fyQ}tI1gKLk0P+c*9Quof~A*itVpkW zd%x+e(DuClPsPZC=63+If!>YlynG~TJ%Vb_7!#QAAvN-0!lz z`SzM`t6u%aHe)-zL8Y$Hy7;c`N_$nT58O%b-H^1Sqx|>*WG^tsXQ^Gjz6W2UI~w+U zB1sR6a&p3MDBmx>F*?)IWT?Tso_UqY@X7ygzOUdz`m;yM0@kDeqY2-k#$-lF#iqCG zoi-(lhwogxE?r5&NWYf4f%Qpj)sWrUyB-eLUsjDIUoC+kSJG9ONZx1K!;(G)lbZR6TjLnV>8(-QQWwx&*J4WEw*fx{!?Opm?j~m7S5mueSM&-1_jYq({oP zMX}CR{jn7|nZPs21ECbF{zx|r71G)40;q zU#1Jpqf$Kqay9nLbdhJaJE+tUK~k{GJ284|h}ZQGRYqFT%1b5=;iXBX?Tyt>n^xK7 zwhm3&OwF2YEB|1AJT{)r7PKcA_Xave7ZH`Sa9!K_3@>a8XI_#5MC`OJUd6nSQ{LdO z(wE()3#Eupv>AKh-9&L=$07X93r;iQ6rLApNqgt>MI713qu0FORlDWo%xni(TRWiK z8*iJ8Nlb$|iE1{J9`zSmz1dV#ViNhz9^xKt^nPN-{4@_0h+zW;sYRsBV#+>dNW>c|WGQRtB(fkkMdjUk`+W z523Dm_9_Rzdn5*zv|oD&-jt&_PE5;OSG$Fz&zo)2*`vRogIQ){|4M-}8XP?a4$AgYyCd_;lm zzdUlaH7C;@K)uFD0V^kAZG5pAtl{;+%p5bKEVhbWqMq)nxZhp=4^A0}lU)xv=Rt2~ zJn9JcD<_d;nIgE489_3m6Ji6a1@*r@JTKBVp zAxWBWZZR32gItEv+Wore^v!C)h2=nFU7yl^{Dt2)r_U>OKVy`L>dcbtQN2}23iwYv z=OaSWmt|&a2=ZM!Uta9I%6&!sK@Gb}3oB@K*uMT7{U2Y0Bis<-0{p?HhPkjpUjF;M zwR(beR}7bzX09m{%~g;uh~{-+UbK7TUQg2VAAs3J4N&Oc|9}0JIr;~>vuVdPzUSu- zGp-vyEO($)KF;+_czQsJlqq8)N;ZearQ2Y}Pe=TI#{k#8t+SQ8F^E_O zxrH8@x`!p)5Wd^G@c7+bPRRK^1ms3xWNqY%CY+U?0SS^Z{ReWNl0ks#!=%?o@cMLG z97)&K6$`6CBh;3f%DO-xxG6(g6Op>`uL>~GXQK65Houq@uMCKC#AT3#gfYE6r zUahdA*VhAz=8NJ7n{A!X5@c za&Ny&u^y`s(I%5ey0vXN>G!yjNj99aCn{_$^P^Ad``FE>%hCe^=|*}YcDfe}sMGTy z-SfO}R>|=h(BR#J@oiN4aSh*PNC$IbF{%H_bhVhfnBR!}!PeQ(`SS_tpr*B;7@LxF zb=TWgVlA|*qJM9{W8T0p?;Y`Sh776P$E2OBby=n6t~{>3|A9Y#SKec$Nb5tY^DnBC z{I^9<#N#SMRbG+=m&X`f(F&yN#V%-->3VbIr~B){W}HgwFf*3y;lef*ht_9hg$W+; ztik&?#pZhpE(%J~IpkOzW$yI!4)*wY-ZsS(dLDoy1^?AR$k?A7ljaQoZ~-rktKxC7 zLzSE2dVA3pMU1cy*t4bt8Yetx9F}XsmwYXq?(+@5g8zK?>A|VjKC%uP-)4@-kzUke z==-Z&SvchL68|g-&XSe9@@!ojlllaB-ZFH89;%~q%b+MJ zDf7I)n00E$o)%4#TeuY>RRJU4Cp6=X$6>G!K0fr&-D;fNnn|nH!;+v+?T00{efV^VBLAcQkzK@}_AvT*<@^uv#)xF4>_PiWj7rl z$=1Ug$ua$Rpi+keXHD{-vvf*jvqz@7fW8Fpl)|Jg2Z)8bsK7NED!#a{|DLp)$GJ&9 zD+96x(SaI+ltf*ezAj2tQ>3W4{Fn20E&1Fa*ejZ3EsrFd!J2X%{!gE!EMn_qL`t?G zAaA$7Ir#Wpz;Lo09~z=cqP8Sv2kchD`#BQQn(5 z_~S5cTr~JDZ%p2dR+#wM@ofRmnMR^V&wou8+o8?8d?v zb;HG7!1A8?Re4mBHkHS1?~%M1_rgU<>-zfBfp_~wq3x(i%?t67pnsrc$sv!8%}VCe z({i#GX_H`%pY26PP$U588fnG?&4D8gX-$jQiw02@+N#&SjpM)cDUyx%sBqv$MEqB| za~#$OZv(yg5A=rC0jv|J)8De2k`}pfeie1*`;flf{}dkoc$>}mkBf#6cG1Rs)aVQH zIxDhk87Jy;XoP&w_mFIog5l)#bG0hWj(46lKk>A{mfvHqdSmfZM#_{kib^ouM*v9f}&?}e@J!j5h*Tb$NF1{t`$-doUiripmw^yM&t z-Bzk&C{p7pd_({B0@u1h+k|h{oy}C^c~|#hO@VA%4J@Ou0?l*$Vr7r(B?HKaV?ncn zP_g*_pD&!qQ$;gM>bL3)X{akM$Qy!OtHe>RQX2Bwu=?DjoIYe-7ksFb15AtGHScyQ z+vL#8Th{a_L@{VkH=5Y{TpbWme*Rf&Ooij37>2mHjA3^RoQ*@6SHLs13BK5!>`MS) zQM*1^Qy4FS_GNr}wat6Jj<$kHPis&;X0T!G#QU35TfnJpYd}N8Ztk6nHTwq_<<{#H z=DR_gOQZdBJ@0P{flRsS>?Xnb1y)-v^7$_1E&vH$M83l1I45Y<<9C96;`qh z@st?f{YP*H;j}s=Nv|bfClF&vLI&i|IUjKPr#{}<(~Z4#mqGH2nah30+n?m0j(sJw zk*3RCa_A`65RYnR$dDCfNy?pkJhzS+K!bcU>nHpV6f#4w?&rYT3P|rQ?eq8eG|HLT z_RBeD#w=}yFv5nMaeBwNXZC`Eeht+J?t-M&5GB`;Po~z3Mq|1`CatZZ(|biM$J?^e z;V#-@^bbQEyJ|W%ZUu|3<=jHNC1tIakAcX_ZS7NScgul`yzUA`qKQD9+}}SOQN9bW zdRdE(d26(A6K}pqowxHfuX?Ca^>YY_7#z_{H@7uuLCPuLngGNcC;wE`&&|N#`fd8} z&3-Z=EBQ$;sWfdFWFO$RKE^*xGWSGJxF9kCoid}Yt|dSXwwMfcfB?4yu!CuO@oL+Z zIwp1FyBu4TJ!($VH$ZkihU1#!t$Z)OH+3Q(77~=E%oLB)%Un6)!m{&S0)mTLG=ki& zY#m@*|MRsp;mUpE@RF1L3VkQ=q=Aj_?3pt5)K4KF7rNf zD_<1>qIvhWxMbIv?mrOOFq=B3M?ausizRPE=6h|6#V+2qtR`LrLaiOJqN$Qh5?qBc zk)HyqO`sqmB|nATCbjI1P-cs4t#zGCJ!1!QL<|JuxJo>$6s~%G%hpTQyQO;w$fgu% zBE73k<90R9=`1@!0})JcT8)Ty2OH+ilMRSDQDnJQ&d4L?Dez4^?AB9QvE9(Eo1EvI z2H^shEUGIwFVE5R!H*GKxNay`2QL`|R$hj3TW;}45t)HBV1th16qqF&)TYZY`J(CT zU3u*L8lyL%@|HAX-b9r-sV33zG}$laX+>2-2Z5E$4c{RLMYx<5%uy>kO=V_QZdaz8 zLwBaU!c{&)FWoi!%?WCL8<0ees;n1vKr{=59J%xv2xI;e;~#R$_=s~=`-#Q zjAgsKWxb)`PoRmS`}>B*@THTXXo!M!xHr2e%G!{tFrkMicMeT2=)2u4KWM9>mAt4&Q#j5w*SY1U}s&#pF%RkVX z6HB3gb_^hg-#0{_dmUymA6)PH2a4xWx+rMKiJ)-T&rWt+LsIMGm4i$O7Y*&by$j<@ z124bNQ#Y-De()l(t*74O*RKz0NzPW}H>6yAdG!?%JJ`lo*PA!eD(9nI4#S*FYVVPf zwGO+78U9gW+-kIwM*JhA&?h~@`bjaqcF0f7oPd&p8HTAZ0OVb}?Ho!{3-4=)FHr2I}TMqOV5y>h)+KI z{IsO|b?EQx;o1SAM0XYrsap~wWoq1=^E4`7iPu^kR)Vh^&G-q2HD(oCLjrtce6{n9 zMse@2ObwK1WwnbVyH+8CHl@rvZTA1U+6hd7m0YS^PCfginQGoA`F!CW)$I;&9dVp`kslBypa_c22`$K*vc4I=h&@{2<@Sc z=TM%T#=<=+#Kn_l_RpnH^;~8(wKT+u@>(*Qu@V|GvTsy!qc+fCtm^=B{Th@v#*)H~`%&3qM2U!%U4=gP z+{QwpzAa%GRkPVxJHV3e?gB35dW9EVmrT9YdhPVRgn&)Ch97YfulWIqhlSUW3jI{? zAiKJ12;o_)+DZtI)_SVlU-R+{!ew`ivPt+Q#WkVbb zr!cx&#dmL0SE^ZuJ9EGff8A@s=txQhm+3rmP_aRYvi#+OB@BbGIA8KVP&H-pghE3y zUcLSk&9}`XL3}dfo5g{h?9HYN5{GpsK~LRU)<@a+6rNn3Q0GT+eto<6VDskErbk7) z#{^Wg)pm1TzS3>C{IC%i;4**8>ugHhj(qWbx-hw*HoFq%+sTL>!{@j*^Ju)EhzitwUEt}ngJx_IcCT_5)5 zc=t_aMB_{Q1ZfAp+tFkFXfS~{l5$6_3Vx;=D9PxYfv&4Sx?(M{bG-ucQZFLoXj|G0 zH1{^dYzZNbh+6@W$I5^ln*!vjR8v}`YzL*b{(%N1|A9Q9O2;ZiWgHUiMewAarA>~w zqEbh}Bq}cl#Sz|g&aZ2_gW3yK6%~r11w0xE(`6WzzkhcX_bGt38t~7a@y0aBP99me z8+V&wp%J#l^{FeGUmQYdpU%jzQ48d0FUq8eX#^p6pa4Hs4|dK0*7yf1ju}LoRU_s8 z+F%Nj1qTEGTg1W?#^TqBmFV)KBtD|A-F!viQ(F*>_@wZ-j(CYI;@cX>(7VIXdvtRr zRg?PG@MNy3r~2Thd!e89#3$gztJOWQ@N7O(`tl910a&NZ+RcuA!k3qx6x#Po|Bavh z?;n#|Zxb}6BJ&k#qaiQZzBAJ!h`N3*lIBAW|3Jx-;ztrXsYWs93hu{{dR#F6cr(_)bas~zAYejL&$Z9}vY=7-fXZcTJ#)f6ep*bqF#M#Js ze06Aus9T88w4Cm9)epM(pn0ay!3PqHH2MO(;^?){5LLK;Lg#npP(;cW)+ru+AI|!e zB)7U4)HeaIo$U`S{G3xxdgIcVFlP~`q0=!#$Mo83O}o|+={|>z`mJpR~aF_qSZlMJtGkkRer~<%FL^WGd=J^wsC0ic9;e(vpW({TU*L zc>dE5sO?T##$u7EyQKJ)V13iJiO-qtv_&ai%&`HUnGX}A8smCzWJ6H5;b7W0)m3Pm z5Xt^r#C5D^1^IkwQ6H?n=`vc@(S`S+e^$c}{chY!7P@l&TfC$S;kU-B?) zt*6#Mdm)cRvN)1YHGqt+GI%f8(DbdJjywk7pwicR@R;&=F~?5Aty z15jFE%{qm6GU1yOg?>bod=IunRxP?jbX%dqUaD|Ur6g&6kZp(Xu?L4gEOJX{&k``c zIk=jC5$db7$lsv?2DtyOR=<#3Zi!bhpXZ)Ev>UAEJ9rhpoPB0~fwea9F`tsROU5qX<+SgjT4Rek*ZR&;y4PW!C4VBBDV zba`K>thCa)8ivy|Sr1so_=}(VXaYyjBc=q0r6BL zMNL<{?}#?B`Jgii{ag?7KIJ%O40f z0buSFhj92W2U~6kO~IX~*ROCiLs>({mV}4_ak9K0d1>nDm~G&^+LIL4O*{T6IbDgF z89Zh8H?*$TBgZw`Vm0o?+npt2X(f>8=*x)J_}+G_e)XCuN8&^04Bp5F7&Sbz7f08o zd@Z+R#K-kdBkKOBwuij+0H@OPS04rkcvxR2(5d6|6|QcaXzGa{TWwbR*=K+IR$7XY zZ12y&`4`VKnfF;?cIAT0<`H)ZOCO2+#xpx@PaR5J6^lP31eZ5Gj)d{`zEQ7rmEHH$ z8D$3Z%;55+nq8Wj~7$t=Qtw zs48{xDR&uST>7Qv8LwRS<7Vstn^M9fBXdu7(CVW~j?;i+kDq?kw3KO8-W|U&dR=^Z zN(13sqs+GRiUNcBtL6vyE$I1|+NwW7j1pH7{Y3B;_Rk5bv|yOEBG|20OtMZ}k-1F@ykQJZT#of_0y!zf_R0NO2o^CwT)*ccJFzl|$h zrN~@lRw4qt%B{B0VB(i0hUsb}z(vue9|RNs^xKjqx^g*DZMrL2jJ}@b>==zm@FVXbV9gXJX0S(%z*u4ck zx0#YM-O|TLNP_tqZfT(Qx4|FGvg&y7527~m4S<(-p>R#Um2G!|jvu*;+Ms6-$LQzu zK~rK*t?9p;)WxaQ37D@x?2{CXnno?vZsS&Ry4saiQqWa|EsoEv72D=OZpw7lFN!~C zXtVK?5yeW2qf9e0Ix+8FS*!#^s6OvY@U+9`!6Z3tA^c(^VEb<_31I21`1ePpNyV%I;Eg)P{0x_$YX2XaH@BV{by*F89i!f-X@M zP^I^h;Thq{RnBRSvj&qAOre6IHh1W#_C;?;aHeP<0VAL?4F6OD;~@MZ0)~H2FHr(; z`zj9cl$+;-O*9jHwNs&GEcz&@nqvqi(TZO*H`b~2*#D6t5N7r6o^ZqSt5idq-`18t zPp$^+l&|Q2rd%dehaJV4_i#uNdZ*j>Qp*1*47nrSWrb_F-#i$+{djaC^b%XOV_xR8 zbx}OfXqn$*7{|>5OIzGNxF28LLCd(x+c6X$mVIyfsJT8U)7skdNWEEe%JG0l!IH;3 zE~UURN=I7Hdr_wQ?nO4@FdpErD1$TTSII$=X-xykQ;%$r zw1II<%CL|YOoj`EHrLWp3vk8&lrvfM>N@Zzp$Nnyz{sz(5+6Zur3lyXuuc7*u7@&O zY)Q{=v#>G@zDej;RA;)ZCtX*Y(?)e2NKRfMlVDzi5Lm>-R<=+E=SVOZFhYc`8hm!Q zHb$EXK)hrVAEK^bxxy`T62o{n!Zhi!2+KdOgbf7$fGy$1i0zbfOnbHlK7KB!6D>m; z2qtn`1Z$ocVhBBGhL(w?H!Lz1gTrGfH`ifGkv|e>{Kw?h?3jQ}bwYp%RjB25b@)8~ zeifQ_3O`jZN^5QN89&jHA0gFC|6W9Wr^G^nZ3p_*C#R~Ukk_l2Tb$xf0g$0hI!n4L zn6xWj$UmNc9{D=(KW6T9 zgVs7mR18)3fT8$BB`xBUNK%f*_m;-!N!t_?fjV7EJoCgiD4|ZO!&Sf@PGup86aR^;JT~uvjqE~J=YjjBOZ)>bRYWG%@oBQR|F9NR$JjXtP z=#z6^=7l$B!mI&L88q2#U2v};HFX{kp9N2N)Ru8`t-6H9=9OJF17ZMx^5+fDP36Aa z-@__@pjH^gI4BYRfIrEJ-ceexd$7~;yZ5jzt%UFjfuCzD1@8@FhJhMbE?+%hgFi5 z{4P&A@jNQWD7`S=(dE~=1er1}QTx7g$DCebX zIQiUW{|+zCXcHVV+moi?KWQ5i9<}m@Ub(s9v!w9gsaHp|bknOLnILW^pidRTf?7kb zDU{XyCBuSF+Hp&xlKB0uEXh^LkDT2tmA{X(IF_t%oxw$5H!pWD*h5{WsCE9_?*CTC zzr?PYiK&8o4U5TIjm^^yL7Q#C?%a(v0ZJXUGe}vNZHX z>hs6<|29z0C7b;@+#wK;Mhd19=hN$Oky@XnT)#;cU!`M)a~ghph9d0#rhJquPA{|S z_`s(?tz2JoI{v=XF^;~&pR;k7YJ$wWY|GkVM>E+b`rllZlG@~MSYaFe^YcVdAEGND z^|3&+Qj|b)at1E1N_X&N8v|%;<|nmAzZ+VR9sld(J}sb(94Ejdy0M>ISL0dX6aC$F z5T62P%Dv`>Z0v+%9Nv;c9R=Cr=1)>LYf3f#n*@PnlsY48(;|F@4})Zhyip!x_Pi~( z^39N2%}pqGiNO`NHtQSjZDhS3FC~IUI1-v{?tR$(VvvXQ#e!{f;X!@+>)T5_6CRaG6UR{D*Dea}tz-0l>bLKuFgGrjUj1av+PIp8lYpEc`GfmH(>ZfX@OXXs5og(=x~HB(G;@O2%+wtT)AEHmh8$}41& z+{Nn6Os_wlQstwFuJdC*qC&JP5K^_10F-FS5B0X@&n6Csl=ZvQQeRa+i;1uA8y{in zy~Rjx`Ha76wdU0I>~(Z$(7}3YD@6f=3qT&+m9S{4Y9xyTOj7Op|l1 zum-nwKaZkjOUJ4Gs+Sp}F){rP_cf8q3%kEAVL`WY-DVyX2eeWeFdOB2M+;(=9+@F5 zHU!*>&vJ)S)4PbJ()bZe#o#`(cPb~)x-DI;M zBy_eYlPOa_-NP$~F@%AH#ACV^?K?QyjOPDvq0hQ=h34db=v2&K{z!*hZ(}{@2aci zhzwC~EOaGfR;_NvW0zwI%g!fND-}J* zWBk2(U%)Zpi%s(y*SY?$x~}7xl_6%LQ%q*J9mi~1j}>qD$l~|f$vus3{RV9mqjqN2 zl-LBM!Dd&)Q|qU%acfJOY4zv{rt%0Atl{9q6R)3=fhx?ji%51+t%HX9BI#XPrWCMs zwifVW1EMcPV4TUV^@l*X$xHt0gVdtTpztd+HC!A^cP~=Gym;$)4qIE>ZF(pv)4YBb zz3A>+qhAP}f0EFtoLT0;{*3DH{*}}#%z|#eN=l#4pw!bA-GUd&mLiMGTPf8+7v!;h zryQ~(Nv@c5y+;ujCE-^I?OhU^;SXQhx0}tT@^r^vA4J88GzlRRNZ4Si&d_F zAOO5Mug|gMddGE1iI{@>bVRGE{CvAhX32V_cyMb|C}kbuF{^Xamv*gU<=XSIGDO1; zlc|tn#^yf|-Rbt0zGf?6;|{S3boQYr-eePw@n)acQr~I!r7Lk zwXICwJn8+FD&D~}uAz&m-mcF6ZTk-domtX~!|e1IxX!4E@!TguqY%(?c+AtxZli6h z`qU^Nr&l81;gvH>*arrw?!SlM4x0wB+yY^Vk{xu^q?V1Y_;R`3X-tG~`636Wnn;DY z{H)m~Oe*shTUMl$LD5Z>Ux#JF^%-vYfKmY1e|7d>+ie?JSCe>w*8&1y;+=DC-Yi3? zwog&`NUMOb_38E&XFT2f7OVejCDS+>M!?nJRsCL zE2^Iau(%_GO48c>T);!+=@M_)O%3b86-@Sgmy+~_D)O>$>lBY!q|#l>5NO!$iS5Nk z!X_~PDy%*y0(<>qE@pcE#W+G6YzPw_p-&EFY6oDh4Jw*FEpc(Tp%Tnetx zhsDG^t{*2K<{PU`ta(Q0FXH!SIraJHZ*f+d3c||j3b{Hi=WM^=% z?cz}RKaf1|!3`6OF47KljmCNbUk@WGxfhFz@)d5AQ)w^PaYdQ6AfnaOJQA#XFC&I+ zY9j086@cTrFpH*wBYPCbJ~Sw0jzEM6!C~t;FKcwzEbW^ct>4i!KhwEl@YE<@`6-uq z!MNIUNbe5NrvxNtqx1P2XiH)78C=AvWRg~_Gp@Eete$%8s=h%CUJq51GWGG}y`;@&XVIJ5KF)Wa?nH8_J>ND7{S?06$- zLO5M=Zh^(Hw-c2Ydo!U+TY~$xR{9UO)^*aanVPuMiC$&<0eX`>(Az{}{?7&;kJqf9 z4NPbu?q$LXx10sz-$<*`B$U2?J6L0Bk<=UhWZ73GPQwvj$Yb8v7p*6m4htghBgc$~ zukReK`8ZMCsNeApJu+5>br<5FNjF31T0frmrPF16AdIQ^gosJywtiXy5IZRsrAdvlIMTZ)@VFh>Y;d9CF!x)oiqT z(}glBv2Kw*bZ^9Snfb*YR(hN)PEsu<3uN|`7r34k&SX|@B?BVzTw33?@WFR$F82>C zUt8X4MQbOn^?_{jAMZPt+U?<{cPTo1w&54Mz&MzHpplFH=H;}1pqh<{>V1S`ai5Cx z$0x+>qO+VxgaYkR%daiKyxgOoxS_@=@(Fg|Vs19V5oDiB)Zf`Ca;4mFpKW`L&!HzP zPRVhrD9aeDFeS}A+Fy=!j~IsRuHO`JwPdge)n-}+P=qrjg$@opF$WEm>y?FH_vXEU zO*Ic7ZTSE)V(`j7HHl%YGs7e03J+UD4aeI+ABWX*m60$`FTq-wq@Ls?h(HDqTDV0S zNzG;q@7Dd;kCtm8RHf6*oH>O%P4QVPJ<4KdP$qVuSZ{Jjo9LuF8ion5nDYN}&eO>z zV{u4TX#0G_VyI;5Lc2T#qjI6o5^-$t(>GYDlX?Zi2v6<`-1t;)K~{DGq#|G(U-RVn zZXZ47P?gi#( zIO&apm2SsZ!9M~Cl!$fdD_7{IKDk8+8Q9Y(bi2imMSY2 zoM;E_18)iR#Yxaf@Z2ip@1foaYK|5tS2>;LBdH%$x~Z~y=R literal 0 HcmV?d00001 diff --git a/lib/DFRobot_BMM350/resources/images/cal_pic2.jpg b/lib/DFRobot_BMM350/resources/images/cal_pic2.jpg new file mode 100644 index 0000000000000000000000000000000000000000..0c427f041a44b94357a3fb7ed2ff012ceac2b912 GIT binary patch literal 11813 zcmch72UJtrw)Un=2c-xI5vkIpgFqCdiHIoDi&CVCsI*X{C|y8MKtVbPNH3v7lp@l5 zuL&JQ5^8{ym-GMkoWptN-tq3c;~#&>8e>ng*V^k_YpyxJIp-!!5EcNYn_9YB00{{R z@PPOS5T*eQfQ*#%w=eNSPW)1wp`aiqr=X#tqC7)KLq|tTLrY7~aF&Ulfti7pmWhpt z`5X%?D=Qr%`*}8&^JiIDS$-RYgpAmSoPwHyf|`Y%mY(H*{ULk>n9l&)z#JLLC4iKf zgp8Sl&<212fP{iL+utVqj}HkcagLN!XQ*jti8sKQ08$b%GE#D~-)2p`JCOK0K+a5Y zmiNka%5#PfsV+TZk$xGMd4^BD{2S}tK@`7??ek!28aDRx9Gn7zLc*6tWaZ=)6qS@U zZfI(0>*(IRXLR4##MI2(&fejXqm#3Xho_gf55(8+)$5SZu<(e;_;>FU5|ciBOwP*A z$^D#{U+|@(vIL^y-*7P#agmaflaW*XhKq#MhuFxN$tifRP@cVRNcHg9xl7V7&#sO%F7n{A;LXiFm>5+1Yf51l$Y+yX}>L&jS46>%mCX8ec>FB#c}6#FL@j_}YPj$r-rxTf<4qr#BZ~S+^U_ zBrZMIoaK}J9Z~GhI%s41M*={DhEFLV>4KQhVZl|i+Q=HLh(4_$Y$UgK)Mvf?Xjk(9 zDkwfaa5I(v?be<1i={06ltF{$BXg{%+0^ZqD!RyduI4DV!Xh&#w(2psUBu)Nhl53T zIH~NMMg7;J9bw~{>|h5YHwB#6N%f|CPpN&C6#+oNOB*~U2|&d%ekaHgEByO{m&$>w zKF1ZhBpatAz;u{*-w&13A{fKP`{F1XuS6+v56Cplpv0bVNZHwfRuH!*<(=_;>E~eS zZ@_1&Bw1aj$mh66+_Ps6e%bCUgLcPwFAO0VFH$`?x|cvk4ih8*rSfpufjT~%Zy{dW z9hW3|_-+@B_;Y<-OkV1rXh?=M3t{gJ$hD&d_Bbua(kETBFnV`JkTu%nG1`pcxmA(W zaUaY19H~xfi&jnIwwjX2CQ*X01ijWMOr)$2T5aT6N z04cqX$_;J$Qeo{}Eq+#?NzjhFw;le$Eb;E8YO@P&C$FAUZtV5PvdyuKt9U@4@zfy; zRqwSQDBlio$jwjPRf}+V#;H}IEcUF@-B$O$@!QG-tDg!1gP$^|4br8fo88veI*pK{ z*wP&s0T2)5{1xl|``Z4Y%w<7b0s7ULXtr|ZL6`x(E2rG*1dN-@+*Gr-DpWRsT1rps zcIk!iu1-D%9e(LD?gRrFcK%!NKNJT1k6jbJ8)^A7s87)5pXg_S=7k>BPyf7=(g%OV zkI=uZm2obMN7=zM>A!15@lD~Chd+@H1mGXbYWVxsnZGyeX`O8A{u@S^aQ4Tr%7`A# z1)KyZ+{F5dMcwVZXSwY;jaoN$ZWwm+fB9;6wdUs6)QPVbd{piR_3_a7Uw&LF)HEXY zsCwK@u)4PHT7`C@Rqp730IMmhC#iG}D@UhYD0ePvvazu>GV|Crf`uP|;{SmBP7AD@JfbB%Lx*irR8+YSY<%g)m^PPO1w;sggDJ@>8i4J12 zz+|^Sha_pEOT$&@i!CQ5QUg5@>tYi&*WUD={gGt6o8i>trsZ&kdB;6!Qk} zB6E@*1c&Ptxn&NX4mK*dXJ{heoRFkes#}9@Dqs)6lxI#B_baQ()oUm%e5N*d3|GD_ z!MC~Sq*6T8#IR@6Ek^blO6gsa6B5QU7q8kdx%h1!cP~t zn)eLKjm~7U$ABk!KW{xqy!;5+7)e{o9$YXY+n%X)_a;#<3KS`1SDpnXpg!1x#9q$xpxT8(5VSfLKxJ@d~`F7Q}?* z)YohGY33ckS|Py{a~pc+NBIWkMl(lfgm3tsU7-%vVItqXv@?@`r|qYHL4f%I)^qg8 zd~-GE)jG~?djH6xAPLDhMLOOxKGj=@ac$$_t3VBDsc0g(*~Tc!hts>v?0cTiP%lk# ziM=V~Z@(Xm?N9g;bO~3WqKfGCFs*cFge2V=uJYf!N{e$hsEBb@bZCg=5PudC(0L;i zDT^C)44mM2`Vxt`c88KBc3T920zWAEs=%&V}tpyf2{c=$+ zl{_v*`9dL)1M#(Hy2yHJ{23<`9%<-V*j$$6v`ti-))oFBlPSL8-r&#jj@>&kNSRdZ zua53puNJIdlABvXT}G^Ax6fK*(xis+`aQf3(ywq)p%sP6%(#!-@RTC=SD3pTp-D^0R{t`K2LHon4}A}6W!{7RZi7Z4Tn2JkPgkSXy>={n zaR%xXOlp5ifJ9Vg_?qfaYX1-T<(C!glu1zl824$`%v1RQ7Io|hl*I^QljgU9;b-S5>M0p9+MhcB$()lLIbVEy}?Z11S;k% ztOY(9KVECrjyKk^e*nFHd{uVOVp`^mDAOH_iKMiY7MGQE&AMZ90LpgVmoE z=J^S>5qxLLez5TCoy_@ zn^!koFAF7J?N#5r`?l|E9RE&L2_Zj6SB zNG@H+n$)z>1p8UKPU#nBI^Uc|c$Ci#7vD;fE;sacPFD=Dz~uxO2z|A1ZWQw2i9j>+ zHYAw}P72|B@O_HST{`lJ73P+Zq=Z@%vKUp94roRjX&PbNVljB?i#-% zW0qr}Qj{P0R%O#ecm^FBf8IV?58ET(Jh=~_gtsWKWTV+|_*r+K#X{jCFQtngp`H;u zEd!Ky`5d_vo@$&Qh-)_-BLI)w*v--2*~J8)MHflS6{u}eHZJKIr9os)?A~tFA#++a zG6@7g`sMuW8;t758c7lJJLVwb_l@hvVi>EK*xpoNEjo?bZyEw9T_d! z;youC)plC~rZ2a5W>lhiWcx`z+}+te0Ka0X9xE22%lzG-d;-flP~;}I_4;sF!xhQZ ze^#Um{q~Su{Hc9(^KDxKaPu8mDQ%+43ZIX@8XUz3$Lk+Tro~sh(>o@v`ib6g0}mLy zwYsp)yrw3sMqT~RYOJWrzsclgh-B4zB97PcBc0)#?|?`!|K+D;I(MY*OURq}+MTG+ zT24C44`8pNjVqC6o*!UtdOAY{pz_dpP{+*HnLi$FD|qih2w#jY$R)n3(eYkuI>}>C zM*0mk&ZKrV{!y&>v(Mc*=1w)c-oh@gMp^9Tbj8C8}$kx?{1GaUS^ASbB2^}UYcTSu4za>!V)hDiUjNO zIkc?^#ujBsQF9)GEBiwnhW2OWXSaVomUE}oL{Revd#UNaw|!dlW}|n70OT~Ab(4kg zJ1V_v2a%|Nk=?WEI~%+AY8vZ@J#osSQD$*GgGD9$wbixZ?-dgq-q!TiF$~Z!*UEUW z&!ZZ!ZmymUKI@L3@#%rt$91@_S@#v~gFYDAQjH_&YZ^x*n#&3jqso52y1IGjSMrEl zL(faWNbJ|X1=3u5FH$A4pKckYQSgO~bZRVX=|-{_Znu#$a3(n*smx}*HzjsI zIV74acm8R+V@3eJxF4?(fMbq=4O;NNJ^`=-5daNY0E`W4Cjgf7N5uwrPF-K4U@`n# zV=^TG9SLxpht0BOf4c$aELIJrKL>mGxwUYf|6pvuY{rVqbSd6He8Flcd`URt2Q}~c z1<#V?QxjfNlZG%XA{|>#;0)8Z#nVQ8@HZr=L{MBI_e<5WAW~pzfihj9N*jX%MT^`FEa^SvUb_Lm|6{&6IJ!Gh7E{& zaiw#bWAY4#iiP4=hA3(({mcQXHEh(WT7HP?M1)%y- zdZSbg75fS{&k$gW?kg4Z^PJ;GGfqCqN|nfAe`dhK{MFVepg81=`rLygrK{dhRzG@L z`__CzO%~vEGh%~oq~Pnp_)r(W;C|da=(sik80ZBU2>_@ZIry^8mRF1BKwNQ+rr|CI1Ob;JP627@91 zoIs(b`DqzkDFIzg!mEJ4zYrNThW{bO{yA<2-6jaLQ$qksT(JeiGXnJmfoT8ZKtYVZ;9FZfQJ2tc}jKb9kS!|WbE=_bN`YQ!;Rs0BtS_{)0DXlgslO&hwj&D~jm>_wJ z9j{dQpcK*V2bqP|dM-)xj;NJr|Ds0Y?Q{ue%}>%F;!x8Z2Vqmwx>FMp#n8>;LEJY- ze@+762HM^BB>*p;69BYqU=_5#X%$b>O#s@)0{g!c05bDAh{Oyga>^V1PI*mws<5B_ zV3f|gE7DMlKX16tscEk&^g*8A5{}LFM-4>r+)nSn>x>;ZZ z@RXRSyo{$;tKPSfD?CXovXb0A@?k#(Ikr0X=&+Fhd{u&Ck_!+vZ}3#;dPt}hRoih; zfg@svGB?m&!tG)gyHGy?FkYZ=Yd;?%($&U#(O>}-8FT@Yg!`P#-M&5L*?CvATh-uJ z{cuT!M8jY*?T5v8c9J3|-ql>>TZ#%)UUfp#+Srph=)wg!Rv&a4zTC*5*2{wK(~B^8 zFh~H@4%0DIk_6zKl|G9T=ck%e{gp+l5)C9Dmp3a=B(uMXn~DDFn2+7eD-w6dYp{X# zTc9`^5y0UTm&?l+BLJfcI8P{!Zs`0eBlZ`A#?4)d^=rj1;O~oTx)K1MG6GNwPSE?C zk-HG`&s8hMj@ZeV0POcd6BMC8Ol}f&bBh3E*?)fBFFq7-BZv;Gj|rC}01S|r0}zW# zxy#g}(#$ml^CF)!Vq06iji0BKIH{r$io4akW+cXnPs^OtMBXi|#x`G^g`~GM3%c5{ zY)H8(2jyn1nJ9NFM~Omsh8{Xx=%ssG#ZQlkeii)YDI)MVQtw8SQqaw@qczyhuFsQR zxCNE~berU*$JcboV9C)`QM{?Wd1vx3D1euL&t`???IX7U47UN%{|oHJ)=Yer4Ps%-@G=Huus0W zgl&O@LP(pdvOWd&!V&O=X|3Z-eWgOR;+j?H5HWh$F`%E`P~*X5qhrnA>5SyT5>@3b z3@R3&Kb_ew7CzNYX=1w3z+c*r#T3ZXXR`^}lZIXfMXS20ypcc{{# zEkm{a2SNuL&=#-M^oiz&JH&voe>}AYuj+sFp)W|k*|F0~5SG5>Pq%-ff&gp?Ik0JeK4g(S{rTMYc4az^iKiMKTu7pdkQ{i41b}kjNUoa)2@WpudWyS%05tc+EJwuIhe! zV=t%l#hRB{z?HimNsn=Z>vKhe*G&JvtZ}|qvGsWCvFbrVpm1#SPKd~h;tnl*2d+&#rYgi<$e?r8KxZ7^m(=>N{9y?`G1*%0!CDG1m-XM@d;vd@zw37cP>e; z3aQ`X!Kpe*LUeVT7I=P4?gE^0-eMB+s(p$f%=f7+)AWYp# zzJGt}`dx(;b&tq=sJ9xy9+{>Xy>{hr)RPoMpccKOVQrbWdU>2k+ai>1_Kq zD{@z3bj%(@9j1$kndqw864?e!NzjF9h(sT9nZxu}=vtk_)SM-GF9VAVbLIIXqf{5O zoBD1(hpu=%n{8i)%U1=rYLLkES)V*>8=1*pYJ8ZR!{6oc%<1i%Vrrtb2J+lA`s%FB z3G#_EWo&a=qjqnVFRK=2mog7EvtT+};cQ#5Xa;}!bFJgg+tuJ=%2m77U+k((S?OPw z$v&;U4BAE{%R3O$z5wHs0%wb3JiKpwGFx_feUNCNRy`wyv*ND*&dC1*2L2y7tot%j zcXTh3bPB;VPI)UL4PjZdNT+Uh7V32;hAQ4B%m?w*rCZ1Z#!9}5^ha_q&Y-a(=ecp` zz!kYK{vvk^TqhL{$QnTWvb#9I5Y_cNIrO^0@)BjJ&bN3HPNWJURU6oP?#p?r($_ij7-NN7V(85Cf0? zPy&E*Cl1n1Bm;jNGL^;SAw1p&bCv)sX(XM)5|#Ta(Gv3eI$|Yk0O-Ij0*?JH$AtET zwk)HlaExkP1mIf}oB*&}ClqXW`$?pD<-4#yH8nNAF+5{s`GYU={0N()k1c6F5U=}{ zv`CcdPM5}I4suV~fAJvq|M@|AniqbD$h6!>092qTb^_4JLyWclJ0Q^CP>&Z3YRhvS z2@rsnlK2}+&%pg4ECm7B(N6puA}jfX!imjlW*g_4>f@02*;i(!x+=aePQHKZT3jkq zQTa*_(}e8y*BP6mjh57hCklUOE#a}4n7idU(@B0U?S#Taobzo;uyebOaq7Na#V-Rn z7mwf+eckCBqgCz=KfUf#q#u7KI>1;0keQs8QAq%d=J$!avL|Dy?ezbUP2KMexJ3Zo zQWAB@jxve>Orzp)5L-lS1DVmQFd1dzh&(NAT+!3-ZS4T>W5o@xju|Z|hd0tkRa9 zSy@N+>2}1>CESKyjRkY>zzv-j9>D9IL$7U$^3F$LBIg!V59&+p#G?5RmFE3SAF10* z{+Ry;gl&RAcp-2b&PE577iE(QuvV+(8bPpoDgn8zdYwtvg3(ehm zSaEW1YOg#C zo?6~wGYhx)8wv==z>iRMTq@Rakuic;F(UwMkm5Z>6O)ifmBV|kW^bqS#d12u;%h$G z(0o%D>`9mvR7i{ISRe*7dvMlXWRxU1#(TJ}vS(a+Q_5LNU@5+$qAFTSe>t)txNVi8 zwXP&qcSy{WTY27KSgd$&lh$jJzBosZ#ZWTq%M0LuG}D=-e)x33km8BOVChO!lH#4!yzxA2UdTxRj zkVHebDwJ=Y3T6#X8`%<#A`l)-%<`4EW5@FHPhDp)#Ej!r9}tNt37q-#22b!(o1*8Mg^Mf@x*Q5q54U*{Q%(P(t|&7u>J^!E1%0`LR2!P*8q{xYz2r(UC z^X4@=d+kdzH6|nrd%dbQT~`4u*YG-d*m&qy)pY)jbkW%1l@4L!Z&U5w)nnfj71;!z z92gFtloNo95GPTqCTNr7t`hif2&4UOJOMP+nGF<95Bn@Ai);#>^{${tWy?Hn*-gxkk0DyPlUv7^#ctN|d@UH$&m}hL_ zzB?u6m%%y6qD_i9I_J3L9a5iCmFKEnL%x_`wUl#r!1|*%50iz&JsPFr>_nDt${(me zBR#Eb+VFxy-(e5YA}2_Sq_(Sig|8#z3=tzkizDMd;#i;MHR`!7RU2`<3Uyqze|V6~ z`YcHdA-U{~9Tz>aNwP7%k+5FtV+>D7KH7#F#R_3|Kig;oE-pekEby7{K?eKIKzK_;|A8l+&mo*;KO&Bk!$pzeQM5n(H>j?9d+h^CJ~m#!+{{56SuLf4AIqozV^YPp+_$|zKEBIeoy%eehk z#=Z>Ff1#C5z#sLsw2VJ5UnpPwBd(78(|o_65zhKcQ=g9n zQW>DK@yx{_{7Yjnh9MncZghvz9m{79#*r35QQY8`*#B`3O%#pBMQNc8!dfq5o;K-%9|JNA^z(dnAKX#NUd*zZjSAju^wyn~W!~j*P1Qk|j3O z49Gt5!%wL3;@!HJ-M+7S4+}Q7$`O|*(XYTPX+;I>Z#eC zome-254Am!&+~O-snBy}Qn+*jI&&-Yv(BQR%=3Pg zZ!vv5k4>LpyfM8_%n@V9=lozShIju`&pAzS{>?hhzZFFW5PdfV3tFfpmG;{lV-ynn zQXC5nRK@mwHkHp*OO?G+^uSW5MylXJoxhh;1W7mFgQEwrC55|;c$$-<&+tWXnA-U= zU-A8DQG@!C&+!k#d1wpH%F<|=*19VExCn4Oy?tA;JV7;;TKB5&_Q-J%XN%Y)*PHLx U>pF~)>7vephx&3mj)cko0vFWIUH||9 literal 0 HcmV?d00001 diff --git a/lib/DFRobot_BMM350/resources/images/cal_pic3.jpg b/lib/DFRobot_BMM350/resources/images/cal_pic3.jpg new file mode 100644 index 0000000000000000000000000000000000000000..5cbc8ab913feab4cbc4b4d352998e993a6ad6979 GIT binary patch literal 154473 zcmeFZ2Ut^Gw=Nn4L@Cliy3(aeSGpoi1O(|VC?bRqBGN*Qfb=FHAVrFFX;P!KNSEG0 zLI>$Bp#})y=HKW4zwg^;?|x zI}sCc1Fp~#5z`V~wgb2T03uStX#Y0gzrTpC5XN|w?Amp53POWg8o(7IV&W?##D5z# zp|wBZIDmwfly?7IJot%mJCJQSczkuK! zA!!*|xqJ8J)gGy9XliLcer9BBVrph?VfWJhm4hS5$<5uv(+lS96Z|eDG%P$KG9mFp zQgX`2)U?mJdHDr}Ma5sLs%vWN5Z}Jnx3;x+bawsh?im>!8=si`HHBJSTK>JVy0*Tt ziP=9mJUTwXo}T@UE+PQ&{~+rR%Kj(1XbE&(At50qA^RI$L|42Bg_xFv^tQxRx(5bi z&t2)cB?GT9JdDq&Y`M-OWr${c@n)EuiC21&5A!$D{)Mvt9AQEKOO*XV*q?Nv0F=Z; zgvBGK1*ibd+K#)Bvmc5@5#cC#gV4tM_|V^2HSVpF>7 zWVjKvXcQ^9BRaYx)xN=dLM3KluOasI>VB#=MfZK)JH(sRTrhfFY(%zfO0lq5H`5Yo zRnfbyy4+KT< zQ${CarIHNeQDuZk*TMw(J)i2|AE5J=4fA@v`t{w1lNTu-M)e~&>q5}L2+ZxtI4(ve zmGNO{kX)+ib9>=cse3~0FKq5M7`>73vuMKFpR4*Ak2M;U+4L`HraJGG<-3Xa_>b4c zfqYk5xSl#h?A-tvgZIm4NB4uH~R_buP@{p(p_8rhR~FQS zOYb(~jhx;mOc_3m>63Nei^;r?0e0wNHla zZgmw=ea|IMXbA2Y^E`kZwPnMKRyocJs}ZLHp(bijg%SDS^%rSFRv#fKvzOrR1Wuhn z-rG|jpxrN;ZeC=|gkk*q>tV{&*hgi4+R(+~+G3d(2vM2#r;3uApx^8T=i$RAKcgGp zbKNXEub4tE?#%dDiGH5x02ls3ZA5_}U*^=HULa=)66Sc`9C03lr0LhZBvQoh`>1u~ z+JIDp$4Du?+2bY~4j<_JPdS^874J6}yAr?E_v1e7{ASN6Q_oqu1aQ^t==;V?m z|Em-Y9LfjnOvx7S3j4oBvOKE%=xj6A9zWB%J2KPy!~31a!@|^!=KEOP#li4NrUS6S zrsZNp_Va=*xip`dNA2_sTTqb~?pyCZNX87lm8-Lb2H_d>Z>leWEg_nZ$7xhKq(8kl z?i_*hJyc(_Xp?*(J4T+>sBy|@g!=+`;O@N}cCLkudRiB3(1`WiC~%VZEcVK6E7)v3 zc-oZNn@EJ%H-0uizADN0=5@|Eg{@9bz)-*~%u80LPuVbdD{3;zLm#0xVKOI}VfJep z<)7-nELHn9O*koGf0nA+@~UC~xAGC;VfdmU*4n*EK|iu{X@W|gtw>~U1iy5>Y+~_o zpP|uv`AW*yi-3175X^I()XjIDG$fVKI9nU!NX*@YA{2+Y*^*na#xM`L#fOm#` z#f7hzcD&y)u{M3g#fTTirazpJ>33?=MDKh`wA`>@s`SX$mQJ~%0ZuKbO}KCE$`V5# z@WaqhO?KqdT39m&%&Rp;)|6E*l_R>&2R5=G(Xa?<+nWx0tquKH*-NLV-TxF*(aJ>$ zy95~3j?3JWp|G}?qjyeAjwqP}nZBZ%j@FmSt5oP}SiRO~#Hl(c^S~`=60bA^qhBfr zTu|8_$J|KgJ@zr4`_9qv8)1Tw(%h$r=ZKr)iLYk+;9K}^*Pm9IGf0(oog3%bBsMx zl)5P1F=#D$AoR0YV}<;2gk(<9T)>F@A~w-&p;w=BBgIXJaiuA=7+f@8n}ZCR%7^iN zgUCQ8!J6E1Nzx-cVyw5+-W}=^FJuMdWEjAp!dZPuC+(8-e$8j~O%2H#-1`aIVggAk ziO%p_rZ2JqfSZh*sc7+*G?f_Bj^ug|)YcsjSO4pY#tjLm>uWc}cq6Cs@3y}@U~g_` z`?!1GmP+sQ&_4AQoXSba^ilC#7^8QHs6Mi>JRU>Nt7@Y}Iwhd^HOxiV z=0e37jf&q)Yntcb2Lp(PYluFpeb!d~P!C?;0Q(nNTbG(R_sl)?u9A3U81Yq1u_>E> zNW!E>KS-Ho2-5d@3TX2fT6V*4`DX z84Ii@2e?yNWE`hn4)S~tE9p#2{AD?1K7;JrQLx$;`pj$izPb|nF=VD~{erp8$1CjR zSeAa>xq_1^1n%xt?VVWlr5e}1e4D}6)^+6jCx?Z?cQXAl&V{49Wvx!8tc|7?0r?&d zUZi6yeIx2_l*J;xxGu_~#mALakfl!{Zc(EFirCzaIJ-P7_{Xs+r?6Q?-netEzekzK zHfmxWC9mnmQPY3l+c?^xN7X>vjqQb$TnjRM6sLtvT2j)Jf`js{VV0^$#7M=D@=UJ=eDQ(R}=#zKQyoO=-BI#}}{hETGR&yj$?lx%Xr&u@2n>vxPL_sxsa)Kr~iDUrTEGs{b(} zE?FEq_BwiWi9ck?+P4EpjgwfiezV-E%ohvMF&(*8|1I8bqJlfdLYtnbdG`9@$isIFcttPoqzTRrN0+YGXkbf_z2YPS58ktji%{ViGFwojr3 zLZvz-SYS+i?^a5O{4=1nuD>FyN_1_E@~=VRRK9rIpdFrvyM6t&8s-s-iPrjo${dbB zs+#j@r5kLumRq^LUdlN|R=}B=0XwaeZl(4Ft+kg1*)v__kyinXvO;S*>I}wojQXY{ zBDEL%Cpu$gFPcUxY<oUX7T>?TNmw@Y{CpaPT9j@&xtQlL@jBFgR(aBXl(x#c49xA;_JOoLz3$Icno$l(#f_$aiiMj<4hM+Qg`?{ua5 z&S@W(Z?Gr3y_M|KR?_BwKP^UJ&~__)Z_0W1X%;&7TnxA;unKQ&v^7(JO1|91^~|m7X78P?z#woM*6aMC6Ac!qQ~7Q5 z2pNIe&G9cPk5LYTfJjhvNf1HfvDy5DxhbCKygE(hCWbx3w@q4$#@^Iht1PH=UvxJm z+CNT+shGr5pQ<#8qLh07F}rcw-{Fl}sh0rq1KEoLY4AIAAFD&CqHY=3;xJ`mc)iYZ zNVGq{BmIl@gV!T{@fyR)D)--aPAh9dFnb6z@zO*S#z7zR%q#t~SD2*a_Ur?ti#9pEy@mE~ZcZ3~a2zGQikOMqSN*sBnV zOMs&;i2c<)+&jT-KHiH7;oH{f;waOHy1wmMG~A8jwQypUca2K^V29^ydW*XrR1dGh z7N~-LhmY62{2EQvKu$Hgc@77nl^%@fqwbxjRZL?AuoHO~{I^ zL&;0P-+K}KhrEUueQi_iz5nRr51FeK%uNlej!5|j zw`%?&4o(J|Qq&Ig;{TR^#y-cs;vC=y{?YVL$thN6?^DWng8a90U>JG-qwl>`_&yzK7J4{ZC@4h@@6f!7LqPH@9z zsL?ajeB#|^7C%7*){3XL29pvl<9}mhe%r?;;)|7~OkFyF$JzDcqP9Kxm!dLP-cm-G zi&>WH`4g3cah1Iss})9F#J7k>-NhKW4%23?`iA<1`_j6PoIICU7|1@TiJ18XCrwMS zQ?dsRK7Eb9g_Eep3{>WBCEEy$qV(!dmW+4tZSy#3v8D?kdWl!EJLl#~LMy9uxy-f$Q4vsPy7xhvu}S;a!KU zYeb&zv+sUIeS4epuxJb|@YXqiYaW{n=5RUN9kd*KIj&M&!AeZ^VMGGdm=It3(G$|H zwHE}i&W%KS=;z+rL5Tkl)exwZ;bY@OyOqDL8Zm@e=2Z%>jhA;l!D0k=XC1B9#63`st z_Ted+=06(6)wB_2?iv1!alk;8gA4VXU@#Y70{qF9|K6SHeRaSelPdTp6EXaE-~WTr z{(DaTh3)>EPyYWUI}eV3?yJ(V(_J_F6&*``uR;XFU$_M4#F>sYvV4Z6t+n{*g%qHi zwb9iMB$TpeZ^n`Dw`6@tZ zL7BXhiY!ZlWz8M@h1pHt!RfYry_A(!ZPH?lQ>kWMO**m@M870AD=t76@Rq6O*!hW) zLwtRzJfg!FNxJzIYsf*?u0q$SV{eP7kFF=J&ER|_vi-GN;@h`S6-j+jyjBEn=T0R< zQK_}>aV5GuiMIahaHHmusHD;rY6h!KdFupk*?Q+Vq0~IOZnjYU+r5t%dgJP&jazq| z=C9Cg8HO2+D7q~TQf}$m)_dj@Z;Yb)#R};fDSDqbUfs0 zFsxK_G$(gDoi;0bAX%XTx}eY=_2_LfZL{GYnb%=;?{$#LleC(f23ncG{sBhV?E!hnS)Wa3R0A8!j<=uUesUqW zs4(dga7;)y)lIL0H{gt)k(dw7Ov8S1OVl)K1=6zhnMmp>lY!1x5ieD$ht=cLec5gwy=gDtBy-3$^=c0wNwC5R!(B( z8lRxvmj7^)IjF5cg~njoo{a9*Lg~TBnWCe$6V|}$J95Bowin@zCmXE>o zVj&(>H7AK`UT^A#bZHTpW_i!<*b7xbt;6md@UMw)kLS#Q(%!MAgeyKM0a|aM0y67M zM=jetT$~-!e09R3X*#1spmNsvW*UJXR!+>JQ|J0)&N2*>ID;i>`c1D%R=*LavnUJA z*OgONWqmZtwuC$wVJacn)_TQ|V=v+NGn%OP^zY!a2&1V)9W8t%W{)gw=6>!lV z2(&p&6MYF-dZMftW~MEz1Z?vui1QTLt0}X-E!Dci`uLqpV?z68H#d#JbTJtTt+nYi z4}KeYvO)+BRvqeJH(zJn3-_?}7VwREvnpJYloa^rWzaoURlqGsjCQwT;&kM6={ejc zpT@sRWw-Yd5CFv8!91zHDxCFUA=L1ik`Gsz_EXDCK-u?8KzZ;bK-EH3**uvhzxse3 z@I_mo;=y70v!#k~7n~Bhy3?XFMGCbk?-}Fm1(8zE5;F>!VgpCB)7-emGf^KEcT_ij zG;|4Ar!rEsTx@`{z)a1D#9t;0E13*{Su(GXL?+zU5YoEEF46gbWg9HiV^}EI=J}~f z7j&;P&#JEe`$1Vs7o4FNE$h#)sTFXSuV-CiR;JX!y-Mvk{D@0{JcKkyjs!sO?h<^j z!`Uie9OckD7|eB}QFr-UMFpGr&~^p%$T6?7F2X*6(d#yUCR6I*z?|`y#|z>!Z13fA z1b#p%3S%LDmUY`(vS(yCo-eDx+Pe9w>*e-tX7S~k-0R6Oedg+xxQ;qck+~4h9c`*zxxer! zJAYUKcN%c+lynYyY|dm!;P}R=XT~Jx9Y&)J5O{3-<4K(iNsZD zMM!k6H`~tjhE4NVoU3nGXhzFeQ#DF0>7-lp7*>zeioT(MQ6=R~Y7?tkN?o@$o6*SY zV*7AkjPY@`cSRRiJ2l2nz3q!V51Eu+XffQ2D_b(estp&7ltk^1;+89{qI zrw}O(mhNkJbG&C&j-9H8rTgiq*gBi<4A)Xo&Zre^)|I`OWSV%!DE`t!$0X9sOCy@H zvN1cGTkrdTT-EAM#nIL!AmI|=>+8AdIbC?PaS2F-yIW?V95nA_w-vxlJ6LyXOS*~} zhn+=jnN6zAy4k&6>)EGrYigu~&KVrzVyBnqnWD~3uxigL@#9TZ6OAg1-)n^9Xs5vS zwN;u>e|tdO4mCTNM=xLT_vy90tHuPMu`&kG+B?s%X*CwH+xJh}OB251C zWbNkOpV*EnE-gw@lhg<3O|n4C|hju>QWZM(9K^X zv53JXgI(=^|KtsCue9V<4=#E!qOtvpC<*{b*T)J;XEAD*nPW%WCyKpAm@Vo)QK0zh zO57MgH@~Gb;a|FJF<4HJMX=fS*nWLg)?Yq9IaB7lS5}rkGH7Eue|F(Ht$QR6<67!K z#2wB0bm^h-2-4&zZ@0o3r<2!h93?Yt{9Tc^S5tYHDLL$>qKj=8vbXV5TqlIUEm9oM z7_%@>@(as3X%y6I8S%_uY`4~2w@sKa*_$%9B!o*);O!gNv9xs|(>As}d$=VSyYpKP z^LW~NdgLsCgv&YZyy_A#pF)W9EC1Q062p(+o%lBiE!qLU++1LK;fZf(_f`Bq zX2x#O-s%Q0#k}oaaEr{$Cgc*0kVnHRhZ3svV+7vdCA!^mD=8-Y=fVNuXf@&J{L%0w z;804H(|k!+za6iHttf^`J;KNg1|5E)(5)GRdT>ahP`>Bi%WXVjdF3Q@7+i&Z^tE>m z^z{&_mNi#&08tc=FEXT+_!?a%Q8gmzE;2uxJ6>hb2ic`9@hIjSr{>mbv#s!It`xLrRIix~Oy_ ztD57My=4TlI`DTY{eh2IuU7EYOvH)hIX>4b*QaY$NqoeW;9PC? zD^t@J!`%o3P6qE=duG#VjEGEtN3({+=9j}Fh+&%w*8J1@_0vxC7(MmZLo>o$*b|lJ z#20Z#4Qw2`CKs6j3i=)k(6D-Fcny#~bixj-0A<_^5~yu%Fplr@mSTIW6{%Xm`#7$8 z#gj6m=@yP|XfP@V!;CtjuIng^@wPkQ+3#D{#Sfq~`nLBqwjC5s2b3*Z(fZrd`B>Sl zwi1CzoNmQBp4}lub6Cc_EG9o=yR`YW!~^z(yXJi4eDULcZM7O>C{LX#9G(8!bp8oF zB=2k*Gl@oBKzzZ~B5;tkoBom9ga84oU_FKZq&s_i4*9LsMo? zfdTc73VGwmvP%F*W3BJafNR*5=g$`^u7NU{hZNl~+$*^I4y8IgN*O6=i@vOH3H#uv za69k3X@Oog1$s7ifKht=;EwTP10y|1o-9J~nQa;+r@*)75y)-YY0yYb@9Iy1WPzDX zwcQA#-ixsp?4s$wsj9XImBY8u$mm9cMT$=fkLu7kM7>e+8|@;C>7ZK&6H6$wlY$Ki zUdNd8PL|FgS^5R8P|>nlu%$+GRn3^66!kmQwF1i9)lq}Lep;JHXAvCb7gMbn4);;H zdWNpMJJ{(J^y%JjT7zK~@qxd4$_m)pYp;Ut;pB%nK5|9AMo4o$SxOA?{B#udmJ>{{O-4;I`$rsqui^%ScQb|1SY<-8)B^`fOAYJGnLSNBCYzg8-gYZ#bz>xYS*35#msQC z+|Xn-99d{fwx{#l=iDGzd3LPhOYNL^wY>PR_Vzrtg5-k~#y+6xqAfRrB8$IlPRQR# z^(fl(N}dJLIwhe%O>Om1n3KI3{?Sh)Bh zo3)+(_ep8&a`M5G&<)PjDRz5St-zVU2D+=h2EVVCF&JBG8dZ;oPAuVfDFj)~7U^al zR~9E|UT1yzUQVj2h(p_!jQ_1D0a`*pH2tF(g_%}<8{2hXuYjzKiQ2`Q@6Z`bw#R+r zkta@~szht8f$eg#DclXT^see(iFs=wRFGI=Mu;oa+ z58k^xIakYuzy60Hs0ZHoV))i)`1*^&B5{>*@e6nT3(BV?|C+o0)ka7^{Ks(rG3@`_ zZ=%1j*e1oFF7C4-5~e?biNakr`~=XBc#HBa4E0p=^hILf4A4KlZyz@=B#ub+0to7W3cA(P=R4f(bg6%1I zcsA%D7l%)e>(1Pqx1Y1^7mC$gh;NMJ**3jwST6Dc*kOZ9D!AM7)KN7M2XinjocTDQ z5TfXIWq?(B>h`O66UprynBfiYiYFCHi7ja>SzY%UjUAXi$p(7l@F&9f>S5)Ov^)99 zvXK(>B016NTH>5Tl5*}94~v0Up#IQHK%hbZlPFGa8gwd*m-{!0=fA9Q3L`tc-^=qG z9o}cS1Z?+aof4ulanzV>@*3lcKdZUtl52Qx_;MT0@k$vZ_|F=?j}Uap1Y!yCA67t# zy2W4XD%E1}wG_OfO6OalVH4yZwYWd~{f{mKV{RvON{A65u*jt>#wez-*eLWan1FE+ z$poga%ql>{gKJ!SZ5LiHEHfUe9NQ1#2<}Q(7u%=7oJ8T-a2E9#U}P=z4OkC^XR*Ab zblME|s?%C2GAhbcXh*ca)1Z#3DkhhF4b)$7?&1$B7bq38UTCM+jf>7AzqX2&yP~Dth?E!L-Vvez<4Ea zT}fCkQrI5eX$bdEo2(y~M%}jAX_^MUd(phZ`6=^^XKjxRXMj;5;FDlN^PQ|#tTs)H z^Wmc#QoOX9)E`y8imjPA=GND1{kndfWd8g7dryL~KXgem#?OGdothFW(CQ^G7FXm{ zXPTB#Ux#!M{VmMc@G$gd*>W1)zLb?PljPgTuoXxfM`0MA2J6u3IWd9adMB;RI)_@` zd97af>%kRum89RNUuacL_aow7uRWj6a5cnsExH6_==DO|Is%wS6m_3deunLMq~CK{ z(gxg;FAaR_OecB2MY-np=*oUAZng}LwDgN?n#BauuZ z!R`YL#|bkb^09EU`d~fB5rwF_w@{s8arz9a+|sAhvw$yhJt25Kp-X^`nV-bc4#S3z zbLX-aHU?Jzq3*ommc(X<;2q}k4--LF~`}6q5Bv< zzBVd4x9x5J1l}x+{4E&by-?J7S6Cg-;+Wu_-YAnVm&!3Fp01_0zH6oZCM?#(lqkdf zjpUR}#`2(c%kC-i=9K@y-l(oK==y%Q@__g*a@hf@0Mz+)I?=Vv6@%x(26R&CZMD{q z*ua=h+I_58b!#?{ua4X_XYv9~@7zVEF%K98i)084?r#vJVXr-gtd*6)Gr^G=FE_sZ zYLfZMXpMHcT~Ifj=(+`X%kgW>-C0*&j0=DyFhapUOBKtrK=AQ9N;^KoxY|&P79$_V zM%tbr0-+yve`avU-Syi$sXj>`8=DirDlNvbsTFiAiIc7S99r19RO;&M2dzM;i6zLM zeZ`fWxDNRkkGtgMO#<7@RVI|bD2dtW3JMmEVn&2lYMR9To&8cua6k+qLVAw|Hn#-1 zvem{6yk3UW!c&daY?SYquf%#vH2CN7th7+hJ)Pwo`@!RVh@|&>fytx7Fh4`%@C+k| z)M4GMvyP~;yb&9xdo{5ek$s7ur*cb!?sZ27JgvKSN>&B*V?f6ir1{vu1lmqOh33ki zURH0^?TSLIWff^x0<@--4WmMMf+X}N11Mqo9h}^wjSot(;t$4;cI0fU#>H#4yvxfx zCEWM(?M2eflG(Ic?z4}}RyeNLp4#YESPFnu4344J%>mn{Jv(w9<%Ln3^Q?^lnF1K& z*-yx@9h~@Lznj*`>S%?ifP6@wSEacW{`3`XJ4R-T=j0994=a8-xokfp4EcKVUF>rw zlub$zm8Nwjk#f$BQ<0txMB;T@Km5)mz~gHj_0L_20dP~w4-5BIYYZ!&>mW$X+p>!m9ni@k`C_43pIyfeI z$SB)#WW*P>L6-nZq|tmI)41~ue4|hP*eivX%kfk zX}lMv81_(PE}B-QQ~MfI=))u1u@b`q z77g$zd}F|S%-34)LCUW(uO&!c0tD)@`iq)jjU;EmFo)JOl`zYvDFclV{vNhxZUQQb znPzO$tBM(!`ejCA1b<4!6r+WaISIrm`7Wv2@tA!Z75&}VXKx|3#wfo3;b9}%$S%7e zZS7s!u*KFIA~VIN`Q*KlQHp;fvaq5cZP$&9tYsc7HLR`A}l!_?gwAFEY!hYR+Dze-X=Zd+zI$a(Axtb{c=+ zaIEatbl&%E(RP{Qgl#GrorSxt)-sO{apXdW2WM?lZ%@O&I=~4iTF!GnB=W$2zG={6 z;10@a_7Xttwu{nPTYu(+K|s6a&hfoFg~dx}avc?s^*d{Uhu3R95w}?!SMrypoUnd) zxbZ?qE?gvnv}`-F^t?x!e||5+gO$MWZ!f!{VIb%KVG*Q$bUbJ_`vhpD?y?IoE8^-Bnn;P-m(!Mm6;`< z@0g=w@;tWi8x{$$Urpz(d2(X-CC5Y|$#l&Q`DP8`FH_=2iw;08#;COUWD%IE23igktSMoQ za)pjQ#&s3NK=6d&oVEx1NKfGNN8jE)DiWP{FCCDRj|m2ej^mWE`bDs3mKe=&8E`Me zu07!P_gJ0u2Au~Wx(DRmo@m}z+Bayu==y$FYpt!Y8G9wAWb?Ime5= zn^rcFv-n8}%7A4vm~^%usX4Dn*GZTYG!H%SI3MMH(qZmbO+k7Iup(12wDjXe&t^r7 z`I(cwt1(kFcH>G?{>~9i;V)z>HjzQKefP^+6b-6<|5_=FvIK%oa6NE?>UV9IXCkdhwWlsA2*P zWN!rL>SGiv)3ryK+nPy7bDL7M)V*aWrhxjEiPR{PAi;PtJzsE}UFDPbNmk}@7p6yHS+e!fz1PtN+EY6- z+!=X7YQ&v-ZRO`v28Vlq8%a%?gME{hxbj&fb+2B5^hlVH4?&s;F!_pkm+;d#J?uHg zR2_X>A{U7hE%>D`G0Hu1B%D-RiwM=3&aX4gWb@ZMnqv^*rGrNGp?=C{Ww^shk&E1M z$067X=u(WsqlqIe=_V@0iyN&vg2U9)H+kCl+P5nX=ub{f)B@9v{Mi<~g8l9pEUiLj zWh0iA*L#u3cd$8nk<#yR{?gRadDimv{;uc`d;R!di0*DbCG5s>lS|iPW>bX~OwXUI z^TZ9*oeN^BF59WjlR{=xH*QzGg$$;0eQ35hIPaQDIq4#7NNbq47!bNV*3X1{|7yMS z^YhnnF0+{dayuxkPS;rB4_JkBS*+IrKGD{>hJzJK-|%o>9h0m!{(@m({uBaS-raQ)20sg2VJe=(aMroB{WY<3aYFirULsK zc6HC9a@2j@9?=w0`uXh_o!9&FT2&%>3EXkLohq=a`ufaWSy5*K!HSwiU_9MOPBS7* zH|t5-wxxxd#POG~5X|rP;RnvcQo$WTFv_)@;Eu4)4}{VkS5m!-pl`M^=|Q3HDyl_56qVyzc7c zefdVAJhzGt%T~ld-wCi%*-LJ?|cO9UFtmU0Mriw3G{x=Ad|j z;V=HYUb$sao=X+d)Ku2fE3z3L;ZdSG@w0@8N_i_jnfLP!`6WOTr1WZ06L=Zd7llem*#@=l!`ZAfdnS!quz=sN6@d+Bdcm|);BsA#Pe`zzwOP$#hHn z@bN*w;DMhy})il=Q5i#ewv60Q^OkI4Z;mGd>x&!4H*8$ zM+o+9hD*+;#M;>Kk!O z)PzV6Q<*fC2V-ddmj_UVR=HQ|F~1}pRPO(SI>*iN)<=*d~}}*Vi1m&o5Zc@=eyCvu`)b>2D7{hFaiJQLl^8R~?ot+e1TW1f)dK})_9>-n;T*^g@J zQysm&!l#b4IEc&1xMZX%;pqp3A4j@r{eK2td(jSHSi4uD zFriGm$@*!s-7@|nX$_m$&dOf~;Y~;6$?Ci$|LMto7wjEL^v!QMsk=*M0XUURFm2(q zr~|_wQGJcN$vr=!pH1iY zORuaRj_zFo-qwwrta|~en(u?MSX^*2B`_6h^wE5%__jEILuE1sXc7yX1LPPAyd)2L zw)#7vKnvb92wIpA$J1k@NXPID7>$@E7=)MBN;}tyX0}vJvw zoqFfSz@wGLFeLSzxeLfE7TBm(lRjWr+=&je?jQ7d~=IXBnYUC(A_ToCv3Ly-gDgdTuM{_94~ zAPG(n>jo`_`L=8=LUh_rCQrO3BX7mG}D?SQJy>rnjZX)6jx}Lp&!8( z0fVOXq>c3fDR8KA7T4RX*7v%ek9GOFUn#psM$`zqbWaZ@hIF{~4<=yd=Hqyg$GbqW znV!{>l+?m`^lBV_8m@wFV4bH7P{Kk@(Wb!_e)<^d7D;fX-~+yQ@{n!M%9)0{KyH$R zC5_bK!4Dn!V$?lhD;zNd!xKpi3b-{U%{It_4H&f=-AUU&(8)3i6f4U%I$$;D7XMCj zo6_v)m!$b z#r0?2ZEv;i2asN*LUD2!jtUt;?y*BKB;cf7Hmx*Md>jRo_vVW?+AwDd-*m8-472UY zJGK2jJ!&`rQ3Lnx>RO^FP0Gg`=M}|ryrK5kGB}4c>SSLDz9`<2Mdb%Z>t;pz2^Xou z3ufq|=^XQ5yf^vp_#te|i40Be6NQy|$`BxhR}{I*aY|T+e5@TXPLG*YZ_7+z)Ftne z*e$XR^ZDDJ~%)3T1&uc{vLy#q+5$?kGgm$ zY{V<$q99=QgpZR#th(t&RY4EzuZA{YCR;MOz7Frc8WV@+jW2tbmP*I)9~d+zNZ-<0 z9hti$U>p;!De{)*s|l)|+;o$}8T{AF#SsuyqfPVpD}?>9eS$OR{Gp#RA^x6+&D?9h zb0g}DlXh;4g2iByI7_Nu#OJAIG82;7#MbYD3s5aHYICP33#+x&DO$!RK8N zLE?0|2%(8WUnGu{06K{%I#h{LroqU?)B>+T@*qd!klf6Yq}6s)@1 zX(!tBz|iO_$t2pVQ~Wyipk3~aGp5K&x7fT@EZR%nzyFKXbc&!rU4q%T*z*~Q)mH2K z!1PtC{Iaq!&J?6B-j`W<^b(+V0>@Gi+;nD(==0nA@V`#Y@Nw3e zSHmUXhdCUZwkeo>1Ng62P_!q-=w+JZjCeXlwm>dZXk4$(gWW;m{ z*m8ky5$<3eVk#^Wy#!3m5Db6^1cnj?{573e^jA((WkWgOU>$@2g_Oyc^1lTPBmz|W z#=rdaru_eHzgxyG0n2B=wo~$fKLHvR@>w{z4i>UX!G#ReKDW-q*1|*}U@6_=GsDE+so^;dxwqsb-@KG|K zce$^j_Jnu(uo_v=V6ju8lhUoyR138%@!4n^bo$&3!A4=!p2aPugeX2+gmZ#D@gDEw zm|mSf41_>eOdkkNh@s|xRvRiCGL}6?q}F`@6?GVyQKa}rfwis-Zt34X57miMXE40^ zXQuJrP1*ft(sUpf_{u!KnQ%|haEbPxnYiRNyfuOER=F-%YlzltxX0!fO}k2b^A%~RUuE89D#^Jw0@_kTGtsO zL{VEj6sMbQHf3r3YaPKFvYRE^IH_lwHZsMRDU&2%PVC&8B+TE1qHZ>LSdSopx(UeO zEFJH8%h-M-Av=XwDaV_P%=2s!f{^0M{8l=}PMmaO5I?zPE-p1+{uB?VR@cH9j_tY4 zRgUin$q!`CAMLLyEm|e9Twj2O&xyooHe)iAiszhcC@}m{i%qi6h^3sE(3>Xvvra3f zJkGz)OSjBK{HuG9=KV4TI;HG8D|zal=c;~I_+5cj*3gnzp1$%xZpt2^u4J?H6aMei#L z6t#KyioH9t`JUUe&!hP~_iNVF%YcM!;k`%2*(KmeoA8_^l`S7?B!04@$?S7v-R`afV^0Dh zg%__$QG|O6q@JGzS(K;BZXh zy$O91=@2{H+Zp$}d7)HQglOP8v2qaNCrNN%{LqAEIC7P+7Xbw>0qWYSj6xLfBZSJ) z5PY5D+1Otd)Z4#igU9}=p0cTSr0|L_aPZU;W78*ul;BMy*Q(R_U!U{wzwNi}CLD7i zzK9EPuz`O8o~>t{-7MqK$E)PyRNj|v4Ib$bc3yhI&dWfg^x#jKC@lIDuQ5b&NO*_| z;~*B0av3GI zR%H&%)r26yY|DANK|5bB51#O4L?mNn5`{vQP@*6SLP51(tYqABT%n@fvmV@iF{=Ta zJT}7`FV8wnnvLPEFYfI)*7A-EAfq&E4)$JJB~g9Q$DYB^ z5^()Q&W%*k+JS6{b57E-m#ECoNR3DB&RP<=l)&Hj93$_Y@kF#{68YCH(*5?Y)DVe7Ch>P>KkMAiYafs#29IAYDLu zCnB8?klsP*Eg&EuARxUHr3C36q>0iyBsA%vg#aPG&pzMmbM|kaecp54nKK_V{E$=c-47 zm9FkcGSS)&Ijw^ANVayjN3 z8oa`j!Z&TFnUP2EpxTqF{N?R&KkK3n2Uj|VPwq-A%`)`6f1)UMo}SQ4_+;01c82R% zWl%0x){r)TRuIQW`k&g||4s?{|9Cg--~Qm4Lx62SfqOe8tKg1@+h1O3D*yj~0r9+-E$N(r?hr2b$KED_^P(+IR_Z=$WPt{!FY*5> zi^%=l2&|JQuujCdxAk~`NpC;@WeM@zobry==+>~KW);oPtuJi%;fO3&RBPlZ7S*d}Ny8B=cPo zdTx`OY3$yUitgpCj?yp=clv-?jhaM`JNL}Xd9rpZ0`|)Q8zYA&|IK;)56qx{JFoG> z%K>`9X-D)iP0qjbcIv(5F}MsAPO%R5Kj-flQz8!uRxp)Fwy?8@c8zi@Kgp-C=_8|? zgCXC)nm?hR*X2z4{VA{2hMn2g=hUmvKF@6zcgt5b7W)cgi9C#505BzOR8p*%rLei? z0vp-Ru?|aar4t$?P<`UB_m0c6HKl|j`Ig#oe!JZo@;dn}Fpp@E(eKAqcUG%Ua}}dc zBp_X@9WHeGy8P9xP8D7Glv$Nbr5az2RrV~vqz~xVqEJ7I z16?-u^O;Cfcy8LfrK#2Z_|Ql{ihu-5dZgczM_Do{c{YCSO|^lc5;>9V5TluTLS+c2SFP{Q|(T~Ci7G=rJ-GI9p?9fL{JUqVREdP zz-N;UrVW+XQbYVsuu{sXx-k!4%bB zTH^n{|9h=e+f=KwVkRdsab=R(yq>r1#?%td7n`>@Qb?oC$8T49hG7j?rZ%Ad2Oq3| zdG!5b*a`a&g5N3rKXL{0ivQt=Y8s0Rkmx|lN8z}~WrTeprI_%SU(&~a9Pek^G^Qv& z+)Sw$;3Ij3xBm9Yu0GGCdE8`K(Y&6I3SHM>!ZaX|G4It7n;vI-(YoMLYe7Q3A0Lhm zoa$uKv#iCt6p_Im(FOBdB}t3gZ6$w@q_!GTYKr+cGV&T&3IlHgb& znMlqVAuc?}ZwWVtN@`%j%XXxAN)b$Xx0Xv9-Rz-YJe^aXcY=b}Cj>4N`~uJ+joDWL zX8|i=I8IDzPwu_+V7jhLD;OfjdHQlj?d#Nm*^r-2m`UC>`&{L7cOj$4r1%@}S`ROT zhO_uCtt3x3>q1(aTYM*83tgDQ;h~{|<3KR2*QuQ`^7fIZ@#-MOs6adimLH*fQtjs( zmZ0s$L?!R%Xw)}M@|}2I$^9&6pn4!9rH0p84FMxp-nB{=%z_y^pfa+>+jMB;!4KTI zVHmxT^$>-`Q-)tpwXF=wlC7Q8OJ@v+FU(7WtF@5~ zaI*u2k3R*zTkHw8_;j_U8Nsjq;1TS#9@@b)7d)1l^1vM}mO;(@-ixQB=E#h&Q*tHc zFHpSK(5msj>G!EM^~#T|>!K=)1GWpIBW&m6SgwNwsTD8$}4>Im;Z5X#ZzssHkp zm47jD3I&yZ`I`04W-R?TL6C8bx2lIfV96b zMm`B~&Jp*Z{NJPYU&~RQza9>F|5%Xz6Z9cjKZZGqKf>8p8(RK7Ej0M&`1pT$9n|m# zkB||wfs}vy2Mix=6d+`Nag2Yn9d`DF$DT7=s~pKZ>qD zF;@q&_`Q&yKDwJfQaCc+G6$+Wl}kL5j6W47oK+1*vVgUJRu#Qh%#g}i^f{`Jpt>vi zp7d^&`wZTt;kEqBhN&t+Se2`FYi$$MK5TRO+0if)p5at9S2MdNX0Bh$4pCZ#>AZ~S+-e=nJP+u>v`gB z&NPq!O2KH|PB(Qcv|&dPCTJ!o%o}=qO)9}17+(kqi{J7+a;E?wpUKeXiLHT6b54`}djF&U=2#=oIz|77CP%UkY>Qu2H;Y zdGos~`eo03a}QYhAG|JQ9G4bq2CaVdXorb@pa>EG}98Ha22} z^hbM*i!Kb?PP?<9t3r$-MjW2%eCWtr@%FnDdGy+xU-j*eBd$1_Nr{^jO1q#6P~BEn zUL>eKZx6D{b}z`}r`I*aYXLm6+Z;JOzi2jZZe>}ZGUK?-vCtpc;R70ei9axO3*|IM zndp%p7p56lnOC*;W=`jJcN94Jb*U8e_}g$=eOB94%1*VLSkM{p18)K{;2@hT#U06J zyH;ODaX3^gVCigLW7)#>yS3Vq$}dq(#=A9dY!W?042*XPLjr>MudCYc1<|)m2T7tl z5%w9@h~MG0&gW8t5M;|>BytHPIUVN)X59D zz9yG2#LI?`_L%doo}uciDwUa=Pv?IJ&RAI*lMtXV{!5kZ9n!uscSJgmh&bGTc)CbO z*cMVB(*0@}Np%&h{Jr1Ms0vo5Hm(n`{qIh)e}4aetpIx$YKP2}F}8NMt8${nF{mB+ zmRdN84Eu{>SHyfdHuN43y|MN@Zj^tt(4oxY$|B&`4RX%Cag@=&LPK$9r@7VL%w)-A zZqBSly z-$%_FZvMUCgfq4@UEOZc1bSddXA3@Mp)NcCVy0DS=vfPKMdR7Vx!dmV>f@4})x3B{ z-+gifARJ$&L*eqpmktWtysPCcTQUXr60BcE+nDh6awg=Ix5nB!k=O}n1rm3+NxqzF z1yn@zyG9vCzQ*(6+h&l4buFf@QZs3l2!5Mbpc_L*JW@L_`9OTzOP6N&-252p)i@eH zjdKM^w0Xg80#(4$KleZz^Uc!6ufEZ%xAEnd#ZKa6$~)1r7RcWjk%A03JT@FPEn96y&?5z=XUycx&BIk z@U(#VXG#~(a8D`){gtza3i_F58|=I3X!rR*W#qtR9UOykq&(IZ$0fDvxo zfcU>-q)V0R%p(qH+n8hhGuD%UIz4iDmEw{$Nb(O}cwi__C<$ZHjt599wt7M_l0eOZ z+@1VgJQ{^l4_yU{{bV*F-itK=Q}4j39gqFK2h)Zr4-2i+yu7(Y-YXC=-*w#V3FYcQ0pId_^ncvr1oS_+hj!f4FDrw> zSd!4=`@^v~KLG9q(B>4GIvkzwTlwGqs1+Rf{vSL{vpm8Ba}yVxM-F^qdF2mYJWRhJ z(M9qYc(5BFY>WpoG*=!&3P|n$#kw?;Q}hPt#O{qQLn}<3r}N_&_FSoK$)un|YGVyP z-dn8fbzwbg67jOFV6x`K$Pm{#BAF8c^lPf+;^)V2b)I+{)BmdU>k`{ru9i)^5{l3; zEH~44sw^%5`??;MkN*W5`X})EO-|Q8l+}O9Z`(>j2NFO@C*sZ(+kdYb|5In>pF1r# z;?~T#;6g;Z)UCEk7eI@cG|k3bDxsaK+R&)IZ8 zy!ipi)sWZg8SGnGse3tL>~FRrcvxH$oMtf=6~gN$-Jfx6>KE9T#o7|ctl|Kl5P#sx zWzvP$Wbj%sY)Ev1D_~}mcpm`M2;ALQQ}=t7 zGR}xp_Y-w%rgA3B4}QLHLwL-E3QLxE^p?`TC{9C47lU)b{tALjg=OFEJeYi~h&gYv z3I=T}rFdD763@8p3~ZaKMtSsJ1xeV&piN?AIjRK(y$-$d#HZ3GEWLk)>>3Y&;HAA| z5msEkgyrsHhBcawLK;IU@(9y21RiS^F9EwtC9THR#r(VP`rR6z$IA&RgsIT$NO`bj zAW}G92+%=y7={~uFlqRaTDGha>&u(=)od0egMQd-Ik0uT7#Sb_0ox0ZKC)JNJLp?I zk+QNvf~Wg7R_&AfRO^Ikud@*A&$`s{;a`4`utuEK#C_XFKB}mpbiO*MZdzY`VoaX8 zHPLxQ0K3IC5k9UBB5j8XvP>uL%)oIIt1t|&0UJI0WEGAX`?9|2$STu=>O}F#HN~rx zc9wln1*PM|g+Ek+xAydPlh*b5J_B&d{s6R}_OQ7bD@??)+@uWPHgo%O+A?o$8{#Bh zRi{jxwsGiddUJTwKi68XvTm5*kWI+X6FEZL&i=J2o!(7PQt0Pm4Q6FS=FtKF=@yQp z@5uFJ4b*eUgkkHoUjU)dk>u4?wCBG_8qF4~yW6U=Yq=r>o*2G*Q#G8DZ|MKVFLo-W z2l;TW{>+?pg>rq?qB){2D4Sta`%_^6LqE~3SP(wst(%1!Wno~bu zc;QlP>XV#6!xbXFIo+d5EEM2%(G0$1gQPncViMzeY#uwORdcPi_%syl7c|1O2UhY> zS`<(m4F-$?*rE=J-d8$zoOPX(sxAT&e)W&{aJM>AQ7_u2D_@DyDqAEy#v}M-oEqAt zhLbW6@{q%y45BOqdu|6XUlvjANE(GbaFgkAru@tl|E1S1hOa6=gWVx1Dad&39V^WK z7uoZ>8$IjyazE}TSzWbNy3QaAM~ep>xEC6#Tx?A=v2g?CH)oQ@qvQL7tsbGlX{Q(a z$AF~_iyRB0V?O|sR6S}KZbv)@o3`~9w?~zh2 z&dIt^=ITtDyL(@4W-oaW?@hiULJg8Oi|Y+wbOh|4>E1cW(T~drdX}3MpH5$j*S{$q z|3XSQnQMB#IDJWQX*Q?#)7@|LvZQNt-EI_EPmB}HkFJk$QM~|sw@RPMG(lfwXqU@_ z)8i&rOd>v^`b!2=b>iK!@dg%2Ff1Q?m}&FrglUwgd}w*UYVRym{yWakE0k^QbzF_k z&4yskt9wB%lUU&^B|jl#|C{(qXLPf`m+uEuj;`D$MPwB!dv3-S>%>rXVpsl^F)XE| zY=~&+M)e=OrL^79T6rwhA3OyNDRP&B(Qm>sydTF^7scQrKsC~5Q(|Q!%$NS!m4WF7 zuU(QW>E6nhfsNK$A!m0Zr_xZRgZu$;L}YnnrT)C4?gxLffD@jE)24GlYF&_Gh#XCi zpZQwGTNwya8cM8q zclNaEL>px}y&vOVby0k6aFNiGP1?9QxRz?AB1s3Lcv4|-kpaRG|NbQU-p;h0wZ4u_ zzgRZEpy9H~*GgmQ@Fy<9u^{ej>__*%=<)yOljy-`vVYZ2peg(pfZto*f9NaxRR@YU zc(fG@7$%UQGAbIpLgIe%0J`1|@fjTd(uL5Xgrhv0`@5rp zf-vj2=l+(E>i8AKg&7z9?_XgfK_vpL7+vOx8+|ua(fx>Q*Ip;p98X62-SIhk5#f<0&BH)>%mJ@Y92u*a-1{A`8767w3@eGG14aHBbM+=8y&rs42;R>m#o zs?KK{eYJ?rCC4NoL7He9hZ5d#uaFKvn2A#=eyT!`9IFVf&H|~7`oSo+}H0m z1I(?m_t{=FenllVBE;Gz4oaH*jSe)8!VrayHn$%WyhAR!r{OQS^B;8F(eHcnJDxbs zE9a(C`jSo9{8-OS?NTSF;Z2_l_GtTnTiti_L#|xA=j-A^Kv$mEf+d$1x6R~tYk|BU zmXY<;Ei#Xl9TST@Wbq3*(O@JWh=P?wF>p1X7+p?3wW9q-P!Q3ZELCd<-yo5HQo(jR z)Co#4uzU*ugc{cCP{PrtP|JGEVFOfyD=yF{kwNgla+a@ev*_r3M2aMSieHUX~-7j*Zl@iS_RKW$nS%p#4oeGr%HUnxa~|nGSe6*c!p>FJmT%5U^G{Sv5}7z zlLjmGh0bqjTWUiD*S|`+_~hy>_dx{UDa0=h-YHREJdgc0?REJ5Q{x5*L$emz)xlrx zRKUFdW720c6hmHYcV2w#K4TQnUw8!WoL7zB`!r6lk03Zio=h@{ice+BnrJ;Ja_Df@Eh@OA=W@Pa_{0*1g z%%t(C6kGQp4VD}D&ZAT_FHi>^NOO`_!?GTt!iptQZ}a#M?`c|7NJ^-xeCdULeYI)5 zcj8)2(#{HyaRI1>Et1mAX_;}R)o8*m+dPmoJJaQK*R-Z6N}Ut_NrAtlOY|LYTBcl3 zRfsjI_KXiefxh;6)-iT40}@Qn-raz;j2$tKL%_6U zeJq|KTI*cm4mZ`b@g18O#LJ7Yx+wdOQn2x*LwvoU%D{7>=HjW6VzRF$)CAvh(qiHr z^|be1-ONo}J(sUNk8^F6F6*AT{2Wm`=9A_voYfj;=0@a;Ens%wDMk!${z`jtoH$yJqCa9NU=$J1#cDb!rwdA zC{^*b7o1aWpX)e=X%@#OJXm5t`Gilj^Yzh)B#BwLfz#;hGf(pNPX6XO0_zFA6{I}* zYNCNHhA~1{t{6EyM|Wj-CV|h}08Zq3SxXeX*L15QO!l41{0SRzkT(!%R-)x8S_J`x zaJQ~=WdT-xT)a(jb6=2!SN*lO!IE6D1KJBz2jA{q!~=b>%xk^uUqPsbL1e&^39nE- z?64c#2WsodE-J198IG zdx(X@dp9W=r+%aoWMn2(sste;af&gxg)^>d~D z*h>CFWE#u$bv?JfV80ST&RIc27;BaPjs^T{LyW&S?lEq-+xM?@!SdwZD-=P}sLj&A zd`pli6r?xll0BG{FH);SEz0luqE#fLJM38k5#Nu}0}YHZ?)K9wN=zmCZTq+!dywp> z6-?ucx+L|yo|94LhrZ4{$8mFE-K^z`RR*gK%vDyNA>Hd|pf0av9N&zqz!C z6~^~X=to%Yof&TjqE{xdOGnYYn&uQNI<%j7!!;Tc@7oF~`hVnO7_>87x$5De4|{gI z=|V*qQ;3u+_OqQl3vE#Mzz`w#%>|yVQU#!-0&Z`xqkKA6^Jo@&)(**bLRh9!XudVn zPw&~)XBG-{YEUWb4L6zGOt3R&jyt{f?Uf>`E;UtlD&@}RZi+kfDtX@YT4%JOF7cM0 z6tma*%+|M|H~CMxy3rcAkZ3gT9UFJk8rB*<`ZSuSnkn0o)Mw|}PV<-iAlsF6`6PLJ zH|A|1^Q*wxPP^1VWFGrhEG%rpiIztCr%l#5aC%RoZnDQc7^YbE?}UEtw?pv@2JCd= zGe?wdr-Hyvq4fY%Dv1bW;qPhZn<^RysX{oelxJ9FRke;owo+;8zyGSTGOK_rOuQim zziyL8zrKEl0}RsG$n<+NByjAgU|g!#JojV>+mzvFfQgz2Y7klM6IJCD*r_T*h_Y@N zE?qY0odJ@Zp2$*}A|j16G2ACA`2%dFjtNmzSo`UGAC3$&E4D@k_?PLVmpk;o(B zJ7U=Cd)wJt6S1a##%kYM6Ol`y?&$KbF3B(Y)Gi9rH_|++UYHU@SexZhg{~&aQwhpI z#8^p=Xu~W0v;*OZLtCcJDWt<{GVu3IX=)m9hUex5i>5hD!^*-NxU`@f*I8KnD>1*< z5W3E0$=Q&Z4RKt)`@^gQoZ3%ze_MGJ&#iYhM#)132T!rXz>jD(A18HG3Ox)mb%0r6 zoW5>sH_N8|3}jMkw~n>;e)#6fWK-4RfE}8zYdqPjoqpqk|L5g4ipW9KEKYD>3hfuu zRaWgRdnG75eK_drqceq*2w*N8*?lR91iRz++9U#=){A z9AcK=bM@JE9?J}*eQnugo1H-LcI!lf$Z9w-TAn;GJAc15-D$UrNg;bh#R2z^YY#Un ztvP4k^1I<>GOV0kI(7d`RsJd34m67-VwjNf(j-#ZtP zLQ0g=79+=Q_&M}mCcKRII~31hT|Tgl5q*>(6Vv;^!6so%K*tjl@dvMdpgZZdpAI_q zXe(Nd+1Xk~xOhj$iOl#|vwhhX&*B+FswbDH|JOqDOdSDl8FIk>q6O`QGiRGLK^GyBavxAjGS-taJ zBNuQstD?&a@~E0vuvF$#65%H+g5JA$N1^yKs^91R8`a&FsE*Z)4ubl_NSp5Yw|n{2|2(`_~*joG$UBRJBB~>_2!;Iv6f=17fRwI)q>`M`K?4 ziFGRq_cf^8S75tVR7~`V$q$s7v8rQtZAZrYT`GUQP9&$+@#GXPbjIee>_|n&oQ};c z!s>_6uu)D%ptSl*6>MwvDg&UT9U?jsqVYDEUUvhX-*RuOBBMkd)F^R@9VUTO^szNtfqe8s7vG4Y%xJ_QPZN9TPp* zp^a|Vac7dl{NGtMX?8W+zFDrt4sK;mGw<8lMsp@L1w?yy4A;C~De*sK4|}A*J`;m| zavd2$5X5^V!+IaJ(o=a$JU+N&c@wvZ1Z++YYHDhqH&Us6{azJkq>MlF=`P9GI&oNs z6U3p%Y$SxEVX8R1x7;6nRHe3XkTBqL{9|sJEzr&QyUTkIK#ND(8_I~qN057aS%Uim zSTidbo(ns8hB6M5(kB#-T5NJZ5Me-vH{m_?CLZdsp$Ty?WBvrI1SV{`pJ&dHYYKST zq$B0(_Fpf&jMtWdw~c#DShA%yTLzl(wda+Y?M&0oOiMmmHnr%lQ}A?S_uGKJ<=g22 zoNn0@Z;8KdgPf^$)+6VgM+s>*L+gbHs!7pa7;niq@9!loPQ2#)r1bdYzFtFn$r)Xg zHM2{ZW6Jt(M;pw$v3~=xIZ)}vg;qOO+&^u9=EqGR>~Pgi7PR=#q7Ow2V+o|Kv?`ME zTLR(Z`eA-MYY%kG$_>(r&^WkU(#@XC8oTiFkJb;Kj+X}3&nWxau87ty59Ynn1x3-V z!0F=Jc`>+^J{;fVdPf_)MbgKIMCQx_Gt?80j_tF!q8O-$da(yG$l~TNFUK()Q`dg>OgBl_+JE!VnM6hT1Jw0 z8b*~ZA%xYhMO{nKiX`iDdPi2sJ zO`0q=Mw5G9VDMIqh9LQ9_w$KJ_DT_c(Fd;#zP#)VQ;;eKK0e<;bPsNPxP8w{ z+xMO(64b}yGw~c_iFc&kk`Hew)CvuDM+oA32b(#K-(t80zY;@0hSjbXm3uxKdl2#D zk8< zw}fClxgXksd(YXVv;>F6jN^83(%&$R$V2kq@)UCHN~Mmz0hVZ(e5{NlT2`U-(J(a$ zfsTNuQe)7MvE%gX`7-_#=g*irq@^#~7gf>-5r^j>$L=nf{Dy_nv|}KpS=*43rbLNF zInc5c|Ayxm3B;!#HOsEUV^*LsEy($uZ3!40HmtdOJfnHN)%*)2yM#$a5~U&X;#t}1 zk3RXDbws4O?guGXIz1Zo7A%6>L!iuZFF3s4AZ(9^2uYfGrDK!&0pIvmWA|e0QxrNT z_kPoi_&#C7sN!Ka8cq?q(VLEl0J-vmS+|AoU$0^-4Cy?HO!c(4y&93(*r%4)L{rrv zjaWtybgE6K;6aT8qBK?j3j(UEp3AgImc zxM6TT@f$oOM~fNg|AL7}^Z|kO#r#=b(rF-6L+f$XJ~CP@$0iOb*5J3M&Ul|0#&D9Q z%B>qNJVFKwxX#!O3`U1mM+^JRES+9;@WXyy62)Ci0MCC{#=$9Y&5gmtFGZ7uqMPw7 zH!+vN`~l<2%ZPXzPp)wpd+Uc+`nN_rI4Jl;hOR!c&ODz9GAG_AufT*F%|L|fNyI4j znV3kmo|wnmpbP0mq@`PHA>RcU?!Ns7RpUSid7K;}iob zwZF@K%g)>`2!ZVHZ*cKXEwOoDMJHK?p;-)FuY^&uLXlrb-?W*nGwuAGO6G&O$K7S% zc;63irQBWz?}TEMTI~S#`&j%Ryu*F~fBxRELv5_zXAsaLf8`^;?olNuR#nrnza5&n z0Z7lH{f2?&GjNv`D8QLd2D%*)(*2-Q8B7Nb>zId)w+u~`3C+ho9p{+zUMPPRnV5K##Cw@l|;H#Zi@^Hez^MJ56oQ}N~kg% zS1UG5ku)+gQhhn3Kyc%sz>B3lz%=gd05%Hs)4VBkRS(cQMgH^6Rk8P%0azn{3xFxk z*8tV@y4l(7t@itV%L545yR$JGXLk#o(rwxlD;=7GN{#Q~TB08jKB`q@6?on)+RMBRWYhs4udh@yLvEtcc2V@4Hw6y%o*CXuQSYqr z>&?sd(T9?-qb>i+lfomKeEOfWEI?S@GV?3#WgK{P$C9awTF>e2jE?i4*`_)rOSgdnd*liZr4h2%Z(GMTiwE5PVvtl9vx%Enysp^#&!$5o9aG zT^XT9XQDWoCWIiL+7jv-M*5B3oov*794&_w0eoq{1uIu!+OqLaGm4UgP*ZmVZQ@jw<^XGXDq1|h%uzNrgq0gw1wwrM&SL`F z>v3~y%SFUmIS7VyYS3~pPZ{o`&G5J`S+71#dSIFj2IwNv{E*Zd(ueHF3SCtYH-tnB z0)eA@D|;mgojT=?)4 z-kZsssl9JfS>knzSZwvNr z?%vib5Hp@k^*rzXQY$~g@FUH&%aL0=K;Xc*y_`9_R%8)Y{gO2Lt@#tSO!O@ta~+jp zBwjif9tpeg)auvdUOh;gP0Pa8?@)Pn$veh_M@OZ%0@E5wsV}m$wuxslErlAJr|OU} z%)^eoKv)pu*J(%0GC_kRP6)M;J-@u|?goZx^gd1|AZ>9<;c@z?Lgy7`gdfl4xRTv$ zytj6AqL;S6iqTm!u#GYuZ2DRA%JOUf_#<+T2Lg(B%kFHwuE@{)z&4vhivEqUsl>zy zO6+KX6l$B23u~v(0@--FQL!}ms$`}H2TRS$%7(=5`hCHqiivcLi=QW}?p5Z#8L?5i zr|s2LGj#x4USesko*uz@VEN0e9HpiXGHVueY|3V}(I<0O&wmXQRP;(oJt8zUxvPK| zb_@2V9uv(y-$NWtkjs`EEL%T(A-09I#~$0L(<-sQ>@sZssrkJ?ocOprj#Ht;+by3W7cF&v7ecWqU7#3vGAK&NJr5=twq#7{j_?HL~+nw9aOtTmG@C2&X!5n z@CMt+@K|iDyX&TDLV^m3O$zvu;Akd(ubs`0vsdonq)o1+ywXICxb(;U4`S8SkHr%2 zKF0fc`whuW**>53`YlG$QZp%D?@)P+%?9>GAEMHp-o@3@P%1TA;KHzG4J^BK7|6d= z)EHnYL%M2t6HyxRH`+N!GhF4T*Z1eNaHG|I)D}>V6*JJ- zF4{@mHEO)$V<+>D09eMVxA$ybw z(bO^_wl}qTg(YM|>;`@-VYIbn_UDly#`Py)j_ON`E3-I^x@X+fs3@z-ozE@c#HT#4%5 z9IA$th@Xd@7y8Ka{lGQ(IMCf{w}Uf(`$iR0uThb%jRyGFboS@Ij|+x0Mo81CMC)!W z_(EZC>OVYMNBV=PmWGb45JWZLK8iZhh{$GOz`RsN}&bbRj>N z`6k6#^mfn--E>r3PKbETCaO`vU+4X`eDAqapV+@oNbkQPqr&ussLX@3$ClG{~^ zBK|&l-?-CoXGhTqUZ7|k12Co;DX7B2t1_{6;_7;Ehlc1G9{%uSF1|9t%#VKyYY50d zA45jJnOhvPIdQ?FZW1wdzgdm4wQ1b&y+qIP^(rugrv1)iP;ih98>Kur6vJx-MG6va zZeI1h0aWCUOWV!QrL`N$t4Gj>lnGK{vxeVh^BdJ~RH&xB3-kywG*&UN^X2w|HI}aY zyvU=hWhRvAkFrtjrshGAl*tENHu9UT+^!3@%rGkQkUvhoPV`CBYLxhggoq^%-^jdMo=nK64Yg5$m(5846X}15(0Rb0$VEZ3I;MD25^X^?S!oyzF)e!+t7!`czwNhuOod47k{>hWgEQb40pHq?50GK&?oh^ z*edth_#(7RPU#6^F)Eh`F3sN$Ujr*TS?=YvR>3MmDK!0aqpy5%3yevfYsTO^r+9Wgk!=y~$_S3~ua*no@Szz9k;xBpIJmQ_K;F3B|q-Cf{Cimo7?AjxN zN(OfV_pY`G=Xg%Ql|WSVs~|KkM<~)a&M-}Nc%gLZGM8Isfj?1MpxIBYd4I`ZUVSOJ zdLQ!CXBWIa%K8hZ&pEw(tk}pyO!kha%wg9?mLs&T?IF&)rpKque zMl;u-hINi!%WZK-TH2UT!Lrs&rd)-D+-j0(AIqeQid8o}dr9BIjE6Ud=MHL;hu`Ty z3X|eSK$K@7QYSbgyb@BRb_g!-VV>TcV7F`;xKF|}>?s=Ysw?iT?#b7V8$r^D@2v_I zvvVdozW%}9QVL*eu(RE_ER|POPdW!3UO&To$dx?c-1DeZ+es0u!#%Se(0V_#j8+PM4m=os6QmQ{ zhddDgef^Z3a_;)6=wM;W6x?XFGmirrWLv%*r0J^m!bslzhc*_s`YzopKsH8W2 zimvaBssA;=>`A{2dW@hLT>^Du zrr;@*GCzosDQ3x~`Ox&7h-U08PHZhle8r%Z_R_Lr)z_aTR#{`Y(KgA1b)MJb~b zw&IQB=7;rnMei^V);Z6*$Wv&hRKZ3{d52OojrNun+J|f6HS@~rjeFT@b@q#^gVZtE zMHv2G$^d7X`!Ce4|9gs7Bh|PdQ804LiyWKPR)yQfvv=89 zPZ9Y6lLwFTx;5FD7k9>2cFh(w1KpgM?<#l|ut)_uWjVqGliycpvwTQ@)fJ(3`~5B1 zDeCI#f%P|8Y~6zL>L|c-IJ?@|VEQmfjhnHisZ5Lm{kv81Zm2ia^K8!B73GX&3n?T5 zX6cP6jp>UZNr@yRB(OW6J+c%a>UC8*5lwAn{frn9Dek4}?X1^@2Yu;;4H<~u+@{ur zxNT!Bg}WMl&(mSq`bTjO<&$GqJBYV)@lZ9Hh<(RhRl zspej~21`plHZhoYD7Y~54x?+i6OzTI+iW93-(0oQQDtEa?C*2&{?WH6g9oOZF8hlN z_(sfI9EX6BBz9gPOBP;O?R2T(gf=pwl{n9ge~~h7l+M)R?d@XWW+%vbu(I*_m5S%m zf?tMKOSVZI|NC(#su;I-Dy*6xQ(lRvP#mnQeE+`1qCm5mcPHfOPVS?bR(Zg#N-Idd z2vgAw(do&EFS{-P$8gRrxaL3Ro!f9MR=>eN^oW_3@R@CkFle+o1l@WtT^I;(4$OnE zg*U*zy#oH9mbxQGj?8SQ**D5&9IIY~G1f<2=TGd5L+|g84x5W`$mj{6hVNDSyFVWB zCudCK|M5nAEJ-RV16ge?h!u5nUtJh#X7wO?@+ZcFjhAE349ji0SxB8xh zgqvR+UA<9Y7E~=LW!fGVvVS-Zs4!->yy4pm)rml$&ZV3PB1Aw$d*+|(&}NrD`=ZGG z{`>l!su6#CUVw#>q6IO|@&m8g!QyaYyEuX`6K0xPoI2(i)7Ybp;Ws>whh1YE^Mp6Z zuD*V&wRr#@-+}%3a48!~+abp9(Rim43%g86=gQ@cdv40<&G)_M{=1!9Fz)dV`+Z@J zugw0^~FT0+50%ApNi)a|Sd8Tje_Y6v5;8_#Lg6KV>$@xPe+RxMhng53m;zo-@J z9SnTA$u*OLeTvzt@awTcUAKQlh@)_+$V!q1`8!rZh3MEC_9Pofb3|{RLs~%^*DctC z&Nn7B_{Gjkf17W!x=^$2&4*S8Yyki(xeX6oK8jdvvQ>+xn5VJ2Cd1nk5?Y4ww|zV7 zZ2X3R(n9Csiv_^9n&eeV!P8h@e!FmQPYl&iDAO=9-_w`2lqc;vIcDiOm@dn9nP~BF zF<^^+--048MAn&=?TF{gG>%4dh443HT1jfvZc^FDn)~1KhNM5kkK;zE6_GbNGhZgO zPkDTNJckXMg2^a5sz&6;cg^S4c_Q|O%~K6H{9)E7#$NDc70yQgSLx!(wm!VpkKfJ_ zrD&oqDnlL?wN%q~Hwt1KFQjqg5?8LHu!s&qS2;@4Stod|+>u06zR5zipBU7L{E?!F z=cZ_v9reh?pujjw-$yvo(<;--aP=_O>ggnocM!pL7o*fOAN0m4Z(h>)k}cMLlDuYX zj=)2e8`@6RV$UBXqd3=ZELUl;;3W44Z}ShHEAR!LB9HHcP>|vs?xBBr}!Ir^*otQ zzK9$iG#EzXL^tnRAXFtjcFPG;zO+4Yq1Vp^HjJ~+;xT2F06pyI8k~ayp2t+)9r3wO zP+RX@&sw0y-SY&{^6KlA=vGmfy6j}Rh)|vk+{}BOF|uG7FB1z-o}%CX;ChU{PF2?G zfTgwLmL!^eltFGSIO5W^xylwSv?@p*6J4dLxh=biGVV9AQs->^~mBkY*+N660rqn0(ndq|%QBtJ!LKvEoUeT1LcM9*XA$|6lL z+9WgGu%WN8BUh-kw|OK2Vn9GYdEKP!m{T0O>vOm}eqDc>QQc7!YkJ`n=<9OAHc#9= zUm7RJ0GI`rv^RK{I%nBeT`G$3uk?Za$&R13Ta&bvfX%?IPY7CRf&WO-sjg4B#~ zrU&W5^)G&t9e=&E5CTf0+v9ss&COrb!qvW>u?7yGTDe^6nB=Fh0Cqxk(zQFl0Z>eA z;www)GCHW5`O%kIRnjC>rMal%&MCH_}ntRvpH|I!0xc|v}zUwGgmtHIFg??UdE z_{!9O{WtVB6}Fxb=9+-4woDq)fx&_0^SA6iJe-Ab6n@Z~B@BCvmqPP3+&K;p7b51C z*c^cls94%bUDT{>%q&y)yq}_(A>3M5XIn>i5zp%R1AKcIxxWMcDb{#A3UQ$7dtH6s z8p68i5ks-WYV#e#Y&W>073j9l*Fh#Hh7CDFw}GALqW86?dL_=S=yU9&4Ra+Q2y^j1 z2tt-9{vssy(MAg#_5`t9e-IB%`h!O;2D|B}eM}m7k92t_APqMo6Kras=K#ZphPTbG+jR-r!2Xpj;*;ueU(bI0Fy12T%}QSEJ0&H zmJ&=DvV|qTPLR7BGA2oTj-y0Dzs(?{o+P%FOIxncn#@ZivnoCp;4b-<2ISDVr;;99FQ&N?x05F?)DA*M=c5QXLMNFoBeblEIJWBU|*Sl z;7MR?uvt|CM~YfsLH}M;mmSr2e3^Hg@6Hp0)^H@2S0Wgg5hfFSk+lu+utET7| zP`B5jiy*b?n?+y9#~8VEI4OD4dk1d{oeF~dLuNYa2s8E_Pz7wnmf#syrra4|5_tXO z{YLXhQ(dlvSPp^W$pNu&{K=?!k7s;KelGle>Uw1tO&y$_KTdYMFk$KPBwFKM<68fR zz4r=h>TS2ZQK}RXqzFinE)b9|MWP^GM0yEDKzftjLJ*bSq&ESP-g_^RE=`00kx&x^ z=_E)AE$=t~`(W+&Ti3q!{>nOB2RTVjW|HTc^LfTS#&3W(n{*b7T#$_`hd#KhE3=GC zt=6Xe6F|=zjbwsW2knM0N*{tL;2ww3`Bd2a+|mVnujZa_+4E*Zo!eSIf4D^|)%Wqu zyOJ;PDb0C$c@vrtAf{}F5s{oNgPLNJJd##J~hbDR)!*p9c1a~OWK zmX}l9UNPjyTnBU7n+(P)i4P|_M@G1~9Q=4#)myo%-doi*dwF*)U?`U}(VFs@mTmjg z$N3ah?CmfgVB%DqXcDVR{n&n$&E4&$+ASmA@C|q??VdJT47IM(7&2amSL?PZb59%} z%sA~2xZ^RtILYz*ubrH2(Obbk-k+sn3FFvt^hyFY6@3jTDd82kS zbY`@{=tYXmAAd?&g(kb4^FQkW`}<|k2l%=gJO?KwP{_CBgjM02T%IolG5${B%i?w6 z{#3uf3r#8WvWX{}Je;r5rBT(s3zE`V1PoJgqT}L0D|Yg7AW-PGn&POrEb7Qv!4hP- z@EtZDhSg5GMVJC+zKCHfZXD;82uOe6O^%}E_WK_z!*4ZZNfj5M3(Olwqg)ThU-u5{ zeo+#+a=`1jdsPB7(UEBPB6q8aUoJA#0u=QY74gN0L7Bb|PB};A%CQBa$eP1&_`T+W zMEGr~Lndb-(ACk;a*4VUca6q$Jl0De4jZXU+rSGg zKlG#8tU&G%Xk>|yiPjnBiHbmOGitf>Pp7KfQ+oZ5W0>PU(V5$FK# z{GjJfrXnysQ7ajx*PeU^B={c*IDyd*HfdjYNE~bYt=W~>@MWidxc)!`gRbWJ7Pf1l zMg3XdOLDVfL}`1xVylTz{0{rQ&oyhJ%jHAqK6 z&BM8Td1X?n`s@Ci+LguS764D$bhw8ug3WSL5%}?CgE{*^*=87p3e7BsfR2P~bCT^S z2<2|ZXm1q3m@iHCbjo9Ftg9$@guvn|@9;?^XOpBmK`VQ1l$+pP{paqUK`F^jF^DPXY2myu2Y*?=W^?-cIkN`eEOi+(C9C_S;PH&!_PLk zW0a<3ZqwIA@U^sm5z#A(t&i3c=oSVrt5hxq78a_unR;eAMHOjT`&mm<*=cIunO+TL z6&)CzYoC{0-Tm8t1U0=bzoKO-3HH5~ebG&rGd6yGX2LY)!Tnxxqw{yO%T$-s(cHJ! z8^o{ysOR+;Mb1lbAPi}MGg^=Fv_EodUVNJ5=l_gtj7K7&{2r6T12scOAECCN_OncE zw9@8U08|c0l_h--9G9uc`}5c(+y0hN>U)U7kIC|$fYz$q(d8`|!@otVo zDo$9t9kFQ8lz8+5^TRJ=#iBCXmj0dL=-o%^dOy+OZ+!i){jRgG>;S$xxY2sxi6qA1 zkl005*zdP9^CL~rFIpd|-OhU-zEdP>j32N7^)UNBu`Afs{S$1MMSTwD%y<^6hw+Hz0K;SOAutyNARdOZP&rIh(p?q)?9!#@t-Urn z!ZJJC)bt)gTU(>v9EzeIS)pr#dpiig98E6$(7!kK8ae*`ug$w*qdIL-jN%h5sa*Hb zXMZ(^q|)9Xj4e=$+3uwy+hp)dy(@D3J776S@5-0vV%(W71dF>^BeRgKZ{Bo+C@r$@ zd~N+>d>+Z;^jX8sp6Jpu5-R)^FRao!4OJ-m4^^ivw0ZKuwfF>+kfr7G)?5s6! z)BI9635@;AEsr`){Oq27n%tq>r>Q^oR)hTBcXr__QV5;V=)Bf4 zDko|-gIGi=k?AqJ~qThChyDB zU-^3(zq)cso=3E?@6W39|J__}W)oXc{|Bg=Up#_~0moZ)xWi$beC9qg228)jaeH3T1YN+W;tFae+;7Y|-(Oil zQCP{%Nb$=o-?1r3Pmi4Evk<6*0lhZ5G%9__UP>V4LZ#moWfaLGW`or^&1TJ&8<$ud zSByW<771~n+e=vgRI1@L_Ib0xPyE)fMMK=h-MO>g}MGi6d>^IUgY$jNTarvfbC5{b=R5yayvwwb6X z8a!`ngRZC)l)LQm>F%$XSD4w;i1xMDGMQ0$$h2*FM#64D#j(a6?lpk{=#h`j?6!*m z$>q*D>@_WekhCKAWFG1cWBbR7kvxTU!*vV0r&S%-pFL85Yw({pMl6@N^|rJdhq(Tx zgu>;BAA(p!#?T+^qkpgrgf3o+z?NZr_zoOofIu_9Hse`1uYaW5Z2t80uenB*$WB3M zhQ=Jv(a4Q@!zM{#&%fAvo%aGqZm;t$&g^!a-iHjFmwK7EdQr|+sxcrkMXL817N-wp zEKiJ$d!q&`F8!~b<7(lRuI3~0EmaRa7na?m67(@+GqdUaB6>V)LhrioH`$2{#n_zz zQUCYh+Z<$g&b3h8!A{Hl!$BQa?Z^{fIlBE`goi^09TXA7EtRO}aa8%W;Tl6E!zs~A zciqenkT%5@iHByKmD?B)4^y8#{VMkA! zx09ar7OM}*I6?jH{DSda-(H8!aEq|L>6PObz1NXkR zHGS4^QD`kW^!4^mf!6ipYODGqw}!%=z}Zjk`A(rmFu!N6e&Jws&9YBn%VJ=2!pEv3 zB!PyX?2a$tQTmN@)HbDU89eFVzvvLP+B8GnJ=FNwt^#IO4Hp2 zcI5yHujqV6MS6)JZ8_nQz>s`koj#W%p~j-}2KtQ^KbUV~E-DEem#nNaCkPp7=#dV; zV88mGrLxyxFkRZ^eZn!F$<=DU|=szC*N8@OmOrog5}4ssYyh7TEji#G?#Vp7@$^_;$##Lhzf0n6H7q>WxV?jfH}ac|L^>DaGnotFduBTLUjF zYGDJSyKP{8G{HOUR_?7hD}0#&-1d*e%~2(pXJr=e4JyEeJ_fQ$kPyaHpF=wDj7L? zvY6YFakA`QBegI8=T%3h?Ll$|mDBG}U&TZ&{cBBl-#E+{;%Eng9mA929p^zwkvf%D zr6so{MnqoTh##rH`yh0T(U5-V-7C$Taa*f8%*!D#kCnD1psB0wpS)j6$8VVIb$%J{ za4_1Bt%gbyA+_L9Els0s*o-{PKHO}5^OjTVXnwX=&yJa1F-1u58#S|IXvvl0tn~=T z6C7DdIaSa}7U;N#|Bo(o%FgaS@1H-)RbnXqc33>cQPbzw(l90bgYJj2(ctDfrWv*k zKqWcO9h%M9uQy)ZBNJ;rFEO(aNN+EsO@K?Q`&>Q^lxL^andg!xRFzp5Cox=rBTjTw z#>G1{>1{}xvUt_0Ywj1aYt?hzc`KD>9^#5GIdjG7Sznh0uEOvj5J7ey2D;1bHc(d<@4dhQ+-R1_$}It)*DM zmkXnV%FRG^Yt$=OEL^F4*qcxk?kBn5-4^aWRMYDXPtfW#9e_+JG9D})WoW-hj0mOjJ~N(MOxj0W2<|GW?Qn|5Bz$<%-Z2O5C;d|f1CH|CI zxc$9aa2~UHJ&q&Eu5vrz(+;cq@huPnhZzj4c z1XnoT6Qtd&r}_Zs1bKSrf5$}rH*)L0!^LNhZz#JHYqzHtXX-R(sL447GNgq5cvyf< z0L<0LlnuaF1`b1%Ghg3HhM`%3jm{RM9pF{oCNPBcO9P(hpF$&msTXl2tQAW%2{@u% z)q%1Iqa*@x8D0;tG|dBQ=hG_AD{@_IjgTO*EP<|ulMrqU#@{YLt6%Y$gRgH^hhf>l z{mtcHs8{i7&0!a$rodE3J}iRs|9Az`wUs%)qm~ki;2Q?^jnh|jp zY)-K}dznZu?|hn_jPzGC(qJ?FOv(#A2VXJR4dnP&Frbp&w~U8Ttw6GUueBcTZ*=5^ zzv|mRi-;%Qq&}~P8J)vCGylE_tmqYhn4+wghS&!?<6M|om%oYmDYV;rN*H9=v}f@C z{-e}lGK|wfJ9!!-^^y!DN3(*aTz4e zwN6@~V~P!SPI!H(suuEBV5~Z$R!A%a@V=+d_$TR4?aLOM1twt*+SX~K%z^Yq3BE|L zW3~+8HyFFJ(~mKs|4t=*FQ3`jbXdjnhMA?>T#9uWcrEp2^lqM0%2I2!>o&t4zEM zOeNUg(CrNXrt%fK3!u0G-u}6F~5}Nkz?S!1TTJs!Pk)z$t?wXf^K~RjUVQadSc*G#=@y}XCNzQ1#<~Uu1pCF2Dt#xxvlefO{ z18bAk&By`v_(kP3$DT`V*h=OqrIMJ75;69mpj2Hc!6T{MYWLH)(4^F-;%RltA?|cG z_Gb=?O>_}d9oJQ-kn68|a3?s?XvMwP^*FLz!In8U?sQY(bW(?e0A@PPzwWEw-z0l4 z%5vuXlRgfsFKHX3fSTZn`d7H*X`_$#`2fa=(mr5A(sZ}AkZvG?U5XHdKMB*)6Sy|b9s_cWrWjHxUV ziZ2e5gq}~=9_R7tKaaJZ0eWyru&Y-LN#D$M2kXdoCGoN&sOR*~cZY)Oo>VmoYqh4V z#S5m``?bg4Z8TnHdql;NGC0Df`%7)CrWP^3e3d<_!dEw7+LAM;pHH4WEX_S@kqQ@X z^w3+ZY;r+50zM6rZ*x#t+HVR;G|n^K`9cWK{J(=DDtkH33m@r+P16^D_b0Ep%Z112 zwM&LZSxdnN!x~Aa_R7#bel1}PoOc702DzsXyQ861+SYuWbSedT*uOg2Y#tjx%*6jA z`>HmwEaKz#bi9!HZUc5me%Jyq-58eYXB0mI5skF-72=n`IRt-YK_5A zDC+pEtui{-$1%^^waR{4T8IoV&AH1>G|n3jJd&f{_Vp^~3*$ykiRQ0pE~%{p1^QW6 ziq@0vZY%L{JW8e?vP;#oxz!rT6|JG=9{w>rK$L_kGuU;`ujpT?H)?5iEY0iuIX*PGX z#JQ`n38!UOZ}3lu_>l4r4~}qA{sQxa`69arKa`|!v;g*FEuVvHRm&rPw9U zIhD{B(Q7W$Bz;HoZR}uxx>l1TQh<(9${7(aQt7!7!ucT8{$BNn#PGTh#$xAn?bqYx zw4ko8;{C=h6J*mA7CzLKC;5CJEgl zBgFZj)?+Ql^aFc5uBPjwZ9AVzJ;^7QhSbefb^C{;&ARd;6xz97RS+m;!8 zQhXC>(D~YOqctKuMcX36GR2c^Jx4~AA@$GfI0v2lbgJ=w-CAfQRl+uo8l7QWbnCA| zuj5#4daAe9_HpMtil-dUbLs2~JU!%dOu}oqu*fL)1Ex)OdTs3xc#F&{x$X|}>X}jQ zvMKH~!k#Oo5H~D!yP!?1FG2T3TQ>(toCU{(jDIwgY#e-e7^foLnXRVQ4Q&ALqC#0J6brc!wic{ncTD7 z;1l)T#Q$4teei$8)>Gu{UQ>3~qto6~@Vuunt(&aF3(7{ftVUTkne^#^2bB2Z2CZ*@ z0RU+iwV6`ftNNX7k$f$@!cB~mJ?n19Z;YR{ADB+M0xG76q8}!S*=0q7sZ)CdI27*T zvc;bIwIvzof}VTb#EW8^6uS(Q8}Fx+5(isDD)!OZ3(L|tfzs8?yeVM0n_!cK>#{=K z)k@@~Dzs!$wKP3L`MNeXwtE&X*ey7R52IJ8@pjl%<2h*H=@fb!qHbXc7uK= zBcFK&^1VYMNZT>U8(Mx8{`Y|s)1EhF?XAbQk?nO0x8yeTW9_vU;_i9a2KV`P@;a%nzyz77DtnLK(C&{U@@ z(5L&Wgkf2IoNvl?>-XpRuI5>fQ$0leb!pgIt`)^~5sY7bz3Cr2Bx+-6zQ~Lz#4+|_ zh4<*YD$FKpxPj{vlPcYNTL%Y$ZqE9EKDL4g7zdWDY^~idl_6*@|56hdA zifwnAJtnyfmpX1;w!eGTpvKI68hqV;ES9MBs1-Xo9|s(w2o+((<7L&dr8xdK#?Cz6 z+$wA&$^%?gL`xr&0YKOREIcW3wJK0|zl)tkIar#lEMzOk%U!8T?WA)FmlRo0FZ<0i z;=-(@3GY|z+B8ZnZebmmLszLIsa716^;zQiglWc|YL}Nv7DC}z=KV?Bq8?U##L{z( zki=dPL0}7XQ83+Clr4NJQe7%JKm+&=83Ii_WnLr_S$=uPl9zk18dcB+AE=Ar-~uY1 zpMVGDgXY9|5Nn;iEg#0ret%D38_)jb@tT3X_@7fqVRhMGH zCAcmk9;LGyTicBn&3Kc=0zy-4aXemlV~G$>n9;DKpv@M@jUTjewRtmJ$DY@AOlVd@ zMjk;g#iq8DOE}DHd{k%gCNEugTTvln7d+d#cz*b>^_?pNtZb~*C4M7w0LGcWvZ&sf zB5QNc?^Dm0EF4#iF+FpJYWgz;tsAFLV4j2t&Q?-*-xKnFr91Nu2r)$pZl@cFYQ?yo z`v*6)t6z(3X*l}#rRSJ<|M(_+y^3AMoPAURp{$nh24*^XB6)W0@dLc{gJuB_oHmT! zR!c?>-<~H*DPy(I>VBdnUUF->HW7Jv?*ACS8ub^-WC!7l9S}t1!lk7JUIJP0xe~{R z!o6>DJ$ANBfeeO{Fbv^|%f;lwYt%Ql39Ok09Uarhc3J4=Sd(#ZYR`;ZsSsaQ;lS9z z(q_kMjFMOrvf8G%zM-vQ_Cc)RO%$|BoaCVc$vUsMS9o&%A8-I+-WsdrS`f=gCmnVl zDuDwfCWX~nu}x~LA>;d(bRPud2iDTP@#-1l{wQB=IpgC1_ckyR9fmQPxS z3qqwEq9DyOCW3Th7$;(Ix?tZj$0o{K!Yg&twsEU+Wkt6ZjAPGT9d`!ToR}!Zm^_8Lx6HqI+>TLIK_?DBov1Fh8&ojy>yR(mt$ z#w*v;brt0C)ZOj3F2OQI&Q;D$2S;@xj%J0au8i)r#UCO`?sHJ^w1ml8(a!-G!bRVF ze-KHxa`#50*Y_vUYc87uyqz- zezdaR1FCdAxg9H5*9^}7&s5j{LaIjxn9+$KIw$?4)3~eHbc^0xlV&LG!m!b*ySkQf zy^~oe`JL9=*Qp0>it&DFhA)M@yh63&KU+>8O}#$>Dfc7L%VU9JgFo8_#Hg10YRuHX zPBNq}Q3V!4Ae`cQVpPqdJ3pKF=_I~&Zt5~^ch+p-!`HH|6l!Ez)@kWYcUk?vbXrWl zY3&ke(|m#|OQre-vgd%b`!w7n6YaQ&jh!1E^C)f$xk7m&4129SHnko;d*;@9S=|#5 zCi^=m9u>L|-)B~;cN1NGp-U0O>5@q1gwpf39;1n8Ui`82hjHlY9_|&s2uBHUT6pVm zGN~9N1b-{SmkrRTc7j9mliYcR|MF&XOoA~ z^VQQT$Y*8lx|BGYk!U4$=yNPQ4r)hD5Q&k}QPIr#+ecvS${fwt+~16*(m-v#G0`x4 z5ixe4`eU-cL&MiSOc@VCC*4{JG%?S8g{{t!jghAK()@QVgRY#VxH&vEpg{2!$2$FO zFOHeTcXj20rL`Slod>;VV%HC^Q32h}1+r)91xuOZs%KpVB06M+0)uFrCxLE1w3}N| zmErxwR;D$|N`G5_A$O`i$lCc^j!xFmz#i#oT3?N;Cv9MoKHf_yi7d0yx&BHSmoSTP zSkc%-G{@v^rk7ceg_lM$y^xt#?|k+2t!gNbDsM`_Ikb)mapGm!<~rTAh&xAVf-_~; zx)0fVx{Wh%&q!RU#RZ=ykOB5VBJ$UynyQRCtH!)3(;T{&DqBjj$ZqK}bu^8(c1wb^ zj=XlR>+lYgYolPnU-MzkHTPA=;2_OPTK>wXr znxf-aO|d>efqdok|JaP3|K;Bpnr0kNdgqVf#Q67r2aNSxl(^gK^DX6n*res4?d(|T zI=rcf#5;Tny5(ciI&3$7mDf6a?aZAu86R0Mtyo+Ac+nPpOiS;|$#|k2vaj^xuloG) zI7mT%+CIbUewCLeA#z&yCW+IQwHHmtx}5bhT-d%W0AeKyoa!gA;h2&tx0&;~GEk`H z0}l~q`@xCI`g5?$-%Zq!S`A;f_h3m!D&>Z+%gn}Z2z1p}tSD3U!t-B5G#z^kCXrX7 z*F~P)2GCXxek=e?-K{!gv{ZrmID9d{A6|K!Vn z%m>FZC;9odYS+w*(gM2@$f%vC;-t;npB9ZRlM{ONOC5$L5{wG1L^UmZeoVbHI#2+N z$8YcwR5r7F0LioiMD43f~{F>w~-kCLT|q#>>wD{Sj<`LhGQcO5{OgyZsLzy zOW|1_GYo9&Za~+>I#}YjrzV)CMeJrETovbEgbvjo#*7;vJna#OdcUOJ>fCMAppHx9 zlBgd`x&8QuT4=xk0Q4gv(9Rx*h76p!7VesxOp$Js-M0RmN%Lueq(Wb&5&Mkf&(;(w z?vx6j-+5Yv(|wjdJg$n&+9hz$v_PsWtT}e4D*_Hg&G>VsYn`2Wj{{bA7OiJ{1@Y#8PV<3P z@D{H>f*$ReYXNrg1q(O}XK{0fkkP$r!jz)k`zylE`jk$@LVvYQKm*lzW)SAuWT5RV z*s8+Or)`izrRr8bC%(lFUBlk3OCn|~ zR@U}DR9)L|g}05F$WxWunr!pWd4Cvd6Ram`r3&-k>MDtTWLK0n z>s6g%S`TSqc0FCSmi74)hUXLLucOC9&`B{+Ka6llf(-bcwu|pLTb8oI!na0-PI7<$ zG30FqiMnz6c9F)1b=sels-g|RbPpTI~o7Cs3H|u*^|FVK*ZoMjw>7cM5Yhcl* zm?B~AD0gA%)QOlpIhm00H=dS4EG=p9Bnr;b|Ck6gBBIw^yI~#6A#mNS7=}p*KD3&@ zQmNjOzwUGRXu4uyrtau*8SsqcS>&(LSdk;`d*QZ|8Feaj(UF!fAAOYTPR5-p=|-=M zxI>Kv?o^mhj+xBuWxkBF^jwhK&H{w1gj27;xL~N&Y*b_~5`GE3WK=?)TAm;EBL2Aj zm4Ws;rnUu4Zme(AP3s72HU4ZKez9e#LfMV(FjQ9zazQ{ z2g4L#%RsrGaU3>Gy?)L_vj^GDSsGYih+J=ZA9O&|FP}BTtVd5X-SpW{8?OdfbJiH1;y-UcmR8uOXvY$|*ZHwv6qj@0E%7=QQ7qSmm9!7I=&`l6d_ zHovVk7pN{~Nqm-TI6ChYGpOwQJD7BR!?b+3ma<;q2-ue%%6I%U==2Z{T2H zjw?B&6o})GUQ;5w3lfsQDb9-{N}gil*1Em*{=w67=24ozENmRPSUVLga_;tJAs(5%~VQ+ljvao%6 z`;DGO10DVZ1Wg8n>f`IrKqIU|f3M&i>;YA%0tCm#|MN92!oWa36=SSf#sxSAfx1~NsZrtK|VVin3x9P`rE>8uG&}z6KVH}Qq zMWa2yNk30Zzhm_P=MY|LP8H;~F-!Bi6;Vzq5dUN8=HjQ?W6mCu48bpW-60SarY!;{ z9{2%$77rB*z;JQ^_9GWDrqr^~vdhqa_94y=kJ#>7oAz2&WuA!>*h+f3YeAdT}c7AxST7A zrcfU1ZtR~JsI)(3CCJvy19)FLO(S(tr0`9meT12%b!5CvubCZKAkdmXv5qrdH*bv^ z#M<6 zS!eJBaC|oXwWxX{O}RnxYgYq(m%<~xv2yEAUDuLUlS2A=kGqvEmfc{kNh5mw>p}wp zY3Wp#-HRniTu*oRkGlh4QpJbpu=l5{R9y9vfyz(Vo6Tx|MZf6`Uwco3FQRqxfr0H3G zM8Lam6yrDH!PA!XCASu{twxemIAi<&Ua}@CE-oAdW$x49{yw|@Okf|y|!YU9b?_xX!M&Ptxlpalsyl5?Df4MI4 ztBL>iIZy(UXk?n8fm!S|mG z1y?^UhFh7}4{CK=nE&3X4*7NerLMMc-OC=iP-nQeiw?vc)Y8^7cQRds_C#^6oA%;{ z&iW_szG%hP4HQIOr2mL3#{2gze06+p602R2bu}}|L+(DABHJc1$ul|_SZ0JhSwnb8 zX*>H~MuXBFo!|T=*2y>X`A)tucD#Osy6%PB*F}R#2oizt5odd^+Ca|1;PfA@of`>F zS#IW-bsxyG9XFF1zoD^R>r=yu<(|6(P!O6kx>pYC(1Qsj@6YKiL+4R4=jzXcYS{N{ z(y3t%*7qD#)7g_X?R9=URdwJLP8b)OuX|Y5afzhD%@c#hwrw1#1ZxvV+qy!RPrBwW z@{@4ns`ykdtWW=n{A^*8&d&qsuDZP%vYmyR7B+;JySqr+DfV1@6UCUgpg3q-82j#v zxWIlLp3gWNbFF24AD?SJ&(qXsb2}Rxd0^oG#UUxH)_(c#0Bc2tl=ZpOi)`XC%hg+3 z+c@IWFUaEpT0F=6WiqvZGk^QC5n;bhXMmfWjm!2-mbreqj*fSGOtgK)4@@ttr z+rjdD(&4{|K(wit&-3XbWMbq7tUHEPV>9u#g&^BQcMG>vxCw8`>>{xKKSJ$rVtwF+ zfmid2VxG{pHstBWn~Rp12hHWYOIB;25}IX(-pRbGvUp%j&A>S+cH0>Sy6#pCKqpbC zU?y$XA@z;$c7Tc2(LM{R`5xW7?QPn3KSkaB)~7c&caJ)RS}w+M3a7DnO|*`k0TvwZ zw<~wZ+q78jG+8zYi@fz}Q*Qq8vf6JsaX25lCY#0G=_>)e5%w>-G+7atSpl-;Rt~Ij z)jefb^}RG?C?H6$d*~9EBzM&^YG_OuZb0#ReOiM zD~@Rv5A0`2&hT=$sD2p3Py6Wu=tJg6n@iEW5Ojw=RiS%^9Z3?m=4M4QO8*Ddp`-h^ zQGS9+rf&XAiN>w!<|my{$Eb@IA;0ntUFY!}tD~l6>yTyy#0=7KBz8sLwnp7~mT&;$ za|zzR1V@yl%+HUZrkG45bUj8>eMdyUC-H9?G1O%fpMMnB0w(ZzGm3JT+E8v>Qok5& zAix0i&ljI<9rAQJ!;N!WpnhbMJ>*uC5R=&exNT&cs73$$+6%_XJdBnmkQ=4iF^I8T=OfMl8V@{b*9%!<$MN)k;^adMsOQJ2A`^?!}ITDT61{cul}>>4}N@22SMQPZ~Bx6(f-slN)no(Wvpg2G{4Ko6@r!R(5P3 z%lGfQL5ui@`|i~V(1n{CvHl7y<2|gqk~=$BXViX@X91V1dHnNpQ0SuN>5AA9*dHo@ zndBK!x?hiMX2Z8U;l2RNtnASHxBsBvI;y7NsvxQ$xkJGXrvQ6Qk?yQeT-U<5)iH5~ zZSwgg{8e^Jd2XP>_NLF75lFf({!~XAYwQSh(M|uQkwaa)0Qo+PukB1PTuXPF7q8!9LJ^|r-O5hk^+1H(=SAMn&#bX zyCV1~$9QjX*Hbh8a%35xTSAs8SC0JDe>qjtbpk|ienX92-&OPnHE(G#f0)0&*e-j} z_7$nEX%;eCFy-Hb9T}7t>%YE>32lo!sP1M9D3?iQYVi@gdGwn{hK{AJF`VJc_o^mu zi9g<-L;_tg6P<79g)F*nnoj7Gx_KDP={D3Mb@30&`oK&;*eZ9u5$o|;I>A6?{=xhP z!frHwlVYtsVV;EOJcai0qnA{que-7;+W^Sbz`n%gpcQWe0t!ZVt=@4x%5a5%Bv!Pm zVkj&8AJV^Roip|zzoEIG^H)6Z-sAG--^i8Fy4yHoA;t}J#s^vwE;}nbT4Se{Zgn$< z6_<$1dmt>(s>ab;R54U#G5UHY=4-q2N4@6S>2GH59uz8nYV=i0`1JN`Pi1%2sTtn0 z@`~@epqm*T>i4(C93_QpK!}r#*Uk z@z$!qo|a~p8~ls4+>PQz!k8u3|Sa4zB1V< z|DG-fzTu?M5yRv375$(~Y=gIr!z72u_|-QL;(IKW!6SP^PJf9d0Ze2~HQ(Dhi57Wyx`s_)lTy z`*&T|?q5Tvo&gn26aYJ%=zsP4w@&4ge^bV{Zc>3ybO1OHzz|lEW~wW#1z3otJwua~ zOM}xadz<1q9BQ&WiAGVc)Ppmot_{MFfPehwq^{-;8;2?o2zEwIMn#kLV5aB-qs)QB zmOGnOH?oR45F;e~7*>hZ1M@BIb z$ZmKe4m?C_MXn$i9q#o@e_cA~qlH{<->wdQ!_VJ%Ti@;qO>xaCF_#N zRqYc(7kB~+-unlnX2|p}qFs-$-7mmT&Ges|vWb{EcirK;g}_IwW#yva`Nc4#3SjA% z)_ux`a=Z#0!UOhiO3}_obI}s%|urYGt*HUFWAI7Iz-qBwLeP;68YTqt~K; zWM;;WKO_z9dNs$aKX;?GHG*v{A&V?P&dP)ZMRw5syH-Nd`j&KTpHaF?Q|C@DzDpQp z{EJXOF#EkdlUQA39NYWD-1~>P_5z>lc+S|a+Q!7Hq`${$8w6)}`WpWM+ckn*p#;Wv zPwey%`x)!6GPOH$N1JKxB^$+0t4$2C&>qZ1{kS3boegNAndqfy#@cP!8Fc^be)1LK zEa?(3PZ`H}jIdnRxhvmQ6q%u&5nZ3q-ArkeBar;pt(Wua1-{@PdMSONz_U51J5zy( zN$|M2=4sXRli9kcqeh3UF5w2jS~Zqj;+$)e>-XR{VoZ2RO+3(S#HRSr=2XXL&)2bVme44OU zseG!oN#GOu^vt8?MUy!zWNXw9K<<2TNEsNiPQEW3Qs zLT!I3XYS-J;7ReSW`R$^FklGHa3j2B`n69lYZ0&Gszsf5jW}_U{?)c3<=U>1=X>= zu8t1uV<8Pw6aFVtw~Y6kk#tNc#fmAw|P__$^q^I0+{LK*)dgbLPBjo_FS)HS=LUWM!><$VzsS zoqb>Tb^R`%Q8KKBUR_=FY_M9H=dP7>WJn3Pi7_kApz;xEl#Ejd4NJRxwqX&c>Z3Fsm5$De6*@OP;Cr(#Y z-7hNVQBLypz1iRV!*vCqexe!4YH`-W$#S_%e9m1P;t9#)%&KQHIKTDLdw|bT`2f7C z*17kx1p~r`y3MxgR%p?0ZUiCX{O5Sbw|@NcR(+MApWXnt!>X*%e{poQs~IWY!-5Ytr zi`nFmT;^T=)q+JN{O~f{cx&^*xXR%yW6wK8!S>o6XMhc=+%d_jit(=Ea5gdS7e1$Q zq_2(>CM)*OSJil4LXfj7yHQ5nXLKD1n}%npeN-lcpvWtvYk!IHwc-D*i z4f=E`UEO7>4qw>r&{I;bXp+Mm^I{+ywgDsZCI=?_ooGQIHD)&&)lQ4eTh->XY>X6; zHkqhzd*a40W44v$gy>NW(3nt2NR-*M2n%e$q;Y%a~e#(il%Y2tn3H+9ws=Rh?1 zShCxvjYl;H!b`1uVxg*F|^&aN_CRYkyiD^N7=To z4_V0K!Zhy4*#!{Mzs&wB_>JS+*`*jp1y9ls=wqP_(n_qWiAhCZocy#{#BlnFi}*s% z&mOK%j~X@XB%gfHA^VoreAoJZEexJS`{7CX zz6EPyeujT@K>?umkKPc^I4!Nu(zHPhn>oh(8_!7TP57MN>QFAeFQ~yqU3>0WiAJ3_ zVd#&-UDq*nFy5E3WMX9M(yVjb4Rx_(*+Fss;Tm+YHVzwaOI9|yNu(w3jU?4|A$87c zCr_#?sXhu>*V2cNP8C1v9L*BYef1OL%F}jjF?8cJ8~m&gYoVF-OZC;LajB2$l*fme{lR%P5HIYe;vK)HR$dDJ) z(QwC0+$SM-hhVPP)w-)ST}5eXf{d>jx~_Dc_?U7qk;Xe<3vh6cEd`c-uhuqKv(mzW9W zTvOOS+p(F{sUrG0)&mu`uwp9sSfELr>HR(Z7n5~u&Tl^W*%fReM?ob7aui?aBWrsg=wBPTWU+0ZsCx_ zFXc6u#K4Gybt4Gbwd8E0Cx(a;sXgKFDC zY=|9285Y`E|8*b-!B`SK2tll?JDK#tF|Ap8TTJ%PGbaKKs;mWQ#M3D39NfsXd? zK$x2#S}N509Wr%&FJ@%iuH$VU#q&6&r5Q{nN!n!C2|vFy+Ob*EEw^?7DQEXC&l-jt znkD`bSY^=7TlvbT-7+j{{&m(*yDbnWG4A{`YI`;e#^5iuTC@e{FKk z`-LJeuhw@MZ%}#Avdlap`@lzf%7iZj2xF}{BGfnATA~o`ROqFT#ydPim3xHLrF}H^ zaSGL4kCMJDMc?tF&Qr#UTwD3mt|vC#BovAk=DT=yIo37I{D|cWEX%=bXgm;q+9aqh z*G~{((_U9LQN%y_H6^VT3LTp~DzH+<;VioKz`?y-AZEaai z_weg-Xd7N_dQ)!xZ*pPk*5{ZP6uL(CLDGkP<3Tf*2fna6=c|ay3TxL8TQ7>u^dX28 zqs%dJqUqf2%5pjThhg_t!i|Lxp*A@(+GOXh=-gzVQm3n*MK*kl%X3*D{l*rwgpX7{ zP4sGhq2_(sslg18!6TJ7trD1<)7E9mk;<}<5if}2E24fb#M@1{n$_hdRA!pbbz%O- zziVgrXYIBUoXXF2Rd_yG=>v3i7?~T#GG(dVV|s5|`t|nHktg(Mj_{6^67!kD%D&L@ zZ5ClGCRuRnuWFj?(+1Z$At8;;mTwDRe-JBDWY=_jYZpY1WUqtCA?)lk73~Z8yXXJR zJOTgDnFsb1Hl6p&E&G~(Zii($soMc_x4o)dx*{_QT0TLRR!_q9#r&DTNo(u#L}PA) zNdeAhq``|lCVEEvqnVi|TOmb6qe8iYriy*!W%4ueewOgv3V8OCw~F0%)nMLy-#Ji) zw$cXsYdj-X4`s#b$faJ}%p6}Hx;>0@*HU^b)_Tv-eyoz`r5^K(CK zz5W1Z4A()PkTdsyldw1nA%%9C%)!)Z6Pai3;JT<)h46ZKzQA)S2?b&I@WaHt3Nmr_T zf*Gxz zUp(HZutoC%`xOaWUj)2NCd8N38xyJyOE&=mTU&fRJ!Q`=ff9YU)}LkofLYz)lJbNGuvX**FU* znbK}N8kn4yS=g+dIA~*AAm#tj=5_K5&=&~)=j{&h8z5A_6H2uqB!6;a093;PeQ0An zPP?I)8?jYfgrikxDc~r|yJGrAviom|NaM-P=`TwUyFMuwh5ljvE`R(oF27*BW21F16D#v$O)M zF2nNtf^*hkLQ&7pXFr6SX)P?7l*ezr7qj}xT&T2t`f-WzY3O?5OFX5l(qH0~OPk%z zz%Gs9h}@_*YJg9AGkMSA$6K;q#iAa$9q@5xslB|b`Jpj&QVP8I26TYs!!C&#R2+F; zTAs-Z{jG|T=j-O6z^ZgLe8O2_=wJ%duPS5Q8sy!Q&lR$d<4-_}o@SCC4K)hw%;;R> zTvoo$jxmfY%8aXV4|_a%Xq^80?w<$M1Oy~|zi(GmoXsy>;gpZX;8`7K*qfn@SpJg# zA>{losQ3i`^RZk165;-P;W;70f03G90>l0#xdF5T6UlWbs|8kb^v*lv$NY=Ojz!nn z+a06d4xjQ)8O=kwQI98Eg^2b_{46E56zn#aal}ohDw@X?UTeAar7ab8;o5NP_n$nm z7hWSFy+Y|z(qsw7#}+M3=8zbjzrIKKI}7zbKqS*KbdAm;JLR2lB56yd)zhHTtDrn9 zNqyfDMgt$VAD*&|G)u2fbh(CwzSgCPJJ=p-t67~D1WS!ceU+V8UU)b<>Ki;lb*1q4c8_w?^z#BEVnSfYNpLQw6Nd`BS!nHa;n$J$@f?%Jc@ZmhgFhJV!l zv3*QxSVuMGNVmQ*Iny~s-LOFg)eHGF1EX^Gb2=&-6#3Z5s+T9BGQ0J6Rwd#=IU9+Z zX)PZ@g^AlFk;3KSwvO^F=}MBX{w%t0Y_@0~^{m)J&BIktmoQxD(SvZX0tC<6fu3GY z4k3A+T4S`yeWyA1rmZ)iLWR&DwccftZQ*_8U2#2kYlGuRtm9;7`)Qs>S6STVm!mYJ zAlAJQoe`ljGvlBD6Hob5F5LNnvEay9u?Vo$1uArAp8-Ogi0*$cx+nOzMyL1R2q5oe z>;4OvYy^_TE85^fzmysN*Ei&!`&%cB2RGM}{z2y-uwp@_E`gnBRPD;OR-1|Lj2%rs zl-vez?Tyk|f64cWAh9z}CKb>_czeR+{B2kNM*A$Oq6TIS8|=O`d}kILU0PZ73`MP9 z;#2VRdG)^at{9V^JW|^Z?K@rP%@(G+L_(&On^VZ$VQwVe27e&V4|qAqTil))froVu z$^ctWNdqKYSh!a!U_3^_^C`Kz@>_xtrB}g`D)a}t&2m0RYC(lnMMXuZ&{ychmo?=S z!hN!thc5G#W*VM+K?2BSM!N;j+WdY8Rec9DemFBLEl?%8UWC;oamTJ5V)oj`@ncSm z@Y}R>Mv(~j0lyBtxvI(0_jz#Quyzr|>Jpz(Mkpn=R=>Xfw$LDycjA0Y{dn))>M~iY zHDRF{{2OS<1DpU|U+AC(E$lSg*N>EyE^7j$hm7jFT1(9hLDkqM;h}CIamRfN1b>g? z!4R)g#fY{F6kuV86CrF78P!2$FV7p4ITEGad#{WwEx4Tt^MtHByp4=L->np89eRB1 zrHLCgJcsWbD`&?DpkYu|xq#tkli{0b%A$@Cs|!zaS6)=J)Y2&G3I~|3!}9RMV5(Lg zpTc0(iNvDSBWi4>sYQq;>pk6b*Wc8dCpvwD3-m(?o1si6GJn=&t%YW{XCqnxOZ9`B zGCXw$^$z>PYtdzuYtbvAJU(CFqq#me-v-H9=hI4#^L(tDBc^IaHxBniG@LkE8oGaZ zSf>>LvUNI>iWx5J#kXPP5kehbf?l&^YCTICft0+Y{r|llB7n*{?55TISohm*%IPGgNmRCW@`4Gs#;kORexg0J0+j|skH109I zlF(prlVdH=pMI~x^}gG7$0UJysrTIPWH~xc>%!VIpcF4BI5F;M@M^eZ*LdcRx5v7)v&L-yC3m~KhM0EbGQBIAW|GIa=h-suT zYoY`U2(*S}Srslb&F7DA7%L$~!NQ`Y)G?+IRbNq29T2{~>hC`Q;nC0NvA>v`kY zXQhzW)h;$xF1$Laoz2s}@P)7kK0wl4@^$~=eI-hHPp<~ogsA#++Q>M++0C7;02Bwh zSKuu>B&vshD$7N@W>Z7zW@~9y()i*{!{JroXJrwP71nJ*E$b{>8=m|#aWO9)^qzd# zfIgHH#L+bx5!lh2RPWOKRjUB^aN_6@n9l#lp?4UoTq5%XMQ4^phF)w8%M%(cqLn)( zl?&%Ui)a{d;3k$SD}%M|F*<*rr;O@nzHX{bMReKIJW_io@UX>Tz`*pX^wUD*y<6F* z5Tl#;V4A#|tunM4Lc-GDQN1mOt=?&xwQi59aL2>BNNE!IYf*h2 zps!<6cWh%c_*F0epio*!_LfUwMeT&|_Ja0aY0$1e-+pyIY><(IsoWLEh5q4sryG86 zmWBSXNh&M$&m$7q&vD!*B5hr*2I=k+48k$DQtd-dz}dj+51{4N_HmHl1)bWZuqA69 zq#CPYmb)HDcC!j?;5n8 z_XpE$Bnqf=?@5=u3XDSVPBtqOpp$Sk7TV~dSZO7Fm>@)Qp@*U$jng+{g(OJq|J~1& z(0#D$;6!5fIE?KuR>NpOb`VUU%n%G|$M&prPz|r>((V{HgJUujDqyHi?TT;<%ZTQ5 z(G69&7ju~Qw@hPiWa(xDd?)Il{)hj1H%Bcv?j7zH-9_NIdTtPz+iNPZ_KW*Kk>hWf2reG2OiIJ6lU^oYf{;)wo$`+XC;^KeUi#<7cFAAH z@5RW3ZNl+3+bMg2zlF%SsrfI98eOC1RAP4K*z=_i0}K0lk_i0s%qA6|t%}i^V;3}N zu#xAdNNt`CeS{E+G)G-A&v%+g6=!n2UyBdUDuG=h1s1fLmk1WSBswJ}Pt!FSzkN%L6 zX|JF`7;HqhUnM}vTT9I~XCL<6A9@~&mi-Xw5Co0L<&7LPMuQ?##&#!NUVRVqN|o-J zWJr!@PHX)gbu-?n3W`;uz2^1j1E%G}!m?cz!h^bPpP*vJxLTg!#mp{3d)s<3rh#Mz z{|gC%_|9A0-xg+JbN?YAZ&kxYoxj5rMJRHywW7FMV^I(}Q3q<_;k#3kpAortB)SI* zf3&4`76R% zn%07_&v(^O{x|Pl?oE_X*=x&HT;q~PYl3A=K3j`ZJ?glSw8CGc0(NL;Ux%$RWg@er+xs|0?(x9kr_{88l^Xz$VqXbUA zf;6R!OhBo^wL@vNd=0l|1`{IIx)tq}!_*O=^(AP=*qo2?aH(>bo$Q)1_%?=Pe-E9w zhrkO>pWc8i+ov6-w&YE{paf29F}5b|6?}vDJbM`L4y;5hE@!h89b{s1L*wK}a>^iC zOG%0AGx#n=rF_tz^O=ie?M*UuS6jbC>$aEH9(-S>GKDp6zL$4kUwMPEKsC-PH@@!| zpb5wAhXOcZ09L45f0G&dWg}p2dGqM9!O`u|BkL5hVr`t}{Hn3|Tv=9VEnXFzSdmnr zBVA+!8A&|>qDF@Se-GZEz4Wj*XyP6e;e?NzRLC2{SjPI6W>u#QQ#Y<0`txJ@tcMZr zd0sG(&LLrMZjx2rs>Fugg~@Cyi(xW>k}Z$?ZS-PV{rF~6W7e7mr@s-^7rJM3BxZxR z`}i55LuN3WDPYSRKg+@3Q=wuy>oX|Eu2vBe5v=rM>Cbt?MYRr4I*jZceK6Rh_^U(Z zpZBQ+8#DGU)MYkmnsn~mUf%Y#bzZ|l@95+*vN9uR8Hbs`+B7a!@S2c!r*i)xi1%f| zm!aeO7_8_dt71jHg|@v@UEM`C857*rC{i-?Spy>6dm^cxFb%`#oQ*lCTOp8u@BTr* zfegkOm}>dn83ZJ&+L#q2dpSAKX!u<3Face8Ye4pU-zk-qE{68J01HL8^pvbt1X&4` z3&x0ktF6!2nCrE5G|3x$1Lrh!We!F4_B?0ns-6p0vNHc1nF7KMHG*YF+(jE0d5Z)F zezfRox2RR5Ky_z_aEmudp-vTkD`Gu24uie9Y_sniQgy?%v!6BT{u<$R{+9BDI~J5D z@q1E&f!S8DSg>+PMH?sZ59|=*_+D7imLpbbN%CcL_Wn<8^Ftxyusye}hSVTydji@z z+Vsn`nooTjK=zRsPjX#~ALqFL2%8VQ_$;0Td^N;H%(b5JGZOVNAsx!qm^8f6E%HgV zI)anzuwS9w;ikO9{wO-M_FXQ0)YD(Hiax6r6bwLzkiqPJxkHfLQABrz;>1D>55qU} zide~%(zWF$JYXoDfQ`GRW|$5eV_wPWT)D4CH&Ey+^>t@0TeDz7+p}Q0$$Q!<6LbX2 zt3on#05Cbt@HgYY3c*4<&o4c|R(_Z~+qBHphx@_fhb!o3Y-Pu^c+w_}Duvhir*T)Q z9QWNUNl7rQ+tqjfY8`CQdMSWvrSnWOA#<mQAXx?h{Q5op52Z-(aLN)y&fNMuR-v_}bc= zM1*S<>@8`(sfG^60>aA^|ZryHACq%?1pf@8$+b)6Tu>})#@Kp7~du*^E*@lY1i-$THGxRE8-_rRC7d5Z)(1<@$=q^>598w ztqEcnh+hh@Pj`K4fvMg({KO?(7;Y3&!MuA|QG0kAn4{?W*@NwMoBd@XbE$_%YL=${ z9@8~|APzh{nk+ftz|lk2DVxv>D;eQGwyVla)z)0~E2P;}N2t$jojz3uX*ldANJ`u< z!&h^DrGF{?%nW13*=oQ@hao;y zD5O>SEXz!?f3dgrGucNU<8hffW!z=l!hiC8hj)0*#WLF&0d-2GH3TE8I}xn5y3FBk zhvhS9R5m)@^I^NPDDRbZs6TE97_9#g|5~qRMbm`xwJVERgrg44#X6RlY%3s&*uJ`F ztyns$s&*39c2L{gtTS8d400|x@4(Tjt*I6PW{C*Y!!b8u2NvZIFru7d`tH|!%iI|Q z&nbpkVd#{hxu&Pj-#1-TwicZ`-sDQ@&Zn;07loffS`u`O)2n>gbhbZTz}=#&_+KZ} ztVtQY+AfwbgDV8q2Q_MnQ9Y+CII@TCjp53oB?SX|A<=ykQIAT57KRURELvdigie5@ zFdqiG>QKLat$Q04tT^84xK6>0k52 zh|kAwnsH`DIG0&Gi@zKGqRX5&a(n>G!h zEO!HBSySx#8kBl3>wRl`TaF*#rR}zhm7C!wQU9%nGEn8zTI@M}e*88AHrXOqqIkni$+z!RjwvVp#MJ;RAMg7)u0@FGS zw*hso6g|u5ndyX)X0DrQ&B*>u$;&e41hD7&Lm*sA*+E%H@uC;TKDL4(3isnq-ew$I zw%|xkA^YX0y2+G0_;53=>S^E%V;D?gxWvDGw7Z>as$RtFjYfW!#brGS3^~lC7Z1N1 z7o}HLU*l01Xp;VM#N~NJ5v4=!we!+8?h3LSa&h0^IjqN_()69~ulO}&oF)D^lpHK& zpe@((L>cHdOE2i~FRn`e4}pyeGG7Z@v9bVc=#e{leKKNF)MT?F%K1|_+b?aWpUslI3}3w2gqeMj3?DX9#p$apgLekf|7Y> z{e1npAolc1K-yg~<>cH2eL8!gKktHUPgvDjhzn|2Cf@mp6cODreQ6`p_sJpJhUuBQ zJ%Hq4e$#Z}&9%xFk9fg|L^YLBa9QPb-w$;HmG^9Y(rsYmk+6;%RW>JgJzn29`1`AF zTKMQtOyr<)r7?FvpJGa1vwTcl-;(RSXSx3PFL(EWKx*UC2KX6rIR)#r~~<{`+W_Y~PXXmfuijn-CTI%bLM?{7p`@?|nYzKLjk7%LY?!(m|J1 zq6HGVl5P$ve}X9An|u#;njz2hmA4UJVEM8^fHp-pT@c9LoLN@A$H}+zU>?X!#4o6l zPm-_m19?Sms_rQzP$EmkNO18E{sB(@+AqD#r8+dAQuQU=adB=|O{5nR6ZN&q%Y(IgC8 z)dh#qPHDIOKH&`h?5H1+9QvKD5Bi<(hSt;CzMby6)PMXbu%{{?4y=~Iq9)_)WHXdat8rvMZ6-dS zYnpCkg40sZdP7+r4Q=b-_hkOXNq95$Z?|Fb9$C^^!}8e}01~EnGxcw?;Wvtd|I#Rp zO#Uwu_jrNOgOqHa z3@sUkjkiqm_GIkzx}OhDM02irxA8paocf|Dyr`415Vj=9lZJ|N(Am$vNQqg;}iV-F1 z)h@=zD64*EXB+j_JZWE&{EzC~c9%>apKypxbf66rY`d*Euq64rEOxbQx0O8UX1>82 zlKbNeaZ#EC5iqJ(Gm-T!Z@!P1GTw3Xfvno&5o}hve7YguGq@jH6Z-%QB*+N~|8qIG zns>mrMs*vfH{o-1PnR;i^fI}8ESqc1*M<45WwQ8&f9Uv#scI?aw+23Il7XFf4`w-N!4ZRcFvZjReUyiC*zB9>s~ zKjJ3GQ2M&PebPtp>B-+j4=d|};MWj!asvfbHS(gQk#=3GH?;f6E?K(V(*F=7E`Ptd z`*o$pX>DgTnv1kH%|!UCt6lq`rp^KHMXHIP){6t(h>m;8GC+ zkA4`k@8jWWZ5-IWI_CAviEy+i%;a;n_cPwhr761pYmVQc{$Hk25&UY zz5(M1@q%>FN)KpVjNIa*Pz`52y)7Z9b=!q(S14K=q+pIsy?)~?kIJF+29ueCtXxbC zxGo`oEe4@c$ z)Qj8Wc}e_TQUyxW+6T4b%KPG`UwQ8umaw~I)-Sv5<8s?yrFbyX=@N&R?^x5(eYL^Q zELOKo=&F@E12L}b^KERkK_s^u0`NTwvwh9f?0O=>i?fPIN`Rd}Dd>ciC z&IDquK)%yo0X!M}EC_P1X;!p6nx;Qg04fcH<(@o0R8@~JF1Lvl|6@5j=7V)z9Zi6D zkm3Ry*F(wUw3Kvpzx;)VIpO}u)YP=TEBI^6CGqwCZ&~ttgdr8^7Cfo0SC#+u>+qfi z7Rt<3CG*XS2@4Gn-{hS?ga(#cLeWcf4-^Q#+M~s*+oSG&oy?KzZ4Ce&6dvqtz@BuY zSZyC;o9k;z+mTsu*;^iOEE@7O6oh`Jw9m9vZG#(TyGQTgo??~ORU(kY2~u>Jr6~`s zyY-uY)8Fwlv}hE-GxpeD(^9)WB21tB%g^fc7Sb7N3!aCp_W^Dtr#v$MyuNnEC!;WG9%R=9Xch-X4&c5szQTRXPi$wJcgAyhTgu{oW^!GCFLQ}x#SwP%mXFPd zMBkW3*Bgt7AhniijN40*ZL$aB(-eN)EZ~UKk~1YogSrW+Ihjj%=1KYezNWCszcvJe z_lb15KcLF6ke(~X1Yz!W^m%;|q(T3Wbx@APp+fY`(_8#zB)8t%%k70JK~Bo>q@NU_ z0OrAp1>@;to>7Fp8hmbQb!h{MBNIaSJWL(dPbQN~8Gj+C&q?~N`Z?oxw{g0>Xd%;y za#XL~r7O9EEjhcb$(-7OOudz{@AN_C!u&ogLmx~D8wh0(?Qp1?PZxy=IcIIfgqHY+ zZ33yevf_?4d!_b2^h3rq5_Rf4CtsuHl;0wF4VMS87kJWuQrQ?ErdEz0&dqMg5Yhl3 zR~*3I(wwTIaEq{$I$(unk(1|xYh0h=NCFd|g@&{r8&Wxm;`e2SeM|{??L`_FAJa5! zgU4+a3g!vPZI(P0ZN0O0aR5h;u7WaS-^Lk2fxXbPCAwyr9JGwL ze#1KldtvXcvo1NVQT5~zVmlC77hOwW{b^~73gfl2x=X3q<-c(XWdTn^rMHr;BlMmm z$G`3pe>81_k){i9uM`cMKXN;lSjDB1$RAb)ktQRS(=~;bymVJRYjqueIJYMN|AB*G zxI+mhYE3yCIJMI5Ts>==aoq@FO(1<@b6<6T+71Vx zR<#Gsp^EWsTTPG=qs6JGKFnabcH;rISe72tRe85$6Su;`5{OKx-8BaQAj21_8 z%ZB!F*z=7Do7;H>=btvtW3C(8a7jJ6RQIb@48O9J!K_U34cf{l>vOJi4(Knnu3rIv zNzYo1)-94KWYQJ!_t0bPuH7sQm0icq#|Ror!S6P0KOSe&xoLNp`bHLU)LFACE{8;u>DH?@yIet`U6I6z2iNM>N9N*inngUjSp#ChZyxVg0JE}r+?+O z^=PeJjCYiyzvKk^wIFL->FY`K!)s#nyUmR8r^BkI8{_-ZL?HQrUDWf)CD&=B0GDx+ z1IgPJnxV}YW!=>zHs!*=tHdHN-l8B6NnJ0cjYu<5ZX2_u`556L4erzw9mr^p!?eJ2 ztAUJ?1yGx}avvu^j=Y=Ht#7*M>HamKf+|L3v$Zm_BJaoI%@*1uNl^*I`aI4IJyPvl zu~YLl;5>zBuE*$H{!EQ@SMxEsgv4E#BM!i_hJ^&XtFQ;ZsPyO67V1`J!}zxN!Q7Ci zW({eXG%*h>d;bc@I()iAl{HjNqpw9+`DTT<_tp>CB#L}mQQDa@fvBp~e20-G*i+>b zdQtwxLqR4-){n82PrYA+$D8a8ds_>=kohs~^bT)TjA;xP?(q-#GMQl!?P?e?>APjV z$81)IoHWYc_v)Yw=EdK}2CasY_XpklxDw5T{H$Mz8#oyf7k1Fj&UQO!T1bsw=d18G zLLcGi`py%>yTFtjzftrU@~9q(<)=P3lG+I<^;0-JXURU@S`s}Zmp^4-=1?rk!;CN&NExvg8Bs7SWjCFWD-73v$kJpQXYU6}d0 z^W*9h^dIHww3%Uyf4WXp50j>dd`x|SfOCu6jJASXQWY0g01a8mL6u=1P5#bhLD!EY z7b#w_G~^Vhv6@>T9t?AJC-eR3ePT~OUU|vr(y&rY+-D`0cW!r6Ax-fd+1Du#4^y;V zr^tHEE}oWg$OK6KlVAbT4jsf3j-( zB1^CBxOKVq65VR$Fg)1ehCBE(BAz_ce)r}}$4V9lbvql*1c>Rak1{$@eB1UD-_>8h z1_o?3HZ?{}uO+l@QyVBDgb^N`zVBtBYO#r&jin55i{wu;{p&idwT{X`L5X6Hj!=+m zd#+j*&K3BkfP$X`4%6b+XDd~7pkTfBy06&@G_x970tR!hxLW(0H-|<@AKgpVs!rV` zW>SQARmE}ulbD?dSPSDAt4J-HDjRbeS0SdVOPi7K>4nd`Nl9d+SsKCPQoL30w2yE; z#nlo*Oz!@9Mp;)a@)mhp*@Tp7T+1>}e;N^=7-%m6_$! zTT)`-@)#K*F;GTkZW*@6{k{=|jtTy0-Ab7*m?1=zZy;`vi41w?gqf$Jo~j5hGcRNz z9Z93LEcLBNI=6u4xu+|qr>8qSx2wY18ACgD@@Ine9$^yWisqb5;LqNsY6e*S)p>t- zxn;nlLu7k5bx@Adh-sA=$wAf54d4}uqTYbem1RKOQYwKYL)y+RIWRx}{hv9YQHon4 z8F4!#SXqH8*0)F`=pBCjr1ft^?YjuU&q$GH$O)@c(JL>Z0$fgRripnj$MrupigpJ4 z1YR8I8*96%`sN?Oc`OQTRZx7aboHLl!Gqg?$nK6yiM34Zc?k-^eyAi>k+QTFV>hmx;ES}g}<-A(VSda83j z{=>}H%N`@rUXee{kW*m#vZfdFB|n1Gf$(ifvIz`D{CZ`k?>BV5W1X@0z~(|5of$RZ zbh=aVV@j+FY7>SUb`+^m<$+6-e3HPb63lqgwqFV(#|=CpCNn4=O`ee26uS1ppx*;Xa>} zH>(}N+3t6^k`q;egb;W_SRa@ie4f-lUC=`=YlM1;gpcf zAu8UD==U$~Dul%cMTBJBxqBwp-;Xk={|`ac7unV-t5)o&5HsS>h3RZRSma`Al9M`%xBp-p*a_jqvVTBI9Y)=zYXyk?58 z++0~_e!!BgWWHN*iEju!-xb_@ISW3%5pClhWu8$C!O$X%mFdS1f%9mES`WL>)c3mj zj)n<0&R>&UGLx2)8q}?R&5jJm-2VP|X!BMdo`CP;p9C9>1sjP);Dqv>VS*iFr>1AF zU_*FqL*&FxuG#urj91yync~QKgjVz3-9*E8h->MpPH0qvGF=wtD;760tn4$<3dyC(m?1K+OYHWZzLU5MI~n>6XMVeMhs3M!*`uBBz6T7e zpDv%id;P9grs`XnuiKt>D47L1@bZkuseV?s_Zl~ox3uj~RE>f3C=<=#>~dMrtF0Kd z7#zg0sK*Wes>`ec$93*UN!st@`d~QP>~>uAvCfKxTknoHG!9JfvoLyRo7P#LII{l0 zM%zs6P?|qtqB{e6-;9RLVxHdYBF#yAknRc4-CT9R^7p->_*#gp;beUh#STkDUa4m4 zG7@asBW05E@ReFRvwCux8q?hm4@uumRM>K#SpA9%5kU3o={8b_pm-pyr|u4M-YXm}@dU4NYc9T^sEDG&MkI_hA31IYWY zuS36FDC@Re`0tqOW7VEV?c=TDiumS_xTmZaAWX-V116E&=?>=iRDFnCgSRA@3w>BRJFNa>M1#7g&A=)3HFQP=G!AzD*dl?t-248WF zcY{AsWX6w?i@U~A7un-~uC+e@?w!B2SQonLfl~v%Y*qft77Sb(lQ6a(pc#+IJY3Y? zxbaWop#uCpVAf#%=%!dx*023{yXt;0KUytLDrrB*s}o67TX<7(ghv!RyXz7oEo&7Q z*Z|E4)E{h@@h(@}su3+4d3cr}X`F|+vb?JNLbhNE*05*Qb*2@aP2>}5qDv$#AxIQ_ zcN*e@v*kIig&a06Bp@4dTANbgxv{e+$^mifqdhmYow;07(*GeKan@V5K>Qs2sqHIL z!TEV{seni}cEO-MB-^xRG@UT~x?v&wG%D)t^g*44)7jpF$O~hF%L{p*eB|%H9=&t9 zW@he>pLnH^tjjSqQ+4Uy@i$Rxp6~_}`3I>@RQ}bT_y3387k#73Qw#}gj*9m& zGt#`9Ina6b^nPBS8>9s*QuM<)Fyh>cJN2Hs+S5`h;^ok7p%FzRK#)=e(y8Fo&~1md z%+)|aESC=FQ(-&q4^x-%D&LANzDm^>&rbtQsgCadGI8HJnN5;9om2#ubTSVFw7+HQ zm3@z8NBF9c9^pw*C7A-NL7D40X@d*>o;A#*C{v zsV);j7pQJZ^x$%Dn_TA31pn8Ccx4LzyCd=c)`;f`4CU=y+dv;KaT&Iyn?{>G^`~kT zKRmvlt5&|isqALU?-euWvv<{cBy6vOZ>~Lq?@o6(sl2}kl#QYU#&l=dWQe?W?V_+a zNSmeAm8@3aj<>-OV;Z|-X4ABvv61Bz_s)^4lFmN4`$>;MqDZ~&7cUE##U3>IG6%D# zF$RJMVt}Eu3;S{P=2576L1?mr_4qtZNU(?Q|5*(Ju`QAK%UyyKkCWk2@2x_>a0XgJvI zj9giKyUunO2C<-yDH3?ojnX*mko9gjR%tk1%;xRYD~#)Z;%t~O#nX)6x3uTIY|((^ z2U_(l{f}C0QvW`6tXSC|>JcN0Z`7L5Y5TZTcD7*x?mJDHRn*9FZIXzQB>}?{$g?Ia z_~IOY6Q&5k*sgJR&?+-jBpep`Ig-n_M|gO@ZEVSvsOCoZ3k868eT6v12}F)%TR)mi zE!Qj`P(iL=2CIZVp(C z{ZJZmpo%&oX*0^;uh{Snkg1g@d-vj3_@flbv&_CcEcfzzJP#z$>iY`F8OEXpb!01? zjt_L6dfRwBZ7g7@_@|$D`jM(I${KP1!Ji4=Wq8p6>srzWSq>^;#V6%G-_$CH{Vy_? zZ4=kte!53sL_-8B8g)<+-T$%jp;5NmO68`a)dM58Y7?wHC2cax1@8#Efo^6Gu=t{!qd^`p*^N9Px5&&u8Ay13AeNQ=Zev)Nr{8ZDnA1YE#SA)otph# zu`mL~EG`ZeX;AO{Lzt8wY6p!j>I9Gk;jORA7x^MuWqoI5{3Zh`=x(tipRo+i_5BSX z%-|LvJ$PS`1k`{4xXy(*i!m4%7^jGZN=Foq zv6;>OYWo0Wj<6InQop9eVS*j>vn}wqQaS<@B+U`)8zQ0uRJ3YZ?~ShYmuKi*n#QNVhv$Xd91Or0Ex<2`zs`6 zJJJMCH)gBY7-+W`Yz(gWwPDg6%=ynqj%8dm>4AV5HP%M&VS@GVelO^=`2a3Voh&5_R36dQkoAF38k<;29xxCsDbf^{-R()UtC}5 zF@@ey)&x9PO`wIn{Urx+Xs2;7qjJ+~RaDm2m$d{Hty%Au!ImHp&9+KjiE!8LBa)}x zOz{FazeRbjR~xus+h&&2qWt?*LOt43l3uC*~gtW6xRe{rm>KHfcrx(tiY+7~i zIFq}p1Jo{#f3A(+?$CiPf@|EWu66t&2)Hui?6>h?v(^5eG8)Ah46@=nHnhU!(IfGS zX?FJHa`r+eQM%FXim;ImT0qN53JdhjFL9aJyV7YY=D@zT9Xm$ae~Uh_n(1F;93DfA|liK{S8N`tvV?q;`Dk zwFd@vSb#Frjt7rx|dY?&WLP%P9a=h}oIB30YDIJk9fw}c}DYR=4$ zx|CVRr564V*4{Iy$^YHzxdUHk$NN^AF+11{lpw4o=XMraPShTMa(-|Qr4bma z5H+jX8!7V`?GyD?ZfjPYldJdXwA_8WawUAVfR8TRy)!n`QEtL7oMp!r@jK z({oKXTJfXAgMOPvxi7Rfuh;h$S>Q0zN_gFPQm7wa1OgbT!93~GT0eavzT`I4uOFu2 zm6uoRz4FRwgGqa|k!QXsZ36p42Ka)Q8t%z_slCN}uc@QHG1C5*P@K27{OYi~FH1jA zaLvl;uMas@JO1eLd3@O~g@dUiT1UP`$Muv!8H;*vzEN0Ho^`y`T>AyceZDNbpyCfX zEA!o|JNypeK3+2XC62nEP8vAv*Ov6uy6#JC^FjyTh-%LqYEBF#t>N8 z*RmqscHVR#+?m~VnL)rQ@9>l(WYJjZx$d`yOB+J`( zr;!Rc-`?EY@4teCpJ122T!0sCn{uV4OQL;wy5iQtQm<-KE>^v6`#Busg&iLlk3E9^ z0&<@Wk9w~3zVT|B>*k|FH8@&q|9*D4D>-@Hk`~TVTlZn?G(FHwRwi7mM)s4)FkMvp zTIpQV`6=MhFdo7aKLT>MIf{(3*kk=OJa#;Rz&5}XtHIy{NGSg0B{LqfCcRs>28N)q z(j^rg76-jv2F$0wRtyY|+2Pz(Sk{eab5^&3TpGuQYX z#Bx2tMkl>2Qp^W~c!>GKj#;VC1{$T6Ug>>rQ7r;58*^uk*j`kgzQW)93LOK|N+P9; zBq!29dB)R%$PT46J^$_ae<+ZL7}JVxspZy1L;bgm`{GVijzKR9J$);y*2tyzg}7#t zaIZ=>Qsa8_uPW3=`lhEkyIfn{R^ik3A_me+B1`R4;U<_nyR6D7TfUMB z)|YL-W5Aa~HQ3GGc}sR?)3Um1szbP25lco!OZu#RHJMP7q8>o^hLfwqhPA`+o0sTCML9>r>SBnAHg{GW=8vw_k#jJN3m{ z#VQ0vjTK5F8z&dp+(5{<^(Gshob39#Ue4?S>)JJC-Y%e5RFd+fX=zmnd^ud^4+7^W zb0V_l={uDEy3@!HQC0~c52s+*@2NGVcz}n25$0x(9aX4BDL$IR7Bj2*TcUKTBzjr= zO`=-{W&94ui=Vz}+e3<#fCX5+d-tgRYEu^<4PME58hm14Wf*VS+R~tH{k(2eU?i?B zt-?iwBT9nZ$6{>asA&L*7qP|PTr(JtKngn-dp73M7C0gT!d~kZykK2#Y6|=uyL994 z{AU@aebdO{b5bc;3==lOw__I`;h@m;AQs^p?5G+}*vZr#9NNyiQau{!P<6tf?%q@oIJ0 z%qzE9*yi$EmxlPd`!NmE;#4vMmpB-PhIH>HGUzIxHLejOG_HlpS<>1!~j@Ny#{?i5dNj{ zFjQeKlnxWP&-Zlpp7o|;I!9?z#;oqT_WBJy#yc*of{$EX1$c+z!9Y#rCbr@x9ZcCk z%5O7F*6zZZB=16ZqsBdabrI0!e1P1^A*$DuZy)m>6SwKoeg2B4F?zY{jY;h(WS91$ ztc(2qb2nRXAvQn?15DD>#vJrN6s%*pZ;S0}=4&!VT_`!ZES^w{gQFGCGk(p@cihGC zrlTeAhgsRrNHl<@=sNsP3txYH%)3e5mjBZv)72z>@NNLS?_hx*6E@ciK>7ALN@Mp% zS7Hfwar2K$79WHP=z$qh`JcgCh4;hTST>F+S;quv@UknRw}V=6b1 z29MYAIY!%gVYE*#HNm`cp5Sod4&g`(Cf%jJENxm1^My`g^FYzh-yY zjG5Cpt$6MyUoGEW27C7Q$&{`LYpOnoTFD!okk=>5%kV+^gmJVs6bnpnBfRAB*O7`&!}? zIuFWX3q?UAnU(cwp~D}1Y_z?eMSy>m3l5sDu)Hc5uCTS!NB9+DZ+XcF=g5 zB$FbUkOg}wYM;Igc3=aw_lB-trNSKnlUsW z&}=D$4CyLRhtRf!>`94c1`2%W`u4;Bh1M8YU8eS|%u0hrKWceGjvTvp${-F^3ko4?#jC{3VfL~)i>F9zl zR($nvq<{l7jGD+VZysAb&4gzTDtKFz!0U}PkKNG&1eO}`Panm2HijGd9F68=d$qO#npQ0@l(hDu{9QY124Q6Fq_&fwJ@4TZNec2b24g& z_CtSmGN5q*-Rep`XKVuoIQq!d$j8&WE;&4Bn$#7BZHA#Ota_A*-d4ueQfvFJ52I{n z+@Bz8E>xjh0-ZGrP#erms#RHX%sF>MKJ2q&T8hG?rJml=Gt;(U#fBN7Pl&80vaWQZ zv-(nt#rO*Ox^cVg9}2!n65mftzdsix|4`J#{XBqfPGFrD@bP%j=ei0p#6|H3F5pXA{p2d)R^W2W7FBFG+2|)tL zNoYo;7=4@x@aK~OBU5PgWnxxWUa)F<2W{&DF4I zHf0A$1KA-qt_Wi1;@R(6({P>@Mvw#-37K^FKf0k7L^Y8zi zu=pQfu>VP7EeQ2(qIMnckUzQ-@fLQ*BEF74`|v*(S3``2c5B92 z@NuC{B-!bF&K$;G{s5X1j3SOF_O2~A{Qql3rRs7V$Po`e~mylkt*IV37g zdTP9i=cxagZ0Yp+X{3OX!;p>Lx||JqBQ8nhJ7hH67B&%jEoMx_1>uu@$NYZH-Ys=I z#}KV1#PK#tXPytM2e|F^2G2iGpwtn$dm+^x;N@PL!#MNjQY3FQ<4vKh`qT&7DrjJd z=@myZdLNSTHvDQJ#CYz6_=HDV_j}4{b8B|~H@SBdoD#hs3m*x_QC!t!C1)9b02b1F zIyng-$m%7L`k+Tc04W!ieD49W@v{zJw$&(g6&&IEiiO-CMB20fsQ$}*tO8Ha5dKY& zY*gY3%ZheSJ~GZVk_PuJ{^IW*e2=91niCyBH!2s=*`}?LGWP&)e-qKu;nLvPIa}8M z4@G5AM_6CD$=LlZ^ZXKWHiokL?ab7KjY3!$=dpB31Moc`)|iLdh`O=iBD$oAwWG0P zYArwOOxP+*<|8McS=-;6ut*1-3`0F zs}L)>ccSNNIqhu`Z*yOJatL!5>L$t!rg%3(;r96G7T^_xo=m2K>^)xdf-p!hmbRDM z<5Qj&%z}3$^G8SE+`LgX)+(~!`Q*V#Ll$`%zexNJAd=)H!a!)(cDs>16}YhY!Rl}$ zsiz41!W{ih`EH7_*EC5iFr_z~RgDu8vPREskFS{}UD(A;NPDmQA+n{JiiOt`oora2 zzW{T;`+;c@brLoGLXPuYj@wmA0>*!x;pR17X1h(}S~L{IOzbOUH#3S)K=OGTAn_K( zgXL48DvCj(ysIml5z8 zzFQsae__{2Jbw#lu-l7t{CaUkaR)-OqvCQ6X}Wtq7WenpMW|_BT9{J+WL=3RBw3)X zEqoF}XkTCKgvi`CX;b%l{`|cZ*GPV!=x}cLxBeJUL zT)gn0CC4|%RkjkNv!0)4My>c|y}&kTmd?=39F=}(<#nJ=aF4dvQB#*t!+qL#CN=ve zH&Gx9uRxwCT6Z%`QWnT%XMNV>x<~-`whGy6$%s#RH2b19bIN4mI1aM**3Q}~yg(2l z+553I16-YW2ka+YN-T!5ghH_6yBk<$z4V^oxr77xfN4OJ{3vJ1%=LyemG;CpTDsv#ti1Oe3%6slCJTPJV<+! zJL)3Q(l_u;mbik{Fm$z&ZEIA+D7z`sV;}Cm&8j0r{gw5Yk!QDh9(-U@q?+&OhZl56 zLl<~y@mgz_@LTqv*2enqQVDW3jr9OmNvO-MxI? zn$X^A_%ie(f82+kF&@jbt{)=(C(aO19ViNA6<x_U`Qe%8Q=1>^>DkGV|Zpmi;s^ zcrKu9Y(VqUJ`9way#P+&JaD9QFTHSgMsr!6j2vbSyW{EdZ$ zq{QhBoQ0uptG%;c7T5St%5d|F{Y^hc%w0!^it0^~3&jqyOdJ6w zu;J)?#$!-(i3&vT1v4W~$^5=3B->OkcA>W}BZzkBLt9Q>lxd!cgFvbaWmueJ2jg@G zl}fqek|L=J>ep-BZ8qw|@MFj@H`rHo=+w&Kq@gB#H}&vOA0J*=xLca6p0T>(mJ4|i z#mf#OSzMV}UzY_D$weaINj03<(RbOM~pCmJ8+bZW4gU1g~EHu`|7|H z%u+`RI*)shz)kmQpcl~bao$$7{K0rbvsV5x$5)CQP7$UzX50)_e&?80Q$M3C_uCC) zb4dF&u+jYaEzYD&#qRNey43D|^}M)h$3QU|rwv$zaW(ZjK#k&7Xc-m*G2ucycACwt z)>9@=E#e;*rdi&)6C3~jV_nf#7qH)bV73NVc$eJ2wyZ4pWI8}^FnP<`;Dh)x13%#o zK?0o5pDm*ZC0Hyt!=~q-l53+VR-U@x+jgBh|Myz%mdDptQ#~8rJ0+rnLxy`WQPM9y ztRb9&5RR`T8$I?m+c5OEx0?z~J#kxR{m$*Ws~$zJOhxCWw003aBBo4g-}hbkbn)U{ zwtPJ>>MgPtcRBBNYT;Hb6}W2krl*viK$@PLlfGQ7#7JLunw}cGcLl|cKIj^KHf)F^ z7j;b{XnrPQQB}IwmpxEYEkVA#mDSb~siU;1 zR0Ye|o6Roaa&j`)Xfao>pakenM_uuG-L29|Z&mZzdu`RD+lv7-kExOyNyMmj!J(G@vE zR+N9w53-JK91aunL~qD9X+dDasm}h!w}19^$mGZd8zrq^jVmG7LSM9E**_dtD_N!M zAfxH5%sQu8U-Pz^|oXt>DI7$wMw14jUu1iF_(lX@Wa2{5=KJyI+WHw?3UgIq9-@kQOS)3*3 zZDO^3VikN)eld@A$ArQAAAJ_&e_N+=r?hz>F#?jV$_I4Vjy-V^1Ugw+6QzJ*nr3H=Wf7}Nf+n=>p&<%aM zlfR&EQ9tE-WIy>?WNl}v#9%7^b6R4DNQtmVr$YS^;6eB*9LA)O1Q-C&A;o5`W;=M| z$JQ(^19CBw7h8*38@nim!K*?6F5m4&UTV6M%&|JXUXm)PJ#PuH0%c2+hyUUiXHNbY zvl(kYN~>LI@?%UAZ**FL45i3$D@W&ipNs4c7Skorq8d>xh?9RmKux*CrUyes+mauYZE)#%bF9+9%!fXth@X_S8#f_+T6iPsLTOA2L2e>jzCq zZStSV{2c2m(h9il6^~2l4Vcjo^z^UyO4~s}6MLRc9u#}MtFy6VW-+?sJILQ%_hQJ2 zmX*tjy5d1m6%I^F3BaDBhV?Qpmbd6pHLv>mC5sCL{oZ$DW!Y?)H^(TGB4oX8t`6*0 zuZ^S1dh3KE6BhO>%lmsvO@4E()oqT$n&&OwaZ)9#ONKl8Gu7U2_n!2-H?<&IlfLHOGKp_hd2rpv zn&B}gC4<*V3h9d7dAm6M5oD30aGLGFJChk9HM{dJvvB+kWECfgIHJ(uSnXsMQ!U0e`N2))2g(ma|xyTzI4@#_KBQoEtHVNjFbqv zpg-@B_t4{Jqgu}_p_$(w8INT`_IG)a4%c)2iVw_udniKVagfJY$#C7=Qga#ny&f1nS+Jx)hZ zN3>&?PRsb^Pd)pw)kI{Xl4MU1TT4Fqo=VertPJqLtAt#_ss8$URt#3?IbU0+4F3V+`Gu_7*^v_; z4)mmVGwKxo3m~`b8+pApqeOfgPNbbazLJDFxJ|A?dAJ*A{t1ot|68NNw@F{Ca5OrK z%*SWF=^DovSYWDy3=53nTkmgcKA`-86EJjHwZ=WQ#HJ; zj5*uw>H-kEOeg5@keaV4&_}6>24LEs+AX9=v2^94qb(Ik#iu-^ocr7@eWpd< z&Yc|bVQ5R7Vq<|5nZCNfD6pQ)P1ajUkLKEE=$M~2U{CXTGCo1=^#+AA{r5*g(n*1p zCwkV~Ww*6n{BOanZiPOi#syL@c*Ki9$#rM4IfAZrW`4FR&2p=YwT-;QQQAd zuKa&x%iF4$PVy$~X6S2dVgVucHz={RX{q~V8mb#_Bc9208~o$6lqWVpJ}2yeBs zCOvylQ7s>AEiu6SF1I`;zv{p{>lmQi=>+&)ggJ{K$^GqQAl>VGiMHdRU8)Ku15(KH zdXQu;>#OcjCY`v&eJS8u>%$)}*2c+%bl5e5<|;5AN3feTIUqd5_&{7kOZ`A#1XZEP zx7zD;8%PH6t2FsrQkXAa0F^U`l6(KK9ML)ijAC2B9^?{BSTczZ zIUDL;z16Cs#w7-H7;rpDnby z)YD&avgy>YkaKGPW%^HPmNbFb5eBxnp^V|uCm9kovd5jVRvLVuS2ZJ<0WyTNenSA! zxg%t5(A+ov?e|#&b<-6b!RW93od+|2jCcxs4L`44HYt9VTCVv;cBZ!GEm%PF{W`nz zLSVFyUC}gjW@fl)_O!9g%+sUgMK89oTKfAUXtUZqLW|pF_S;PGSSiP(;Z?r4t`}Ew z>XS2$4|eIk>~wMfK%KM>TQb|f{zAF)E{!Z_jt8HLzxw)+_QBx2)v800xUZb|Dm9&Ng$v50R#cq?^8Z(YFNsp>LqY@@U*k;;7Bb+m7CE14~62$-qM(yV*#^t zrc^|xWXSNL248G*M;862Z&A-AaU=~4)RKfigo~QASM&w3O$286soJ!ff?!!6SwAQ5 zsomqO$8RU07n+3{vJ8RCj|I*|&^E<>QjAo;`CpUS@+#*J0R)z_RiSpA6&eylutMvL z6Wx0q8IiB$!!(2o?Aq*#Sl*n!9^h8}nR172##~!SSU@riX04&#Fn2`$Y zzstt@spCZ=Y4W&DlKy%9)Y}DRd7{b~OH*S5BF-tAD)q_N`yy8?9#K#{prEj*I8Pwm zTKj?@=vkrImn1kBdA3s4d0EMBp`dluEEBe`Vtr@`zshsmUsSPt&Z3B+4K!LvKmCCd z?h21nx%ocyVK{q?ZJ3NgUOw<=@+Qb)y+Gi-bH+2V$XiZ}X*NC$;t(RWb*F2zb^LcP ztYk%f#w#Zq@KCGwc!qbWQoqtO(#!6CXf@spJFJCQ!k%eiAu&+{r-m8K z0+0ZiOpr}}ahi_zjXweY_Z}JBQCEDqvI(q>8K~Ad{eTAuA*yt)%)D)Xe4LP18G60V zC0>-WkKzhP+$YvMu6o>$sXLBrU#@9;?Xax5OCvYN#NDhxYA|lQTzPIi;lR>{)^qUe z5<-nk^o*K@A4A>&nNH}$Fkb4WQ#~r5PqWx2vrFP#5vi#YUDvH2P(HXDAqUI^)Mch( z+RfI+yDKGCcTuhbr@6}t>%N0D`XC07lzCm^_rSu;yUji9sNbf&0V|E;dwMm2X9GYc z4L0DiW1w$0n{3|;`Gh1DUtEq4KnmN83kkS>!)P5^$2*tj{>)0w!Oj}ZKeUi z5V%p>Phwfr>y&$g+h)C%@tH4qZT-_cCHqSDn5`~t7jgvs$WELgq!9+b`x5KE222#h z86}1?-!6fVQa@HWX+N3Cd;aY~^kd3zJQ3)C?~(`$-za0Xfl~%z3DN>LdD))}jD^t0 zewl=h`#`EC5$&Csf>K{OnPibonGTBmK8?l)q$)mMVg=cy1BvCkO>W}j2vpL+J$K}t zl-HHyZ)_riX!`%zu8pK(Yxz}et&D5$x*u9tnvX$k z*lBwD^p+nj)>3n%@9K=6a|4>L&_6?vbrpu|1EjIX6`H#m~#=a}t z3yF)5Yz#lCYx5K{^`5naxHVZB+3mGdlQ&2PxPv5uFa~(jb`%@}!Pae#7Uk~Gg4k$A zAC0zG??367G`SnC+w|q39IGTEBIJO;yn|7Sg^Cbvway}TMvY8jF1@#TWREP|()7Sj zdZ9MiZmu@AF3Wmd+Ru~nbl~L5v8C1Uh{o2pBsm-o_swk=bPI8stt42 z#os8JF9K}Fej0qCy4blsquWAlXa`$zpc%x)EaCZc@cxO8&Xv^fk9#O|UHPLacfXNU zZVU4>6dp45>&Vm1`W(CXK(;%)zCXYs$f2cR>)CAEPW5he?fJ%~BWZAj2Wdbq)F|rj zxQ6Z3xc5sTwrVp1vto{D3gl9?-dldi6vVGuf9usZSJc0?O#nmZG0IjCbLZ^WZ$EeN7a(jYQEzYf)uBffr<5vR-_1`Q|J8A#v=V*7FvcgQ>gKt=_k_^Sxdw|EZj((Z)P5F-KE9f% z$vg(t3A(6`^q0Qn1{I(O^W85HitJ4C->Dv3IDF$Cx_4tHF#oZtFYuRv>rMyjM5q}t zpNJ^>?fDPI{9Nj`A`sH3M;i9y4Q;_J-X3HZ_Nw7*D)c`sZV>07l&c?&hseSi%esr_7Yx~1c1a+k93#Vt4r{<{r5 zmW5q84aJ^xLF2cV=FN? zyAM#RHn`o>In-H{nw6TVwdeQ#Iu1cyM!Mp!%G3OJ6VHPvk)F4LcwG5+Q}Dt{?~uM^ z&pb(F4(a7u5g2x|r{y^HXht%39?f{eMk@5{eB#h(z1Mx7#=k4Fb&RX%^0CZ^eP;HJ zE956Y3@PWL(J!HA4R4zda(3UdPk+18BMx%?3dIC~8eoNr(&|4S)o2QA9 zM*f$rCY6#A%Zh5bK1u`e547fNVlfmSUmJEj z7v~thE|5W&*eDyu*3ubGqL?JNuhBooCdY6ZNb58tPqO)Gr8yLBW*Wp-xcD#bcWH0B zDQ~tuyW}$Y1nQRy0Eu_(lE4Gzg?8+gHC%T-ZHOuloI5SlolBCPKh=f|6o`#z44$ z_`Cr|yn7#0pwmK^BX5kQE`MFb+Zn0#%cl{l>GH3-DH?~G-xs}c4gUE(BD#>&ysVKHZ9S5RF=P{EeP9usW`EV2Db71rB_#TQA4O&H6>^3V5A)P{zhCVrKt zXw;=@{wqf3i?)hD8lc-%dr$+B$2@kArW(T%o^?#!&7GZd+BFgrGA&2wnKaN|d*A0% zpopt!!Wc-SYx2>=XF!@o{FqIyJj~W)*pLC0E z)P(6pv=yRvNPJ~a6&{ssO?9+m)LAc+KOn$I2|FbhX{6U5Qhes-}E4S3h483dDe zKvlPkza8XQ?RwOt(TdW6?AMMwY-6LEK01ltijhOR(4Fpg;^*Dv_qDKBzYqq(O*Aa`#_SPM((kZUfh^r={=16$-~IeQ0*(HwHS5|ZTujdnA4_zz*{Oq$H|4f+=-b<> z7w&Mw=Dr}ImeqXco_+F}us-0uHgtkQnpa(q2XM#g*R-kUCUXhrc4&)LwZfAAzsiul zIoLhD9op>fVo$sR{~}G0EZT;GTBg9RK~O@0@$Im)+r9_6!(^zjGa7brgUnnF3ddIz zSiam9XmpQST3+;I=Bz2p+%%Qhe7>>3XJ*jUlu7Orr&|73op_SI9N!D^S)ec2|$Tl_WOunBethm^^w~WR6YJSU6`gXfrS$yw?$#|}>XV@ZHixc$Vjm->x9Nr^&+Ze+nm${QnJt8W$02A+%dbCVU)=fA{g!cUq2 zC%?k~()>q~=)3=8kSOa|s4gy?Abt>2Ac8ZRzfKu@i}-V zEAe>gUQMybg4R?+GpD453B~Ivfke%;fh+-rU|Q{z z%=dliw?H@VpYSaVpWFy#MiYs+^c-_DSUxNz*>A*NucMM^&E6TFdtDJ zQ9PkGkJ@dbdJbl|)i%29Oii=DkO}`C&OjPx4kX{E&!;*Vc2J$Cj$d+bK=vSv^AQ4{Ua~nAPUo;(YQ(`8zctXr@|OOTWm0>?z7i5X^GTw!iHV(`S((4hP)= z)aA}i;`gV|Gq$yD7E z$$LlN0CEvOu8wrN&iw)Gl1(|3%lK3@AOXsS}3YN~_jEoSI#boAl}wcs!k{Ym;R~p!bfu zOE0C>!`OW)PU|yt#axf^C)}Z}I-vu&9$FCaZs@3LGMW9uH@zbr>!pP}%caewj3#f( zV|7&gAz*&(Gz0r*kG*JH4#d_J>{eMqb)%%r;hTp3v*Jpf`-HlCE*X!{?ao~4M8sjL zMDkGURoVGoLj*hb0ja>2>WeXW#vJaC`jz#w5wSSY3pIV0!{hoVeCXaoV7~5dfo!5j zn0qevP{T9kwwuKfa2M!4?6{{Olu-q*M9t1Z0)$S zgya__k!1ID(NCtkCVbiE85UaN$L?ey+6nf7kFkON=2n3;wgq>mfNk>S#482P1EI#Y z5RVB9OORx)wA_9sMN-As#*>3rgpgGuyx>4DSQT?S!wUmr5A-5iXuZCjXX%3lQOnCH zad-DLMoZxg3zPVf(DvTShmW`?tR>voOfHb;MPE0(w_%kEhsy-BkM-em#vSnlCP?}Pzh;dw~I|qoSVO3 zPEJmoKsu)9^Z;)f`evDr^s9|4cquFqUp&BfsvOob4%>8hTeTWls83pG3_UqkhdzZ) z0-AHuINI9j4T>1-KLL0e=TzCJEZ&qdKVU z0ylSz@r(yTP|4+R}bE>wZofV^H4Xk;;I zX{P?Qv>Kgn9x=*E{rr3DM;oT+*E9T8WQ&|+jbVfI(J(ewZ2ph-I*(j4n!dP?D(Fw; zKh=0|!O0`MBaj#R3&kEI-|hyyy`9^aT<`8xX?tz+_pnfgf2G<>8^d*h2R))giHx%y zc68Zmj-pS#wx-uxK3h>I9i4?9MJl^-UVm=LWXLM2nJf3_)8||(P~T<6=|n%OZ9yL} z4T-c3=o?!*m#Rm}i>{Jl$ z4wzq9bA=5Y-0uDRO??R87&RI_@B>c|Wy-!uZX=A#tJ~4jpiiLAhcC_14gG3a- zl3;)av-h_OjwNAu?)NxO?E9ZzK+9fbDIV^<*lAU|Zbw_u!yobGg!TB7L#PF3cU2JY z&;VxsgDf&qrW;dt@ehS<(x=kmhW692DF+_Heh%Ki2e*HY)MRMuY-{b9 z6xSh|?t$5sobL*;YF|A<)-&1H0$Rdv+X2I4I@lqsjE-@?)BR_&sS6x5Vo$eCatK%@#YYw|Zdl8P_*L{r zJv2|7@CQ5?mc7WSko7WqYohLAYDui4obwS)iTAgvlL`zHhEm*%YgYG52%qejw zJ_lXzJ!DecJM3XbSl@YR|Oh1)bs|SAd5a zg<#kEF1o#BC72yS!KH=%w)>V=rl;qxa!8gzEPviqL1rG!pNoFQ6L*VliQY{X-yus; z+`T|-+1pDvioV~Lu9w8opw|GQz87>q%Y0UlwruFf!g{f&f1SSY&s+B>)9zW|7lpW) zqx&kFrh+tf#*YET%`qy2a>xj4R?6)+-zFpU-i%!+@6H^X&dxfP&4*)6r00tU0K96d zt3(L;Z2p7{cVxD&^zhaFsIY4#L@|12Y$$#r+kEfMHE|hQP79#U={5YdwUx+@J2*=O zj^%OL4oM)F9-poyW_VhDCHrQY$L}KfXea-|dlu%IizDSn+6k9Fq5inCxQ?X~pmp{X zc=)fSt&7mYaMCs1me*4mFB0vTyt$JnkMQ^hENDajg>!oR{={tNU{P4d;ncZs_6b442`}4 z8RDJD&W>_M7pEH}jD+nSrgITXRYUKThf8*+u{}~1pGo2}{hXhs5g^uOIpQ<@z2V-t zs6rX^ABy+q4~y_jq|LywoN`n#`B4aX{?kghW9H%79a6?=0D(EHdsc&$Sn;+OCpc}p zS$rDs@o)N;k?=ga`H)5p-Z|`c<9hQW>W?(#{jUcPfe}!i(C4#K(vk$gY6@du)~=Su zFO*b{!ggP$ppyKvA7q0mU`ZpoQ;W==`wXZnOE?Z^Oo@jvG=#uzBdW|$e}kn;SiS>q z*~tw0Nw}0J`Exp(r|N~vz^K_2!?TL?SuK&mY@em_cNN2HUIAd)KZK)C%R3Qy&9?rOUHcK#UB*I)d0$kk|by5NTaaEvP2CIk24i$K5y1H{7bh> z&%YO+Qd&{!=V{^~&Crswa0b_I~xp!!(E#|Z)jIkKc8Gy1p9Ao0r_%`Gugsz zzoOFjh_AwRuxwsN8a?4J+|1D`ER%KVjsFjA=K&1o`?q^3k_e*rAX=2wdzVD?AbMGB z5IqQ@#oA4X-hvt_-e0(8?qOJv zUL<+-#|Hk$1?Dc3QL6{n8F)?rep67y-K{{UJH7rzvEb6E0Kr_cGv0d46GoQ^>Zc+) z$<@3$KzqL2qqf_y?{y`!+i}00XjfJZsl;J44b|gV+`W{aU@B4PNMK{A^R{=)vuSDV zGwME^eG$bdve&Ik6P50nki;t_pae-&^p)%WEw2<3&7+s}Fpyz4J<-#A_wd5i)gaPj zVx$13h}BwW+F`W&Q*9BR-4@*67*nZSusSPq%6IRSy~9uOfn!=&D2&37Rc)%Qy{~xZ zk~t=Sss0a~&+%Z~Qi_-F?T_f7r+v4lb%Ws!tRZkRc@3d(U`Kw`ZO&4E!Z3j!(h8ON zZhOD0iZ z%z9HQb-nmrfx4`$&uiq*N)WB=Kw}y!rC+dCyQQXpu2xH3CY>wI#FFcEz*<7Mh-?eJ{$W zD!RU3ki|4FF)txblsonr7qtDYTFJsfkCQt!xoTxM6H8NS7-aNCL-&g(FZQ}C=mr_<{#Elw!OMdCzb zHspuZ7?0*#T%@{IYQjFit%0_^WhD&2!7J#%7^kBa_L?Nd$Ti){-JXjKy^U8~ii|%r zB&jS7KstiGc$_Z^UytWUTy`Z#EU#o=*>fP9zb?jXh~{4n^gJDCQ|kGBRCeCh!g|vW zaaJD1WaxuyCSQ;cj+7U8UDn>zeX2JZqanTQ17dGv0k^r>Xa!Md1Cr2 zpU!+4;jeI(3(9k$o*2a2N~;juwEPwy?I{9*XkAh3UKzm#S?@zlP>pY(gqXW8CLd(E z5)MyE1%(ZP ziVgGo&m%3y&l#HoYR@;{H`|KaLkeJk)bQ=mbJ1dl zq$Ny6Fnl!ui1Jjl8s+z_>oQ=SC%f9;%0{OVjv!}x9}$7>54nXigcCPK5V!cuEL63y zVtJ%G;nXKfO zw-QaOblN%4`rsWSkni_myo7@@688F^)&~F&LdjtI_D9y&4%e00k{;Gt?#NRidMp(( zSr!uR%HNylYg;zJ>60)Ymi#o?f!SMnL0<^JrGb`8h6u2W#hP(VezVSP@I_Y&WX0c{RM zYTzW>Ow#?wQq1h=9glDKPv4q0`{#3O)+%f?14Z>>5skidKfYf2EjG99jC44Fu6E2U zwao;ZCEiW6r?cMaK`GI~JEh#K> zeGlo2Ufdx0T;vU(I%4*tdxA|xF&lK@c_vn;-!bb@5l$ujkhAo>_bBLobtOr8o@jLm z@9mq4gxEHzj~&)Zv=zZH@*QH-7!x+~CxB`boVJ%5aYD2$_R5*wZu!BK!?VK8ORW-J zZS#DHA=DIRzIb2|HfISft8aI3Cv}hz^9BoCwmRE-kk*;&j6RsxN*mRR7ohf?GF$Fh ziOZzKYF~-q*rs4NuyEyej8LS!tJB#+o0>uM@u4Aq?3;4?3<_FZKEJROw~sHwe+vb( ziQ*QnB%svTI84c!V0^A)q6S&$DbpS}25@EhV&=6Ap6`#elly9HWz{rB7dMhsR_P@u zq<1SlaO+sj6SZDYTK-xL_o0x2(ruV~d*$ySi<4_7`mlc&|bCuMpmX#TM5SCD}ng7rJk+s-*YjQS?7eoVAPO9$!z{*ISyKR0EUzTljk$ zs4_6}WEsn`CYZZ=&FDIIofwE9)gAEM_vsPJpt{%f#mHp&F99#tY^FlPD%pNk4h)$^ zEDu>DWtrYu(?!xumY3VL(e^T>|A{bHFBQmzh$GAOZVn^%+-|Q}wGKd#VuasB0@rFO-`~GpDP* zZHvM4U48xBidx`%=eUmmA@yiMYfTb?ap){7#x|du>Qe6+GrDEl6@gU+7-bk9seUx% ziNJ739R}U8(_grtxy*+oz^i9E<6=HTq3F;I?^OYpE@IS(p{4WtrR&<{^ynpQRiC{c1D6n? zgWsbmTs$Hnh7;-u8X2;DqrjNhV`;Wx;&mWBF9UN=T}59|TXXa9bT|-OF6F;#a57)g zpUhDRdya|yxCTDZ8B(7SUot+|O6l)tsBVdM65w1Msy5Qsl+^2Gy35yHRWYixzxYS@Elcm;wzxec1LwVtgvzW} z00ID%izOJfx5R{}$auzd?P8SixYktQdGK(k+TjHI044Gc#Ov^aW)7~`&JUHtf{UFl zsf%VmzEhf|4Ds@cH(uGy6##vun=W+>#57t+|nJ{u?P*^}>^=&FcZZPa#{u z?s~Nv-}a!-wS`0Uwkib(s$j?OV?0yvD%%_ z977{ecZ2bFv8qZWeyqyDPsa5f8ik)9aSVX6Qhz6?I>cAfc1K28fM^>d|>4k5O_*Yhbr?#XQu|0a!m5al8;)b$xr=<2uujkn8FNWVW{hEZ)DN?04^H^%h^6*C#@T-=Q?G-BZI2 zFW|k)l$eT6cz6YBEd2dLJnIZceW?1umg8@ek01Fk0}QX@echRozTSC|7nJv4cVSH- zZ~2}q$DDahdQzj-#D^DO_3wx7)o#V_gVsf)_XEk6e$^Zm;LQX3PDjiH6p_8fJG)R+2(N?O`7!dqXI5YSD-!U*(k&Y|J~1aEv1WbK4~F{a1ax-Cx>=v$oY@>Y+#|B#r&E{Y1^kYff99iwINKXJJRrN zlBn5FuTN7KYhRj*dT>@pQhbN`_K7Dic58(~002ir#2;2l$9D3c@8T$&6&)7514u>b z1rJ;MC^a^RiI(D7XLHG#&2Bk_KTMK zqh}9Y6VF9>y%@hJrL+SK#2{<@Pem$BdyxaGLOZwGT$aVmcK} ztEewQx9)VyqT)tvDuEiXh>^x2gzXtLD#~-1&oxKR3bOkVUlbB8eO9wsq8%DVbu@oOW)|n)a9AWpfgusi`F?FWKKLO0K19NQ_d0^LK)Fpw^W% z?sZgWRxRB}1UjkI+}Xv17RLJP;E*iiA!bZogF_JZS}v%u6ZOSg-|)|00tP@bjk}!1 zB=zQ^!+O%RlRx^3C&Vxz=&%3pjHEFR3h;Y4I#kpWYLjabQE$8Mm# z`y%Cy5R1+*4%wvU9@LJ*@p^qM569by=H8LbvR{Sc`wMmc_RG&M{!}-AaS601bAT(5 zRSZcV5q;e#d5ly&^muE6^)_w+J2mf5hwUGQ;f1lpJ!#(<-6GcE4_stpdXFAY>Q0qy zC2JR()#u1?-zSo0zM)W3QPCB5bHxva(@7gXCs#RhA`u0@isvz?Bv<1DJ1R&&?l9=E z){R_#gsnmAfIBFyVsx%Fe*K=vZF>vdSyQ);H#Z&|T_52C2R#d#a~)nzwoI3|Gf~Zx zf#{}qtu^*_??UB1#@YrW12la#HA(;ihKEz_bh3+T?Rx}bT;jsu${*iVjg!Qv#;hv^ zEfdZB0V}v2Z(Z4{{5-(VxFgh!ABXLqjk6_7FGdByP92{W9(O)hDoQITvdi8{c^{kW zdnXGq*L6-O<*Q%n@syI+!Pn;zU*YWp9fI3wxTfo}4tD{QwJ@X{^DPuzq=XzR;m*rG ziP540qS}j!3VKOYYjwYM41m%I3$>ZrOaqm+-l|T`! z-@g`b1Q-1!=sWEQJEqC-#}~o(a^TxGwf}oi`sM9^7tH=OAN}NER&R`pDSE3*iNU#@ zRfBVSzc#8QN`%tggB{tUS^i*67+s_=W0xVddb7PL@AD`7GAZWjw}yDm*$a&i{A zDuS~)V`^x2aS^n%ALe~Z_WO=4*R&Rm>-U_>OP$6R*5LO0Xnb4Xnl2euu3J_p%I(vz z_pG=h?M7ZASDFSnXDmaksXJlQR-4WY%u;F(53};!F_~CyPn#dxaINczU-yOA&P3L+ z-dfpv&k~;(b->uI9c)zl>voRxpY-%!L0}~b`UCR9&sFnV=ardnjhdrY7;u`cn4XoO z+G}`cnp;KAcDxH?Xi<@4il|E9)`+NTC7Ae^V{Y^l<-v)8WRDOFuX(?_D2cd`RuH^k zPstX;d{$PZRq8yWZ(90x$x8m?c`3;#g~4m*4>dFt+5E%A%n(ML5ZVD5Z!d3&5+Lqj z@2{%I&re#n9uwR8jER8Ve9Aqd4_K0PjxG zy5iW@-NRG#9dC8bKTKlKY~MQMhOw2JLN>m}lRO*^c2?;_oad&WC1%!(TG zpd){;xgu2DRTn%_b)8jY<%H4latMz9-9Koq=zpQUnc;xG>H;8!?ob04R2j06D9=;VZ!Z1cQFxGI96XV)ev+TKo1E*CJSONd(FavO6>>~0n< z{*m9EiG7zDV2|`-#)|S6RL$DsyQ!`dP04&86Je6ouB``2sNGE!5sI3_jEfg-YG>h? ztnLE^2?%8ms)HK5%krQNV^@%hD$H+4o7~?azVOuMoFK~fkQ{%@5k)9gdDwNC1oWHT zaaz8Q@%e}nB6YO752tiGFHr*uI`_8&(* zK`%$;EiJ1sI!mRwrIVJX1s5vG_YeqbI4Ft8w|EU??`~}a-l{~rNo-4tf7QWIp!W>o z81IuDr5*SHw5p3_jZg$l{Q(IvV?9@1G=O=8N{_6yv~1Q?t!oCt^xOFxElPWGNkf_Z zMgk*lcDj5 zK$u)Y_X*Ry1J17p3uIf3i_24i222r{((qI<0bn)$pI5oV8Y{Ab1jmD3-&^LNLXDr+ zB|V~2FWo1DQ2CXv>2Qrn!L~!j)wo6U#*R z{#7M+zzN_B^qmNWCd2rE$?k{!cWn@J45x9zXi7s6&#gX%ZhuL<@8=I+pM5$WfxEbUO2`Sn=_Vow&IidY5{i7@~6d{HH<#mck(W`dB@&ezSdtp94E zbES5si)=m$1#9|_dxGynlAJwWg|H~RgqtRhx#0!Q`8E-p2su?_fjm>V2!Tm zp$u5wHEgTF>e21)f<1H>S~)=B&(!*}a^X!8`ErWL4c|i2x>T>wSI{C9ukD^P&9j2Y z1-Ln+=)4ie){9OCNA`=opgZCoPERh{PQEPSIbxEmYhFBS#+_huuipF3tVu<>)s6)_ z^1lPg53v+ZYY1%Ys>Z%f9QsNVOR4xOUw&AX2-MiCqzppewd$C`-^QLm(Duz^2$y*Q zWOLxqbIusMTOT>?rc8U-$+vq{e|t-JmU%_k81amhmr(Bc0LIp81JqJSFRtils2XDNI*0t!%B-G2wSnP%Z)7IbnhuHs! zdEp5$et*WfB*=G_dw<9O>IGDz37wP@b@x+F?S$PFaN&rGRbLLQTjE$RfPjYT22k(0P%Kxb9-)gIc9Bas-mjxWd_kE z+v-by<>YWO%%kcY_2rw1*rrB7VoQt9`;wK{8Dm{T3I@n?bC#l_r>JXVS2;~`09$62 zpBGB3Bs2KTK9R|G`A6{~hsSM_v`hCh@#{RC8roREMR(#4y-;rZxI~QGx<cx8 zg?^pw{rYURi7E9fMj2$dLDXeYCfDM9e5#mE)0faQUJ=@3aQ5?yh4q-b5Acc0Yv*eA z{fWy#pC1UVZF^&Jb`^e^>pjBGWWV>!Y5q)KxoVCHzOGHCGY)??B)?lyS?nKe^pxfd z5vzC~ck?<9C$X+X>-Ts;8SRTaQ0khG84bNmu01#LPv(!urC%xFlv~hY2Q;hxP^m)Q{Jx^S>G!Y4!$`Nxb-frh zNIpah^997xgGfY!6djw;kLzqpiCu4+3a({D#1h$?%4a9MHCHA6AS?>zo&Yvm90ub! z71{#9c<&P4B?0><^iLlR64~-An&|s-29re7{3_wGUO(1D@T}R& zXMJopvqs^Oco}S}_xElTkX(<_pK=vAT%SHbO+BW2Vdr>1mnh3?U!))QWZ|ie&z8g) zH;zgR=z86kmsw+Fb(!|^3sA*~1D~w9v=`x3b;FJpQ3cTjr!N%QFM9tt(dY6;?ClB9 zr4NGw=qJtqzn|8ru~%eseQo5hw-FgOmr9Qsj1Y-IH!x=%Zw_367eqn?)SG)zcT&6&#E4Q{sVnhzJFClgk}0$*@LR>v4*mq3YtXuJA#p!Y!X9e z3z@v)`x)g)Nu_D#^?&4RG|(%ZN3(ZP0gGVs#hv6?+QJ zXZS-J2k7l(uWcnlz)1^U?+ZgrL8as|11>^Iz6C4neZI~*J`5CQp)&+YuhiwE4~>aY zN@%^6xkGpqgebAM*{V`}#2p1ta|@HtZ(TDU|LRS!=tbTfdIa`H)J5!`#3ADRkHXesOI7#{D%)O&oG;mjEHy*)3QEKSF zcLg@-s4*=b6i$fZwO^?bucqm)d%77H9nGZWionuQvzCh2LDu}$84nt9;FL2ve+@v=YDo8bu6HwwMSN$#?yyFiBW4F}}D=+8Jy^n(sm2ZbNFFFAe@Ogv&gq?NFA zaDb|hmt5AS|7>lT(IG1G?%lIu%XN_cH!gl9{>^5qzXXA)@)F7GZ)b}QYwW;eVMPHN z&-7aACZfKWFIZ+q%mF3dol0oUu{(2qISQVAYp{l5tf;zm^F(RF^x&HQUxF6z1g!{; z1mdsY2R?z{K%hdd4{~@OY#91vZEPRm?~cIMbf25^mF>gl@Sw>Wfs+0>?k_(rAImq< zKR@PouYO5m7Vom#F?)WtSB0kQR=V$}g|wngAf+8NOE^N(&J-Bj9Fwokm1vCO`B=A9-mR_qZHPI0PjwbE_A*{}*yB9)W4j%iIXZnpg8_2QhWzbK32Ty-&( zp2s_mDLf_!qa*#o^)8Rva!h%O>iM6Bb=#e{f3U%!UXDL|Oq@fExO9y8f1#LdYoM_v zCc378Fw&Qf9Xl(-jsUfZYT>mRx;-xbdCryj(TDYw3!?Tap9}qHC9l_>V}xD%2RJ_z z_4lsesOE6i<*=XiwC@$;{Bs9Ty^Uc#CUnNfISXAziTe#ADKFIRqKnyvKowv0ko_tTv}UTIU}UWfAld`QucuC@{bl# z^7OZ<7ZwW}PJNaEKoy)0`?^I7aac0hqwcP>G9uMtJxw{zG_561ljQdFS>V`onTzHa zgFBK%`#=a3$*^&K4VTc%TE^#k2h|PUs%d6+>Nfg)ArR5$i?duN9`})iN?$ASvq}t# zJlOOXE$$CT@^w;TB=QR~^+!k94@)_`^{%#OoIh}jLYr=9jI^9OoONQgilLs@X*loI z5lZc}kw0m=HeU_4#@xkyDLRwi8J#dvu$;Z3gROrShTj)op><{<|8@9o#C(41#jpLx z0Rd6q!g=2B05~l-m%u3L<86x1Pw%vQNh89G=!-?2{N-3{{XC)u&`HIugJ0~pb38RQ zKt6$gI=r*5RIWH-6Z1zsmJp;O5vEo0EwJ#ayvO;5-j?ZfG}Vec+!b2%F3y8EeygWfR=d-{6>tdwV&;HZTR(UG(ykvj=_9BQRgrkkf57US<;`nrSj={)<{`6jwG+qRCZ$^rLbN00wQC?= zaH99C+>`P6Aj#-AQ38hrJKuNi`?*}{UJZzGOT)_A!jVymUuch}GwZJ}V`i4Dfw2gTi) zcQWS=9NIs}@ zemsD1|8XpidocN@!ET{p7ygugvlabz1jSYN&A(X_d}6h0;#+O3r)xN&wjZ|7i*W}7 z-B-o|BR<&O6m!)Q!9<$V-1C#J&)w|eBUzbGxaPq{_lbtwY)_4#%)rW#^Ao6fbBJku z*8Kd8g>j0jHta=9QiN80NICQ`fshCPU>SS)QA>+wkft!C)#d2;Tq-22whebazH^>? z!5W1MMP#lSQ}lG!UXO*ys7R)Kc|E^VKlB<*t{aSJbe23* zWCPx8V=~n{yh=>Zg!w|~J%=VgTkrZXkG^z~=csn~q^d=eF;-gIt8QR!5l`jkWjX`t z&7`lNsPz{g5p`)yLlG{zy31Gf>d#48^j>Y*#gT0J4nB#HqVX$fUpjp+*wgd)&$#aa za8#K29Uv7WACQex95*nUKFo`pH_NRLlG8GCI~3&d`V>pgW|CkcpHW!)mVTWeeq;q0 zoe@sr#PVGFjG9}kr!r0VS0`&rhKBka8~jma))5G03S%>=@5i&Qfr!Xe@4cY|S~!8l z5;g!Sl?);C7O$S-4%STGDQ_L&&7n(ar zzje&S@~uYLrG7*=bOmJlb1Jyd?okoLZQqJmoD52d92mjFI==5I(oFpkFzLyBP(N`x zTid3nwVmBe>PPzJR?;|3_)GMLP`_Efq;gSIfKoCRpgqb}8N$?i-K>d<@tDukOF08*lzE-{1RJIq>Db zaX&vi`j6?W&hP)HH2AMFA@KVDLt6fydje(;@6@ZyFzM=eC{I)biD2!fV+5(aO4MPz zDulq$08V@UzvHx-kg_WO2b?zOHza~Z5UY1Zw73JK#zN3zngA#6)j_$^>t8`-!h{jRseFyTgtj zE}a=EZkx1qpcf*=_-#<{Td}5l%2EJN$=psLZJgIx(83u4tLD8X*G8fEXxqi#g*;6o zzlma=h7ItD&4!GPDjIqExhWd=nXS76J_2mYnGjYB$Mzjtu@A-%T{jdc`~P-d=x|6Y zYw$siie%&}5W@KP<`H4w7Zd4P;PCR~TW9NHp{glf304Yd1HgLa4;5f_yVKM{#dqwb zD9yH~Ma-WaCmD%S#{d+dNU>PLxXxYG}AcSjXYielFUWtk61lvOPfBe={NBqEQNjhI->hf(&`t z-SineOH~bn#5(VE2p<4*?^GqmxCk!v6}F<=1qJet&zWH{8yX<)-`-FD_<-AVUCnWB ziYT7O{*8#vVy|?Qsz}$u=wE{Am55^;vq@NyQ5jgtvso))q(s5ncv)k9rq#DOP*Lue zK`#qA=0O%J#-zLXi|lgl24I9U>$#DBrSaP9p}x7O8~E#QJ9Zg%{sj09=WD>&AM_SK zv<$*}2v%S?`jX#=h1D(TOkPRp{&a(8*AMEldwKAXj3$WXe2?f7hk+0EE#6$2bXze` z;#g55pr;c8_{kU4;xb8hxD8Nye-K+0PJlk-z$+*5AxX zcF7Z(;g2v*u3l-_^mP&RI;tZQXFA>CW_eemWs0;SeZ#-&o|R=f+GopNEI4}WPKOvy z0GLnQ!p7f?7JzDdly{deSPUvIpgz8-oabtE;EQk6*Xwvc`_^m}NYe@P&|H>4!u}G} zs;0Z3qt0@$VW@ub5sv5ewNtQ37wen|!qS&7BIF91*Ykd3BD0G4;PFKoc$~V!+B&lpVQUooju78HT+4G+&BdFdxLQ zi-Nza$Qkmyc_8|PL19b+*rY3&F73c?z?jTd<`$i1&hU(r){QkS5damOc3OD68Nh<8 zKPn;!x+fu{C`J{r6%*)MQ`d3Jol@HC@c;{Byja;oYl=&%*Wo(8_4L|`g3ezS*4R9U%Nug z%c=9*8gOnMw>GbpQLgxu>{%Da&)*hy*`L?7#y+6~o!5WRxwqI6AhCJk_fejAEl_pp zQA>3dfcbdcFiDgzOy|yDoBdLKmY$#H=_{Dgw&Y`MIoBk6D7YGpe9%7xEy;Qc$?2#D z&Jiu0j9VYxxidqxqwthVT1azS%cnW*w$)V)EgvPRy87LWMPY%16j>XV7|y!mMiLt5 zlO)-wC6|gFyxLJK7&+%=6q*~|X?T75`d}zP{8IB^?{(YeQEq+g(5g1E*$kc^i+F)v z2`dwXs;p^i_W=3hyIxJVeto8)d1`OZre|0~{yqK*fnMk$MPL2nm*=0!nit64F>bbQ zrSP}%52cA4o@=Tq+a>X;v`9ynH`C zzwMSw3Yxyo!wU=j(EZpB%%kS;GamWog>|3$+88&@DDTPlEPv|dN*2Yw^10KibK_Ed z>eJ4Zsa&5IMiWb-Lr0A^4VO03O+w`AUhXXz;ANiNI(oj3kfz=|gg$ zVH$Nhttf&aQA55T#=sqQCas(ksl>}TsvMG^^$BWlMR0R&HC6auf9Y^STxZI=!V!@A z>~cRjJu~PYvv>)0h9OOJ3@d}&%Usfdq*r~u$vN%j$xy&ITq8{k2t;go77Gg*5KB-TpCP5c@qN`C^4?En)D6nJeG)onqpw_;qj(biv zqer@-^RvogqXNk$;L_g%5wHDHMXlMzGSWSo0NZQ7OQ*5Q|;+uxo3JR!a8a$ zW&~S(&d2>K%oF$j63qXcE9=RK`Qp@OYpk~wn(*T2ektPhL(-6vP2-y}{Lih!3v)V{ z1Axtlk_Qx=YR{lxp`-UH!#sksG(Bc*>EgXqGqk~7*?kp2mVzLdnUGUmDu4oN9u{O` z;^7~NQXTJX38G@VfNp*Z|Lupy`bC5f)O}6@K?;&Su4b`deb*F2Xn}B_{Umtu^^cP> zPSTAkmB0ic(?w7b&ky1Lewq%5KTyJ!O}1FZTz6!9AtgU@B0ot!?Z7=k2U02V^pXQ; z*J=KbfOt#g#gCjSd6#upAe9p0Ekx;;Vi2tM^K`p)A$=(5+4p_|0#UQna3dqa)KsIV zoVV6liQsNRp>R5hy+GP|ORettq{Rr*FR};C&l~iG->}QOv){RRa$`=5?qy3vkJm4x zem+lEUV`WRR>h}5F_OUhjo-M4bg2I%M!IrsxwoB}w~>7>xr?;Af$jr9cB}x%PUatw zU5wPc_|S-IFDRnaZn13h2|%)2$c+ZTYbpvM?s}GY6VlDU15reBJxCH9ux76Unmsmg zt<6^#Em`7@8oQ&WFp?27ops~N^17;v|A@b&{qd{(pQ=^zFgGImms5vIH7f^*HBxSH z<#@Zu%EA!BWtV%RRg;oF_e1jB#wh#!9MM75;~PN9Q?6Sa(!ZU-MzI1^p%}JHfj*MS z)UR=dCTK(Ar4IP(e2ikKJYC^6lHnnJPnHU>#Hx#N=;;g@^rbjsSC~W^>l5C2jL+AJgYs=1gf< z-$%{?jfn{_Mdo>wpD!>;pI_ppfCak6d1x&Lj;i=rR@daZOdPNTemNPIxljG10nuW1zLRhC@xnCRH<_yACbB9-TE_bzL|r)3sffo#8B4d}0A z#xwHF`Q}(b0pne8A;6!9o}CT)1I2JDnM8cwdAaX}XTOAH;E}A=aoqw+XI_(nbs#3P z@Cj`E`mZ{ox@!r$hS*J3Nv=qczcSy&V~zC_83+E~lD#UBVOAoX1ZEu@r~Ff1pkN7` zqBoT_SQ|QZTW4fcV{!H#fz4}vnrBru-|ag9ZO(x#WIn7D9+XLs_9-iTTD1HAoqpZa zNUTapY1Qcme|rE7IpsR&H9w)dBA%kYCVV{?Djt=%>QxySE(<+UlxXXqPN0Y!D~m6 z4OW7o4EgA>VAmt4g2X_#Q?(M1a~d+{5YgT2COEN`3rnK!-_eud5p<~TD381pEN$#d zU1;l|v)#D_ZLK_9b^;pc5>ZN_@_JmECAQwhYIh?}Bg{A>D(GG$Z!&=!o9IRTJ@2hB zfLL!co{Zh_Q|`_b!_=h&;S3Pw&Hyy0wh8*;@BK(!p`s5BCYl?)NdwKH~2qJ;n#= zS^U{nrqZ4)taYgRvf218g^t9HV&3E0SBVNrj7~w$S47vAf!FE6B*tz*B^rLcvh*^* zFn>C$@GNDXo~Qqsk310iVk_XroMR#?N#kYtIO9qXM~2GI`Mt2JsnOmbA>xhS3ehS{~ zJ{#bODf3ln*>o2KwN=y}F!ie9q`GezwP4%U%H+D2$$!$GL#Cel7^fM3Z9K^^ARJu} zq1Qj$e^y9>EDloZH`)4OVkmr?7@J;ZiMwPS_c!RmSeY0|j*3hm%y_wmICBZ<^4DhC zhX24c%*PChuX6$a!3qn0gi)csWlfiM+dL)2UE*Wjyf%U%`RvI6fB5lp%%|wDs5c)u z4r~Y(Ws2GfaT={yU5r|10#44Q!Ub3p3zJ5rD!c0Er1|b$ zKL_k@7_Zfg^7taZyKAtz0?YZ`&$V>TAT@zsk&S8w>_1A;QezLp`&?e%RZi;fy3SB? zV4d6QZjNa{l7%on&hYa4Tvu!U?S017iTOo%=|HtVq(9xZ@KJF;t*XI?eX?Be4b6IX zzL@7t-cIIwmnVv1f@_N~v&5-n+n^*Bb3wkmUrmfIE^RDJWI6v#kZjQ>tVq1bPkAb9 z=JW8nHmN7o33@jzc6~h-R42$yA2~dt?W*dt;5{vw&qO%nI5qs^!zK*Paw1-|SXxrA z>LF3j&sduMQ2d=zLz;jJ5}#Fj6j#>H3x#2TdY&D`bgLBgK*8+j$wfS$^1Ucw*&6OI zC;W*#R`lxN`=jcYLwKT-@6If;*Xi<>Iez6b~n1Xo5?oxtFf4uO)(vgPT;IeSW{VDP0;(`ON!}&cM9S~ z3%)n&;>k~&VU!iafEkOgc7FftQLWv2U?(}R z;gX9@b6x-)wwu6L^H`bW4bWMgie!_ma)OAQ`Mu^(B>`*9vc};**o+(xpglkrw`n8a zZjWo8g=o$CkdpOS)a4ekBASIAt2bGK*)FU z?X%7pYwdB?80TW2GtR}n%Eipg7)j>*&;R?r&+~hdb^)h-w)};pzMroyVG(db93yTV z$1*<|?q#8Lf6p*2uzYoSWrSali9OqF*T;rQWaG}exb`3TZ~aYmQ_yf&1+0eGUixQ6 zk8k#WaTAU3cy9W(Rl;(A(qu+Q&eJ({8!=&ty}T_{vSp9%VZz*2yRuW_Sbl@@>ChCh zUhPdks)PY=d6&O%*prhXDz0dV)0j==ZHoMg->rQEHb(U!@Ov?Qa|tT3eq?}KGn{S0 zYzO4T8979c2%Wwe&1n}XQTY~49D2Oez9b)IhJSN1^y!Q@|54QuRJ|IZ-c)>>5bi>; zsP}eCvi`?2O~ZClj!iD2OaIoRQj~=%$QU;4)6hIvVO7@9)ZXzsDOV`p2)sQqET+i% zQM{0|BH>MsRH->Fz4RpTpghtpY-9h*jag{m-R@!9POQ-iLTkYX&=Ggw)O|72fN4fa zdUOkc!LZ9hd{cOJC{MMVS+DK)+=zmdi8nX>W0>*nO` zYOG>vYrKZPR8KRUazwnz@lELfh;DxyAAGwWJG>LTlyfoJfk_BP%OI^`$Q9Zye%DrW z+QW`5HH+4^ShbjAj=MV1271+W#-ADHUxoVc{Z=HstyZLgsxEL$ohvaejg|c*O~a=} zT?BbbR0weCGLa@XmfgE=_w!Ega1PW8|DS%u3Ssb$XajV3Rz3%+rnnq;dQJ7f64CGO zsi+wcsmYN>qo}q~M8f64ytvpk+SFacXz<-gQv^=|`f`C``8amgZr9dIE}NR&U6N~c z-q_eOV&bw1| z2Wl60fA2;avZ>yLrjB}rGSn#Qx7m=p`qt&V$|JY*oHJ{T*xp|3hjA|jBPrvpJ8B`y z>t9@vr`9j8&y+P8#Y?JoE_YIj#QK?tRF?-DZHy@Dxi?dFT#VHPzphEC`Zxg+&rH>S zukSxsmaFV+N}I88>ww9*tkos;<>0B#L9{5}_;Ut%C(m!MjlCDc%&dP*a8Gx{fET$< zp<`cS`>fLKojfUb=b(X`!4yzJj8#DG{xeF^ekS57eRY=-1O?}|P3S#4OM&g|=d;j? zc1D4(DNBGaxGC6OucRdjq+<1Yw@L8fl?a)o>3)n`nzoHM`yd0qiSt$pp~zv9 z_TtTRDNXJphii74dR^LBW3jXJLVizeE31{Qg`8Pz;B9G;5{R7MIT2zo0kmAmBK z#H16Z(GU%O$ogG_nj+*U{_YW%$@od@!iA59^jMFWM!adEKk(d5&{X3=v@+j6mb(S* zR}?G6}=FI7*}go%VX`V#$+K3l#jEqN1hl-ADd_Tq&vesNe&N&wf6 z;ok}vw1``y8WuBMpK5Au>1>bgYqR4{;#BFg?ROhdeogu@ixUs0P6rH{7ptEruwTJ` zEdrzc-o7pk?;Gr(hR)8nS{eAxEnUoY{%t={LcMV(1NpF%$t!OJ9E`y6nR>67jKiKg z_x1L?a05K>$x8klEl?e2tR$W>{28C~-17pn@O`a`G)i9PE2hwVs_7f@M=frw$h!Nh zOL2Rfnje!mV~;5pf%JNt+{@*~+lMofV+!;-O*2gg8bXpc8V0MY)AM31dP5-soSY%F z_*5qn0s_Dm97`)|(t(%QfP~qPTBT2WMI)-2rZ_(pLJDqlehG5X+i>}Xsx9B8tg39v z5Ls;zr1;~2>&rM--@SU^$%2TRcS+QmNdrq}Yt3sLgNhvj{Eh?I4+n4jVI(dd7|#vE z{p-QT6^Y&rMiIpYsRlU?>d_)nF9Qcp-rW!PR8{VNx~433mG0<)fdlP4DUT9nwdLuh zPw#VOOA}NUQbZcu<4C+Gg#kLCnMQSq#tKIqTu+<(EP3|yc;boQ8Oap7F_PXCz%_da zalhEuF+4XMSlPKCPS>nV-`4rdus3yWiJGFdwwfi*CJd8`z_hJ!AHj!aPngricPB>B zbJYT-QOASUC#7jlOPG|tcBq3od)lkZ=8BJP>eisjGc`f5p$@qEu;Y5|NEhX+hq*yf z4fYUEdq0;S!c@@C1@r0xcpD!iX9hJyh2vy? z*`T7LBw1Bh9kts}j@&7#DN@=(B|}ZX)3k)1HpZ`{wF#20X;E>TzTrX7oef-rXlD}^ z7P0ld4)TtIIqF`^bgz}7my46r-&G-Wd^65zpJAZxJb)7m$D|*1?L(gZY-^$sdoQfC z#LX)!-(UCyT#!AjVrPepjv*I5LDe_9wfJ{tnuMiyjoM@9jEf;(V~Rd}iVYn!TBjlL zNR?gq3Juli&xc z(WhnKvZ8`xj-Vi<@S_0}en}Ja?s$3>&-c5kiKcV2&xk^P+vL(nEHA(!hxG?X^-2SV zI~3t^NXxOPKY9b3kNpIyS*#8Z^I%R+dyDvuK~vP>?k4*p^M+!zgJ049BM6;#pQJ7| zt%Sw$%k3qGtuOj|mf;Cu!x1mk9Ei#4x3My4MyYOqZYZ+2tvT|wi>+m*SR`>q;C)8M zquhmaE?@+VHrSc&wm?w|k~P%$#jde4=WxlYdFYjeshUTa+Rvpe*%ce zK|Y-+IVf9I-|u1dAhAmrdL`&>F#7Vv;)nrYPjGKmdig!Z6K}6?uE304B%vqcrKpSFJse^nuVD3XZ zO}pFK&&|fk&z`8WSr|Twx9)R2pKdMA3O+z7rX_qZ6Mdk$^V#g99ghfDr2VRBrim?f z-fgewXl_K}3_sr*rlO^yfmlI>{mMmZOILQa>F(L5IDMoad)>Qg&!aaS)+IfCj~DKD z(AUEf)DI&JdW1=34eke0RehcNy7Vp|x4(mZxxatF4f5cQV~PDyY_G@a*GrIlQynNm zdbiGUxmF#lpj6w-9^;|=crvCttdgi$N9(jf=gbW8Hl}0_F>es468p4P5A&aqW&b;Q z<9{b_{Qo6+ngal=~x-SO;6MtZU` z14l9_3+3LM6t(uCS<_pT3_{;;%`oc_ju`PPbfLRQlUL1%ci2?r(dNu`V$=&DJ1i@< zP0u!YgT+U+MN7%)CbB6dZ48JnL(1JxXpV&KGoQ~Jwplch*mNO?#Xg65hx0zTCv^_Q zJ|Y~*&RZBfVc2Wobdi_8=9~=VRPNyE(3}E?X(wgGYI-++lp)w9byRN;T81@H^}EO9 z-$AzyS@d2o$hmM!3wl0RfZN^riy47N=r zAS9M20T^HBO4~&aYA?=Yb%PMsQ-~i}`WNfV2b^EgkPfBxooz!M$s0Mo@$^>95w}j* zT}&zNei9m_g7&_MTZd6Q`$vVAobffl=T96$oin8GZL}voxA1~@Ckqad)x|7!6&x_$ zlwMd)VVT#1!(U08Zpuu>LMTB?3c{; z4*^^?Ii5ewZQVg{^_aJ)Y$`)T{Yy>M_6uIJNW0HdeYUPQPjwc@@ET#6hBK!&C|mn& zK9mbd^$>D~oJfk4>{fcy)YU!LEG+tVF%aZxpXz5~w0IGoV94ws#kQ&X@7~3URlch_g(TpRDsot=esLGijOy z<_ntbq#x#tF)M^v=qFhv2Jmzwo^r;#sEZm;q1_Vu>bT76V`C|ro2cl6(Lo+idLc|L z_orM^u7q|@x3%Ld(!!Dq#4rm(o9NHkpUrh@)OpXX0u=n&r!9H<{X`xq4jabz)RXDQ z8D`eV=w?eNo@!Shv;|?c@CKzwC?gWKc+y+=y(PuMg??Ua_2-yZtEaZlAL8D8Z{ssw zfFUz$Wz%q-fB+GY1z+x#;7M5h?2VCGV6f+wIY^PGsjf#QcGXMp@g><8jto3=TqmRV zN-UR#Y7$ll8v1gS;!Eqt3Xc z!}OvGUt%^<3sxwlm}%s>l{IamW7FqB$@eu4>YOqh;u_KG4~;VJ;8&`kFw$r|;=;$W zW2fGdP>o6q{O3UsG|}*nPXT;5+qKi2?dzL-zq*WFuH%v1ZzIojVG% z>(JD?B4Ya}`;3c=?dr(Pgr4c|TuZm-H;9E1niuBa%spFkek5yAG*igv!JQcU`eoHe z=tPJyaE5D7+a1HLKA`Q+cpHPy3g_!xJExO2#NXz@6_Z%MU3{Hqc8aGu46j^uU^D)b zbl=eSub=#e4F=zrXAJZx$An%;%@x5r$e4|03sMCx~w!0ArKXC1zE-l2<5kc?ist zw(yN4=}y(`%`;2C{||u|*UR;eZ)Zld?ven}n-{oAb|xuUg7qUEZRF8O9Shyh#iH&L-=j*Q;E z*5X~o6Qf5jWage$yL(ladTy?0t@ZCAbwrLwaeh*M+$rwD+{z7-cYMU_4$`_F`oHsE zIN&=>*zDHb&^_E;?+!4{Ig*XfJY5?5V79VzBY$d9mH2af{IH(HkuOsS@{@FP@^A#D zJG|EP4?&_WYUdM~>0Tz1XYTKwM(UbQNLu8((%qDnI*m`nKjbSaJA#l<8BA~yR1n1$ zfn+7)qRT2=;;G_Eq22y|Rh(v9@rAWju1>!_FY!f{xFw~fl%`SIrFlypULszzTe;yx z`>wHyhl2KLs|n3VH?0X?SZBl33bddGI)+ZVxQ+S_qmvRPg#i1|kP2ZEm5%N|vv(^y z`i_Le-UF6w?HGKa$x{=I@ef%7#ZU_yY)NR~_a)uf^ZPu3f(G$jDjO0k(WB#u@$glE ziD9U+V6sN9QXU+o&yME+uiim>FAU_d4;~b_=8JT`2HqboRT-1|0X)xX_7HkspF#E$ z+I~O#omoiE*0t^hD`pO<`w(KH6q&8|sSIL%(?1`%!z_2x(jCz0^I_Uja@Cw*$E;zb z*~l-h4m?`wEu>=(+0(1lH^U0zC_90^f1oW&JiT_$O(I<~YuT#fm1|?5 z`Qm+0VAx0_%TR=+2~BwE+tjXXfTnxx7+}$L^50?0p8UI7p4&pWBRgTxY!G$JuP!Ih zhg372-QTWDpd!Hh8;w=Yl#Iv)W3nHkqaR9{Qy2qXV|93|#=^JXYU%qpW7LtgSejRO zHfsbFPzJW6m}r z(@DJg{a)^iI`9XC-v8sr$*1XK7tKoXs^jP*pKv4jYwe3 z4(cSP%ZxU$nMhM|K6%N~N>Xc6fTf=~!uA>BK4o)8eWXF4lJ2aqH;5c`!2H==sK(ap zYkO<5CQCiuZ)y5rRGEmnm!z#bpQ$159%4cm=QJba=$$p&zvFE**IdfaH+pm0YL7jH z>f#*_xLX*W%ZHb^MGd&KyNn@Ax~CT2)KArLDf@D}z03NUp@-YO%cCni{Mobz6`}SI zLEF=U=6>WJ(xt-d;<-fpCVl?KcEV88&a}CpAdh`$+mYxnoC+t<8~k-|l@qlP|D?Ss z#qE5|;virIuVmWM~(vlg^_p{oDGZ*OyRzcI_S zqkmUTGA9(1Js9S4v8DwzewRgtgUwD|eHllg{HFb)+)POB%Q=$vO zKLoW=rX&3fWA8qH0*)sDOtW61S+Y|dbreyRLZ8Ntz+Y)!?EOlXwfi(fI5h4-`y!u> z8qj=v-LvL#?L@ML0ot*w(VA-sKx@RNhJ=*@yS=(Im#o|a6_4<{0ecL+1~3j(g=sXm zaHn4~`{@O~t6@fG^@nyh(Sw6VBjxrR6HPccSj?$ zXICGiii;1y<(M}sNxz|0q+kHwF>H02wk)|!ZoE+g`5e2)5k|n5eQYURtrzoZ0$!wDe^Y`YJc|M)Ihjx!`B*zzC6e) zs!7-YK7@E$)!hKTY$&`qGRNH-*r~m0m}`PIW9UTu>{^bS?fSrBxU^O(sio-fty)k5oA4-rET`;O&h3+ivrgw7JC~5p~tGfp0XDcy#150@e^(p2x@d>*rwM#I^yCgXg*AD2U~!z^|eI ztsUgwW1;^IqWvzp(qA3Cmx&$kWs>?YR;K^nuky9^9|8+c{7Iy^kY)vCcU;RZu7m3K zjx#|U{s8_4u%g0+%qb{);93y44))tS75)UPGfJC7qQh6&&Bk8;mtsTj&VPgg{O4C< zu&!a_loz7=m0o9PU*9xeTU$qavif7OGNI$+0b;#7+-V_qr10Bw=6)O{`Xoszi3z{> zpZ;MZNj##u5LjLo?mSL`N!;6J)6YuTe)%KitMOZ-&Y&@d1SG6IKR*o z*DYjyW$nI*#aN30*an5B6&Z=ervUG-wK*Uw(xQHZ3s?Ew@PTLYGGU8-36}4 z2%w#W#)7x#eQoJa;4(=Qz?7fCAyl%i+~oIqaC6h{Z7#~+|8Da_2vBuFQj}V%q*#(l z+|tFDM%mL*6SAmXLsoBjE+2J02V5M!0HEPVAjQf+d4+O?Z|R`$klFD|AO^6uS2= zTiZ8l+ZgZi<-B=$#}~{vq}#XFIynS?2+7*qsYD$~$#qNgUGp?ocP&8yuPxSe1XR78 zG9HT@bs~)cB9HsqeX?wTg+W9MSpFJF&|{QiVWBG%8?2>|=T~X01;|~P{=EPvkD=@1 zK8km=n+&yh_Obgv1iu@H@!7f&Wmt2JC-HDBOh4v9GxFS?UV4YzTQ&Rl2S<}cTEmCq zo#?vff%UhEiV@}*Q3ox6zttt4TCbG*TvzhD161elvNxLsA0Ic7;QP-cY z#j*eKReIRNj!A_Sp>}GE$9Ber-58e^j-v6)+NwrEQAUc5$~ryir}Y`vj^@>B@4|hb z1#^XoqDioyyDwwn4!_f8`%MxI2s1pmf8nYK~B&2H5nx5+fpq|V#) zQIRi~h!7r&U#|}8#`Uprqz&LX8c`u9TOFBa{C-3qC!T!dioJjo>S-zo6bO|4p?%46 z$7&0ogX?hf8UuQTCdP#!;p~5on8!+1T(jTH#6A2-^ogkK4fu0k$NDp8)OXtNS1=qI zEjrE|!-&M^SyQ6G`xqtlx%q9@bMG6;U#}d6!=JtU0T@lX>!${<-e1{p}4_Qm$+2YF@3~nqckVj%mMd z(tlUHC@k?lt)H7>%ZrJhEcF&jGvnKvZZu;M>wGo_OT$VNAd6KeZ&B(z|LVMNkkeN1 z@FXiHZ4k(+$f3N65#>TFBw*)F<^#qo77u~#o7Szes02jnA%Bz-s;Z3iI{-rSPHhwBYqj6eD$4Bs5SL%%ZXwTOJxrVS9 zP6%*OD3U?%EtsTEJmOp)5PBCq!pQZYK%?kQe8N=Sei49h!#%pCho^a(OIr@)awHs4 zo=QYEgB^&3dUN?m{2?udws4kk-H9)k74==PIGDXX;O(_vw(5txk#=}|#pN)1WhFD3 z)d@av@H)p8!RpxfwW?@bm#6>X?N;b6E0v zy87van*Mgff(2C9t-RWBZ{f_h-yB~-vos&Et4z7^%|Sgjm@j~eXVA)>_GLHjlvh7q zj;Ctfyrnfu^c()OaAp9E>Ii}Jz32-hS`1JuvQwExCT+`1PEAGh{xWTuUSc(b9Zu$!d-R4nWBbaAw5DU z>9le@a=WCIg$m^D6aOp5rY+G6fcOCrBNDnJz))v0G=nZZgx^p?jc0mz4DZAv=_e;djlSYsOfOS0ox$gcE-$yn>nBe#HVegQK%2+vQ_n@CsUF@Cd6ma$_P2Vg&B#jG{vO=rg+C=7V%bw@0pP&6hAl#yeSNE=CPsk&S zBSz2eJ+=M1d>(Whd$D?H&??h8dz)AQm&Y@m-IoAExI36u5bAP6u{faO_d%9eKkZPh zC(qnO-fS!pGxyb)x*)@hi=0v02P4w8YewL!(4l^2ou6bAa*~&Cu%0n(Alg36V8npt zTk+U*C-zAFK)|H;*<#5k_Uaa2lC6I=pU4`JTO)!Bcgq5>T$ia!``61CDL>9u)XcbB zV_&3%BrrUjrX6d*wyCa&{*emez%9Wa-~lcnN=+wm$5PHB?8<19QqP(_*-8}}=8Sw@ zY3KAvn+`@Eu{v(CJ1iAdak-vK?tgvCXq&d~v;@VMZje{M z9kZH)YE~_FPvDv^neuwGSqnDIzAWyj>XG<1K74G)#lR}~H|#ti~I%Yzeq(($E>@P4=uHPV-ZU6 zt1?;bL-^QdI}selXm91xXcOy=kCtAFcUi_!KL1(lU%m$FX`RDq+$s&eKOqNFhL57e zlQ`YpiY>{v>a~K(wf0x=-tXEvrQEw+2OE$7A)xBHzqcxk>8y12SA&(CyNq8awi6e3 znI{}-J>-GsBi_Uxv4|DD$2d}#9a*!Y1#x7;NKqoFdMBzT3pt@Zz+bd4?y@w9Ndafl zCuG>u{rUbSwl%v*CcU_j*(@WBiU(iaeF|ETb&AGOV#rlcxh*q$tMb}$-D<*W_js}e zHJC?F?OQY0LCm3pPAX*GDPoO*$el6vsLM@8YyA~=7xnP702>gX0IAifB_05(Y3VfQ zopzA{QwdMQ-GPb051TX6-Yy(AwY!_qu!`!;2zNyzoGqW^*#~I|`M%greD;iV8Q4H| zL|O?2q2}w0AvwAMx^x%^WXr6Zih#N|eEdFdZ$fI&UVqsg&(Jo?dL9YUCnP?l%B z*$#VjrYTh3oS|_l@#6z%TRhi9phspk&BGTgaW)Y399$OeWmzEfE{58n>BFSpRQrPK-6H7o&NvIO+qB;a@z#!bO6TH)8_ml7CyUz4pGJ|x z6IvIY_;$S#hQ0W2WAhatA07b*Vp!cVahoM!0qgLiwY!kGew?tz-w9F8wyd{3i5Cn# zGlA|zpW;PN+Y%iei2g2VaD_#AqUVF}L8AK6kWOn9xa3oyNSoW=98h0o%hb~HFl~e6 z^mC(hzZ@P?u5n@j!=Q&E<82PqIU61;1vb%i2q?O!-r>8a8yYPDLFIxisF-k6jQBd$!Z?MLipx)+u`+Wci68k0W1;PYP zxs***yv)3$b~9dMiD>EAdCf=^-;ubHaI2udt+{^+Rxhx=H#J!!-98G0$kt(DiA~`(ym_AV zpogs!HFz7bwcsPZD!4y2$^8AX!0W?LdRoxsRHG59%l5r41$5eXHj(2%o=v z+n%|%ZP6}l&Kw!D5&hsv8q@;6QIK=v@x~`$0f&PhN$MCV1iwKgMT#C_S<5j_+B)R= zZ5@%mU9pnF`~jwK9)63s7xNk(@Pe6SH`wQ(5xea^;?e<6DbO6@J?{W!VOf12 zcXo)~FfSJ3KH#q#{QxG`(#2$a4p4GT_fFJ__mLspelBk$1EYcR*=_uR@+rkinnKOw z9Zef_ zgk$6a5xe#4zB}6(hmBjM&G)MusPlPQ`pCa>#hnZGIwpQFV}$Dyjio*frl*#VlP*!Z z%;H}kB!v*oT9jSg-iV$ZAWX(>*96@Il^*By=;~ToWgHcw$T#y7(80a36w{z3idFF( z&DL3Ot4D9T)Utp4h+TA+X-cX6*|v6zoRs?Y2d~g%hg9?fdZy&Pk=3?i>PbImYu-x* z_-)p|5nGYqN@3_z68>}wdu6Qvz7bfPK-Kp4Jj}j)Gs80@&s>giy}lTdhU)m#Icm&S z_(hxZIZ^1foET`-Zva2xq%gHbKm;Uztgq)`TU4KaRAkcy>ge!tguhcGBmdwO{s=Nbv_38c|_!5dDkip=BOxxrCKBb#QV1ml`s z&v?sp=4Gq5M5q4whk)b$WgGXMwqDWiCu~*H`Am^(eW?)F$)WO%fd$^4Hr!O+gKrnD z2}grHgXyGRXV9JHhj%Nx(m7Le4G~{}SedB3aoo8*;=%wF5F{dl~V^uZ7BO5(KtL2F{@8s zdQoa?jzjvMZ+I^(=)3R3ZvSN21v&H#64$(mpt`U9&HT^8Wd~KX@LzcSK|`0xS+rfc zz==lDQ^d->z$h2yI;{{W9A5%A`o?ux5f4Y#!n9k^k~n@{YNe>AgkZgyDxd0@`g>B$ zkm>a|hBRNoIcVe?B7!{A-Cck^`I&fX!+V^y^R!797=ga*Icccf-3ny>hR@wZzfA&F zI(KB0)D~NnesK@9k)0$OyWR5UF%1Ya&1N60CB)Y1-!asd0LHRG+apU!K9ND|0 z9MpX2H5P7+Zx8J#6kL<=AO-@_{v;xi?Dw1Xoo#LT*T)Ra7Tx-A<*jNHPe05 zNxb~gN5sRL_(l;bg;tLbVutcr#IZlX1ovf=PgGg#`y0>Jmaj|*c@Ee0y?fm{(w>s9 zEL41PJGbidLQcA%_SP4nJCK3GulO}femMFCa8P_5rg}XOptm3-)MfY88tANbQfXna zpDf?u|Lw^{U*x#521nM=Gf!*ZP56>_f6MA~6d)Wcu?Zt7#&8qx1q zu}y?b!niur+TGLBPG9uFlu$B<8C95o-i2%0LpmKlJ7nbv)t~Eue9?I+;@nB9j2)?T z{Dh~$fL5E^+LxP{gJb0YjEdb6R!1iN&L4X_0~IV;G1aB~CYDZPUc|rk^bJ9=u2mbu z_oLS}X&?*p717F`oA<3&-lW|v-8hTDo9<3l>ln0dZx9b!0WXj_Pon>WFVvcD|HYjM zH9vRkZ28^GJ|1D(0k(a-ML~0CrvjG1P8Cis!On_teg$rwOuMmNdv8(Tm*uf`y7P1^ z*{PyX=B18bR6l-Ov?_*&iLhWi@%)D7(kLjQSoW~#)bXxNM~sCZcys0bFHQs_oui-D zq_ipR)(Zz%KfJMdH3jdXS>KH+iBq*(Kl1QSP^H$4bb4r&fF@*E;miAw>JWO$*qAJ# zBefwT%PEL1l=K9dUneG^0lj$K)}dsz;1Cl@X$5eJQe}E{(lFHQ z7@X)K?_6cJxsF|@?%gT*)x!%}DcG^#bzZ5inZA0+PaQu_xARc>d*4Hbb*E@l z)S+j&IfNHq$ugCPE@=ZFSVID|7YfnV_2pk)PesR<>bBVs7c>-P#Y!i$9GU2S{nC?g z6(kKuw&owyEgNJBU!RAGS@wB90>oeFFis3Ez=oY>% zU#IL<)xc8=6}o4fAGmrKZ+BLGZlo+U)dXwc*GAPC(+TNqz8T$H9w54%c=#IOe*Gu- zoTPmJzr@L=D?8!J;RkqQ;2+1*|3p5UJ^wET%>O+5`G1p-{~r?&ftvqkJOO26 z3_twv?*^;C956nJ(Y-}9$}6eYTi@B7#Bl#Z5Dk@C=a*u?hZ%>A4JTVMQpim4egP@O_U-;i zQ1aL5O&6K>Gmw8l>L$aUG+^(|-V0)%y3&pPtg&e8mj>ot$XcR#E!n$#6JNF+b7F`dlS+#S3d>a#gkNF8&UnjT4Qg} z3z0QlVi)Z^p^P(t}#zw5f&Gw(;V%e4&jKkY2ih;dB#$=R2&JaF~dwOM@mwT-!(SWl%%^$xrwaL6yD z*P})UNS$S4V_un1XfPF?o7SP9Ha}&qVBlY?8;D=Ws$9(7BZHBIb5&i8MXHL;WtP&_ z8$X(g>8pjFsb$WeT9uK4hR#?MHQgKeE$>Z0!*Neh*j0*_7HyjB(YMnIsAOaT2SG$& zG@s(%oBL=%BtmG^FT6y`ivoKk3%fXN0$G-6w z-C^@6EcKa2Fl|vs@F3V0(HH6*=aMCBX$WKp0ZI{1|G;O~23Bv`_=*@`q^_xc-ZmJT zy=YqfgLMjfevw77zDh`|vnmcYKd`F$hhSvy+ddHWhW(*#E%fd}s&;veFkWTg2?nz? z(3w6uoNsvi5@Ni@)k4agmt+8%!zs7|3A_B>LGPfo%~0FZ3d?Vo94?AD@~6FHN)pw) zyiIk+28y3&U@kNM_#5q$+!st+fZ9jYT?;?xYm? zjB=ikeRWHq+Uj15-SL_C4yJ$Jwa{!4BgzYpd+&T{@WVc1lvw|aW|xeB2=z=%mo~x7 zfeGU3lU@x{T$>-*l9y7H8L#)7=O2wA<>Qge8d&o!$$_`a!5Y^{dk8Ru>ufn?zcEz( z_0D?x5<-{myAz(0?v?V$-^z+I)T{Axt2n}3QLV$-#0p+er4e$^*Z)JZG?v~ua z3)IFd@Wq#)aX_%5S=1>zq~S&Zw@B$`dce}hQT-hp zNRDqI0O&aacb;5K`u-0=Gii8rlM(~MQk^G#H88Taq+>A9ejs6kpV1Wj;hPzw+1tmP zAGt*Pm721!G*dlnm?!w@WSB9UG}c>K6xw=CQqL{1Y}Nbe%$%VhNxbC#X*BOkjaTg| zn%BXq0_ps7Iy&^B6JmbQO(6xfsuQ=UGvxXS!vWi~_Eywo)cLKt)$DPcq^wDnJJ0wT zt;)CwH*pSG)i7bm{k`nltlL=JJ=e86I8t*LwkNl1G2Ytk-r%=$d}f8s*{ZKi^)p^x z*~W7G7LlKn05u#*ozV6{?eQ8U_YfR48z#D%tVH8|hJ&5h!tMqQbHgd?>g zlnQmoeN2EX^zl@rei6TJiN27eA zUZjJHQSRK_d{TG*0svr9S$PZv+;}6f9Qb~XF!=_4zBBn6oi#AwK2hIfWn4m+s`{8B z!PAp~gdFyC>@GN&RA8ieIGqe5SgsdF9M7sM+uBy~VAX}|bER)xvi%OzqnqYZxnleWe0)U# zA3IAjFQ!^AQVxOj>LF0W8x<@Vb=>*htr{zb9K$qQO!#a}n+X>MnAs$o6@|P%gF%D& z-x-rDGCP~xengW-pTq9EJlgNrDR(Gz`2cp?T0~dF>+)wbfdcFmqq}?Tke%0F}4G+L?z*|)oY7MyL5H8v2 zGU7t-LM$u9o_rjYm=RI{=?<*YPC-H6mjCo{P8~`evF*CU@YBf=Pj`{|2c3ly|@9_g+hiE5zLK5e*o-8vL!bF|QOch7yjM}pc{UP7)w6h5;xUz6WFgZiR} z6N2rP7$G@MSRO@D)BxaO$p}o8^$0jdneK@g7APdmRyifQ`tbAaRu)g9pO5?B#SY^q zF6P&+iK}9$gIn{y;b(oefyIgrbVcp>k!Hm>ly2W7F;?=%9m~n~@E4T- zVg=@k8<=_0cy{5o2p=_GX${zXF|?Uj(h-Y&j%poJdbF=71&p2sEu3t+h$td%8)&t^ z_#E}JJk^19p7y0Lo`UZW2K|DHq7@brdYJHtaKO|c<#BD1x$C3hyBP`gnU7OKLp90B zS?+2Mds=;F8G1hQGdoEzY5UrrU2agG5g3VTd;k8RqQ0tww_1=79K_>P)U=ZgrL}$84c52Q)t)`95pqF?!ByI2Lt*UN&H}hUid{BJt01%-) z@WExR1vb!(n+MzSb+#gWcDO=?ZA`)$<^T^Hnpi^nNBc8BjQflW8W$>$;_*CPtXc0Q z#kY_~rkmr4W@rIOS<=WWdBZsJbuBsHsG^1sk@5EIUYUOEJu-lC|}uzFI1b074%I&=KLI3jFYi z$;CcnJ0&!!qjL*fnW}O`{5f>^%=1DP-DH59WxEsAH(xNM{e!n@Ryg}wW20ReEI2w$ zHn7f-V#fuNcNum1h^qxm+1HmE}-?w>Gn13rcB4OlI8l zFLS-z#?(ua+VJ$_^U@8Q{~JNhzv3K{2c>x6;WUo@hl%&@buqpUj`@e+TkO>AKLnfC z!2T<;pI!eD7{UKeDV>YGd^AfJyq|;XP{KvJ`iD;58U`<@d z;TZ0wfPV<;2AJfGK18}OhN|U6%PITlS&$N>g~c1eX}IQhFu@xdSQ!xUMb9<#zy|Cs zILOlYSdKQ2l~MUQsbGf{pUXbjW3P5a_7RuDgJkCgCZDJ(i$6YS^51Tb zGP=$ zG}23pF$cHo#lYp*+(irrc?xZ&53pwtrc_zi!6m%R&L=%g~8oNXD41g z33$flXB;!+ktv!xGb#9jAxzyh@!U#0hRwUu*S^8@m#OPm@@R`I$P)X)L1m9C{4iN_hL1p+<)e)QyVi)A!xX-ln9_n(j z79%?ujvH>gk<)6J#Vzjaj^Dg))jwQJl)lY+G4d1p&JOlP-WSC@kY)XF2Fj36C|er# zZML~wxY`SIURmC>9nd|mXk;EAx%5=N#3Lip%nq0;mE$+5X^oEl@Su|3A8?Bks9Zh&*ucq>DnSF`YH@>D9Y@H*}x~HuhG?zwMz|(Y-yyKc% zD!{M5I{3s0gIu)ojjc>YykD45A6m%c>4R0qBNeHtZRyji2B`wrc&L*RS z$Pdg(qk{y2&OoxJfZJDtq`G;{%oYLc0{etpBHvtTcOzES95Suaz@e{_#Bw}dvG=ln zS`|h)PYbUp!>7+JMA;^)mKOKL_fp0{@2*+u=uY2DBh+)s85oe(Ri?*dFY+uMriw2+ ziybc4w$J#qW$>5#dFH~;3ln@hN-+WBv?+=)g+0JZY{2UAbtXP8z@_CnYEgboX5`Ec zum~sbWUkMp*!)`2F`Q&oG*<-`Ey4eoIyHFfj1Rt-vwNF%xc4F1I~3rmXyalSCPsqE`CUMvF3s@ED;& z8VQ0o-#ItC(4=_WV4ypien{q8rhiQ1*c~s&kqyY#?Y&^LaDQ;#o#vOGj|l)!vz6O+k-A(t1e~)c8XqR?Y`Kp3g5^ z05#XH6gL?@QhAqelXVmqr+=Z_crTvscz4Wpt{SPdh&$=ee=;KvV2?OLqHQq;rn7F% zuk)XHUB5YjPN_Lirjh&A$)x0xfCmXlq*7f+;0Nw7z?1@8SZedp47La#8P;u%(7qML z2Un7BCcyho9$L91AVsM`=-)1JRjx8ivgYz8(#2aqv1yCw?c^k0H9?Ax()1ykcRO|O zyPDV3BNIe!Eb)W^B-^}*@U(Wf;E|^1g{H=s>dsfP8(roolCI%lC6d3o(d=|m+9Q9D zK+34<-6(L=SlfAw@IzN1yxj%7<-+M#Xq75DN&b2buV(qwtf{G~>UaJAD8Q?`%>Th)D0C(z{ZFlpsiN(gmdV zE+vE>ktV%^BoH9u@ANv_d1UgUt~{%~ zGO0)zVRo}89=H0W?a#|hnDhxWU8VK_M~d8E1g}zZh5T}A@x*}omTT{m;3^wk05K*a zTApE9(ABC-$p*cV<}I^{HVTzkB;>d^AO@+PPBRVFwuTLvJiqWrQ~jR8Eg$T*19U2S zE<2hU=u7hkP#P|HRvucqGtx|N7wYr>#^$i^! z=o?ApqSV&8{d+3WNu7s#$Nnd_;m;gQ81lihU6q1Lx& zAB5M(g{s;8XN@en!|eiejeNj!>Dw3Pqxk)O#3debXrF&-ORJ-+^Upei<3#`Y4nX_q zKaJx2cNHu@JU`4HX-$|p& zd|^Q<%bRZYt6S=FUF^$n!9)^cxSgX;k-XA;qT1u{IPV&qO*2L~KHX7rpxs|aaloEc zRY#g0PF1pDJ@zW|8tAcwq~M2gWU#3f4olQQtlQ~|?9(n@<&7goubP^bWf6TgIZV|k zc8R!FjhR%F?5Ho?_M4IyWA{HPq{US^$mT@1DnjoR@QOW~os(kFd2)wUDJ6}qJub1I zC99A?P0Cr>-&eQjK{mvyd>>8es$=`%*W2CxoZDJ`8oXKV%dQCh%l$><(D+H5ESL)G zu7aT`siWvDeb7Ic<|$^5&}39KNr|OCzF$d5D)?vaj}@TzUoN=}O9&NtivfqLMapYZ zzo=`OvT$W@Q{mv2<~}%DTgiQ#Zzv44d255anHQjdZ9&B`!_Sq`R8ctP!i8JZPH@F2 zUtee5S^ldBoC3Wj#`jrCxt`o=3?M1lVXnz2b0*!kFWIK&^`T-n$(H8bCScsmdCK&} z`g43hSwBO%WwErId-lox(&eA4%hP86xceVKgXRb6W=G9egWCh96ZH-5K{=Qc=spL= zx|a=dx)D~1)%%rMxsyX1?diRuNh8VN>{tZV@dHE>Ha;{i@x}wLm22`&YH%jG+&`6P z&Y03z#YZN%XBg<0HFU}6mEE*VVQH($9Hv?~Tmk2!E`DNqdasmM$`=!awxJSWSsVv8 z9oX>Q*vTx74d4Td(Q#Vc}uF8;p{lJ|&>3N-08Lyhq)zh1N?4G9YkLAsG z`bwDK59pw$GFacwSTK3|%&*N4x;;*%B6i>DYQD=lmNd=zdgouxU%kOk&cbd4QJ7+f zG$0W@$-C0j##@sr0v%Zc61tlAk7S!n?IbQd$}-#(#)olXoIG|)QkZc$~m6(_1clqv=tKBidj3pslhK|pey~|RPf#97gV*o zH96#lT0V##X73$%7T4`&Kh598_naht?+QG~2nh2g4)n&)hh27P)H>RFd;4D$9+yMA zTh7lqsi-8soF&W;^qE)7A=0!=wwtOU=efy8*wF4Nkm4-=eo=y%#^QP_O?Co3gVVl3 z*BuW9u;|RvpJ-Rz)iYD{{mkYL24VLP@2@~$@x3LdtUc_~So+$9+2g*EtRQovHTPb& z&>SYLKdRD#t2>v*O_AGif{YlS?^t*p0)I%aRUoq_{@ad7kY4EM-=5# zx||#Ti7!|p&X62N4vORPj}a~%(y(qwvQ6UX8z4!kgWBnYP)-XTn|PHkKd#8WXz5rK zwnfa1)m^zWPV{}Wr_f{=+B2ZvffppDBxz^PVGXiTowHFUPC>~)=1S|oWUesum@51~ zWv=wflU)%9kYJrri=sW9Z0I|N@X_=~%?+8Gx*cum#RU5w?@!6n>-s(vc=^N7Tr5PE ziU~i*M%sR(cC5fzQL@qE_0oqNa(=#!BMXbf!o)l^{X`Q+#y{crZSKTg28E(1M0;iR znM-2IO?EDAuG%XRWRoBpc(0jrIr~cL=dR@tIim%E6sLh+3HXUC+mQF8jQCq$ob^j( zy>?vSDb}KD1z@gcozmBxe-XU5&_0XBk71x8hj|c8Us%bILu=sgx0yZ9l)2xKz52{< zBmBW2`tH6!gpI)+n2phZ6Y zAb(M+H&G)-B+I{C{CTbzoCU;}*s~x{e5IR{@yIT}t~Wd^7ud?V6P)LXVxKLo{?vTxwxHcJGHT()TJ@ zwZDbzt-K~=OCS9Brd%Lpdr~Jg%XDeTD&qlaz^YUqC*;5qnP{jqyRhNiq~#wU zG=KQy-IJ6hv1H3VS7M*4gJRyz6l*|blYr=usvJ!;aOQA=Wegg4znGkc%6N=@riW^CQmL3>H}J| zR2XR|Y%v_2%wLdh+Rn7ii7A0QUIrG?)6*yNbaYfVzL&|5d#e9Jg+L$}@QxEaHgrC4 z)Y0EoO`aVHz>TfP23gBnD%Qy6wv0TKNT1hgDrird@MC>&C57+LxpAGIZjjZ@1~;v# zE?eQ5m7Fik+-GOxB%S9{Q9l8+b(! zKbm_bs%V7^*i*EWA4`_2i~EZ}%4*OI9AD{z$rgeMsm-NK$SI{pl zrzh*3{JAz}cI}+X4>^}*8Wr^jZ{Ga2E0FZ@%Yv^4tP3`YtQINx5$%y6HByW%zTDor zVta`t@7?Urq5Clxo=~>+!HPYT+*NPjIFpx2gEU%$_LeRqVOOw>tzM!91qd=0?(I$* z^xHH%ab=~ZA4Lu(89S4ZHZqcpwq#MY)%Rm6L2}C&kO+nu5D<`Lf?zA9v0hv4{;b)x zIF)uYQDWs9M>Fr3S#f7<8&zXI@z_D$NG5*uJoKE)W3{Bn`gT(EJhr8hs5Ri<7UpuM<1Y!hDu~8KP?VCW@URvQUNb9BCx_@ zLgJGbe}P%>FPrA9b?a94sCp%uU0Gx@iiOPEc`VY9RW`XlEp1NwerBxc&28=Sf~Sc& zLN6s-KC363ug8#yU%|iiXY~5|;NI8%MUd{MfS^w&kYM7Jwi+~2~fbGu@uxfi5%-yMVk!c}S|?ob?7Nw!CdQ^+ zD_IjL1^I4ixY<5~9@32;q0H1YeV2>ddHr|UOK1&#iaD*?ad}^CObarbx%6h5xZ|KO zzoby8i8`{#I~6tc(O1API;Nh9bKqU8idI)sSqjVgoMGpt>t6)Ln;kz&E+%0%z$bPe z3x0`*y|F^_W?O&sX19wcg&UGjhcU^VqdH#$+I}Tg5UPJACvo+GcE8l6mm!ijK{tmy z`?-4B#|JpUQokdzS6i>x8~ryNnV!4(-AMM!_ze|=qhm09bv}y z1_Zzfts;Y19gz}x!f7%7#r>6`UU?d{6nE1%ZyVb@TqFGSK}+tZrKqAjx;ngFB2evl z$OX~3nNyDT_lZY?>MwNF^TfXXq`z~cTi|>2u>#jG2Ix{lOD-?`*g@hG3phU8O}YKOX-&7_s0|0V9BsFkMYl$(C}z`+z?`Q*9k zd;422FJtbyCepHp{z~ zVeMR{EgB$E5?4cr87f~lxE11El&MPk-ZuMj>6@V>o_Ab|A0(z$V@UB7PO?2g(wJLi zaLPF1u?WUpDNeci?tN)r>89bg_T~v<$ZLXkY&0S!mZ+BMo%Eb`xEZXq7QT&yM{Q;8 zgMYz+37o(0_!VLF5iB0g3q{G*Mr69B`qdg6n}fdc)=7Q-DBPa={)z&*o@9KXK94J2 zOy!8Cv;9yd-`0hv#Vkd*w?8cJFT)PKndZX8R~KloHU#=9)Nhrgqb5qeWXHA@Lf(0E zW|-G+7~UaPIdQ+-#ycMbLP}YZt}I%TJqI*0 ziK-?U2?PXW+-QPw_W%5WMQ?@$u?47O#zNYy?NQn^*rqG9HuT8Jr`agpglfmSp|X@= zM~dmWLznImLjp%k(d)3(U{wQQY_%Wi1nXb8jU<9#;|dqH6`A9YRa^W;X)MP40+_9& z7Ey+gsyh=UEN}eYl&i!OR%z-Qr3)V6{A%6K)^Yw@f)^IuPFLuz-xPa%Sj{COm z&Yv)gc~S5g<6behRZmL7wVTJ*b&~S|!atyxoP2k>*<$w+$$6fd0}owAu^T@}6?Q#W zBSLT*SL^{A7=|z+hFSQlNps_^%$aG?^`$?9QQ66is~SA&Zqzo9W4SZ>m2)3WwTpwT zT_r~o%1p8(=j$goj7-8ey2y{d8mNsVDfi$1ZhyS+nn_hR?nS}jk)vPkpA1%S*^_d^ zU;3#I9)k0H{4ZY)93jk1N=`pj3;Xz{;U7%3t5j$eIY~cKc9-nv^0Q@%{I+WU#@M4R zn#ho?XLqV>9Lra^6mS=V3lc}WWii1fQMb>fePAvjv_7|go4)#%X|Ry>wJ=4D_$|48 zK9=E%F+l&iAV4kW5N>?Op21>>eK`@mM_yCR@nxLNm5X7?|oh zx)*}Mzx$bbzsr5w5WSI5%=CIk>N_Xg;(azW+23+tw_~i%9kyI1b-1!mufWxHw1oXk z4_yEDL{|Wg{y1ZH-eBFw@cO9oiEhL@K_K=38G2>4wL}|4iL<~cMR*mX!98&|e=+!u zaKr4I6K6?lauy3cq_yvhARQ#SLPDbg4r9qMCa8bbv~wtBP}h{4`Qc=2A?-?R_C0ImR$-yTY$h_hs*66+-;XV7 z4{1VG;~U>U=4jk+o%#ubBiUM|Z|xk>C}*zIR`e|pKe-vps;aT`DZ~?1u3KmXFLw`$ zKXa~qesb}qe?x|obCKOy&aldZI{g2rgIy@4x=-CXLExfFoOc@4p5ypy%4xBOMGvOizVMBDiI zX@!VI^CG*7Y(uZxrX`j~Eu*y>DXj5Kbiwcw($G~Q zP$WSJYfBkZ#kdaZ!?lzkO??oLtDM=?>^!HKz*1x6p64%-p0}?b z5B%Jn?1Wy&{zc%pD0t>DbsA#^yFG#ujPt-Vz<}xdtJh6+vD_aKV)c);j(^Baw z-&U28eohu^P^!aI>%TjZlR%>;fnt47p0qAnKe~H9O#a;V#-q5bUjUO zAceR4R|Re5WTs;Gc$bvf${GY;nW!y^-RH&r7-vmJY?y_9-cL&fmVZ*pPF$=2IK7imn`Dc}Ou- zU)n{h9j)#{v~Ml!$SPFN78mR?3oH(}`g6Kx+@twvts-<+b!WKvwejZ7!=*5*J1175 zxm1l-Bp^SxTgk;QtfLOr#YVWq8wR+bH$B_h?h?E)yIqlYWASsBVWGuLYKrN0XA>?V z9aY0O)NrRFhcH3D;+G>*tGUL2dw(et5CdGZt$=@t(mUvkm1f&5)=EsjJBtC?94)3d z8}0>O)J}|HdCs8aRzRQiK~i-WdZy#Fs_8ZQ22+dI*VjbN7vH#j+S2(P_&-RmT}Jd$ zVfn_otfG;R(tD-xtgVyYLme8D!Y@}{X=tQzxsFh(La0tU!=cM@mQigy|(|AOA(+0 zIE=KJYuetGESS%mFv4{t2AFItBA+X<2UIA#1+PV49QUxX2(>GrYbH0Rs7Rt8j644^;IRp2gpfdb8>1$RNt@E@!hHr_6vwPS?s| zH1ij>2I1NS@1%3n?~3Lyh*t29lakw`PcN*xy^I6kDX6w^^!Hb zr!aMZR21mAu4pNULd@X;ze#B$7Bc^F}oY?wS9@@+<@4N3Y&v z#JA7&oE|Mop3oof`05%fdvt}GtJq9tf!5^~GUy-8`#u?ZtRw_-M$JVA1X`m;SoAR7 z5wR!!6wZJ>%cs!3Y<`C_C#bOkBY&2bHcoHFAr@Wl^1gfI!&Bq;n6ao%I;?i@C!ZM1 z?T4Z^*w6ls)jNuuoj>YW*`PknX@XJQnq-Cx3#~l`8p}!I?L=f9#^h?gFl}53>uZ#rZY3*K^?fofM;?pgY*m)kQfSbXsv0cJR=uu^E$AxqKD( z$T2NZ?W4O>I^JT+?<1MwwCM!7i&tdG(@ zQjGc;lpc6%(qW8&Fk>AI=jhnVL0zrz`MlS5P=C4dn&0!lM$%kB9$ zCF)KdocK7-fDRT-5-k!RSGZGI=5*F{7F8Hi*}~qIYD(@yPNY-%t;D$W@xCxes@E%TuGMXamfrA|kvFS$=-SW_4ed9kNd0m>-Kl;q4yS_!tm34={whGO z6lAo@omm7gMYy@jTbC_4%=-9NlSOIOFUByvO9_2QPS;VDB=_)^`kB;w-E~-6Ztdyu zP6XYEyVCCE?vcYKOAm}LKzRB3*~XC3jN*W|i_o3A>l`D**-&^BWL-bBQ{Q{_U{yF+ zxf)D~E!D)BOV@83SvkcI9tA3TuGhQdFg)Z8_-TKK^!IOtsM-{OT&u{_X>qU5*_*DU zqZZ`8a?zPY$}sfKuVRtsSA~q+bD( z(9hPul`4T4zoeLv}4>$X^Y2S0SydEHT-&=5M)xH|q_|C9+sH7w;nbBA{3Tr!; zd7{+&$*lY=mF`$_sppVpi!` z43(&P|Dwym)>aOeNfoKcfjJLvq|olQqUCCs0z~hef;UjEoX4+Q8vXqw*3+I8wI%&x zv~nJusH}RNPqQ4wC^##z)VL0{G})CPw&t1NnUz_*UDjSi_RyC^XSr8i3FDI za|XEZ62jH>P(+A3c@T6qMpR8Z5J8Y#6DuYo^PAh#O!6ooml=Y{vZ7K$B}Br|H38DT zmDnWm1V%sl$8Kp;I!WYmY_b~+O%abGTv{2D_ppY)J-j5?n1KX7)U8VN)pIBY@K?O6 zn8${IvFZ{dQX@5z&d!=y#(QqlTI4<9>T5`odqdtHzblx<61=@Pv3y{y?6k8vgEDyI z_W<}+?fHJ|M@h^f)Ccu*T zcYxu)C5ZmLCjZBKI%3!*BKLAj>4X^g5%4Kg>2w^tMgH`kN|%eA4bw@YX|%*qCDpDgIzlRqh-#6CwXsh{GYhtDUfk(XoIN777)lK+_1%)B3p1tN zHPMe7)4Q2z?a{X$TCt2gv*$u*tpr7(tyYjx%P`8A+`Twn-gv(DZ$lDQqmvr{bHDX9 zk6$><;0>)b>ikzV`Ko(&oM#s+k7oD;#3Aj8>7+I7gqZBW{m6y50Zy*qpXCBK1s}4X z(Hgc_EHsTTdppVI%nuw}p6>=82AwNC4ln|6tbrJU$)Kr1oc1JS#BI@l9Wrx5-v~|B ztXV!5ni5;_rH(}K#furg*9Ok5!lsi1=l1a6Nb@m>J%RbnVn1GXu&S}OT&7}2S$1`HX+{7V;9$gNLR z7MRS+iRR8c`LW-uo#VP&850AwaNjOYOH*6#gP;?O=OnTjer9&fhAmH=&d9TWw z3ZAm6-Jm><8}9L-H2TVceTTWH@dKK8xW_(?N}4r(A^zAR{dmUcUgCfu)=jVcnWQx(YjTER46_`X;{4w!@1 zxp#>^039eX?pjfvw8aJ5G0UJZzU1kFjn1nd` z&jGXMh>L|jSkyOpN~J8}f<*>$1#`E<2|@nqPCB;dtGV;FXBzd_6=1tXivZ$>)%)H$!Sqn0q6D5hIiHzFv$JK=!oT!?|QkD_#%c4Vi-)Tt7Q ziA6ZHZo)c4#M}5rfY1RVXz2S36Kk;~W)-7n^e?YzCQsUgsb2j{NSDO5;wUY&sSy(O zKAJS~Spg@|!2?pd9uW{2RGdGwo#uE=yUyxnxw+na@Ob2-@xp77Ff|QBR|spi;+5OE z{{gUWeX{TVr;?yUpUZT1W9Zda(wUp^S=l*ifS{2L~9GNAh5j$k5Nm5X0wRS zZ?0cQ&+L*@yL2De{9xQ-l^Wo!PuVNkM;BeYg9qnM+O{0>eTi`+wVGzf9UU&M+h^4r zGEDNfv50Ok3!W3?|1;<&x<9yGkiM){I@l}D3BR!~{D9Zwovr?&Vxj#S=XEyp75xYD zqfq;?JtQMG3I&koK&zHYKU9aYN8U3s;aZ0{Y zN3lO~U8*zb4W62oW_ZfEtCPvSUo;!BHkU>ClkCn-FqW@sTNV=EQDWvKYrEfBSh}dn z6LK(VkoNFvY`B{4b3)m>PKyB%Xf{-C6rM4F9UFw_ZbM_xUyvltGp_Afnnf*jSDa?6 zqp7Ca3Kq89kt?dt!w6rOoWk}WVnkopV`j4}wlZI0Lshf7_e(YX-@0%$hw64p&8H#d z5TyyXs|H6nm4>CCwSAc5hr5w?z*x-YP9&TV072IoTYRjT51Vbg7C`kO&+zb3|BKEs zN4lQDxQ`;UV39|!Et(3OZoQ_>37&ypOyK!I@pJv3s3HQ)N&p^>X-+n3ZfZ{N$K+b% zo-Fryxp2Ff*29p14bFi6J5@`*KE%~jt7_3jSS{z(5qooV6*V?#7Vb)-GIbKuma%Ws zk|~3VS2GK7XL>bJNEE%mAS240-L0hMgENeo*`Y8gx~#+tOK(;AcWji~myX#}%q-AP zSq{E!igz?%_9GNed8$2(phn!}Bkj+V*jMe9R8ZU))!>bmi_GLrLK;S^+#%(8pl32V%P)Li3 zZMF`z2*iPTp6)G2>7s{NPl`pprC+1Q_NCj>1x$M3TaEJoxO*>sEB%6NJ6fd6Apx5;&uJH!994XwlK-|UjC9q749nB56 zzmv8FYxm=>TT!4&d*vjlc!7&`qg=z z3hv&YBZ4vNPKYziv@BieAn(p$iglDu`&1n}wPeL4ypmcJZ`&Lvd`=#wK2wnH$?JLS zYPo5OJ+9o^Mg5)?7SbpJEvcY;D_+)S2p{z2*x0f3*$^JM7QGFKNtJoR-U8S3b^atx z+ljZmjN7^v#kyaJ!y&HD+T+6XyLzyusp?GQ<$D&xbsR}*WXx{wZ*BM(+$`t5F;EFP zc546x;F+UwRZf|G*(-8~lqT4Xxo)3Ki@q%3p4zzgr1bl1jv+#kRWHk)N4!V|jirfT z!K>N{Zr;0EYHuRCk3puJy{)xjQ?KhAnwf*m?AnfM)*?NWoh(eft%?MkHmIG zf_?4agfqaOu>vOx=s4kDFG-Go+fuLLZVCAgwb|{|n6|#l*#>mxxlTL!JDjTLxk3-K zYgpB;f9bO(-GvIj5jo-Rht!3?IU^quxm@&(6*#RkFxa;+XajgS0o8xq-2R=g{U6lv z#JQJ%1*RqeFzIFHWMz=HTjo&~JdE_^DG) z-haS+6SzD6s{p^E)gA}x1*!;f!?OP?!|wl!b$az_hlk~@mn`fbJ&-HtXsNK(~T?nk~S*iolj&Lr7?SLMvC1c-tFHtV8u=Y#lP zAeWQeeey`r{I*n-Mq<$vDtq-gZTuKT``{b5*xw%c4u{u%K~GR z9~p%qEmfTUf4De4zxY;jYAzRhGa;ix%a66~N^?inC@es<(rjCit~0{m%A{k?8YA2d z@_cnb6HX|go33u>3lP5z6S0$b4lPlqu zJ~V@gzx$|o`^@ZLXcXFsE&N(gqzx`U80oZZ1v)IabB=k{L+2p!QryjXwa+-2R_~@9 zd8OhQax)Dfb_l)B#T$eSIX8dXhq@mI#3V%gzftv#fRy$I8WKBeD*72GU1Tym-rjV^ ztkq8adqUkdvc7`grMhOhl6MprN#@ZZ)=`^wVduwlTl5anA23AFII-TFswu`0_Dxxt zN%nE45|Iow*))A^2ssiYBodKocx#1wjbVuEv!cKbp+Y!bO|8(b$6ToBi5D~%C>0m!0?lNJvxMH4S@JPa3em2qN*HBw2}vrswl zCz+;Mwx~v!=BH?_GX{)fNB<(=|8{OKr(yZskP$1nOdM+U1;o<*p6zaPvPrBX{gpTG z9dpUw^H(UQjQWeUa>l$0f70kGpy>}fRo`3?u?Nxn8dx;njuKLmT1~TK zWO?G~siNWR4Niqy@!78N71v%%Ue^9>0U*5LId{?75J*$Rip4!uXjAi*Ikn@Z*CTGd z3rp?Hd|F~K@J~?sJZR|$hWHFXdQ5E(QN0x{$X*S@Ij^~CT2uRuZXB9?g}I3Kf!<6E z?fuA1(&uVr0mV>7jzu(fD6MQHoug|Sz%`Mge9mg1HBYzk$oG*0_k-or1$@fv3`R*v zN`mI#VSRC^ZISjnV93eCldy33z+;B_z z8Jv}L|rV9s7}aNdFtT=+7VhIWs|2Ig}S5)s$|Or*Cks0eg0HL zafB?@YxHe>D86a|gj6Kk?aI~TYRQ2ShH&|*=nJtHcC3V{%T(TpM;NYD%;p~y8Iz?Qd! z4X0-Aue5Ods^JqNMa5`hq8V3pQ-q3$@JYFLlzXEnA+U-H0JWEYrJ$o*&2rOpPt%0J zEhWsc*wZ{$f;4Xx-Pf;gt)eYs%gLfCj;U&w12>hLvU8wRsTnxf z+yBOqB;INew>p2!r5-+V<)>;Ea>Oo8+-YaelhZJqW%I=uHSgJq0xU|y-$NIsMO!) z$axf^9jz!kb*e?)O^p>)Zo%}GQp{YzMWgI2#NdOs;_k$GxdhB6<~U5NHmwDs%n8JY zc3}{y;u4%%D|#fN``XOBX|h(hao_S>t8x0^l`jpqt_;+niWT`H&hFWWWDi9*?i<`Z zx}%V_E$|G-tU0hnF)xJ&&tuSFMs|f`{pl7t)Z|a zM%R^DJ|lZ)LAjRa^qG$e2NCD>J3iqj3RJ5bP?QyoL#u7>XE%wh&G9_Ut#T2V&zacv zkH$$AZq=JN)sGT{>dQ$P-4-UY^GkNq1TJ0Ad6yRL&yCA_E0VRnmNo|)k6Y`H6>_36 z?xX=A3}qAY?u<8>82F~5#(c@Kj0tqF%BoynA|Jca)^tS2K}GALoi2f3EaPIy@Eaow zno^X)6vMvYyU=~V$aCqpCU<4U7O}Z5@A+R@f?91M)(n@}VN26Ns}D$yizes+@>=?6 zq9b50>qlB^?arlzuciG&iqY^TY(I;;sg)>)0Zmzp(m3=Y*S>3s=yom}p2aLg94*IH z?YS9jTu-;Zdi(rnWz_7w^gajbkj!a`R#KZ9i`k#Pw2Qtte|-(y_rR4aCbpI0)6Ne6 z+U`6A+)`m9*YR;08IQ@NGeXeMRN`@J@;N~bW8T*=ibGS+#i3Go2ksHVO5&w`IMP}| zXW(;-&S1Vb3HxIMZqG)qQdgFJz-Y2I-sZQ9g+T`&xNt)Q$=B^q^86f8kH8)JXQUnRAMwps8 z2in$nN4oAGdXpzmJBcsJK0QG1wfA2h%86~(mE?P6EUEkd5m8Ksqm6${d z*I>NyU4Wk_;XZ+wbGH{5!PV8;lzInZozu8OSF~GowIw z;}!+eN6!5xuZ=uR+eCM*j;&{h>i!^u#we`vt0NW;;_xec$E;lr)6|Sagn6K zY>6Mo`1a{aufrWm(CJaGIQ`6ut$~$?T#d3{=6Dy(pw@uNso$SWT;#8U|X%$k_%k?EMmndtXi>a-O*pMt7-uhg1F|?tG@)xjbx>5`oeiHUhBIr z-?{T1Fl09zeugAE*-X_|^Fi7>V9?en$t(m*qoKVTb>jF&(quLPZ+?B z@u{xmJ#|>K9%v9-u4zK|I4G0UHSPnQ<}m{nevN;F41*yRr8K|SdDiS#gxAF*EHbNPQxRK^I}Cy z7=Zj;%Gv~rTPV_RE0T@x<#q+#p8~A>RU$5pm4VOj4(ztgNl*BWi^&DW)iGS{z+CPT z_xHAYN?q>ZUjsO>_5~o*hg_MOGV=#^VYiEtfA?va&?Xs3H@ND)rsW@_8>NEN3&v>O zF~(B$wuaZ%a6?UfqV5}hv>35w?lV2bAyVQ=8-$$b?c*)R5=29zp)km;&y47fn%unI zPtZttWy$qMR<^jRYIlyDi4cot8#^0}nd1;CDXX-#h9~jU2sCJwg=6(Lb{o z-D|jaE8|KIbWhVlli4RfP^4g1*w?ed*>`Sg*kx0iz9r2s8*~55SLwG2DeIt0O-vBW z*nKOk?<)ZH4^%K7+{~SA?q|j)*HVVDn(M!(UMHy!0jQs~es-(J%1?eXvC>}WH!jgS zG1CLGc5H&`c>8lMm3(ZBUdW=*snnlIRcaca98oa|-{!4rGEP}eVjzuvlt(E($J;z2 zeHI8rP@smas1c6PZk@)CT%E>vt@me|nr2b620*BZsr4O|o}&ZOV4C^9r(9IO*cxXO zQ1kLnJ|Gz|QW1HeFysU29_B{+36l|7)r0o}4UNA)(zaQw8ZX%o?lF<;VzsW`;uNtX zt19TFh#K5bRwPgBkKFxP@tEI*T%M$P%}F4cw_R@U!|D=a!wEDq=6&$#i&H<=3!JRx zw2!Sm$uV{kfmqr0AX-d4%s%k}N_6F&%~HpXSGNOmP+Yu2Uv6ZvdbAKn5z%N#YhtOF z7X`b|GX>^%jAj|M-Hs@X%sM+$NV#dAMF}0t6*=rMs#Y;@V+MwExUoMnmEsD}CCMvs zp1rNDhZpZ%_{A=$+$ikgewz$_!L6ALn_&Aj2{gmtgoA^&Uyu# zR)Pxe??cGrj7&Q_TTJYD06D zMjKF4wdNokZN8+O%c!)*t%Btj~(n82hL{I$4ESQiADJ zP_$DuuA)=FMJaNMz1{6UjF%ak`m3)S^V;10Y^wezI4bl=|qrORnxwMji2lbv^(ye zaE3~u$sdaDXTC+pH86d6K{>>izMez-BcM#fa(4GG0t#%o*(lyR_0;3ydLQoyoi9Q5 z!NP(FL3~}G)?`Z(ODwv0>Qd(CM=Fro)^BY_kDVR4tBLD4GSrfp-T#?jba1qddwQouuTw)vU4+@Cvv>#vraq%hG(z;b&djnzE=bbBo zZhlp;hT7m9#ETGNfulZQ)?SG=Z$LJQu#y^~)I~1$id~nmYX&4AT4iG|5VFhwo$wYm zS!b@+n?lU5XigXfo#xVdwjpDC6#cE3TIe&44S$xs3QbLKckJzhvix1xX&@fm)-fus ziB(<+v#(lkSi?d`vC8aH<`tzO(8gMV>lOx(;gN_xdbcVj-7k>JDQ`3V)ax$O&{ zbMi}k=h=U^_GA@;Ws3vy!nga*+S|*Sgnc>p3*a`!=c4n-^$o24{jl)rH3I($(Abya z_z7p|jQ)0rp90#TIWR0x4&Nq#s2KeHSgCOzwpojp1^)^b)-eG8+tL5|MgMXo|9+|d z&!zis@~OKi`kzjREjv@~T793V%5>ob;{FEwBlwTQgntM9Io#yyx1^lHb6~~I(S4O0 zani;OX?<%y5jNDni;c_KW0%i~K848CO4nU~^8!uj$>v4}sMIX%kQb?*GlUPa2`ETy z*SHqO%lSJLsx0&x6Rm%Gi<{YNeA6-Ky^eLEGWZ9sPqg{iiZ0;xWV>cLat8=M84ar$ zsptmy{jJtrnRRd>}|)%|z(%ij~T@S2?JofX|a!$>2XYVX8Q&=23%1!Lsn23A^s_$T~2S;foig-xs z)RO97>UN6TJYFW)9FKe9=#k?&FHqqa{(5}uR>U~Dd*`6z?Gs5m&UBfiJYpOC@IXBF z2PgqI7w4Zl!P8D><^qx?>9fbYA(&sJ)#ofFOim&+_xJR?rIUX$>gn9fi+#1eJA!bj21N zNAR^%Uknepl?o<{d-*?d%jiiSSKXM&;2fQas@c?#*G5$@dcVYRb`P_NWfY?28~|7X zks31`3pia7lc5+tRyeO{)df&@Ut0gxU|e9};MbpFQH* z5tM-JbC^3C_Yn*hN%aCm;DWseoI8xJH8jXN^kg$H@xY2kON%0fX;w3K#V4d=G9 z5VeD5r0fC36YspQ2LAxHtUsn}k4gjzKEpUMfWy>fugRE=TU_pRi2=bbmWTJAS&xI5 za9aLCYg5Mkh4W2L(Rr){YhY}eufzQ$5EBC|&I9;(Z|bq2P?mr)w|j{4R$fu%LDU%J z2dEwznyRxheZOm`_}%#2>&s%$Y6B6ohLsKgK9%~NzbEw<9P`iF3g}O=rGF*L%>S1- zW;yW6;V%GiuJ;2}05Sh7oC^9gf$`>F(A0lSDOAW=E9)5G*uRuO28`3H^%?a@uaDll z!$my5JSpX;xMofYI_~H`xns+CAlSx zoMBh>f6Hay%!GAnz>~u?ovP+3a4&Lo(FSHkt06TcWck+<{ws$ikFQy0Pn+}FE>fWs znkssPuo#*O8T{k19Qg~6hk{DGj?5t8?$nryBUwp@QsQAv8lyURId4b@a3^CU@22Us zf_4)IE8NRm*$hN_nH0KDbc=YWr*a~}?iJHop~0mw+{YrO&s8C+l{*O^_n}|I`Sv(1 zg`(l1@RE_;q0Gx%cf6&gUD1x_QL}y3lr^GqP25-}PdhcaPQgIYON@*AlEc^A+UXl7_WiF7HL}N^bn_-DIBa{m$r!S(Sbye$ImkI+u_`%g`W1vM`1=TlRe7(4bk%T zgOxs}T}z1Nf*h{g#N<5d32Cs*y$sy+>A>(F1O9CbM+{SrC^5D(MzdI{8f*Ob=*Eqg z`HD(_O9Uj#bioBHiBn$6PoQREiW6-tk(joAyMWy1iu8=7z0>itIGbnBwD5lE$~k^a zXW9@f%!UHdb>{-}Ew-F}AX!KdhY!V`+fT+rabq>Q{o#P@zZt2(yHX1+~@Z=UiFuqupoZP zC%040v zDz_(Bxxr2%Na?w(=mXgENo!9R1;uUW4`OkT*p>S7WAph5{#u$0pF6_@I1=-5n#aO+ zbt(G>HbFQ_TVvNM<+L%OulG}1Z)d-q&dr2Qg>Sp^3gsokooX+NcU4)iMP~I|ChY1# zd6*NrXF7E3Ojj1JC098Tn<_B!jv{*8CI`A)^Z5PA8W`;yO>WxWcV(;PZLX0JQUfr07!K?hF5u@c=t7tbh}FLfYHjL^p$W` zW5|r3O7o$336LQ#r?MV%VXW9o2 znE=s)t`yCP>Q}?pF*pw^uYSKW-%%Ct zH1TfUU96s^IYNh2=o6!jbm&+^KBLS4DCek7P+m!Dpbk7jEMu;JQ&SM`Rf0RC+#}I( zy1}ZY>c5N_IIcbMS(;iCU!j>XZ3^d60+i0<+lDZN+q;IX;S&E`kp$P{%5}Q+@2on& zgdEG0rC!oi%(jEq25x6Jdcd=%intpiMH0v zwwOuS%6dnx;W9o_^Wh6;_7to~!nnn(pAXt+6);6R7D~pk8aRO-P8!aWX=Y9{8g#i9 zaCcHG!ei}q-G{z^gdPnOm6LX z2UjZhw>zTD47a;md&Y_g45l!{Fve_&!r#-lJ!pJ96wG9vGv&_>SKfL<(VaR;ia51^ zVx-NFi|*+rB69cKIs|sI)F$RBGXCf}{b%a$cRRkOgo1+#6GLkqOTQ_*KvbbG{V}^yhD<=t|5!-jn~}~2w@Iq8|QXz z)cx}K`4eclBSq7z;1Q+}oi7pAxh-js8t?6Y`Iag=Sc>F7L$oa+2H5sym>!a|?zxmH zq8CJSQVG{K0DI;#cFK0-T0(5$E=B|2QL}lCwA-Zhm{)744(k@7H9Qkc4+Hbpqm`E) zIZYqKEO~cgmpd2QwTqy|4`97$f#mKdc0&C#EPsXXtFiug%yEN;y5?bJ=wA7wiSmhJ zdDV_ub(fgS(5FLV1+!kG77J1H_ae{y*%E8>&y+k+9w0~y*Z}{pu7AEH#((?81k_e>qIClkhD3k6 zBR34>c`u=aWZq|rzKP8gfwOk9BQ92AX9RHGANiV0ESE$w==ogk5vrf6{1L8{>1U&K z>6@2%6O3i=5mZaDUp4B^EH_E+fvRWmVxAP@x`GN1cn5!bldgD~1)QBGuq6FK3 zR~+~p1TT9!pwU$ySvdfQCsqG_1ou9C2y4#&O(iJj6zXPzDNLL9l>KOtqx_kmYk6Vw z&L-lpLIKia#n-}V+#T!PfL{26ZSXNIg@@C>5gc~?i(sivF3N7EZcq8U(wl1@aCMh= zT3cUTIL{6`qRC0>$+c;o7z0eDBYHN1OWfAss2%%O1L515A~X5m7FBon(Rv;Y>f9Z& zmM$hJYO4O=;)Vl0g-RZa5>2PuJdGR`=b=5!x)-M&mTFm8f=2UbdW4NJkX<=*i9{zc zA1x7j;97n%L=_EqPa01ch5BumJFoA*zjwPQS^~81*Cb))mk0g~4fo#eXc1>PpafRy zkA7bUTM}y5cuT^aFxUGYUUW3@RC^`+u+2H;^jED1LK1OfCaz$8+b}UkO!h&RSN%t? zujD1A?=<;eTi%*LCUF75Lk=cyMV+sLH8WE)G4>2f8}NfnBcspt%WB$Jl!}iMn(;$b zE7h|*fyorV?!o;EUm{^gH&%EP@o|-gx0x`@OGf*Yq64;WqrmtzQt|5W+yII%LTO<) z5M5G*ccSC_xY}7Eco^Kk50VaRd?NSR)xF)J1Q+d-sgjk>1qcEfyZBTpM1R&f5+q~U z^vN~D;J#tJk4VW2QDg?~%CGU!o!lfN>5`87-C`Cl0hZ|?**OB*dvO3hu)B(=8hYZX z3(>7+dWHbC92V!R)tGw~@DZkD|9kV#N~-ZtjGGy$2Ko(}L9Yg;3Y2lM5?@I@cw>gYlHMVEpBBYghvWaS@a`fmt^0~p6kGAOV}L!< zWTC}VZ~INd?p8Rs=V4!ju%iRhyaOdfxY)Rxhb>};%u=V#HA=oWQZ6VCCo0f#QpltpUFsV z*fCyRd1uuYq&t}%9mY}JQ#qgGFuYxv-gz|lX4Bi4e)W?kvVk={GDaRrttQ4+!pnEg z7ahhTk>rW!z16Zi*+~4=PNZpB0qS{^B*h*ZJfHSu0s1o;eH1e;JvFcd;!qQsN zSCz64^n@hbSH2RYji&?muEi)6Ah(&!#F#o-tc*`3eZ{^@51O%au`?Bt{?IF{Rdeq!GEGmU zQlOpNo%=%hwG=2IWbiA9;|hmIG0hqPsa~>Xb{k31RmWgfNJQi2x@=*BJhws&b70NW zhzXg5r3!c+SIb&(P3b53c&Ah4yE|RWLdxS_xEcm#~lvsM4kSI^;LOtWqL-Xyx8Zw&t3EbXe$VnmnNHl+ImS+h~v^zBR~5Z8Hn?45S*n zFJt4e^S^z$es#iBs8jasSajyot~So3ub?Z?^Z!BtFopg3$YQk^BZbLa9%EhY5|}By{(WOymKMx}Il3O^`^ydaim0l||d%DBL%s z0A-O4F;u>kGLkCh2IA)Y>q>)i&toTVUhATUHYp!XzdY7LlIDs(k(g_16Qpu2-_AWJ zxuv$03Lgc0Z*cKvV)RI)NEh8W>9@&llb50b#<*^fz3cIr^)>0ichf1i@r`et)FHmI zdFs}7))pNf>Qs*LDV})b_?6$l^N?@5xIVXsfK2k$it-a6woh!-90Xcdxf|f+`W?XL zbGEC19kRAAYmgCx1;`}?VrE17GAC@NIrGvKIw64S})sPSIJ&LF?QBu$q5- z^SO|-Kk+rfPy-$C?UAB?wf?Ig{-2G9@+$9wrveuD$CBbBE0689RRJ}bmJPTl)qvn4 zLqQ$=^Bk+n6cMB&AX24>(mN{B#Rv#U3Gt(dAqGTxjr1l}ih_Uw(jihqk93qK z1c)Tm&`ThphJN|ZJ@>TdoZmg?K6lSv^T*7dJ?ovlpS9k#)|~%2p9Neq(9zccP*6|+ zUR)f2a~wbmKt)OUcfV-V7oFxZ4GlFl4IM4*rOOO-3=H&i^z@8ZS*|f&Wxh&Je~tYb z^L17>HZ}$(4o-GfP8L=+*1spApt^X5n&t`(%@tNgdPdg&aXbG3V7?4!2MkhC+yYQC zQ&2HeoOc5F0RRe`3vK^a_@5gE<%N!yXfI!(qrVtXdksKIK}AJLP4&0d7o!6&?gOZq zX;=jAJ-Bq;_%GU9ZmcrFNnbAuKCEnGGZ`id$=baQxkAUz!O6ufEFvm)TU<_FK~YIr zMeC8aj;@}*f$1|dbBpJeR`w2#FP&aNoZUS^O?(H9t z50C!FMFF7t-?07#*?+*re1VISnwpB5_HSGil-?IY#Y{~jaPJb!17q61+^*k}3BJtw zFzIV$+Z91s6C#`4+hIC(A-OqW(%;bj3E6)SSjhhqvVQ^gueh)P1}ch+#iL>dXaY_p z@DljN;74UXSx6oIo6 zksq{b5{$st3%)^4Ke#j83)c^cHX3OXudu)SLPKZ!i(U|%cn;V&2axEXIoxZsZ5CFS zzT){Q*12s9Uzg`wTTZWyL@f+rM^FznrNeJxz%bxnrX{nSu9;(w$lGUG9pjMIolEjI1hoC9L3%y&SxD07See*)OL@%uR- z%--nY6w(R3zN*rK$=P?^m=Shh(XZ0J^x7brZ*+ahg*se*$GdYT_)HR`Ap^0BPnfm; z%k>MiQF*vFkX>Db-e)%|8%JQ)mm9=XrW(J=ot}6RR{Z)f9OsoDf^s5gwVlbK=YKa- zLFSh`#u+W=K zCHb~?tT)>!J^-W>?Bx{sh}M2T=rpH7gY74={ZviT@O>YC31V9W_ULUxr~oT;+sbQQj}a}J2(w@)}8 zIS0%vp98oPMRUI#-+)i2pPd6V$;10f=YSUJ(=#~f%axTPjUN7kZ|4Bi(3xCdyylkS zIRKt>@`}>$znTn?9TU3Yb`J0ZAD^59=5_zfpY5U!4$lGI@BY8OMp|=B`qTq>%J6KD zX8Gts!;0v0z}J}UcXVR8|0B71@r9nD_J%cg@0pHr;a%rkJ2nTTj%tQCm#xJ9tI7=V3*Q;TppNEx%wmI z_2wm9uN22VA?&uCDu7it8>MumJw+PN;JI~E(~%Rb7M($tP79meD|})*y*2nTQfjVH zw^@QA7`>~TJ+isky-$nWCM+VWf*Bi5kEvcCD9R+3(C0aMl@IlROu7Qh)dWc?0eaQd zWdAZ~U*JAS1zfrI)R*t+42)9r*Nq&3Hpi)*G=`6*s-jbh2k!7~Y2r?`adU%(N9zIG zIRGiGK2*7aNL6zu@!-K7>P%h6*5offxhpGJjgrO)1l09ahEiiwGJS*D7vziY+T6Y| zjxp|hBO_eT*woC6@l4mr=^cERNwhH_8V|IpAJ1zYmQrB?$l}B z`1CfuU0X#SFkG`f}!t2bmc2HEAwRUni(f|&QgHIP~GKkH*pMUoAT^k=KTvrKmGla_e5c64lkf{QmJMMvSUU>eJoWT9fV);v6; zBEiZ5Tbr*?hVedfo@~dwdZBI7^_8hn*tp&W)J%}rC|pV}sDter2Kqsltj#kMpl7@s z-sswc>S3=|dUE+}PBhE3_M9~53g7MI{@V>k9Ht?}A3UnwQ4@8`kZ!-(BXg4gFQUV= zMN%N#b9pTx4;PrJ+mcSOxYE?Wt@s%&pvr4lwhd z^~UZbUpL{U^10}_Mv%l4f8{)nde6zE$Q0a0#C>ly1Kj24m_ygLtxM3ShQv#7GVnxO zeAy=Jg+ELwx8&_Gpe{H@V}vK`9H5N-<&`88(AdIp!iHE~pT>4f_Z`guF~f&BFk>($ z1YW}w2h-s8SuzB&cg-_#tcC&=k7{cd!+RoYqLv%(4GCSho`{}%Wk0>eyC75ZP~J{N z`|TmNFiH)G2Q&BxcJhgl8w#1Ou1+fk3y>5e_lz{ori=*=G=52r7_1?Fye$IzrhrxE#0PgD{2LP9{n5*t=VH1#1!E zS#J2aHrvn;#nKKl1tRP38+K|9R`))equ0Lv#lEJ_Y(Ey%1YTg$_Fml~tmmPBW|gzG z`IzDtkK=@l31;U2rb8N5!Hf>g!`hrY)CK z1ww?Sg{tnFX;TR$`v9))b(3}H;T<_q+{k^4@DunPoW(iY+HhY=(6X*E^F{a41W($J z-k;sdY=S9s>-V2*YU~RLRVO;OAUSB zJk#Pz`ozhe8etak#w|dKC}B=q?u@%#)_l26r8^7nPq3ZGOMr0v$W?SpC(6Fp-9ulI zo-2Bu`S$z9N&)v>jXV;6yOnONWPlVLAIIL;dC)6VGwdRN*}kRTw2ASCaOn3#>qMq0 zjfk4fT7pcUdF9BaJdd8d>S7W>@>`ZUH2gi4K-`r+n#rapTAm2MF)6EbYt--w!8Hr( zZC*1WRu8w9Khzv^_Sx!?W*}#tanKw@i4a>W=Ro2{Dz7}5@ltlYmWVsk4j#wUA&_qo z6O?@)|FlQ;zmH-IW!{uC))_ViX%3zPiVj>r7YiE_Bld;zAIRl@?4e0OMjyoEoaf|l zl2fOJgzMZEQ)Ua#llpsd5#zsxQRo7?lINf9*d<v&^pApl4c?JU;pJO^;#w2N012)_6%D&xo>2MR-{EqEru4M*wMi#u9E&mXjR zhzCPOmZNIIy~;hMIVR6Wr>QW_7R0Sim7r38x02^pO;f9Ht+0?jPUb^@X|5xF6}xBm zB-zY5oh8=SZX-N}8sRAx3oTN)`Yc;gCn$Op2BYn@aj`L}{%?%qzhoFvguSVVwwnGd4= zGOK9GpI%KL_T9Jmu3kfOk!V#kDQlo+PSoqYIc{cu8=Yd`WaXEEP7a$Ft%3*RZSOUV z)bfV~UCOi_JF)aGomw>x4AmjFB0QborMB|TPF}~}`uwg!HSq%XH@1mi)19ozIqpP` z*-N2i0lH(7FG-Kgz5D|EF&xIYHqYYTl8=y&;En=m=WEin;_0~1X8tUbY|3sx1gPqA^S%* zNDMZ-YjOnFKB8u@B^UoZB15Ys+P*3I%{{bnaYJqH2UIS`RWZ;Xg1XbZiw?8Pt`MI_ z0Na8zRS_8)96sodAZfA`iOQ6u*$L9>ks*UYsFsZ7_H4<($X_dg6@!1$onbI=c6g$ExepH{lClc?Ncrx)LSq$eirTRwa3fuTIsas80iA{aY zmV=GDCT)3dgs*1H>Vfpo&kNh9_t%9p`P-rVXF~mN=x4~zsmVD2^XMG#y9;=qDQvswV>IE!&X~~4`fye93u?F&b$#XCSZVRS>7c8@EKgr81w$PCsCn2Q&)|8k4L6iHvCh;YBt= z*B)H~a3uAbaov3Dmju46`9Ef;BPa;eM;4pAIdE&y$CfAF=r$#zTPC5=7l<>u;WV&0G5w16kIFT)yoahps zoByE=y5Of|Q7pFPb&u(swsG0K<^zzt_`#Hh%`5XYz)%*QWG2*ts ztAf));nopU-_$u^VH`7YXuH&)jMxXEb`fXVYa1w@K>h#b+SfrBr)YaL)XC9!O}bZi z$@ra)N@orYX%35wpd3fx4&jL68|*RJ9(Q7Ec_6|(Z#RefwJPqBw-De}Kk8O7@&~4l zXb0kj5h&DW%=!XmalYety^|fU%n;1*hN&9InsS=A74Wmxz~JsOeEi@XFk+iYSn6AF zagk^O$Ds-@sIs@VTMkXLR*?^K_8@p~z-pf0SMcrYge?eIY1*Hr$DCDHL?_ev89@7` zVz9QD_K6FV$Hre*N|H=Lo)<3h%lF(EF~C0y<-enI4}8yx;p@5Z6}!TJq7ZaPaWT$* zfdikDjaa>z<&1=z%UNSMuNkN${_0S>do#4RLZS_R#h!?aE+p|4;{(0Bt#+_*r;fmi z+Nw-z*c?_YuP%hMdx_5S7Y8hg{@RzT`=te6p~5G167KZ2UED^(-xIl56eQVx?a>)1 z(S8-5jtI|dJVSjWzhW|TLhc>mmhHOOx?bh5dt|}!Pl{(t{Tc0eb)QrpJEU7Q2Bg)E zP)MgeG7>XSr={)JzLyweA#|4u%-pK73cu>G@EsyK>d0P}E*@NN6*CXmHCGzhvxXjpw_K`-4c#T+E~YMLdJxSsEPx8D^*3D8T zWhyP55_{L`jl-#lSD&bSu!+wk9qWvqI9-j((5Pkq?lAWtfH6p|wU7%WQ$IJY24OR;ltx^t*lkAktyg1VZ~<#fZei7>sv zk*W^A?R@`d0Rx-Ypp+`9IMWk=(u6+)$J_od^Q)vxL2FU0Bfp9xkS+3Tx zldw4J0v1i8FZvd1CV{KEHCtGep$yIa`Ddb4fRrK6qM2=8~=NYot**o^HLI}4> zw+q5ae9(*mal@HiE@>ib>|vh!XDW+F$$OW!23*+TAZ!`(Lq$76Q*8BhGswNdhJB|i3D z8eF3uI6ZmV5!afT+UWtPtW1}jv88(38%tgTrfC6i7V9;m0qOZ0wgO~W9vP)YER3o} z5zHrC^Q^R8kncj~n!A%dL+-X(vkZvQhErFIr|r%hoi*;S30KTuzW7-@R;~yoI8E8C2iyHv4!DsBcvIcVzzV-_f6^ z{~8yr{F6mN@DB%FCl_?gN0j3sCxLkDEEa1XZ9~hiBhAq#J#oVHeMYYtH*B>`AX#hl-pnZo9g&KNsJ;aHW0ME&)wwI2Hps$hmXV zGa2x&JwNB-EH%^&@z1Jve|lPcQBfXIpgJ(3bq&H*9@%QH1`P$22*2WSbzdmNkg z$(v=!)!#{`k74-xuSS(*F1>|oZkDY~uMS9{9@cl1 z#u*AX6)r2OZHwRF5Uolpwq5_(pa}nrqFMIJKWxdJF$x&b52D{Wbn^yZ-ILPn&bh)p zDCql*{PNfK$TqQ205o3N#f5$H1RuE>8c#+@5fSauoPPqIqxY0+)SVe$&U7ARROI3P z;l zl95o1KYUx*_i@Nog62@~6szc8Jj-!{^!RiCdu+YKm&yx)CSFo_GPg zQxj4FL*#N14dKjVslnS}E+dw7im2aSBcw893yiehn%0cknkO<0z~{FZu&YS+O6NKR zN92~VlP-shT9HE-eIl-WL`TE)4@o*k&h^qOq)Jbeygx6!ULBp&sJui95*aJW z=B>9Nz8FO%T1@$Eq;^2nc9>8LlYLq{>d{mbMg&_uu4NQyn!83F4}1u4!(*6J_C9 z=BDHI;Y0n`<1h2A61p9>>|=K>!XRXq-xwl^`mXf~_Ogs%=qu)z^&bKHT0&djLqoL7 zoH*MQ=E%#$>E#ZNAfZS+Q}{O`As;_JZ(-#82dj0jThKRj!$O(=w(^2GB2+`r2Z&cs z?OF~yG0yYJ9h?S=L*qD}#%wC(aA5~{?$T1<;Onl1H8dvAzzz3~vzjcAxQdD%Jb;~n zi59aS&mxmnpVb(78<7-JVI{AQ!YfJ(Y%0joubnKvrn?d1Uh?BU0h{?~aEgl&OommbV{eue%pQl578S7r= z6KYZUyC(KUL7{y9cdk0@w0~0p#(spDrUTc26xo-r4TraY3&iadc_YkPGjR)(&uV9bHA_ zLNd>$ik~~b8G=D7y-}IBDxYCd_a=2{MPr7V$g4ygkT{SKwb?4*V~*>Su)O?<9Q`j{r%Akt*eLo9sn!Nj{VymrQok(;@; zDkFOfylUY#b-%xmfjTKUKeUYtUnjnR^LCK1zMmT-ZtxFtBwFbB+F3A5?Wwil=o#-t z`VSTnJO^ij@Cl|tOG`m74f}Wk$7Oq9>YZq7Tofu`PRA@oR>zwv=3q^1Vg|i)QHZ)Z zWqA&;3IYv%&_O~yiGp~=h+Xs4%@eBt-7+#1SRL}vwPr|(%kfIWOx2}J zjYBlrv%vQ=Z1U@X#ICYgv+YSZz_voqkcXA!wSDY4=# z7MIs|I_BD-v_7M|xCI^W_4eNJK3@1%2(y@S99bUBVG4k_5fAn?NA`>q#1_YXsYj$! zhc5WzV#h-!tWR?kp6{$QAe_nYS)41tN7Lwcc~;@E414zK4<=95O5ef&dugHfn>`Ko zAV${Qvhq{7^-OD4Xf6naAiH1>=yqJO{FWs1P-1N7K{iWuWkXBs<0fCH<}pX~^!Poh z92NHXD~7%Kl&l;4g!dNt!&(;F?Ka6Kbv?lWS{TG`8?m%Aho!s*%(!x7+ah%Ip6HD5 zF2u@O0(r}JYz!HAbTigue%6A}OM{H=D%4n}=rbnrPMfYRlDLSB%jwLh2=$bc+6Qk` zi|yPwcoT97ax!S?o!^vxb0JVyo6+6fx1jYHy6#a+@N_9v@{gfASgbxqkezq85dJ4k zL^3c6iTqD{OKIpmw?3I9T}B`>WaIfv<)0Q%>bpbF0v(pmjsR?EluDHFep<8~kd!D8q35C$Zw|oNIK(%saUpZt_qm1l&|95`nsO0YHrNu3|jsmDfoh;5^{Z_Rk@p1CoYJ@8)N_$xrCOp?jsLZ<;kistNcLSJ^Uu#^5jh+ z&#v((Q+f@f>2qroZNPmE!STYe<_Gi80hS$u4<@O*Ti>HAX7yOmz7Y!1Fg#qIRj)tZ zGRlh#*(=Prj$+IFJktN!R&Q=Bx?v%PHB=TG140$SqNK(8o*o+?O!X zGq=~B_2myQyHA;iwb(8W`dr?yJ~wUnvIDZ=Sqgo9F#p=7TGwG_!l&vRfpt7av6V!|hNIi~iaFm(~qX|f7q_Odi>f6Hfy|LV}K z8Fh?l6L_^@`^vG#V!HqmH`x&oH6r$EpG`~xRYerOh)Qa-TUsN_eCl}MOg}sWp+h8> zVo!*h`q0O;{fKF3WSAJG{-=j=O)sbx?IecfHA8Kg$4(#|F%>ndGv>N6FSSSSn2bQ| zI3p}!><_4`M0p&1CerO*#Kp#)^0a4wBlpx@pMJ01mXWk52d70Aa0#nR^z9Z3rCtg1XXi# zR}optW9ypG8!Yal(}(tqGX4FCj71@7)%&-eyV1Q)Nqlek7w(3|@U5{L1lHZGx}Ky^ zS-OhJ=H?h)J*euIDjUMlg~uo*aReu|bm%?kPz8MP3$tQ-&%HNTl?WTHfaTVt1rm0& zdGval+=C<1v=U{!-#)n{(Kp8{0%y@jv=k7m4EZ<4>v#Aw0~hyUgEP(ggR)!tAOjh~ z09>`}8@YD-#HMA_p)R2AP-$j62$ddj0tV@J@kx-AXNW0KTYfN&k1eC2zLB6w+A#a( z15ZJl!K8ZYaQ>Ikk4z&HD1j+k@&)p|UR(IBb}760POC<&PpDy2+I+{EovuAqtkUPi zsF)Gn9_3H@SlyrB*=ft_Pd^9o+d#04!NX25J=#?XMs>BJ&zfRx!>&ab`lssOZ;E0* ztC;Txf2u#sRKGA-An9iqkGPjhnEuh4q`Os_{f^sVCG5bI8#jum65VjD1c#BW!nBI5 zasAT$+KOSB=8UtZAoC!ktJl^}L2wC_-g|Z{inh~l^avTH2J_9eg_t;-v}Wxy%THdR zv~s=MJuKA>T*{5+O6t3J^~b4}jd>=~^`f{L_mTvv%Tig}HkA5dF?z?LCIZ6ox?0v+Bae{Sb3nwfgzs7=$~tac!*$(jYcbDYip3m#K^MjTeLC?! RFQ)uw1(yGFjrM%ve*rx+s6YS! literal 0 HcmV?d00001 diff --git a/lib/DFRobot_BMM350/src/DFRobot_BMM350.cpp b/lib/DFRobot_BMM350/src/DFRobot_BMM350.cpp new file mode 100644 index 0000000..b29b225 --- /dev/null +++ b/lib/DFRobot_BMM350/src/DFRobot_BMM350.cpp @@ -0,0 +1,483 @@ + +/** + * @file DFRobot_BMM350.cpp + * @brief Define the infrastructure of the DFRobot_BMM350 class and the implementation of the underlying methods + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350 + */ + +#include "DFRobot_BMM350.h" + +static struct bmm350_dev bmm350Sensor; +/*! Variable that holds the I2C device address selection */ +static uint8_t devAddr; +TwoWire *_pWire = NULL; +uint8_t bmm350I2CAddr = 0; + +void bmm350DelayUs(uint32_t period, void *intfPtr) +{ + UNUSED(intfPtr); + if (period > 1000) + { + delay(period / 1000); + } + else + { + delayMicroseconds(period); + } +} + +DFRobot_BMM350::DFRobot_BMM350(pBmm350ReadFptr_t bmm350ReadReg, pBmm350WriteFptr_t bmm350WriteReg, pBmm350DelayUsFptr_t bmm350DelayUs, eBmm350Interface_t interface) +{ + switch (interface) + { + case eBmm350InterfaceI2C: + devAddr = BMM350_I2C_ADSEL_SET_LOW; + bmm350Sensor.intfPtr = &devAddr; + break; + case eBmm350InterfaceI3C: + break; + } + bmm350Sensor.read = bmm350ReadReg; + bmm350Sensor.write = bmm350WriteReg; + bmm350Sensor.delayUs = bmm350DelayUs; +} + +DFRobot_BMM350::~DFRobot_BMM350() +{ +} + +bool DFRobot_BMM350::sensorInit(void) +{ + return bmm350Init(&bmm350Sensor) == 0; +} + +uint8_t DFRobot_BMM350::getChipID(void) +{ + return bmm350Sensor.chipId; +} + +void DFRobot_BMM350::softReset(void) +{ + bmm350SoftReset(&bmm350Sensor); + bmm350SetPowerMode(eBmm350SuspendMode, &bmm350Sensor); +} + +void DFRobot_BMM350::setOperationMode(enum eBmm350PowerModes_t powermode) +{ + bmm350SetPowerMode(powermode, &bmm350Sensor); +} + +String DFRobot_BMM350::getOperationMode(void) +{ + String result; + switch (bmm350Sensor.powerMode) + { + case eBmm350SuspendMode: + result = "bmm350 is suspend mode!"; + break; + case eBmm350NormalMode: + result = "bmm350 is normal mode!"; + break; + case eBmm350ForcedMode: + result = "bmm350 is forced mode!"; + break; + case eBmm350ForcedModeFast: + result = "bmm350 is forced_fast mode!"; + break; + default: + result = "error mode!"; + break; + } + return result; +} + +void DFRobot_BMM350::setPresetMode(uint8_t presetMode, enum eBmm350DataRates_t rate) +{ + switch (presetMode) + { + case BMM350_PRESETMODE_LOWPOWER: + bmm350SetOdrPerformance(rate, BMM350_NO_AVERAGING, &bmm350Sensor); + break; + case BMM350_PRESETMODE_REGULAR: + bmm350SetOdrPerformance(rate, BMM350_AVERAGING_2, &bmm350Sensor); + break; + case BMM350_PRESETMODE_ENHANCED: + bmm350SetOdrPerformance(rate, BMM350_AVERAGING_4, &bmm350Sensor); + break; + case BMM350_PRESETMODE_HIGHACCURACY: + bmm350SetOdrPerformance(rate, BMM350_AVERAGING_8, &bmm350Sensor); + break; + default: + break; + } +} +void DFRobot_BMM350::setRate(uint8_t rate) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t avgOdrReg = 0; + uint8_t avgReg = 0; + uint8_t regData = 0; + + switch(rate){ + case BMM350_DATA_RATE_1_5625HZ: + case BMM350_DATA_RATE_3_125HZ: + case BMM350_DATA_RATE_6_25HZ: + case BMM350_DATA_RATE_12_5HZ: + case BMM350_DATA_RATE_25HZ: + case BMM350_DATA_RATE_50HZ: + case BMM350_DATA_RATE_100HZ: + case BMM350_DATA_RATE_200HZ: + case BMM350_DATA_RATE_400HZ: + /* Get the configurations for ODR and performance */ + rslt = bmm350GetRegs(BMM350_REG_PMU_CMD_AGGR_SET, &avgOdrReg, 1, &bmm350Sensor); + if (rslt == BMM350_OK){ + /* Read the performance status */ + avgReg = BMM350_GET_BITS(avgOdrReg, BMM350_AVG); + } + /* ODR is an enum taking the generated constants from the register map */ + regData = ((uint8_t)rate & BMM350_ODR_MSK); + /* AVG / performance is an enum taking the generated constants from the register map */ + regData = BMM350_SET_BITS(regData, BMM350_AVG, (uint8_t)avgReg); + /* Set PMU command configurations for ODR and performance */ + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD_AGGR_SET, ®Data, 1, &bmm350Sensor); + if (rslt == BMM350_OK){ + /* Set PMU command configurations to update odr and average */ + regData = BMM350_PMU_CMD_UPD_OAE; + /* Set PMU command configuration */ + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, ®Data, 1, &bmm350Sensor); + if (rslt == BMM350_OK){ + rslt = bmm350DelayUs(BMM350_UPD_OAE_DELAY, &bmm350Sensor); + } + } + break; + default: + break; + } +} + +float DFRobot_BMM350::getRate(void) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t avgOdrReg = 0; + uint8_t odrReg = 0; + float result = 0; + + /* Get the configurations for ODR and performance */ + rslt = bmm350GetRegs(BMM350_REG_PMU_CMD_AGGR_SET, &avgOdrReg, 1, &bmm350Sensor); + if (rslt == BMM350_OK) + { + /* Read the performance status */ + odrReg = BMM350_GET_BITS(avgOdrReg, BMM350_ODR); + } + switch (odrReg) + { + case BMM350_DATA_RATE_1_5625HZ: + result = 1.5625; + break; + case BMM350_DATA_RATE_3_125HZ: + result = 3.125; + break; + case BMM350_DATA_RATE_6_25HZ: + result = 6.25; + break; + case BMM350_DATA_RATE_12_5HZ: + result = 12.5; + break; + case BMM350_DATA_RATE_25HZ: + result = 25; + break; + case BMM350_DATA_RATE_50HZ: + result = 50; + break; + case BMM350_DATA_RATE_100HZ: + result = 100; + break; + case BMM350_DATA_RATE_200HZ: + result = 200; + break; + case BMM350_DATA_RATE_400HZ: + result = 400; + break; + default: + break; + } + return result; +} + +String DFRobot_BMM350::selfTest(eBmm350SelfTest_t testMode) +{ + String result; + /* Structure instance of self-test data */ + struct sBmm350SelfTest_t stData; + memset(&stData, 0, sizeof(stData)); + switch (testMode) + { + case eBmm350SelfTestNormal: + setOperationMode(eBmm350NormalMode); + setMeasurementXYZ(); + sBmm350MagData_t magData = getGeomagneticData(); + if ((magData.x < 2000) && (magData.x > -2000)) + { + result += "x aixs self test success!\n"; + } + else + { + result += "x aixs self test failed!\n"; + } + if ((magData.y < 2000) && (magData.y > -2000)) + { + result += "y aixs self test success!\n"; + } + else + { + result += "y aixs self test failed!\n"; + } + if ((magData.z < 2000) && (magData.z > -2000)) + { + result += "z aixs self test success!\n"; + } + else + { + result += "z aixs self test failed!\n"; + } + break; + } + return result; +} + +void DFRobot_BMM350::setMeasurementXYZ(enum eBmm350XAxisEnDis_t enX, enum eBmm350YAxisEnDis_t enY, enum eBmm350ZAxisEnDis_t enZ) +{ + bmm350_enable_axes(enX, enY, enZ, &bmm350Sensor); +} + +String DFRobot_BMM350::getMeasurementStateXYZ(void) +{ + uint8_t axisReg = 0; + uint8_t enX = 0; + uint8_t enY = 0; + uint8_t enZ = 0; + char result[100] = ""; + + /* Get the configurations for ODR and performance */ + axisReg = bmm350Sensor.axisEn; + + /* Read the performance status */ + enX = BMM350_GET_BITS(axisReg, BMM350_EN_X); + enY = BMM350_GET_BITS(axisReg, BMM350_EN_Y); + enZ = BMM350_GET_BITS(axisReg, BMM350_EN_Z); + + strcat(result, (enX == 1 ? "The x axis is enable! " : "The x axis is disable! ")); + strcat(result, (enY == 1 ? "The y axis is enable! " : "The y axis is disable! ")); + strcat(result, (enZ == 1 ? "The z axis is enable! " : "The z axis is disable! ")); + return result; +} + +sBmm350MagData_t DFRobot_BMM350::getGeomagneticData(void) +{ + sBmm350MagData_t magData; + struct sBmm350MagTempData_t magTempData; + memset(&magData, 0, sizeof(magData)); + memset(&magTempData, 0, sizeof(magTempData)); + bmm350GetCompensatedMagXYZTempData(&magTempData, &bmm350Sensor); + magData.x = magTempData.x; + magData.y = magTempData.y; + magData.z = magTempData.z; + magData.temperature = magTempData.temperature; + magData.float_x = magTempData.x; + magData.float_y = magTempData.y; + magData.float_z = magTempData.z; + magData.float_temperature = magTempData.temperature; + return magData; +} + +float DFRobot_BMM350::getCompassDegree(void) +{ + float compass = 0.0; + sBmm350MagData_t magData = getGeomagneticData(); + compass = atan2(magData.x, magData.y); + if (compass < 0) + { + compass += 2 * PI; + } + if (compass > 2 * PI) + { + compass -= 2 * PI; + } + return compass * 180 / M_PI; +} + +void DFRobot_BMM350::setDataReadyPin(enum eBmm350InterruptEnableDisable_t modes, enum eBmm350IntrPolarity_t polarity) +{ + /* Variable to get interrupt control configuration */ + uint8_t regData = 0; + /* Variable to store the function result */ + int8_t rslt; + /* Get interrupt control configuration */ + rslt = bmm350GetRegs(BMM350_REG_INT_CTRL, ®Data, 1, &bmm350Sensor); + if (rslt == BMM350_OK) + { + regData = BMM350_SET_BITS_POS_0(regData, BMM350_INT_MODE, BMM350_PULSED); + regData = BMM350_SET_BITS(regData, BMM350_INT_POL, polarity); + regData = BMM350_SET_BITS(regData, BMM350_INT_OD, BMM350_INTR_PUSH_PULL); + regData = BMM350_SET_BITS(regData, BMM350_INT_OUTPUT_EN, BMM350_MAP_TO_PIN); + regData = BMM350_SET_BITS(regData, BMM350_DRDY_DATA_REG_EN, (uint8_t)modes); + /* Finally transfer the interrupt configurations */ + rslt = bmm350SetRegs(BMM350_REG_INT_CTRL, ®Data, 1, &bmm350Sensor); + } +} + +bool DFRobot_BMM350::getDataReadyState(void) +{ + uint8_t drdyStatus = 0x0; + bmm350GetInterruptStatus(&drdyStatus, &bmm350Sensor); + if (drdyStatus & 0x01) + { + return true; + } + else + { + return false; + } +} + +void DFRobot_BMM350::setThresholdInterrupt(uint8_t modes, int8_t threshold, enum eBmm350IntrPolarity_t polarity) +{ + if (modes == LOW_THRESHOLD_INTERRUPT) + { + __thresholdMode = LOW_THRESHOLD_INTERRUPT; + setDataReadyPin(BMM350_ENABLE_INTERRUPT, polarity); + this->threshold = threshold; + } + else + { + __thresholdMode = HIGH_THRESHOLD_INTERRUPT; + setDataReadyPin(BMM350_ENABLE_INTERRUPT, polarity); + this->threshold = threshold; + } +} + +sBmm350ThresholdData_t DFRobot_BMM350::getThresholdData(void) +{ + sBmm350MagData_t magData; + memset(&magData, 0, sizeof(magData)); + thresholdData.mag_x = NO_DATA; + thresholdData.mag_y = NO_DATA; + thresholdData.mag_z = NO_DATA; + thresholdData.interrupt_x = 0; + thresholdData.interrupt_y = 0; + thresholdData.interrupt_z = 0; + bool state = getDataReadyState(); + if (state == true) + { + magData = getGeomagneticData(); + if (__thresholdMode == LOW_THRESHOLD_INTERRUPT) + { + if (magData.x < (int32_t)threshold * 16) + { + thresholdData.mag_x = magData.x; + thresholdData.interrupt_x = 1; + } + if (magData.y < (int32_t)threshold * 16) + { + thresholdData.mag_y = magData.y; + thresholdData.interrupt_y = 1; + } + if (magData.z < (int32_t)threshold * 16) + { + thresholdData.mag_z = magData.z; + thresholdData.interrupt_z = 1; + } + } + else if (__thresholdMode == HIGH_THRESHOLD_INTERRUPT) + { + if (magData.x > (int32_t)threshold * 16) + { + thresholdData.mag_x = magData.x; + thresholdData.interrupt_x = 1; + } + if (magData.y > (int32_t)threshold * 16) + { + thresholdData.mag_y = magData.y; + thresholdData.interrupt_y = 1; + } + if (magData.z > (int32_t)threshold * 16) + { + thresholdData.mag_z = magData.z; + thresholdData.interrupt_z = 1; + } + } + } + + return thresholdData; +} + +static int8_t bmm350I2cReadData(uint8_t Reg, uint8_t *Data, uint32_t len, void *intfPtr) +{ + uint8_t deviceAddr = *(uint8_t *)intfPtr; + _pWire->begin(); + int i = 0; + _pWire->beginTransmission(deviceAddr); + _pWire->write(Reg); + if (_pWire->endTransmission() != 0) + { + return -1; + } + _pWire->requestFrom(deviceAddr, (uint8_t)len); + while (_pWire->available()) + { + Data[i++] = _pWire->read(); + } + return 0; +} + +static int8_t bmm350I2cWriteData(uint8_t Reg, const uint8_t *Data, uint32_t len, void *intfPtr) +{ + uint8_t deviceAddr = *(uint8_t *)intfPtr; + _pWire->begin(); + _pWire->beginTransmission(deviceAddr); + _pWire->write(Reg); + for (uint8_t i = 0; i < len; i++) + { + _pWire->write(Data[i]); + } + _pWire->endTransmission(); + return 0; +} + +DFRobot_BMM350_I2C::DFRobot_BMM350_I2C(TwoWire *pWire, uint8_t addr) : DFRobot_BMM350(bmm350I2cReadData, bmm350I2cWriteData, bmm350DelayUs, eBmm350InterfaceI2C) +{ + _pWire = pWire; + bmm350I2CAddr = addr; +} + +uint8_t DFRobot_BMM350_I2C::begin() +{ + _pWire->begin(); + _pWire->beginTransmission(bmm350I2CAddr); + if (_pWire->endTransmission() == 0) + { + if (sensorInit()) + { + return 0; + } + else + { + DBG("Chip id error ,please check sensor!"); + return 2; + } + } + else + { + DBG("I2C device address error or no connection!"); + return 1; + } +} diff --git a/lib/DFRobot_BMM350/src/DFRobot_BMM350.h b/lib/DFRobot_BMM350/src/DFRobot_BMM350.h new file mode 100644 index 0000000..67600f4 --- /dev/null +++ b/lib/DFRobot_BMM350/src/DFRobot_BMM350.h @@ -0,0 +1,250 @@ +/** + * @file DFRobot_BMM350.h + * @brief Defines the infrastructure of the DFRobot_BMM350 class + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350 + */ +#ifndef __DFRobot_BMM350_H__ +#define __DFRobot_BMM350_H__ + +#include "bmm350_defs.h" +#include "bmm350.h" + +#include "Arduino.h" +#include +#include +#include + + +//#define ENABLE_DBG //< Open this macro to see the program running in detail + +#ifdef ENABLE_DBG +#define DBG(...) {Serial.print("[");Serial.print(__FUNCTION__); Serial.print("(): "); Serial.print(__LINE__); Serial.print(" ] "); Serial.println(__VA_ARGS__);} +#else +#define DBG(...) +#endif + +#define BMM350_INTERFACE_I2C UINT8_C(0x00) +#define BMM350_INTERFACE_I3C UINT8_C(0x01) +#define BMM350_SELF_TEST_NORMAL UINT8_C(0x00) +#define BMM350_SELF_TEST_ADVANCED UINT8_C(0x01) + +enum eBmm350Interface_t { + eBmm350InterfaceI2C = BMM350_INTERFACE_I2C, + eBmm350InterfaceI3C = BMM350_INTERFACE_I3C +}; + +enum eBmm350SelfTest_t { + eBmm350SelfTestNormal = BMM350_SELF_TEST_NORMAL +}; + +void bmm350DelayUs(uint32_t period); + +class DFRobot_BMM350{ +public: + DFRobot_BMM350(pBmm350ReadFptr_t bmm350ReadReg, pBmm350WriteFptr_t bmm350WriteReg, pBmm350DelayUsFptr_t bmm350DelayUs, eBmm350Interface_t interface); + + ~DFRobot_BMM350(); + + /** + * @fn softReset + * @brief Soft reset, restore to suspended mode after soft reset. (You need to manually enter the normal mode) + */ + void softReset(void); + + /** + * @fn setOperationMode + * @brief Set sensor operation mode + * @param powermode + * @n eBmm350SuspendMode suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * @n eBmm350NormalMode normal mode: Get geomagnetic data normally. + * @n eBmm350ForcedMode forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. + * @n eBmm350ForcedModeFast To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + void setOperationMode(enum eBmm350PowerModes_t powermode); + + /** + * @fn getOperationMode + * @brief Get sensor operation mode + * @return result Return sensor operation mode as a character string + */ + String getOperationMode(void); + + /** + * @fn setPresetMode + * @brief Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default collection rate is 12.5Hz) + * @param presetMode + * @n BMM350_PRESETMODE_LOWPOWER Low power mode, get a fraction of data and take the mean value. + * @n BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and take the mean value. + * @n BMM350_PRESETMODE_ENHANCED Enhanced mode, get a plenty of data and take the mean value. + * @n BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and take the mean value. + * @param rate + * @n BMM350_DATA_RATE_1_5625HZ + * @n BMM350_DATA_RATE_3_125HZ + * @n BMM350_DATA_RATE_6_25HZ + * @n BMM350_DATA_RATE_12_5HZ + * @n BMM350_DATA_RATE_25HZ + * @n BMM350_DATA_RATE_50HZ + * @n BMM350_DATA_RATE_100HZ + * @n BMM350_DATA_RATE_200HZ + * @n BMM350_DATA_RATE_400HZ + */ + void setPresetMode(uint8_t presetMode, enum eBmm350DataRates_t rate=BMM350_DATA_RATE_12_5HZ); + /** + * @fn setRate + * @brief Set the rate of obtaining geomagnetic data, the higher, the faster (without delay function) + * @param rate + * @n BMM350_DATA_RATE_1_5625HZ + * @n BMM350_DATA_RATE_3_125HZ + * @n BMM350_DATA_RATE_6_25HZ + * @n BMM350_DATA_RATE_12_5HZ (default rate) + * @n BMM350_DATA_RATE_25HZ + * @n BMM350_DATA_RATE_50HZ + * @n BMM350_DATA_RATE_100HZ + * @n BMM350_DATA_RATE_200HZ + * @n BMM350_DATA_RATE_400HZ + */ + void setRate(uint8_t rate); + + /** + * @fn getRate + * @brief Get the config data rate, unit: HZ + * @return rate + */ + float getRate(void); + + /** + * @fn selfTest + * @brief The sensor self test, the returned value indicate the self test result. + * @param testMode: + * @n eBmm350SelfTestNormal Normal self test, test whether x-axis, y-axis and z-axis are connected or short-circuited + * @return result The returned character string is the self test result + */ + String selfTest(eBmm350SelfTest_t testMode = eBmm350SelfTestNormal); + + /** + * @fn setMeasurementXYZ + * @brief Enable the measurement at x-axis, y-axis and z-axis, default to be enabled. After disabling, the geomagnetic data at x, y, and z axis are wrong. + * @param en_x + * @n BMM350_X_EN Enable the measurement at x-axis + * @n BMM350_X_DIS Disable the measurement at x-axis + * @param en_y + * @n BMM350_Y_EN Enable the measurement at y-axis + * @n BMM350_Y_DIS Disable the measurement at y-axis + * @param en_z + * @n BMM350_Z_EN Enable the measurement at z-axis + * @n BMM350_Z_DIS Disable the measurement at z-axis + */ + void setMeasurementXYZ(enum eBmm350XAxisEnDis_t enX = BMM350_X_EN, enum eBmm350YAxisEnDis_t enY = BMM350_Y_EN, enum eBmm350ZAxisEnDis_t enZ = BMM350_Z_EN); + + /** + * @fn getMeasurementStateXYZ + * @brief Get the enabling status at x-axis, y-axis and z-axis + * @return result Return enabling status as a character string + */ + String getMeasurementStateXYZ(void); + + /** + * @fn getGeomagneticData + * @brief Get the geomagnetic data of 3 axis (x, y, z) + * @return Geomagnetic data structure, unit: (uT) + */ + sBmm350MagData_t getGeomagneticData(void); + + + /** + * @fn getCompassDegree + * @brief Get compass degree + * @return Compass degree (0° - 360°) + * @n 0° = North, 90° = East, 180° = South, 270° = West. + */ + float getCompassDegree(void); + + /** + * @fn setDataReadyPin + * @brief Enable or disable data ready interrupt pin + * @n After enabling, the DRDY pin jump when there's data coming. + * @n After disabling, the DRDY pin will not jump when there's data coming. + * @n High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. + * @n Low polarity: active on low, default is high level, which turns to low level when the interrupt is triggered. + * @param modes + * @n BMM350_ENABLE_INTERRUPT Enable DRDY + * @n BMM350_DISABLE_INTERRUPT Disable DRDY + * @param polarity + * @n BMM350_ACTIVE_HIGH High polarity + * @n BMM350_ACTIVE_LOW Low polarity + */ + void setDataReadyPin(enum eBmm350InterruptEnableDisable_t modes, enum eBmm350IntrPolarity_t polarity=BMM350_ACTIVE_HIGH); + + /** + * @fn getDataReadyState + * @brief Get the data ready status, determine whether the data is ready + * @return status + * @retval true Data ready + * @retval false Data is not ready + */ + bool getDataReadyState(void); + + /** + * @fn setThresholdInterrupt(uint8_t modes, int8_t threshold, enum eBmm350IntrPolarity_t polarity) + * @brief Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold + * @n High polarity: active on high level, the default is low level, which turns to high level when the interrupt is triggered. + * @n Low polarity: active on low level, the default is high level, which turns to low level when the interrupt is triggered. + * @param modes + * @n LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode + * @n HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode + * @param threshold + * @n Threshold, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt + * @param polarity + * @n POLARITY_HIGH High polarity + * @n POLARITY_LOW Low polarity + */ + void setThresholdInterrupt(uint8_t modes, int8_t threshold, enum eBmm350IntrPolarity_t polarity); + + /** + * @fn getThresholdData + * @brief Get the data with threshold interrupt occurred + * @return Returns the structure for storing geomagnetic data, the structure stores the data of 3 axis and interrupt status, + * @n The interrupt is not triggered when the data at x-axis, y-axis and z-axis are NO_DATA + * @n mag_x、mag_y、mag_z store geomagnetic data + * @n interrupt_x、interrupt_y、interrupt_z store the xyz axis interrupt state + */ + sBmm350ThresholdData_t getThresholdData(void); + +protected: + /** + * @fn sensorInit + * @brief Init bmm350 check whether the chip id is right + * @return state + * @retval true Chip id is right init succeeds + * @retval false Chip id is wrong init failed + */ + bool sensorInit(void); + + /** + * @fn getChipID + * @brief get bmm350 chip id + * @return chip id + */ + uint8_t getChipID(void); + +private: + uint8_t __thresholdMode = 3; + int8_t threshold = 0; + sBmm350ThresholdData_t thresholdData; +}; + +class DFRobot_BMM350_I2C:public DFRobot_BMM350 +{ + public: + DFRobot_BMM350_I2C(TwoWire *pWire, uint8_t addr = 0x14); + uint8_t begin(void); +}; + + +#endif diff --git a/lib/DFRobot_BMM350/src/bmm350.c b/lib/DFRobot_BMM350/src/bmm350.c new file mode 100644 index 0000000..21b7f72 --- /dev/null +++ b/lib/DFRobot_BMM350/src/bmm350.c @@ -0,0 +1,1781 @@ +/** +* Copyright (c) 2023 Bosch Sensortec GmbH. All rights reserved. +* +* BSD-3-Clause +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* 1. Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* +* 2. Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the distribution. +* +* 3. Neither the name of the copyright holder nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, +* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING +* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* @file bmm350.c +* @date 2023-05-26 +* @version v1.4.0 +* +*/ + +/*************************** Header files *******************************/ +#include "bmm350.h" + +#ifdef __KERNEL__ +#include +#include +#else +#include +#include +#endif + +/********************** Static function declarations ************************/ + +/*! + * @brief This internal API is used to validate the device pointer for + * null conditions. + * + * @param[in] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t null_ptr_check(const struct bmm350_dev *dev); + +/*! + * @brief This internal API is used to update magnetometer offset and sensitivity data. + * + * @param[in] dev : Structure instance of bmm350_dev. + * + * @return void + */ +static void update_mag_off_sens(struct bmm350_dev *dev); + +/*! + * @brief This internal API converts the raw data from the IC data registers to signed integer + * + * @param[in] inval : Unsigned data from data registers + * @param[in number_of_bits : Width of data register + * + * @return Conversion to signed integer + */ +static int32_t fix_sign(uint32_t inval, int8_t number_of_bits); + +/*! + * @brief This internal API is used to read OTP word + * + * @param[in] addr : Stores OTP address + * @param[in, out] lsb_msb : Pointer to store OTP word + * @param[in, out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t read_otp_word(uint8_t addr, uint16_t *lsb_msb, struct bmm350_dev *dev); + +/*! + * @brief This internal API is used to read raw magnetic x,y and z axis data along with temperature. + * + * @param[out] out_data : Pointer variable to store mag and temperature data. + * @param[in, out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t read_out_raw_data(float *out_data, struct bmm350_dev *dev); + +/*! + * @brief This internal API is used to convert raw mag lsb data to uT and raw temperature data to degC. + * + * @param[in,out] lsb_to_ut_degc : Float variable to store converted value of mag lsb in micro tesla(uT) and + * temperature data in degC. + * + * @return void + */ +static void update_default_coefiecents(float *lsb_to_ut_degc); + +/*! + * @brief This internal API is used to read OTP data after boot in user mode. + * + * @param[in, out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t otp_dump_after_boot(struct bmm350_dev *dev); + +/*! + * @brief This internal API is used for self-test entry configuration + * + * @param[in, out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t self_test_entry_config(struct bmm350_dev *dev); + +/*! + * @brief This internal API is used to test self-test for X and Y axis + * + * @param[in, out] out_data : Structure instance of sBmm350SelfTest_t. + * @param[in, out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t self_test_xy_axis(struct sBmm350SelfTest_t *out_data, struct bmm350_dev *dev); + +/*! + * @brief This internal API is used to set self-test configurations. + * + * @param[in] st_cmd : Variable to store self-test command. + * @param[in] pmu_cmd : Variable to store PMU command. + * @param[in, out] out_data : Structure instance of sBmm350SelfTest_t. + * @param[in, out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t self_test_config(uint8_t st_cmd, + uint8_t pmu_cmd, + struct sBmm350SelfTest_t *out_data, + struct bmm350_dev *dev); + +/*! + * @brief This internal API is used to set powermode. + * + * @param[in] powermode : Variable to set new powermode. + * @param[in, out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +static int8_t set_powermode(enum eBmm350PowerModes_t powermode, struct bmm350_dev *dev); + +/********************** Global function definitions ************************/ + +/*! + * @brief This API is the entry point. Call this API before using other APIs. + */ +int8_t bmm350Init(struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Variable to get chip id */ + uint8_t chipId = BMM350_DISABLE; + + /* Variable to store the command to power-off the OTP */ + uint8_t otp_cmd = BMM350_OTP_CMD_PWR_OFF_OTP; + + /* Variable to store soft-reset command */ + uint8_t soft_reset; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + /* Proceed if null check is fine */ + if (rslt == BMM350_OK) + { + dev->chipId = 0; + + /* Assign axisEn with all axis enabled (BMM350_EN_XYZ_MSK) */ + dev->axisEn = BMM350_EN_XYZ_MSK; + rslt = bmm350DelayUs(BMM350_START_UP_TIME_FROM_POR, dev); + + if (rslt == BMM350_OK) + { + /* Soft-reset */ + soft_reset = BMM350_CMD_SOFTRESET; + /* Set the command in the command register */ + rslt = bmm350SetRegs(BMM350_REG_CMD, &soft_reset, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(BMM350_SOFT_RESET_DELAY, dev); + } + } + + if (rslt == BMM350_OK) + { + /* Chip ID of the sensor is read */ + rslt = bmm350GetRegs(BMM350_REG_CHIP_ID, &chipId, 1, dev); + + if (rslt == BMM350_OK) + { + /* Assign chipId to dev->chipId */ + dev->chipId = chipId; + } + } + /* Check for chip id validity */ + if ((rslt == BMM350_OK) && (dev->chipId == BMM350_CHIP_ID)) + { + /* Download OTP memory */ + rslt = otp_dump_after_boot(dev); + if (rslt == BMM350_OK) + { + /* Power off OTP */ + rslt = bmm350SetRegs(BMM350_REG_OTP_CMD_REG, &otp_cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350_magnetic_reset_and_wait(dev); + } + } + } + else + { + rslt = BMM350_E_DEV_NOT_FOUND; + } + } + + return rslt; +} + +/*! + * @brief This API writes the given data to the register address + * of the sensor. + */ +int8_t bmm350SetRegs(uint8_t reg_addr, const uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + + /* Proceed if null check is fine */ + if ((rslt == BMM350_OK) && (reg_data != NULL) && (len != 0)) + { + /* Write the data to the reg_addr */ + dev->intf_rslt = dev->write(reg_addr, reg_data, len, dev->intfPtr); + + if (dev->intf_rslt != BMM350_INTF_RET_SUCCESS) + { + rslt = BMM350_E_COM_FAIL; + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This API reads the data from the given register address of sensor. + */ +int8_t bmm350GetRegs(uint8_t reg_addr, uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Variable to define temporary length */ + uint16_t temp_len = len + BMM350_DUMMY_BYTES; + + /* Variable to define temporary buffer */ + uint8_t temp_buf[BMM350_READ_BUFFER_LENGTH]; + + /* Variable to define loop */ + uint16_t index = 0; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + + /* Proceed if null check is fine */ + if ((rslt == BMM350_OK) && (reg_data != NULL)) + { + /* Read the data from the reg_addr */ + dev->intf_rslt = dev->read(reg_addr, temp_buf, temp_len, dev->intfPtr); + + if (dev->intf_rslt == BMM350_INTF_RET_SUCCESS) + { + /* Copy data after dummy byte indices */ + while (index < len) + { + reg_data[index] = temp_buf[index + BMM350_DUMMY_BYTES]; + index++; + } + } + else + { + rslt = BMM350_E_COM_FAIL; + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This function provides the delay for required time (Microsecond) as per the input provided in some of the + * APIs. + */ +int8_t bmm350DelayUs(uint32_t period_us, const struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + + if (rslt == BMM350_OK) + { + dev->delayUs(period_us, dev->intfPtr); + } + + return rslt; +} + +/*! + * @brief This API is used to perform soft-reset of the sensor + * where all the registers are reset to their default values + */ +int8_t bmm350SoftReset(struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t reg_data; + + /* Variable to store the command to power-off the OTP */ + uint8_t otp_cmd = BMM350_OTP_CMD_PWR_OFF_OTP; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + + if (rslt == BMM350_OK) + { + reg_data = BMM350_CMD_SOFTRESET; + + /* Set the command in the command register */ + rslt = bmm350SetRegs(BMM350_REG_CMD, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(BMM350_SOFT_RESET_DELAY, dev); + + if (rslt == BMM350_OK) + { + /* Power off OTP */ + rslt = bmm350SetRegs(BMM350_REG_OTP_CMD_REG, &otp_cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350_magnetic_reset_and_wait(dev); + } + } + } + } + + return rslt; +} + +/*! + * @brief This API is used to read the sensor time. + * It converts the sensor time register values to the representative time value. + * Returns the sensor time in ticks. + */ +int8_t bmm350_read_sensortime(uint32_t *seconds, uint32_t *nanoseconds, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + uint64_t time; + + uint8_t reg_data[3]; + + if ((seconds != NULL) && (nanoseconds != NULL)) + { + /* Get sensor time raw data */ + rslt = bmm350GetRegs(BMM350_REG_SENSORTIME_XLSB, reg_data, 3, dev); + + if (rslt == BMM350_OK) + { + time = (uint32_t)(reg_data[0] + ((uint32_t)reg_data[1] << 8) + ((uint32_t)reg_data[2] << 16)); + + /* 1 LSB is 39.0625us. Converting to nanoseconds */ + time *= UINT64_C(390625); + time /= UINT64_C(10); + *seconds = (uint32_t)(time / UINT64_C(1000000000)); + *nanoseconds = (uint32_t)(time - ((*seconds) * UINT64_C(1000000000))); + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This API is used to get the status flags of all interrupt + * which is used to check for the assertion of interrupts + */ +int8_t bmm350GetInterruptStatus(uint8_t *drdy_status, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t int_status_reg; + + if (drdy_status != NULL) + { + /* Get the status of interrupt */ + rslt = bmm350GetRegs(BMM350_REG_INT_STATUS, &int_status_reg, 1, dev); + + if (rslt == BMM350_OK) + { + /* Read the interrupt status */ + (*drdy_status) = BMM350_GET_BITS(int_status_reg, BMM350_DRDY_DATA_REG); + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This API is used to set the power mode of the sensor + */ +int8_t bmm350SetPowerMode(enum eBmm350PowerModes_t powermode, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t last_pwr_mode; + uint8_t reg_data; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350GetRegs(BMM350_REG_PMU_CMD, &last_pwr_mode, 1, dev); + + if (rslt == BMM350_OK) + { + if (last_pwr_mode > BMM350_PMU_CMD_NM_TC) + { + rslt = BMM350_E_INVALID_CONFIG; + } + + if ((rslt == BMM350_OK) && + ((last_pwr_mode == BMM350_PMU_CMD_NM) || (last_pwr_mode == BMM350_PMU_CMD_UPD_OAE))) + { + reg_data = BMM350_PMU_CMD_SUS; + + /* Set PMU command configuration */ + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(BMM350_GOTO_SUSPEND_DELAY, dev); + } + } + + if (rslt == BMM350_OK) + { + rslt = set_powermode(powermode, dev); + } + } + } + if (rslt == BMM350_OK) dev->powerMode = powermode; + return rslt; +} + +/*! + * @brief This API sets the ODR and averaging factor. + */ +int8_t bmm350SetOdrPerformance(enum eBmm350DataRates_t odr, + enum bmm350_performance_parameters performance, + struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Variable to get PMU command */ + uint8_t reg_data = 0; + + enum bmm350_performance_parameters performance_fix = performance; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + + if (rslt == BMM350_OK) + { + /* Reduce the performance setting when too high for the chosen ODR */ + if ((odr == BMM350_DATA_RATE_400HZ) && (performance >= BMM350_AVERAGING_2)) + { + performance_fix = BMM350_NO_AVERAGING; + } + else if ((odr == BMM350_DATA_RATE_200HZ) && (performance >= BMM350_AVERAGING_4)) + { + performance_fix = BMM350_AVERAGING_2; + } + else if ((odr == BMM350_DATA_RATE_100HZ) && (performance >= BMM350_AVERAGING_8)) + { + performance_fix = BMM350_AVERAGING_4; + } + + /* ODR is an enum taking the generated constants from the register map */ + reg_data = ((uint8_t)odr & BMM350_ODR_MSK); + + /* AVG / performance is an enum taking the generated constants from the register map */ + reg_data = BMM350_SET_BITS(reg_data, BMM350_AVG, (uint8_t)performance_fix); + + /* Set PMU command configurations for ODR and performance */ + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD_AGGR_SET, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + /* Set PMU command configurations to update odr and average */ + reg_data = BMM350_PMU_CMD_UPD_OAE; + + /* Set PMU command configuration */ + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(BMM350_UPD_OAE_DELAY, dev); + } + } + } + + return rslt; +} + +/*! + * @brief This API is used to enable or disable the magnetic + * measurement of x,y,z axes + */ +int8_t bmm350_enable_axes(enum eBmm350XAxisEnDis_t en_x, + enum eBmm350YAxisEnDis_t en_y, + enum eBmm350ZAxisEnDis_t en_z, + struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Variable to store axis data */ + uint8_t data; + + /* Check for null pointer in the device structure */ + rslt = null_ptr_check(dev); + + if (rslt == BMM350_OK) + { + if ((en_x == BMM350_X_DIS) && (en_y == BMM350_Y_DIS) && (en_z == BMM350_Z_DIS)) + { + rslt = BMM350_E_ALL_AXIS_DISABLED; + + /* Assign axisEn with all axis disabled status */ + dev->axisEn = BMM350_DISABLE; + } + else + { + data = (en_x & BMM350_EN_X_MSK); + data = BMM350_SET_BITS(data, BMM350_EN_Y, en_y); + data = BMM350_SET_BITS(data, BMM350_EN_Z, en_z); + + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD_AXIS_EN, &data, 1, dev); + + if (rslt == BMM350_OK) + { + /* Assign axisEn with the axis selection done */ + dev->axisEn = data; + } + } + } + + return rslt; +} + +/*! + * @brief This API is used to enable or disable the data ready interrupt + */ +int8_t bmm350_enable_interrupt(enum eBmm350InterruptEnableDisable_t enable_disable, struct bmm350_dev *dev) +{ + /* Variable to get interrupt control configuration */ + uint8_t reg_data = 0; + + /* Variable to store the function result */ + int8_t rslt; + + /* Get interrupt control configuration */ + rslt = bmm350GetRegs(BMM350_REG_INT_CTRL, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + reg_data = BMM350_SET_BITS(reg_data, BMM350_DRDY_DATA_REG_EN, (uint8_t)enable_disable); + + /* Finally transfer the interrupt configurations */ + rslt = bmm350SetRegs(BMM350_REG_INT_CTRL, ®_data, 1, dev); + } + + return rslt; +} + +/*! + * @brief This API is used to configure the interrupt control settings + */ +int8_t bmm350_configure_interrupt(enum bmm350_intr_latch latching, + enum eBmm350IntrPolarity_t polarity, + enum bmm350_intr_drive drivertype, + enum bmm350_intr_map map_nomap, + struct bmm350_dev *dev) +{ + /* Variable to get interrupt control configuration */ + uint8_t reg_data = 0; + + /* Variable to store the function result */ + int8_t rslt; + + /* Get interrupt control configuration */ + rslt = bmm350GetRegs(BMM350_REG_INT_CTRL, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + reg_data = BMM350_SET_BITS_POS_0(reg_data, BMM350_INT_MODE, latching); + reg_data = BMM350_SET_BITS(reg_data, BMM350_INT_POL, polarity); + reg_data = BMM350_SET_BITS(reg_data, BMM350_INT_OD, drivertype); + reg_data = BMM350_SET_BITS(reg_data, BMM350_INT_OUTPUT_EN, map_nomap); + + /* Finally transfer the interrupt configurations */ + rslt = bmm350SetRegs(BMM350_REG_INT_CTRL, ®_data, 1, dev); + } + + return rslt; +} + +/*! + * @brief This API is used to read uncompensated mag and temperature data. + */ +int8_t bmm350_read_uncomp_mag_temp_data(struct bmm350_raw_mag_data *raw_data, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t mag_data[12] = { 0 }; + + uint32_t raw_mag_x, raw_mag_y, raw_mag_z, raw_temp; + + if (raw_data != NULL) + { + /* Get uncompensated mag data */ + rslt = bmm350GetRegs(BMM350_REG_MAG_X_XLSB, mag_data, BMM350_MAG_TEMP_DATA_LEN, dev); + + if (rslt == BMM350_OK) + { + raw_mag_x = mag_data[0] + ((uint32_t)mag_data[1] << 8) + ((uint32_t)mag_data[2] << 16); + raw_mag_y = mag_data[3] + ((uint32_t)mag_data[4] << 8) + ((uint32_t)mag_data[5] << 16); + raw_mag_z = mag_data[6] + ((uint32_t)mag_data[7] << 8) + ((uint32_t)mag_data[8] << 16); + raw_temp = mag_data[9] + ((uint32_t)mag_data[10] << 8) + ((uint32_t)mag_data[11] << 16); + + if ((dev->axisEn & BMM350_EN_X_MSK) == BMM350_DISABLE) + { + raw_data->raw_xdata = BMM350_DISABLE; + } + else + { + raw_data->raw_xdata = fix_sign(raw_mag_x, BMM350_SIGNED_24_BIT); + } + + if ((dev->axisEn & BMM350_EN_Y_MSK) == BMM350_DISABLE) + { + raw_data->raw_ydata = BMM350_DISABLE; + } + else + { + raw_data->raw_ydata = fix_sign(raw_mag_y, BMM350_SIGNED_24_BIT); + } + + if ((dev->axisEn & BMM350_EN_Z_MSK) == BMM350_DISABLE) + { + raw_data->raw_zdata = BMM350_DISABLE; + } + else + { + raw_data->raw_zdata = fix_sign(raw_mag_z, BMM350_SIGNED_24_BIT); + } + + raw_data->raw_data_t = fix_sign(raw_temp, BMM350_SIGNED_24_BIT); + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This API sets the interrupt control IBI configurations to the sensor. + */ +int8_t bmm350_set_int_ctrl_ibi(enum bmm350_drdy_int_map_to_ibi en_dis, + enum bmm350_clear_drdy_int_status_upon_ibi clear_on_ibi, + struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Variable to get interrupt control configuration */ + uint8_t reg_data = 0; + + /* Get interrupt control configuration */ + rslt = bmm350GetRegs(BMM350_REG_INT_CTRL_IBI, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + reg_data = BMM350_SET_BITS_POS_0(reg_data, BMM350_DRDY_INT_MAP_TO_IBI, en_dis); + reg_data = BMM350_SET_BITS(reg_data, BMM350_CLEAR_DRDY_INT_STATUS_UPON_IBI, clear_on_ibi); + + /* Set the IBI control configuration */ + rslt = bmm350SetRegs(BMM350_REG_INT_CTRL_IBI, ®_data, 1, dev); + + if (en_dis == BMM350_IBI_ENABLE) + { + /* Enable data ready interrupt if IBI is enabled */ + rslt = bmm350_enable_interrupt(BMM350_ENABLE_INTERRUPT, dev); + } + } + + return rslt; +} + +/*! + * @brief This API is used to set the pad drive strength + */ +int8_t bmm350_set_pad_drive(uint8_t drive, struct bmm350_dev *dev) +{ + uint8_t reg_data; + + /* Variable to store the function result */ + int8_t rslt = BMM350_E_BAD_PAD_DRIVE; + + if (drive <= BMM350_PAD_DRIVE_STRONGEST) + { + reg_data = drive & BMM350_DRV_MSK; + + /* Set drive */ + rslt = bmm350SetRegs(BMM350_REG_PAD_CTRL, ®_data, 1, dev); + } + + return rslt; +} + +/*! + * @brief This API is used to perform the magnetic reset of the sensor + * which is necessary after a field shock (400mT field applied to sensor). + * It sends flux guide or bit reset to the device in suspend mode. + */ +int8_t bmm350_magnetic_reset_and_wait(struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t pmu_cmd = 0; + struct bmm350_pmu_cmd_status_0 pmu_cmd_stat_0 = { 0 }; + uint8_t restore_normal = BMM350_DISABLE; + + rslt = null_ptr_check(dev); + + if ((rslt == BMM350_OK) && (dev->mraw_override) && (dev->var_id >= BMM350_MIN_VAR)) + { + rslt = dev->mraw_override(dev); + } + else + { + /* Read PMU CMD status */ + rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); + + /* Check the powermode is normal before performing magnetic reset */ + if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pwr_mode_is_normal == BMM350_ENABLE)) + { + restore_normal = BMM350_ENABLE; + + /* Reset can only be triggered in suspend */ + rslt = bmm350SetPowerMode(eBmm350SuspendMode, dev); + } + + if (rslt == BMM350_OK) + { + /* Set BR to PMU_CMD register */ + pmu_cmd = BMM350_PMU_CMD_BR; + + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(BMM350_BR_DELAY, dev); + } + } + + if (rslt == BMM350_OK) + { + /* Verify if PMU_CMD_STATUS_0 register has BR set */ + rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); + + if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value != BMM350_PMU_CMD_STATUS_0_BR)) + { + rslt = BMM350_E_PMU_CMD_VALUE; + } + } + + if (rslt == BMM350_OK) + { + /* Set FGR to PMU_CMD register */ + pmu_cmd = BMM350_PMU_CMD_FGR; + + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(BMM350_FGR_DELAY, dev); + } + } + + if (rslt == BMM350_OK) + { + /* Verify if PMU_CMD_STATUS_0 register has FGR set */ + rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); + + if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value != BMM350_PMU_CMD_STATUS_0_FGR)) + { + rslt = BMM350_E_PMU_CMD_VALUE; + } + } + + if ((rslt == BMM350_OK) && (restore_normal == BMM350_ENABLE)) + { + rslt = bmm350SetPowerMode(eBmm350NormalMode, dev); + } + } + + return rslt; +} + +/*! + * @brief This API is used to perform compensation for raw magnetometer and temperature data. + */ +int8_t bmm350GetCompensatedMagXYZTempData(struct sBmm350MagTempData_t *mag_temp_data, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t indx; + float out_data[4] = { 0.0f }; + float dut_offset_coef[3], dut_sensit_coef[3], dut_tco[3], dut_tcs[3]; + float cr_ax_comp_x, cr_ax_comp_y, cr_ax_comp_z; + + if (mag_temp_data != NULL) + { + /* Reads raw magnetic x,y and z axis along with temperature */ + rslt = read_out_raw_data(out_data, dev); + + if (rslt == BMM350_OK) + { + /* Apply compensation to temperature reading */ + out_data[3] = (1 + dev->mag_comp.dut_sensit_coef.t_sens) * out_data[3] + + dev->mag_comp.dut_offset_coef.t_offs; + + /* Store magnetic compensation structure to an array */ + dut_offset_coef[0] = dev->mag_comp.dut_offset_coef.offset_x; + dut_offset_coef[1] = dev->mag_comp.dut_offset_coef.offset_y; + dut_offset_coef[2] = dev->mag_comp.dut_offset_coef.offset_z; + + dut_sensit_coef[0] = dev->mag_comp.dut_sensit_coef.sens_x; + dut_sensit_coef[1] = dev->mag_comp.dut_sensit_coef.sens_y; + dut_sensit_coef[2] = dev->mag_comp.dut_sensit_coef.sens_z; + + dut_tco[0] = dev->mag_comp.dut_tco.tco_x; + dut_tco[1] = dev->mag_comp.dut_tco.tco_y; + dut_tco[2] = dev->mag_comp.dut_tco.tco_z; + + dut_tcs[0] = dev->mag_comp.dut_tcs.tcs_x; + dut_tcs[1] = dev->mag_comp.dut_tcs.tcs_y; + dut_tcs[2] = dev->mag_comp.dut_tcs.tcs_z; + + /* Compensate raw magnetic data */ + for (indx = 0; indx < 3; indx++) + { + out_data[indx] *= 1 + dut_sensit_coef[indx]; + out_data[indx] += dut_offset_coef[indx]; + out_data[indx] += dut_tco[indx] * (out_data[3] - dev->mag_comp.dut_t0); + out_data[indx] /= 1 + dut_tcs[indx] * (out_data[3] - dev->mag_comp.dut_t0); + } + + cr_ax_comp_x = (out_data[0] - dev->mag_comp.cross_axis.cross_x_y * out_data[1]) / + (1 - dev->mag_comp.cross_axis.cross_y_x * dev->mag_comp.cross_axis.cross_x_y); + cr_ax_comp_y = (out_data[1] - dev->mag_comp.cross_axis.cross_y_x * out_data[0]) / + (1 - dev->mag_comp.cross_axis.cross_y_x * dev->mag_comp.cross_axis.cross_x_y); + cr_ax_comp_z = + (out_data[2] + + (out_data[0] * + (dev->mag_comp.cross_axis.cross_y_x * dev->mag_comp.cross_axis.cross_z_y - + dev->mag_comp.cross_axis.cross_z_x) - out_data[1] * + (dev->mag_comp.cross_axis.cross_z_y - dev->mag_comp.cross_axis.cross_x_y * + dev->mag_comp.cross_axis.cross_z_x)) / + (1 - dev->mag_comp.cross_axis.cross_y_x * dev->mag_comp.cross_axis.cross_x_y)); + + out_data[0] = cr_ax_comp_x; + out_data[1] = cr_ax_comp_y; + out_data[2] = cr_ax_comp_z; + } + + if (rslt == BMM350_OK) + { + if ((dev->axisEn & BMM350_EN_X_MSK) == BMM350_DISABLE) + { + mag_temp_data->x = BMM350_DISABLE; + } + else + { + mag_temp_data->x = out_data[0]; + } + + if ((dev->axisEn & BMM350_EN_Y_MSK) == BMM350_DISABLE) + { + mag_temp_data->y = BMM350_DISABLE; + } + else + { + mag_temp_data->y = out_data[1]; + } + + if ((dev->axisEn & BMM350_EN_Z_MSK) == BMM350_DISABLE) + { + mag_temp_data->z = BMM350_DISABLE; + } + else + { + mag_temp_data->z = out_data[2]; + } + + mag_temp_data->temperature = out_data[3]; + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This function executes FGR and BR sequences to initialize TMR sensor and performs the user self-test. + */ +int8_t bmm350PerformSelfTest(struct sBmm350SelfTest_t *out_data, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Variable to store last powermode */ + uint8_t last_pwr_mode; + + if (out_data != NULL) + { + rslt = bmm350GetRegs(BMM350_REG_PMU_CMD, &last_pwr_mode, 1, dev); + + if (rslt == BMM350_OK) + { + /* Self-test entry configuration */ + rslt = self_test_entry_config(dev); + + if (rslt == BMM350_OK) + { + /* Updates self-test values to structure */ + rslt = self_test_xy_axis(out_data, dev); + } + } + + if (rslt == BMM350_OK) + { + /* Setup DUT: disable user self-test */ + rslt = bmm350_set_tmr_selftest_user(BMM350_ST_IGEN_DIS, + BMM350_ST_N_DIS, + BMM350_ST_P_DIS, + BMM350_IST_X_DIS, + BMM350_IST_Y_DIS, + dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(1000, dev); + } + + if (last_pwr_mode == BMM350_PMU_CMD_NM) + { + rslt = bmm350SetPowerMode(eBmm350NormalMode, dev); + } + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This API sets the I2C watchdog timer configurations to the sensor. + */ +int8_t bmm350_set_i2c_wdt(enum bmm350_i2c_wdt_en i2c_wdt_en_dis, + enum bmm350_i2c_wdt_sel i2c_wdt_sel, + struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t reg_data; + + /* Get I2C WDT configuration */ + rslt = bmm350GetRegs(BMM350_REG_I2C_WDT_SET, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + reg_data = BMM350_SET_BITS_POS_0(reg_data, BMM350_I2C_WDT_EN, i2c_wdt_en_dis); + reg_data = BMM350_SET_BITS(reg_data, BMM350_I2C_WDT_SEL, i2c_wdt_sel); + + /* Set I2C WDT configuration */ + rslt = bmm350SetRegs(BMM350_REG_I2C_WDT_SET, ®_data, 1, dev); + } + + return rslt; +} + +/*! + * @brief This API sets the TMR user self-test register + */ +int8_t bmm350_set_tmr_selftest_user(enum bmm350_st_igen_en st_igen_en_dis, + enum bmm350_st_n st_n_en_dis, + enum bmm350_st_p st_p_en_dis, + enum bmm350_ist_en_x ist_x_en_dis, + enum bmm350_ist_en_y ist_y_en_dis, + struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t reg_data; + + /* Get TMR self-test user configuration */ + rslt = bmm350GetRegs(BMM350_REG_TMR_SELFTEST_USER, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + reg_data = BMM350_SET_BITS_POS_0(reg_data, BMM350_ST_IGEN_EN, st_igen_en_dis); + reg_data = BMM350_SET_BITS(reg_data, BMM350_ST_N, st_n_en_dis); + reg_data = BMM350_SET_BITS(reg_data, BMM350_ST_P, st_p_en_dis); + reg_data = BMM350_SET_BITS(reg_data, BMM350_IST_EN_X, ist_x_en_dis); + reg_data = BMM350_SET_BITS(reg_data, BMM350_IST_EN_Y, ist_y_en_dis); + + /* Set TMR self-test user configuration */ + rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, ®_data, 1, dev); + } + + return rslt; +} + +/*! + * @brief This API sets the control user configurations to the sensor which forces the sensor timer to be always + * running, even in suspend mode. + */ +int8_t bmm350_set_ctrl_user(enum bmm350_ctrl_user cfg_sens_tim_aon_en_dis, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t reg_data; + + /* Get control user configuration */ + rslt = bmm350GetRegs(BMM350_REG_CTRL_USER, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + reg_data = BMM350_SET_BITS_POS_0(reg_data, BMM350_CFG_SENS_TIM_AON, cfg_sens_tim_aon_en_dis); + + /* Set control user configuration */ + rslt = bmm350SetRegs(BMM350_REG_CTRL_USER, ®_data, 1, dev); + } + + return rslt; +} + +/*! + * @brief This API gets the PMU command status 0 value + */ +int8_t bmm350_get_pmu_cmd_status_0(struct bmm350_pmu_cmd_status_0 *pmu_cmd_stat_0, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t reg_data; + + if (pmu_cmd_stat_0 != NULL) + { + /* Get PMU command status 0 data */ + rslt = bmm350GetRegs(BMM350_REG_PMU_CMD_STATUS_0, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + pmu_cmd_stat_0->pmu_cmd_busy = BMM350_GET_BITS_POS_0(reg_data, BMM350_PMU_CMD_BUSY); + + pmu_cmd_stat_0->odr_ovwr = BMM350_GET_BITS(reg_data, BMM350_ODR_OVWR); + + pmu_cmd_stat_0->avr_ovwr = BMM350_GET_BITS(reg_data, BMM350_AVG_OVWR); + + pmu_cmd_stat_0->pwr_mode_is_normal = BMM350_GET_BITS(reg_data, BMM350_PWR_MODE_IS_NORMAL); + + pmu_cmd_stat_0->cmd_is_illegal = BMM350_GET_BITS(reg_data, BMM350_CMD_IS_ILLEGAL); + + pmu_cmd_stat_0->pmu_cmd_value = BMM350_GET_BITS(reg_data, BMM350_PMU_CMD_VALUE); + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/****************************************************************************/ +/**\name INTERNAL APIs */ + +/*! + * @brief This internal API is used to validate the device structure pointer for + * null conditions. + */ +static int8_t null_ptr_check(const struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + if ((dev == NULL) || (dev->read == NULL) || (dev->write == NULL) || (dev->delayUs == NULL)) + { + /* Device structure pointer is not valid */ + rslt = BMM350_E_NULL_PTR; + } + else + { + /* Device structure is fine */ + rslt = BMM350_OK; + } + + return rslt; +} + +/*! + * @brief This internal API converts the raw data from the IC data registers to signed integer + */ +static int32_t fix_sign(uint32_t inval, int8_t number_of_bits) +{ + int32_t power = 0; + int32_t retval; + + switch (number_of_bits) + { + case BMM350_SIGNED_8_BIT: + power = 128; /* 2^7 */ + break; + + case BMM350_SIGNED_12_BIT: + power = 2048; /* 2^11 */ + break; + + case BMM350_SIGNED_16_BIT: + power = 32768; /* 2^15 */ + break; + + case BMM350_SIGNED_21_BIT: + power = 1048576; /* 2^20 */ + break; + + case BMM350_SIGNED_24_BIT: + power = 8388608; /* 2^23 */ + break; + + default: + power = 0; + break; + } + + retval = (int32_t)inval; + + if (retval >= power) + { + retval = retval - (power * 2); + } + + return retval; +} + +/*! + * @brief This internal API is used to read OTP word + */ +static int8_t read_otp_word(uint8_t addr, uint16_t *lsb_msb, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t otp_cmd, otp_status = 0, otp_err = BMM350_OTP_STATUS_NO_ERROR, lsb = 0, msb = 0; + + if (lsb_msb != NULL) + { + /* Set OTP command at specified address */ + otp_cmd = BMM350_OTP_CMD_DIR_READ | (addr & BMM350_OTP_WORD_ADDR_MSK); + rslt = bmm350SetRegs(BMM350_REG_OTP_CMD_REG, &otp_cmd, 1, dev); + if (rslt == BMM350_OK) + { + do + { + rslt = bmm350DelayUs(300, dev); + + if (rslt == BMM350_OK) + { + /* Get OTP status */ + rslt = bmm350GetRegs(BMM350_REG_OTP_STATUS_REG, &otp_status, 1, dev); + + otp_err = BMM350_OTP_STATUS_ERROR(otp_status); + if (otp_err != BMM350_OTP_STATUS_NO_ERROR) + { + break; + } + } + } while ((!(otp_status & BMM350_OTP_STATUS_CMD_DONE)) && (rslt == BMM350_OK)); + + if (otp_err != BMM350_OTP_STATUS_NO_ERROR) + { + switch (otp_err) + { + case BMM350_OTP_STATUS_BOOT_ERR: + rslt = BMM350_E_OTP_BOOT; + break; + case BMM350_OTP_STATUS_PAGE_RD_ERR: + rslt = BMM350_E_OTP_PAGE_RD; + break; + case BMM350_OTP_STATUS_PAGE_PRG_ERR: + rslt = BMM350_E_OTP_PAGE_PRG; + break; + case BMM350_OTP_STATUS_SIGN_ERR: + rslt = BMM350_E_OTP_SIGN; + break; + case BMM350_OTP_STATUS_INV_CMD_ERR: + rslt = BMM350_E_OTP_INV_CMD; + break; + default: + rslt = BMM350_E_OTP_UNDEFINED; + break; + } + } + } + + if (rslt == BMM350_OK) + { + /* Get OTP MSB data */ + rslt = bmm350GetRegs(BMM350_REG_OTP_DATA_MSB_REG, &msb, 1, dev); + if (rslt == BMM350_OK) + { + /* Get OTP LSB data */ + rslt = bmm350GetRegs(BMM350_REG_OTP_DATA_LSB_REG, &lsb, 1, dev); + *lsb_msb = ((uint16_t)(msb << 8) | lsb) & 0xFFFF; + } + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This internal API is used to update magnetometer offset and sensitivity data. + */ +static void update_mag_off_sens(struct bmm350_dev *dev) +{ + uint16_t off_x_lsb_msb, off_y_lsb_msb, off_z_lsb_msb, t_off; + uint8_t sens_x, sens_y, sens_z, t_sens; + uint8_t tco_x, tco_y, tco_z; + uint8_t tcs_x, tcs_y, tcs_z; + uint8_t cross_x_y, cross_y_x, cross_z_x, cross_z_y; + + off_x_lsb_msb = dev->otp_data[BMM350_MAG_OFFSET_X] & 0x0FFF; + off_y_lsb_msb = ((dev->otp_data[BMM350_MAG_OFFSET_X] & 0xF000) >> 4) + + (dev->otp_data[BMM350_MAG_OFFSET_Y] & BMM350_LSB_MASK); + off_z_lsb_msb = (dev->otp_data[BMM350_MAG_OFFSET_Y] & 0x0F00) + + (dev->otp_data[BMM350_MAG_OFFSET_Z] & BMM350_LSB_MASK); + t_off = dev->otp_data[BMM350_TEMP_OFF_SENS] & BMM350_LSB_MASK; + + dev->mag_comp.dut_offset_coef.offset_x = fix_sign(off_x_lsb_msb, BMM350_SIGNED_12_BIT); + dev->mag_comp.dut_offset_coef.offset_y = fix_sign(off_y_lsb_msb, BMM350_SIGNED_12_BIT); + dev->mag_comp.dut_offset_coef.offset_z = fix_sign(off_z_lsb_msb, BMM350_SIGNED_12_BIT); + dev->mag_comp.dut_offset_coef.t_offs = fix_sign(t_off, BMM350_SIGNED_8_BIT) / 5.0f; + + sens_x = (dev->otp_data[BMM350_MAG_SENS_X] & BMM350_MSB_MASK) >> 8; + sens_y = (dev->otp_data[BMM350_MAG_SENS_Y] & BMM350_LSB_MASK); + sens_z = (dev->otp_data[BMM350_MAG_SENS_Z] & BMM350_MSB_MASK) >> 8; + t_sens = (dev->otp_data[BMM350_TEMP_OFF_SENS] & BMM350_MSB_MASK) >> 8; + + dev->mag_comp.dut_sensit_coef.sens_x = fix_sign(sens_x, BMM350_SIGNED_8_BIT) / 256.0f; + dev->mag_comp.dut_sensit_coef.sens_y = (fix_sign(sens_y, BMM350_SIGNED_8_BIT) / 256.0f) + BMM350_SENS_CORR_Y; + dev->mag_comp.dut_sensit_coef.sens_z = fix_sign(sens_z, BMM350_SIGNED_8_BIT) / 256.0f; + dev->mag_comp.dut_sensit_coef.t_sens = fix_sign(t_sens, BMM350_SIGNED_8_BIT) / 512.0f; + + tco_x = (dev->otp_data[BMM350_MAG_TCO_X] & BMM350_LSB_MASK); + tco_y = (dev->otp_data[BMM350_MAG_TCO_Y] & BMM350_LSB_MASK); + tco_z = (dev->otp_data[BMM350_MAG_TCO_Z] & BMM350_LSB_MASK); + + dev->mag_comp.dut_tco.tco_x = fix_sign(tco_x, BMM350_SIGNED_8_BIT) / 32.0f; + dev->mag_comp.dut_tco.tco_y = fix_sign(tco_y, BMM350_SIGNED_8_BIT) / 32.0f; + dev->mag_comp.dut_tco.tco_z = fix_sign(tco_z, BMM350_SIGNED_8_BIT) / 32.0f; + + tcs_x = (dev->otp_data[BMM350_MAG_TCS_X] & BMM350_MSB_MASK) >> 8; + tcs_y = (dev->otp_data[BMM350_MAG_TCS_Y] & BMM350_MSB_MASK) >> 8; + tcs_z = (dev->otp_data[BMM350_MAG_TCS_Z] & BMM350_MSB_MASK) >> 8; + + dev->mag_comp.dut_tcs.tcs_x = fix_sign(tcs_x, BMM350_SIGNED_8_BIT) / 16384.0f; + dev->mag_comp.dut_tcs.tcs_y = fix_sign(tcs_y, BMM350_SIGNED_8_BIT) / 16384.0f; + dev->mag_comp.dut_tcs.tcs_z = (fix_sign(tcs_z, BMM350_SIGNED_8_BIT) / 16384.0f) - BMM350_TCS_CORR_Z; + + dev->mag_comp.dut_t0 = (fix_sign(dev->otp_data[BMM350_MAG_DUT_T_0], BMM350_SIGNED_16_BIT) / 512.0f) + 23.0f; + + cross_x_y = (dev->otp_data[BMM350_CROSS_X_Y] & BMM350_LSB_MASK); + cross_y_x = (dev->otp_data[BMM350_CROSS_Y_X] & BMM350_MSB_MASK) >> 8; + cross_z_x = (dev->otp_data[BMM350_CROSS_Z_X] & BMM350_LSB_MASK); + cross_z_y = (dev->otp_data[BMM350_CROSS_Z_Y] & BMM350_MSB_MASK) >> 8; + + dev->mag_comp.cross_axis.cross_x_y = fix_sign(cross_x_y, BMM350_SIGNED_8_BIT) / 800.0f; + dev->mag_comp.cross_axis.cross_y_x = fix_sign(cross_y_x, BMM350_SIGNED_8_BIT) / 800.0f; + dev->mag_comp.cross_axis.cross_z_x = fix_sign(cross_z_x, BMM350_SIGNED_8_BIT) / 800.0f; + dev->mag_comp.cross_axis.cross_z_y = fix_sign(cross_z_y, BMM350_SIGNED_8_BIT) / 800.0f; +} + +/*! + * @brief This internal API is used to read raw magnetic x,y and z axis along with temperature + */ +static int8_t read_out_raw_data(float *out_data, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + float temp = 0.0; + struct bmm350_raw_mag_data raw_data = { 0 }; + + /* Float variable to convert mag lsb to uT and temp lsb to degC */ + float lsb_to_ut_degc[4]; + + if (out_data != NULL) + { + rslt = bmm350_read_uncomp_mag_temp_data(&raw_data, dev); + + if (rslt == BMM350_OK) + { + /* Convert mag lsb to uT and temp lsb to degC */ + update_default_coefiecents(lsb_to_ut_degc); + + out_data[0] = (float)raw_data.raw_xdata * lsb_to_ut_degc[0]; + out_data[1] = (float)raw_data.raw_ydata * lsb_to_ut_degc[1]; + out_data[2] = (float)raw_data.raw_zdata * lsb_to_ut_degc[2]; + out_data[3] = (float)raw_data.raw_data_t * lsb_to_ut_degc[3]; + + if (out_data[3] > 0.0) + { + temp = (float)(out_data[3] - (1 * 25.49)); + } + else if (out_data[3] < 0.0) + { + temp = (float)(out_data[3] - (-1 * 25.49)); + } + else + { + temp = (float)(out_data[3]); + } + + out_data[3] = temp; + } + } + else + { + rslt = BMM350_E_NULL_PTR; + } + + return rslt; +} + +/*! + * @brief This internal API is used to convert lsb to uT and degC. + */ +static void update_default_coefiecents(float *lsb_to_ut_degc) +{ + float bxy_sens, bz_sens, temp_sens, ina_xy_gain_trgt, ina_z_gain_trgt, adc_gain, lut_gain; + float power; + + bxy_sens = 14.55f; + bz_sens = 9.0f; + temp_sens = 0.00204f; + + ina_xy_gain_trgt = 19.46f; + + ina_z_gain_trgt = 31.0; + + adc_gain = 1 / 1.5f; + lut_gain = 0.714607238769531f; + + power = (float)(1000000.0 / 1048576.0); + + lsb_to_ut_degc[0] = (power / (bxy_sens * ina_xy_gain_trgt * adc_gain * lut_gain)); + lsb_to_ut_degc[1] = (power / (bxy_sens * ina_xy_gain_trgt * adc_gain * lut_gain)); + lsb_to_ut_degc[2] = (power / (bz_sens * ina_z_gain_trgt * adc_gain * lut_gain)); + lsb_to_ut_degc[3] = 1 / (temp_sens * adc_gain * lut_gain * 1048576); +} + +/*! + * @brief This internal API is used to read OTP data after boot in user mode. + */ +static int8_t otp_dump_after_boot(struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint16_t otp_word = 0; + uint8_t indx; + + for (indx = 0; indx < BMM350_OTP_DATA_LENGTH; indx++) + { + rslt = read_otp_word(indx, &otp_word, dev); + dev->otp_data[indx] = otp_word; + } + + dev->var_id = (dev->otp_data[30] & 0x7f00) >> 9; + + /* Update magnetometer offset and sensitivity data. */ + update_mag_off_sens(dev); + + return rslt; +} + +/*! + * @brief This internal API is used for self-test entry configuration + */ +static int8_t self_test_entry_config(struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Variable to store PMU command */ + uint8_t cmd; + + /* Structure instance of PMU command status 0 */ + struct bmm350_pmu_cmd_status_0 pmu_cmd_stat_0 = { 0 }; + + /* Set suspend mode */ + cmd = BMM350_PMU_CMD_SUS; + + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(30000, dev); + } + + /* Read DUT outputs in FORCED mode */ + if (rslt == BMM350_OK) + { + rslt = bmm350SetOdrPerformance(BMM350_DATA_RATE_100HZ, BMM350_AVERAGING_2, dev); + + if (rslt == BMM350_OK) + { + /* Enable all axis */ + rslt = bmm350_enable_axes(BMM350_X_EN, BMM350_Y_EN, BMM350_Z_EN, dev); + } + } + + /* Execute FGR with full CRST recharge */ + cmd = BMM350_PMU_CMD_FGR; + + if (rslt == BMM350_OK) + { + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(30000, dev); + } + } + + if (rslt == BMM350_OK) + { + rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); + + if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value == BMM350_PMU_CMD_STATUS_0_FGR)) + { + /* Execute BR with full CRST recharge */ + cmd = BMM350_PMU_CMD_BR_FAST; + + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(4000, dev); + } + } + } + + if (rslt == BMM350_OK) + { + rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); + } + + if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value == BMM350_PMU_CMD_STATUS_0_BR_FAST)) + { + cmd = BMM350_PMU_CMD_FM_FAST; + + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(16000, dev); + } + + if (rslt == BMM350_OK) + { + rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); + + if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value == BMM350_PMU_CMD_STATUS_0_FM_FAST)) + { + rslt = bmm350DelayUs(10, dev); + } + } + } + + return rslt; +} + +/*! + * @brief This internal API is used to test self-test for X and Y axis + */ +static int8_t self_test_xy_axis(struct sBmm350SelfTest_t *out_data, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + /* Set pmu command */ + uint8_t cmd = BMM350_PMU_CMD_FM_FAST; + + /* Setup DUT: enable positive user self-test on x-axis */ + rslt = self_test_config(BMM350_SELF_TEST_POS_X, cmd, out_data, dev); + + if (rslt == BMM350_OK) + { + /* Setup DUT: enable negative user self-test on x-axis */ + rslt = self_test_config(BMM350_SELF_TEST_NEG_X, cmd, out_data, dev); + + if (rslt == BMM350_OK) + { + /* Setup DUT: enable positive user self-test on y-axis */ + rslt = self_test_config(BMM350_SELF_TEST_POS_Y, cmd, out_data, dev); + + if (rslt == BMM350_OK) + { + /* Setup DUT: enable negative user self-test on y-axis */ + rslt = self_test_config(BMM350_SELF_TEST_NEG_Y, cmd, out_data, dev); + } + } + } + + return rslt; +} + +/*! + * @brief This internal API is used to set self-test configurations. + */ +static int8_t self_test_config(uint8_t st_cmd, + uint8_t pmu_cmd, + struct sBmm350SelfTest_t *out_data, + struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + float out_ust[4]; + + struct bmm350_pmu_cmd_status_0 pmu_cmd_stat_0 = { 0 }; + + static float out_ustxh = 0.0, out_ustxl = 0.0, out_ustyh = 0.0, out_ustyl = 0.0; + + rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, &st_cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(1000, dev); + } + + if (rslt == BMM350_OK) + { + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350DelayUs(6000, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); + } + } + } + + if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value == BMM350_PMU_CMD_STATUS_0_FM_FAST)) + { + /* Reads raw magnetic x and y axis */ + rslt = read_out_raw_data(out_ust, dev); + + if (rslt == BMM350_OK) + { + /* Read DUT outputs in FORCED mode (XP_UST) */ + if (st_cmd == BMM350_SELF_TEST_POS_X) + { + out_ustxh = out_ust[0]; + } + /* Read DUT outputs in FORCED mode (XN_UST) */ + else if (st_cmd == BMM350_SELF_TEST_NEG_X) + { + out_ustxl = out_ust[0]; + } + /* Read DUT outputs in FORCED mode (YP_UST) */ + else if (st_cmd == BMM350_SELF_TEST_POS_Y) + { + out_ustyh = out_ust[1]; + } + /* Read DUT outputs in FORCED mode (YN_UST) */ + else if (st_cmd == BMM350_SELF_TEST_NEG_Y) + { + out_ustyl = out_ust[1]; + } + else + { + /* Returns error if self-test axis is wrong */ + rslt = BMM350_E_SELF_TEST_INVALID_AXIS; + } + + if (rslt == BMM350_OK) + { + out_data->out_ust_x = out_ustxh - out_ustxl; + out_data->out_ust_y = out_ustyh - out_ustyl; + } + } + } + + return rslt; +} + +/*! + * @brief This internal API is used to switch from suspend mode to normal mode or forced mode. + */ +static int8_t set_powermode(enum eBmm350PowerModes_t powermode, struct bmm350_dev *dev) +{ + /* Variable to store the function result */ + int8_t rslt; + + uint8_t reg_data = powermode; + uint8_t get_avg; + + /* Array to store suspend to forced mode delay */ + uint32_t sus_to_forced_mode[4] = + { BMM350_SUS_TO_FORCEDMODE_NO_AVG_DELAY, BMM350_SUS_TO_FORCEDMODE_AVG_2_DELAY, BMM350_SUS_TO_FORCEDMODE_AVG_4_DELAY, + BMM350_SUS_TO_FORCEDMODE_AVG_8_DELAY }; + + /* Array to store suspend to forced mode fast delay */ + uint32_t sus_to_forced_mode_fast[4] = + { BMM350_SUS_TO_FORCEDMODE_FAST_NO_AVG_DELAY, BMM350_SUS_TO_FORCEDMODE_FAST_AVG_2_DELAY, + BMM350_SUS_TO_FORCEDMODE_FAST_AVG_4_DELAY, BMM350_SUS_TO_FORCEDMODE_FAST_AVG_8_DELAY }; + + uint8_t avg = 0; + uint32_t delay_us = 0; + + rslt = null_ptr_check(dev); + + if (rslt == BMM350_OK) + { + /* Set PMU command configuration to desired power mode */ + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, ®_data, 1, dev); + + if (rslt == BMM350_OK) + { + /* Get average configuration */ + rslt = bmm350GetRegs(BMM350_REG_PMU_CMD_AGGR_SET, &get_avg, 1, dev); + + if (rslt == BMM350_OK) + { + /* Mask the average value */ + avg = ((get_avg & BMM350_AVG_MSK) >> BMM350_AVG_POS); + } + } + } + + if (rslt == BMM350_OK) + { + /* Check if desired power mode is normal mode */ + if (powermode == eBmm350NormalMode) + { + delay_us = BMM350_SUSPEND_TO_NORMAL_DELAY; + } + + /* Check if desired power mode is forced mode */ + if (powermode == eBmm350ForcedMode) + { + /* Store delay based on averaging mode */ + delay_us = sus_to_forced_mode[avg]; + } + + /* Check if desired power mode is forced mode fast */ + if (powermode == eBmm350ForcedModeFast) + { + /* Store delay based on averaging mode */ + delay_us = sus_to_forced_mode_fast[avg]; + } + + /* Perform delay based on power mode */ + rslt = bmm350DelayUs(delay_us, dev); + } + + return rslt; +} diff --git a/lib/DFRobot_BMM350/src/bmm350.h b/lib/DFRobot_BMM350/src/bmm350.h new file mode 100644 index 0000000..e1653fe --- /dev/null +++ b/lib/DFRobot_BMM350/src/bmm350.h @@ -0,0 +1,595 @@ +/** +* Copyright (c) 2023 Bosch Sensortec GmbH. All rights reserved. +* +* BSD-3-Clause +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* 1. Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* +* 2. Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the distribution. +* +* 3. Neither the name of the copyright holder nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, +* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING +* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* @file bmm350.h +* @date 2023-05-26 +* @version v1.4.0 +* +*/ + +/*! + * @defgroup bmm350 BMM350 + * @brief Sensor driver for BMM350 sensor + */ + +#ifndef _BMM350_H +#define _BMM350_H + +/*! CPP guard */ +#ifdef __cplusplus +extern "C" { +#endif + +/*************************** Header files *******************************/ + +#include "bmm350_defs.h" + +/******************* Function prototype declarations ********************/ + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiInit Initialization + * @brief Initialize the sensor and device structure + */ + +/*! +* \ingroup bmm350ApiInit +* \page bmm350_api_bmm350Init bmm350Init +* \code +* int8_t bmm350Init(struct bmm350_dev *dev); +* \endcode +* @details This API is the entry point. Call this API before using other APIs. +* This API reads the chip-id of the sensor which is the first step to +* verify the sensor and also it configures the read mechanism of I2C and +* I3C interface. +* +* @param[in,out] dev : Structure instance of bmm350_dev +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350Init(struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiReset Reset + * @brief Reset APIs + */ + +/*! +* \ingroup bmm350ApiReset +* \page bmm350_api_bmm350SoftReset bmm350SoftReset +* \code +* int8_t bmm350SoftReset(struct bmm350_dev *dev); +* \endcode +* @details This API is used to perform soft-reset of the sensor +* where all the registers are reset to their default values. +* +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ + +int8_t bmm350SoftReset(struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiSetGet Set-Get + * @brief Set and Get APIs + */ + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350SetRegs bmm350SetRegs +* \code +* int8_t bmm350SetRegs(uint8_t reg_addr, const uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev); +* \endcode +* @details This API writes the given data to the register address +* of the sensor. +* +* @param[in] reg_addr : Register address from where the data to be written. +* @param[in] reg_data : Pointer to data buffer which is to be written +* in the reg_addr of sensor. +* @param[in] len : No of bytes of data to write.. +* @param[in, out] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350SetRegs(uint8_t reg_addr, const uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350GetRegs bmm350GetRegs +* \code +* int8_t bmm350GetRegs(uint8_t reg_addr, uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev); +* \endcode +* @details This API reads the data from the given register address of sensor. +* +* @param[in] reg_addr : Register address from where the data to be read +* @param[out] reg_data : Pointer to data buffer to store the read data. +* @param[in] len : No of bytes of data to be read. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350GetRegs(uint8_t reg_addr, uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiDelay Delay + * @brief Delay function in microseconds + */ + +/*! +* \ingroup bmm350ApiDelay +* \page bmm350_api_bmm350DelayUs bmm350DelayUs +* \code +* int8_t bmm350DelayUs(uint32_t period_us, const struct bmm350_dev *dev); +* \endcode +* @details This function provides the delay for required time (Microsecond) as per the input provided in some of the +* APIs. +* +* @param[in] period_us : The required wait time in microsecond. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350DelayUs(uint32_t period_us, const struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350GetInterruptStatus bmm350GetInterruptStatus +* \code +* int8_t bmm350GetInterruptStatus(uint8_t *drdy_status, struct bmm350_dev *dev); +* \endcode +* @details This API obtains the status flags of all interrupt +* which is used to check for the assertion of interrupts +* +* @param[in,out] drdy_status : Variable to store data ready interrupt status. +* @param[in,out] dev : Structure instance of bmm350_dev. +* +* +* @return Result of API execution status and self test result. +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350GetInterruptStatus(uint8_t *drdy_status, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350SetPowerMode bmm350SetPowerMode +* \code +* int8_t bmm350SetPowerMode(enum eBmm350PowerModes_t powermode, struct bmm350_dev *dev); +* \endcode +* @details This API is used to set the power mode of the sensor +* +* @param[in] powermode : Set power mode +* @param[in] dev : Structure instance of bmm350_dev. +* +*@verbatim + powermode | Power mode + -------------------------|----------------------- + | eBmm350SuspendMode + | eBmm350NormalMode + | eBmm350ForcedMode + | eBmm350ForcedModeFast +*@endverbatim +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350SetPowerMode(enum eBmm350PowerModes_t powermode, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350SetOdrPerformance bmm350SetOdrPerformance +* \code +* int8_t bmm350SetOdrPerformance(enum eBmm350DataRates_t odr, +* enum bmm350_performance_parameters avg, +* struct bmm350_dev *dev); +* +* \endcode +* @details This API sets the ODR and averaging factor. +* If ODR and performance is a combination which is not allowed, then +* the combination setting is corrected to the next lower possible setting +* +* @param[in] odr : enum eBmm350DataRates_t +* +*@verbatim + Data rate (ODR) | odr + -------------------------|----------------------- + 400Hz | BMM350_DATA_RATE_400HZ + 200Hz | BMM350_DATA_RATE_200HZ + 100Hz | BMM350_DATA_RATE_100HZ + 50Hz | BMM350_DATA_RATE_50HZ + 25Hz | BMM350_DATA_RATE_25HZ + 12.5Hz | BMM350_DATA_RATE_12_5HZ + 6.25Hz | BMM350_DATA_RATE_6_25HZ + 3.125Hz | BMM350_DATA_RATE_3_125HZ + 1.5625Hz | BMM350_DATA_RATE_1_5625HZ +*@endverbatim +* +* @param[in] avg : enum bmm350_performance_parameters +* +*@verbatim + avg | averaging factor alias + ---------------------------|------------------------------------------ + low power/highest noise | BMM350_NO_AVERAGING BMM350_LOWPOWER + lesser noise | BMM350_AVERAGING_2 BMM350_REGULARPOWER + even lesser noise | BMM350_AVERAGING_4 BMM350_LOWNOISE + lowest noise/highest power | BMM350_AVERAGING_8 BMM350_ULTRALOWNOISE +*@endverbatim +* +* @param[in,out] dev : Structure instance of bmm350_dev +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350SetOdrPerformance(enum eBmm350DataRates_t odr, + enum bmm350_performance_parameters avg, + struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350_enable_axes bmm350_enable_axes +* \code +* int8_t bmm350_enable_axes(enum eBmm350XAxisEnDis_t en_x, enum eBmm350YAxisEnDis_t en_y, enum eBmm350ZAxisEnDis_t en_z, struct bmm350_dev *dev); +* \endcode +* @details This API is used to enable or disable the magnetic +* measurement of x,y,z axes +* +* @param[in] en_x : Enable or disable X axis +* @param[in] en_y : Enable or disable Y axis +* @param[in] en_z : Enable or disable Z axis +* @param[in,out] dev : Structure instance of bmm350_dev. +* +*@verbatim + Value | Axis (en_x, en_y, en_z) + -------------------|----------------------- + BMM350_ENABLE | Enabled + BMM350_DISABLE | Disabled +*@endverbatim +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_enable_axes(enum eBmm350XAxisEnDis_t en_x, + enum eBmm350YAxisEnDis_t en_y, + enum eBmm350ZAxisEnDis_t en_z, + struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiRead Sensortime + * @brief Reads sensortime + */ + +/*! +* \ingroup bmm350ApiRead +* \page bmm350_api_bmm350_read_sensortime bmm350_read_sensortime +* \code +* int8_t bmm350_read_sensortime(uint32_t *seconds, uint32_t *nanoseconds, struct bmm350_dev *dev); +* \endcode +* @details This API is used to read the sensor time. +* It converts the sensor time register values to the representative time value. +* Returns the sensor time in ticks. +* +* @param[out] seconds : Variable to get sensor time in seconds. +* @param[out] nanoseconds : Variable to get sensor time in nanoseconds. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_read_sensortime(uint32_t *seconds, uint32_t *nanoseconds, struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiInterrupt Enable Interrupt + * @brief Interrupt enable APIs + */ + +/*! +* \ingroup bmm350ApiInterrupt +* \page bmm350_api_bmm350_enable_interrupt bmm350_enable_interrupt +* \code +* int8_t bmm350_enable_interrupt(enum eBmm350InterruptEnableDisable_t enable_disable, struct bmm350_dev *dev); +* \endcode +* @details This API is used to enable or disable the data ready interrupt +* +* @param[in] enable_disable : Enable/ Disable data ready interrupt. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_enable_interrupt(enum eBmm350InterruptEnableDisable_t enable_disable, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiInterrupt +* \page bmm350_api_bmm350_configure_interrupt bmm350_configure_interrupt +* \code +* int8_t bmm350_configure_interrupt(enum bmm350_intr_latch latching, +* enum eBmm350IntrPolarity_t polarity, +* enum bmm350_intr_drive drivertype, +* enum bmm350_intr_map map_nomap, +* struct bmm350_dev *dev); +* \endcode +* @details This API is used to configure the interrupt control settings. +* +* @param[in] latching : Sets either latched or pulsed. +* @param[in] polarity : Sets either polarity high or low. +* @param[in] drivertype : Sets either open drain or push pull. +* @param[in] map_nomap : Sets either map or unmap the pins. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_configure_interrupt(enum bmm350_intr_latch latching, + enum eBmm350IntrPolarity_t polarity, + enum bmm350_intr_drive drivertype, + enum bmm350_intr_map map_nomap, + struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiUncompMag Uncompensated mag + * @brief Reads uncompensated mag and temperature data + */ + +/*! +* \ingroup bmm350ApiUncompMag +* \page bmm350_api_bmm350_read_uncomp_mag_temp_data bmm350_read_uncomp_mag_temp_data +* \code +* int8_t bmm350_read_uncomp_mag_temp_data(struct bmm350_raw_mag_data *raw_data, struct bmm350_dev *dev); +* \endcode +* @details This API is used to read uncompensated mag and temperature data +* +* @param[in, out] raw_data : Structure instance of bmm350_raw_mag_data. +* @param[in, out] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_read_uncomp_mag_temp_data(struct bmm350_raw_mag_data *raw_data, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350_set_int_ctrl_ibi bmm350_set_int_ctrl_ibi +* \code +* int8_t bmm350_set_int_ctrl_ibi(enum bmm350_drdy_int_map_to_ibi en_dis, +* enum bmm350_clear_drdy_int_status_upon_ibi clear_on_ibi, struct bmm350_dev *dev); +* \endcode +* @details This API sets the interrupt control IBI configurations to the sensor. +* And enables conventional interrupt if IBI is enabled. +* +* @param[in] en_dis : Sets either enable or disable IBI. +* @param[in] clear_on_ibi : sets either clear or no clear on IBI. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_set_int_ctrl_ibi(enum bmm350_drdy_int_map_to_ibi en_dis, + enum bmm350_clear_drdy_int_status_upon_ibi clear_on_ibi, + struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350_set_pad_drive bmm350_set_pad_drive +* \code +* int8_t bmm350_set_pad_drive(uint8_t drive, struct bmm350_dev *dev); +* \endcode +* @details This API is used to set the pad drive strength +* +* @param[in] drive : Drive settings, range 0 (weak) ..7(strong) +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_set_pad_drive(uint8_t drive, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiReset +* \page bmm350_api_bmm350_magnetic_reset_and_wait bmm350_magnetic_reset_and_wait +* \code +* int8_t bmm350_magnetic_reset_and_wait(struct bmm350_dev *dev) +* \endcode +* @details This API is used to perform the magnetic reset of the sensor +* which is necessary after a field shock (400mT field applied to sensor). +* It sends flux guide or bit reset to the device in suspend mode. +* +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_magnetic_reset_and_wait(struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiMagComp Compensation + * @brief Compensation for mag x,y,z axis and temperature API + */ + +/*! +* \ingroup bmm350ApiMagComp +* \page bmm350_api_bmm350GetCompensatedMagXYZTempData bmm350GetCompensatedMagXYZTempData +* \code +* int8_t bmm350GetCompensatedMagXYZTempData(struct sBmm350MagTempData_t *mag_temp_data, struct bmm350_dev *dev); +* \endcode +* @details This API is used to perform compensation for raw magnetometer and temperature data. +* +* @param[out] mag_temp_data : Structure instance of sBmm350MagTempData_t. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350GetCompensatedMagXYZTempData(struct sBmm350MagTempData_t *mag_temp_data, struct bmm350_dev *dev); + +/** + * \ingroup bmm350 + * \defgroup bmm350ApiSelftest Self-test + * @brief Perform self-test for x and y axis + */ + +/*! +* \ingroup bmm350ApiSelftest +* \page bmm350_api_bmm350PerformSelfTest bmm350PerformSelfTest +* \code +* int8_t bmm350PerformSelfTest(struct sBmm350SelfTest_t *out_data, struct bmm350_dev *dev); +* \endcode +* @details This API executes FGR and BR sequences to initialize TMR sensor and performs self-test for x and y axis. +* +* @param[in, out] out_data : Structure instance of sBmm350SelfTest_t. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350PerformSelfTest(struct sBmm350SelfTest_t *out_data, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350_set_i2c_wdt bmm350_set_i2c_wdt +* \code +* int8_t bmm350_set_i2c_wdt(enum bmm350_i2c_wdt_en i2c_wdt_en_dis, enum bmm350_i2c_wdt_sel i2c_wdt_sel, +* struct bmm350_dev *dev); +* \endcode +* @details This API sets the I2C watchdog timer configurations to the sensor. +* +* @param[in] i2c_wdt_en_dis : Enable/ Disable I2C watchdog timer. +* @param[in] i2c_wdt_sel : I2C watchdog timer selection period. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_set_i2c_wdt(enum bmm350_i2c_wdt_en i2c_wdt_en_dis, + enum bmm350_i2c_wdt_sel i2c_wdt_sel, + struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350_set_tmr_selftest_user bmm350_set_tmr_selftest_user +* \code +* int8_t bmm350_set_tmr_selftest_user(enum bmm350_st_igen_en st_igen_en_dis, +* enum bmm350_st_n st_n_en_dis, +* enum bmm350_st_p st_p_en_dis, +* enum bmm350_ist_en_x ist_x_en_dis, +* enum bmm350_ist_en_y ist_y_en_dis, +* struct bmm350_dev *dev); +* \endcode +* @details This API sets the TMR user self-test register +* +* @param[in] st_igen_en_dis : Enable/ Disable self-test internal current gen. +* @param[in] st_n_en_dis : Enable/ Disable dc_st_n signal. +* @param[in] st_p_en_dis : Enable/ Disable dc_st_p signal. +* @param[in] ist_x_en_dis : Enable/ Disable dc_ist_en_x signal. +* @param[in] ist_y_en_dis : Enable/ Disable dc_ist_en_y signal. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_set_tmr_selftest_user(enum bmm350_st_igen_en st_igen_en_dis, + enum bmm350_st_n st_n_en_dis, + enum bmm350_st_p st_p_en_dis, + enum bmm350_ist_en_x ist_x_en_dis, + enum bmm350_ist_en_y ist_y_en_dis, + struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350_set_ctrl_user bmm350_set_ctrl_user +* \code +* int8_t bmm350_set_ctrl_user(enum bmm350_ctrl_user cfg_sens_tim_aon_en_dis, struct bmm350_dev *dev); +* \endcode +* @details This API sets the control user configurations to the sensor. +* +* @param[in] cfg_sens_tim_aon_en_dis : Enable/ Disable configuration of sensor time to run on suspend mode. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_set_ctrl_user(enum bmm350_ctrl_user cfg_sens_tim_aon_en_dis, struct bmm350_dev *dev); + +/*! +* \ingroup bmm350ApiSetGet +* \page bmm350_api_bmm350_get_pmu_cmd_status_0 bmm350_get_pmu_cmd_status_0 +* \code +* int8_t bmm350_get_pmu_cmd_status_0(struct bmm350_pmu_cmd_status_0 *pmu_cmd_stat_0, struct bmm350_dev *dev); +* \endcode +* @details This API gets the PMU command status 0 value. +* +* @param[out] pmu_cmd_stat_0 : Structure instance of bmm350_pmu_cmd_status_0. +* @param[in] dev : Structure instance of bmm350_dev. +* +* @return Result of API execution status +* @retval = 0 -> Success +* @retval < 0 -> Error +*/ +int8_t bmm350_get_pmu_cmd_status_0(struct bmm350_pmu_cmd_status_0 *pmu_cmd_stat_0, struct bmm350_dev *dev); + +#ifdef __cplusplus +} +#endif /* End of CPP guard */ + +#endif /* _BMM350_H */ diff --git a/lib/DFRobot_BMM350/src/bmm350_defs.h b/lib/DFRobot_BMM350/src/bmm350_defs.h new file mode 100644 index 0000000..cb9a59c --- /dev/null +++ b/lib/DFRobot_BMM350/src/bmm350_defs.h @@ -0,0 +1,1215 @@ +/** +* Copyright (c) 2023 Bosch Sensortec GmbH. All rights reserved. +* +* BSD-3-Clause +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* 1. Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* +* 2. Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the distribution. +* +* 3. Neither the name of the copyright holder nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, +* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING +* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* @file bmm350_defs.h +* @date 2023-05-26 +* @version v1.4.0 +* +*/ + +#ifndef _BMM350_DEFS_H +#define _BMM350_DEFS_H + +/*************************** Header files *******************************/ + +#ifdef __KERNEL__ +#include +#include +#else +#include +#include +#endif + +/***************************** Common Macros *****************************/ + +#ifdef __KERNEL__ +#if !defined(UINT8_C) && !defined(INT8_C) +#define INT8_C(x) S8_C(x) +#define UINT8_C(x) U8_C(x) +#endif + +#if !defined(UINT16_C) && !defined(INT16_C) +#define INT16_C(x) S16_C(x) +#define UINT16_C(x) U16_C(x) +#endif + +#if !defined(INT32_C) && !defined(UINT32_C) +#define INT32_C(x) S32_C(x) +#define UINT32_C(x) U32_C(x) +#endif + +#if !defined(INT64_C) && !defined(UINT64_C) +#define INT64_C(x) S64_C(x) +#define UINT64_C(x) U64_C(x) +#endif +#endif + +/*! C standard macros */ +#ifndef NULL +#ifdef __cplusplus +#define NULL 0 +#else +#define NULL ((void *) 0) +#endif +#endif + +/******************************************************************************/ +/*! @name Compiler switch macros Definitions */ +/******************************************************************************/ + +/************************* General Macro definitions ***************************/ + +/* Macro to SET and GET BITS of a register*/ +#define BMM350_SET_BITS(reg_data, bitname, data) \ + ((reg_data & ~(bitname##_MSK)) | \ + ((data << bitname##_POS) & bitname##_MSK)) + +#define BMM350_GET_BITS(reg_data, bitname) ((reg_data & (bitname##_MSK)) >> (bitname##_POS)) + +#define BMM350_GET_BITS_POS_0(reg_data, bitname) (reg_data & (bitname##_MSK)) + +#define BMM350_SET_BITS_POS_0(reg_data, bitname, data) \ + ((reg_data & ~(bitname##_MSK)) | \ + (data & bitname##_MSK)) + +#ifndef BMM350_INTF_RET_TYPE +#define BMM350_INTF_RET_TYPE int8_t +#endif + +#define UNUSED(x) (void)(x) + +/*! Chip id of BMM350 */ +#define BMM350_CHIP_ID UINT8_C(0x33) + +/*! Variant ID of BMM350 */ +#define BMM350_MIN_VAR UINT8_C(0x10) + +/************************* Sensor interface success code **************************/ +#define BMM350_INTF_RET_SUCCESS INT8_C(0) + +/************************* API success code **************************/ +#define BMM350_OK INT8_C(0) + +/* API error codes */ +#define BMM350_E_NULL_PTR INT8_C(-1) +#define BMM350_E_COM_FAIL INT8_C(-2) +#define BMM350_E_DEV_NOT_FOUND INT8_C(-3) +#define BMM350_E_INVALID_CONFIG INT8_C(-4) +#define BMM350_E_BAD_PAD_DRIVE INT8_C(-5) +#define BMM350_E_RESET_UNFINISHED INT8_C(-6) +#define BMM350_E_INVALID_INPUT INT8_C(-7) +#define BMM350_E_SELF_TEST_INVALID_AXIS INT8_C(-8) +#define BMM350_E_OTP_BOOT INT8_C(-9) +#define BMM350_E_OTP_PAGE_RD INT8_C(-10) +#define BMM350_E_OTP_PAGE_PRG INT8_C(-11) +#define BMM350_E_OTP_SIGN INT8_C(-12) +#define BMM350_E_OTP_INV_CMD INT8_C(-13) +#define BMM350_E_OTP_UNDEFINED INT8_C(-14) +#define BMM350_E_ALL_AXIS_DISABLED INT8_C(-15) +#define BMM350_E_PMU_CMD_VALUE INT8_C(-16) + +#define BMM350_NO_ERROR UINT8_C(0) + +/************************* Sensor delay time settings in microseconds **************************/ +#define BMM350_SOFT_RESET_DELAY UINT32_C(24000) +#define BMM350_MAGNETIC_RESET_DELAY UINT32_C(40000) +#define BMM350_START_UP_TIME_FROM_POR UINT32_C(3000) + +#define BMM350_GOTO_SUSPEND_DELAY UINT32_C(6000) +#define BMM350_SUSPEND_TO_NORMAL_DELAY UINT32_C(38000) + +#define BMM350_SUS_TO_FORCEDMODE_NO_AVG_DELAY UINT32_C(15000) +#define BMM350_SUS_TO_FORCEDMODE_AVG_2_DELAY UINT32_C(17000) +#define BMM350_SUS_TO_FORCEDMODE_AVG_4_DELAY UINT32_C(20000) +#define BMM350_SUS_TO_FORCEDMODE_AVG_8_DELAY UINT32_C(28000) + +#define BMM350_SUS_TO_FORCEDMODE_FAST_NO_AVG_DELAY UINT32_C(4000) +#define BMM350_SUS_TO_FORCEDMODE_FAST_AVG_2_DELAY UINT32_C(5000) +#define BMM350_SUS_TO_FORCEDMODE_FAST_AVG_4_DELAY UINT32_C(9000) +#define BMM350_SUS_TO_FORCEDMODE_FAST_AVG_8_DELAY UINT32_C(16000) + +#define BMM350_UPD_OAE_DELAY UINT16_C(1000) + +#define BMM350_BR_DELAY UINT16_C(14000) +#define BMM350_FGR_DELAY UINT16_C(18000) + +/************************ Length macros ************************/ +#define BMM350_OTP_DATA_LENGTH UINT8_C(32) +#define BMM350_READ_BUFFER_LENGTH UINT8_C(127) +#define BMM350_MAG_TEMP_DATA_LEN UINT8_C(12) + +/************************ Averaging macros **********************/ +#define BMM350_AVG_NO_AVG UINT8_C(0x0) +#define BMM350_AVG_2 UINT8_C(0x1) +#define BMM350_AVG_4 UINT8_C(0x2) +#define BMM350_AVG_8 UINT8_C(0x3) + +/******************************* ODR **************************/ +#define BMM350_ODR_400HZ UINT8_C(0x2) +#define BMM350_ODR_200HZ UINT8_C(0x3) +#define BMM350_ODR_100HZ UINT8_C(0x4) +#define BMM350_ODR_50HZ UINT8_C(0x5) +#define BMM350_ODR_25HZ UINT8_C(0x6) +#define BMM350_ODR_12_5HZ UINT8_C(0x7) +#define BMM350_ODR_6_25HZ UINT8_C(0x8) +#define BMM350_ODR_3_125HZ UINT8_C(0x9) +#define BMM350_ODR_1_5625HZ UINT8_C(0xA) + +/********************* Power modes *************************/ +#define BMM350_PMU_CMD_SUS UINT8_C(0x00) +#define BMM350_PMU_CMD_NM UINT8_C(0x01) +#define BMM350_PMU_CMD_UPD_OAE UINT8_C(0x02) +#define BMM350_PMU_CMD_FM UINT8_C(0x03) +#define BMM350_PMU_CMD_FM_FAST UINT8_C(0x04) +#define BMM350_PMU_CMD_FGR UINT8_C(0x05) +#define BMM350_PMU_CMD_FGR_FAST UINT8_C(0x06) +#define BMM350_PMU_CMD_BR UINT8_C(0x07) +#define BMM350_PMU_CMD_BR_FAST UINT8_C(0x08) +#define BMM350_PMU_CMD_NM_TC UINT8_C(0x09) + +#define BMM350_PMU_STATUS_0 UINT8_C(0x0) + +#define BMM350_DISABLE UINT8_C(0x0) +#define BMM350_ENABLE UINT8_C(0x1) + +#define BMM350_CMD_NOP UINT8_C(0x0) +#define BMM350_CMD_SOFTRESET UINT8_C(0xB6) + +#define BMM350_TARGET_PAGE_PAGE0 UINT8_C(0x0) +#define BMM350_TARGET_PAGE_PAGE1 UINT8_C(0x1) + +#define BMM350_INT_MODE_LATCHED UINT8_C(0x1) +#define BMM350_INT_MODE_PULSED UINT8_C(0x0) + +#define BMM350_INT_POL_ACTIVE_HIGH UINT8_C(0x1) +#define BMM350_INT_POL_ACTIVE_LOW UINT8_C(0x0) + +#define BMM350_INT_OD_PUSHPULL UINT8_C(0x1) +#define BMM350_INT_OD_OPENDRAIN UINT8_C(0x0) + +#define BMM350_INT_OUTPUT_EN_OFF UINT8_C(0x0) +#define BMM350_INT_OUTPUT_EN_ON UINT8_C(0x1) + +#define BMM350_INT_DRDY_EN UINT8_C(0x1) +#define BMM350_INT_DRDY_DIS UINT8_C(0x0) + +#define BMM350_MR_MR1K8 UINT8_C(0x0) +#define BMM350_MR_MR2K1 UINT8_C(0x1) +#define BMM350_MR_MR1K5 UINT8_C(0x2) +#define BMM350_MR_MR0K6 UINT8_C(0x3) + +#define BMM350_SEL_DTB1X_PAD_PAD_INT UINT8_C(0x0) +#define BMM350_SEL_DTB1X_PAD_PAD_BYP UINT8_C(0x1) + +#define BMM350_TMR_TST_HIZ_VTMR_VTMR_ON UINT8_C(0x0) +#define BMM350_TMR_TST_HIZ_VTMR_VTMR_HIZ UINT8_C(0x1) + +#define BMM350_LSB_MASK UINT16_C(0x00FF) +#define BMM350_MSB_MASK UINT16_C(0xFF00) + +/********************** Pad drive strength ************************/ +#define BMM350_PAD_DRIVE_WEAKEST UINT8_C(0) +#define BMM350_PAD_DRIVE_STRONGEST UINT8_C(7) + +/********************** I2C Register Addresses ************************/ + +/*! Register to set I2C address to LOW */ +#define BMM350_I2C_ADSEL_SET_LOW UINT8_C(0x14) + +/*! Register to set I2C address to HIGH */ +#define BMM350_I2C_ADSEL_SET_HIGH UINT8_C(0x15) + +#define BMM350_DUMMY_BYTES UINT8_C(2) + +/********************** Register Addresses ************************/ + +#define BMM350_REG_CHIP_ID UINT8_C(0x00) +#define BMM350_REG_REV_ID UINT8_C(0x01) +#define BMM350_REG_ERR_REG UINT8_C(0x02) +#define BMM350_REG_PAD_CTRL UINT8_C(0x03) +#define BMM350_REG_PMU_CMD_AGGR_SET UINT8_C(0x04) +#define BMM350_REG_PMU_CMD_AXIS_EN UINT8_C(0x05) +#define BMM350_REG_PMU_CMD UINT8_C(0x06) +#define BMM350_REG_PMU_CMD_STATUS_0 UINT8_C(0x07) +#define BMM350_REG_PMU_CMD_STATUS_1 UINT8_C(0x08) +#define BMM350_REG_I3C_ERR UINT8_C(0x09) +#define BMM350_REG_I2C_WDT_SET UINT8_C(0x0A) +#define BMM350_REG_TRSDCR_REV_ID UINT8_C(0x0D) +#define BMM350_REG_TC_SYNC_TU UINT8_C(0x21) +#define BMM350_REG_TC_SYNC_ODR UINT8_C(0x22) +#define BMM350_REG_TC_SYNC_TPH_1 UINT8_C(0x23) +#define BMM350_REG_TC_SYNC_TPH_2 UINT8_C(0x24) +#define BMM350_REG_TC_SYNC_DT UINT8_C(0x25) +#define BMM350_REG_TC_SYNC_ST_0 UINT8_C(0x26) +#define BMM350_REG_TC_SYNC_ST_1 UINT8_C(0x27) +#define BMM350_REG_TC_SYNC_ST_2 UINT8_C(0x28) +#define BMM350_REG_TC_SYNC_STATUS UINT8_C(0x29) +#define BMM350_REG_INT_CTRL UINT8_C(0x2E) +#define BMM350_REG_INT_CTRL_IBI UINT8_C(0x2F) +#define BMM350_REG_INT_STATUS UINT8_C(0x30) +#define BMM350_REG_MAG_X_XLSB UINT8_C(0x31) +#define BMM350_REG_MAG_X_LSB UINT8_C(0x32) +#define BMM350_REG_MAG_X_MSB UINT8_C(0x33) +#define BMM350_REG_MAG_Y_XLSB UINT8_C(0x34) +#define BMM350_REG_MAG_Y_LSB UINT8_C(0x35) +#define BMM350_REG_MAG_Y_MSB UINT8_C(0x36) +#define BMM350_REG_MAG_Z_XLSB UINT8_C(0x37) +#define BMM350_REG_MAG_Z_LSB UINT8_C(0x38) +#define BMM350_REG_MAG_Z_MSB UINT8_C(0x39) +#define BMM350_REG_TEMP_XLSB UINT8_C(0x3A) +#define BMM350_REG_TEMP_LSB UINT8_C(0x3B) +#define BMM350_REG_TEMP_MSB UINT8_C(0x3C) +#define BMM350_REG_SENSORTIME_XLSB UINT8_C(0x3D) +#define BMM350_REG_SENSORTIME_LSB UINT8_C(0x3E) +#define BMM350_REG_SENSORTIME_MSB UINT8_C(0x3F) +#define BMM350_REG_OTP_CMD_REG UINT8_C(0x50) +#define BMM350_REG_OTP_DATA_MSB_REG UINT8_C(0x52) +#define BMM350_REG_OTP_DATA_LSB_REG UINT8_C(0x53) +#define BMM350_REG_OTP_STATUS_REG UINT8_C(0x55) +#define BMM350_REG_TMR_SELFTEST_USER UINT8_C(0x60) +#define BMM350_REG_CTRL_USER UINT8_C(0x61) +#define BMM350_REG_CMD UINT8_C(0x7E) + +/*********************** Macros for OVWR ***************************/ +#define BMM350_REG_OVWR_VALUE_ANA_0 UINT8_C(0x3A) +#define BMM350_REG_OVWR_EN_ANA_0 UINT8_C(0x3B) + +/*********************** Macros for bit masking ***************************/ + +#define BMM350_CHIP_ID_OTP_MSK UINT8_C(0xf) +#define BMM350_CHIP_ID_OTP_POS UINT8_C(0x0) +#define BMM350_CHIP_ID_FIXED_MSK UINT8_C(0xf0) +#define BMM350_CHIP_ID_FIXED_POS UINT8_C(0x4) +#define BMM350_REV_ID_MAJOR_MSK UINT8_C(0xf0) +#define BMM350_REV_ID_MAJOR_POS UINT8_C(0x4) +#define BMM350_REV_ID_MINOR_MSK UINT8_C(0xf) +#define BMM350_REV_ID_MINOR_POS UINT8_C(0x0) +#define BMM350_PMU_CMD_ERROR_MSK UINT8_C(0x1) +#define BMM350_PMU_CMD_ERROR_POS UINT8_C(0x0) +#define BMM350_BOOT_UP_ERROR_MSK UINT8_C(0x2) +#define BMM350_BOOT_UP_ERROR_POS UINT8_C(0x1) +#define BMM350_DRV_MSK UINT8_C(0x7) +#define BMM350_DRV_POS UINT8_C(0x0) +#define BMM350_AVG_MSK UINT8_C(0x30) +#define BMM350_AVG_POS UINT8_C(0x4) +#define BMM350_ODR_MSK UINT8_C(0xf) +#define BMM350_ODR_POS UINT8_C(0x0) +#define BMM350_PMU_CMD_MSK UINT8_C(0xf) +#define BMM350_PMU_CMD_POS UINT8_C(0x0) +#define BMM350_EN_X_MSK UINT8_C(0x01) +#define BMM350_EN_X_POS UINT8_C(0x0) +#define BMM350_EN_Y_MSK UINT8_C(0x02) +#define BMM350_EN_Y_POS UINT8_C(0x1) +#define BMM350_EN_Z_MSK UINT8_C(0x04) +#define BMM350_EN_Z_POS UINT8_C(0x2) +#define BMM350_EN_XYZ_MSK UINT8_C(0x7) +#define BMM350_EN_XYZ_POS UINT8_C(0x0) +#define BMM350_PMU_CMD_BUSY_MSK UINT8_C(0x1) +#define BMM350_PMU_CMD_BUSY_POS UINT8_C(0x0) +#define BMM350_ODR_OVWR_MSK UINT8_C(0x2) +#define BMM350_ODR_OVWR_POS UINT8_C(0x1) +#define BMM350_AVG_OVWR_MSK UINT8_C(0x4) +#define BMM350_AVG_OVWR_POS UINT8_C(0x2) +#define BMM350_PWR_MODE_IS_NORMAL_MSK UINT8_C(0x8) +#define BMM350_PWR_MODE_IS_NORMAL_POS UINT8_C(0x3) +#define BMM350_CMD_IS_ILLEGAL_MSK UINT8_C(0x10) +#define BMM350_CMD_IS_ILLEGAL_POS UINT8_C(0x4) +#define BMM350_PMU_CMD_VALUE_MSK UINT8_C(0xE0) +#define BMM350_PMU_CMD_VALUE_POS UINT8_C(0x5) +#define BMM350_PMU_ODR_S_MSK UINT8_C(0xf) +#define BMM350_PMU_ODR_S_POS UINT8_C(0x0) +#define BMM350_PMU_AVG_S_MSK UINT8_C(0x30) +#define BMM350_PMU_AVG_S_POS UINT8_C(0x4) +#define BMM350_I3C_ERROR_0_MSK UINT8_C(0x1) +#define BMM350_I3C_ERROR_0_POS UINT8_C(0x0) +#define BMM350_I3C_ERROR_3_MSK UINT8_C(0x8) +#define BMM350_I3C_ERROR_3_POS UINT8_C(0x3) +#define BMM350_I2C_WDT_EN_MSK UINT8_C(0x1) +#define BMM350_I2C_WDT_EN_POS UINT8_C(0x0) +#define BMM350_I2C_WDT_SEL_MSK UINT8_C(0x2) +#define BMM350_I2C_WDT_SEL_POS UINT8_C(0x1) +#define BMM350_TRSDCR_REV_ID_OTP_MSK UINT8_C(0x3) +#define BMM350_TRSDCR_REV_ID_OTP_POS UINT8_C(0x0) +#define BMM350_TRSDCR_REV_ID_FIXED_MSK UINT8_C(0xfc) +#define BMM350_TRSDCR_REV_ID_FIXED_POS UINT8_C(0x2) +#define BMM350_PAGING_EN_MSK UINT8_C(0x80) +#define BMM350_PAGING_EN_POS UINT8_C(0x7) +#define BMM350_DRDY_DATA_REG_MSK UINT8_C(0x4) +#define BMM350_DRDY_DATA_REG_POS UINT8_C(0x2) +#define BMM350_INT_MODE_MSK UINT8_C(0x1) +#define BMM350_INT_MODE_POS UINT8_C(0x0) +#define BMM350_INT_POL_MSK UINT8_C(0x2) +#define BMM350_INT_POL_POS UINT8_C(0x1) +#define BMM350_INT_OD_MSK UINT8_C(0x4) +#define BMM350_INT_OD_POS UINT8_C(0x2) +#define BMM350_INT_OUTPUT_EN_MSK UINT8_C(0x8) +#define BMM350_INT_OUTPUT_EN_POS UINT8_C(0x3) +#define BMM350_DRDY_DATA_REG_EN_MSK UINT8_C(0x80) +#define BMM350_DRDY_DATA_REG_EN_POS UINT8_C(0x7) +#define BMM350_DRDY_INT_MAP_TO_IBI_MSK UINT8_C(0x1) +#define BMM350_DRDY_INT_MAP_TO_IBI_POS UINT8_C(0x0) +#define BMM350_CLEAR_DRDY_INT_STATUS_UPON_IBI_MSK UINT8_C(0x10) +#define BMM350_CLEAR_DRDY_INT_STATUS_UPON_IBI_POS UINT8_C(0x4) +#define BMM350_TC_SYNC_TU_MSK UINT8_C(0xff) +#define BMM350_TC_SYNC_ODR_MSK UINT8_C(0xff) +#define BMM350_TC_SYNC_TPH_1_MSK UINT8_C(0xff) +#define BMM350_TC_SYNC_TPH_2_MSK UINT8_C(0xff) +#define BMM350_TC_SYNC_DT_MSK UINT8_C(0xff) +#define BMM350_TC_SYNC_ST_0_MSK UINT8_C(0xff) +#define BMM350_TC_SYNC_ST_1_MSK UINT8_C(0xff) +#define BMM350_TC_SYNC_ST_2_MSK UINT8_C(0xff) +#define BMM350_CFG_FORCE_SOSC_EN_MSK UINT8_C(0x4) +#define BMM350_CFG_FORCE_SOSC_EN_POS UINT8_C(0x2) +#define BMM350_ST_IGEN_EN_MSK UINT8_C(0x1) +#define BMM350_ST_IGEN_EN_POS UINT8_C(0x0) +#define BMM350_ST_N_MSK UINT8_C(0x2) +#define BMM350_ST_N_POS UINT8_C(0x1) +#define BMM350_ST_P_MSK UINT8_C(0x4) +#define BMM350_ST_P_POS UINT8_C(0x2) +#define BMM350_IST_EN_X_MSK UINT8_C(0x8) +#define BMM350_IST_EN_X_POS UINT8_C(0x3) +#define BMM350_IST_EN_Y_MSK UINT8_C(0x10) +#define BMM350_IST_EN_Y_POS UINT8_C(0x4) +#define BMM350_CFG_SENS_TIM_AON_MSK UINT8_C(0x1) +#define BMM350_CFG_SENS_TIM_AON_POS UINT8_C(0x0) +#define BMM350_DATA_X_7_0_MSK UINT8_C(0xff) +#define BMM350_DATA_X_7_0_POS UINT8_C(0x0) +#define BMM350_DATA_X_15_8_MSK UINT8_C(0xff) +#define BMM350_DATA_X_15_8_POS UINT8_C(0x0) +#define BMM350_DATA_X_23_16_MSK UINT8_C(0xff) +#define BMM350_DATA_X_23_16_POS UINT8_C(0x0) +#define BMM350_DATA_Y_7_0_MSK UINT8_C(0xff) +#define BMM350_DATA_Y_7_0_POS UINT8_C(0x0) +#define BMM350_DATA_Y_15_8_MSK UINT8_C(0xff) +#define BMM350_DATA_Y_15_8_POS UINT8_C(0x0) +#define BMM350_DATA_Y_23_16_MSK UINT8_C(0xff) +#define BMM350_DATA_Y_23_16_POS UINT8_C(0x0) +#define BMM350_DATA_Z_7_0_MSK UINT8_C(0xff) +#define BMM350_DATA_Z_7_0_POS UINT8_C(0x0) +#define BMM350_DATA_Z_15_8_MSK UINT8_C(0xff) +#define BMM350_DATA_Z_15_8_POS UINT8_C(0x0) +#define BMM350_DATA_Z_23_16_MSK UINT8_C(0xff) +#define BMM350_DATA_Z_23_16_POS UINT8_C(0x0) +#define BMM350_DATA_T_7_0_MSK UINT8_C(0xff) +#define BMM350_DATA_T_7_0_POS UINT8_C(0x0) +#define BMM350_DATA_T_15_8_MSK UINT8_C(0xff) +#define BMM350_DATA_T_15_8_POS UINT8_C(0x0) +#define BMM350_DATA_T_23_16_MSK UINT8_C(0xff) +#define BMM350_DATA_T_23_16_POS UINT8_C(0x0) +#define BMM350_DATA_ST_7_0_MSK UINT8_C(0xff) +#define BMM350_DATA_ST_7_0_POS UINT8_C(0x0) +#define BMM350_DATA_ST_15_8_MSK UINT8_C(0xff) +#define BMM350_DATA_ST_15_8_POS UINT8_C(0x0) +#define BMM350_DATA_ST_23_16_MSK UINT8_C(0xff) +#define BMM350_DATA_ST_23_16_POS UINT8_C(0x0) +#define BMM350_SIGN_INVERT_T_MSK UINT8_C(0x10) +#define BMM350_SIGN_INVERT_T_POS UINT8_C(0x4) +#define BMM350_SIGN_INVERT_X_MSK UINT8_C(0x20) +#define BMM350_SIGN_INVERT_X_POS UINT8_C(0x5) +#define BMM350_SIGN_INVERT_Y_MSK UINT8_C(0x40) +#define BMM350_SIGN_INVERT_Y_POS UINT8_C(0x6) +#define BMM350_SIGN_INVERT_Z_MSK UINT8_C(0x80) +#define BMM350_SIGN_INVERT_Z_POS UINT8_C(0x7) +#define BMM350_DIS_BR_NM_MSK UINT8_C(0x1) +#define BMM350_DIS_BR_NM_POS UINT8_C(0x0) +#define BMM350_DIS_FGR_NM_MSK UINT8_C(0x2) +#define BMM350_DIS_FGR_NM_POS UINT8_C(0x1) +#define BMM350_DIS_CRST_AT_ALL_MSK UINT8_C(0x4) +#define BMM350_DIS_CRST_AT_ALL_POS UINT8_C(0x2) +#define BMM350_DIS_BR_FM_MSK UINT8_C(0x8) +#define BMM350_DIS_BR_FM_POS UINT8_C(0x3) +#define BMM350_FRC_EN_BUFF_MSK UINT8_C(0x1) +#define BMM350_FRC_EN_BUFF_POS UINT8_C(0x0) +#define BMM350_FRC_INA_EN1_MSK UINT8_C(0x2) +#define BMM350_FRC_INA_EN1_POS UINT8_C(0x1) +#define BMM350_FRC_INA_EN2_MSK UINT8_C(0x4) +#define BMM350_FRC_INA_EN2_POS UINT8_C(0x2) +#define BMM350_FRC_ADC_EN_MSK UINT8_C(0x8) +#define BMM350_FRC_ADC_EN_POS UINT8_C(0x3) +#define BMM350_FRC_INA_RST_MSK UINT8_C(0x10) +#define BMM350_FRC_INA_RST_POS UINT8_C(0x4) +#define BMM350_FRC_ADC_RST_MSK UINT8_C(0x20) +#define BMM350_FRC_ADC_RST_POS UINT8_C(0x5) +#define BMM350_FRC_INA_XSEL_MSK UINT8_C(0x1) +#define BMM350_FRC_INA_XSEL_POS UINT8_C(0x0) +#define BMM350_FRC_INA_YSEL_MSK UINT8_C(0x2) +#define BMM350_FRC_INA_YSEL_POS UINT8_C(0x1) +#define BMM350_FRC_INA_ZSEL_MSK UINT8_C(0x4) +#define BMM350_FRC_INA_ZSEL_POS UINT8_C(0x2) +#define BMM350_FRC_ADC_TEMP_EN_MSK UINT8_C(0x8) +#define BMM350_FRC_ADC_TEMP_EN_POS UINT8_C(0x3) +#define BMM350_FRC_TSENS_EN_MSK UINT8_C(0x10) +#define BMM350_FRC_TSENS_EN_POS UINT8_C(0x4) +#define BMM350_DSENS_FM_MSK UINT8_C(0x20) +#define BMM350_DSENS_FM_POS UINT8_C(0x5) +#define BMM350_DSENS_SEL_MSK UINT8_C(0x40) +#define BMM350_DSENS_SEL_POS UINT8_C(0x6) +#define BMM350_DSENS_SHORT_MSK UINT8_C(0x80) +#define BMM350_DSENS_SHORT_POS UINT8_C(0x7) +#define BMM350_ERR_MISS_BR_DONE_MSK UINT8_C(0x1) +#define BMM350_ERR_MISS_BR_DONE_POS UINT8_C(0x0) +#define BMM350_ERR_MISS_FGR_DONE_MSK UINT8_C(0x2) +#define BMM350_ERR_MISS_FGR_DONE_POS UINT8_C(0x1) +#define BMM350_TST_CHAIN_LN_MODE_MSK UINT8_C(0x1) +#define BMM350_TST_CHAIN_LN_MODE_POS UINT8_C(0x0) +#define BMM350_TST_CHAIN_LP_MODE_MSK UINT8_C(0x2) +#define BMM350_TST_CHAIN_LP_MODE_POS UINT8_C(0x1) +#define BMM350_EN_OVWR_TMR_IF_MSK UINT8_C(0x1) +#define BMM350_EN_OVWR_TMR_IF_POS UINT8_C(0x0) +#define BMM350_TMR_CKTRIGB_MSK UINT8_C(0x2) +#define BMM350_TMR_CKTRIGB_POS UINT8_C(0x1) +#define BMM350_TMR_DO_BR_MSK UINT8_C(0x4) +#define BMM350_TMR_DO_BR_POS UINT8_C(0x2) +#define BMM350_TMR_DO_FGR_MSK UINT8_C(0x18) +#define BMM350_TMR_DO_FGR_POS UINT8_C(0x3) +#define BMM350_TMR_EN_OSC_MSK UINT8_C(0x80) +#define BMM350_TMR_EN_OSC_POS UINT8_C(0x7) +#define BMM350_VCM_TRIM_X_MSK UINT8_C(0x1f) +#define BMM350_VCM_TRIM_X_POS UINT8_C(0x0) +#define BMM350_VCM_TRIM_Y_MSK UINT8_C(0x1f) +#define BMM350_VCM_TRIM_Y_POS UINT8_C(0x0) +#define BMM350_VCM_TRIM_Z_MSK UINT8_C(0x1f) +#define BMM350_VCM_TRIM_Z_POS UINT8_C(0x0) +#define BMM350_VCM_TRIM_DSENS_MSK UINT8_C(0x1f) +#define BMM350_VCM_TRIM_DSENS_POS UINT8_C(0x0) +#define BMM350_TWLB_MSK UINT8_C(0x30) +#define BMM350_TWLB_POS UINT8_C(0x4) +#define BMM350_PRG_PLS_TIM_MSK UINT8_C(0x30) +#define BMM350_PRG_PLS_TIM_POS UINT8_C(0x4) +#define BMM350_OTP_OVWR_EN_MSK UINT8_C(0x1) +#define BMM350_OTP_OVWR_EN_POS UINT8_C(0x0) +#define BMM350_OTP_MEM_CLK_MSK UINT8_C(0x2) +#define BMM350_OTP_MEM_CLK_POS UINT8_C(0x1) +#define BMM350_OTP_MEM_CS_MSK UINT8_C(0x4) +#define BMM350_OTP_MEM_CS_POS UINT8_C(0x2) +#define BMM350_OTP_MEM_PGM_MSK UINT8_C(0x8) +#define BMM350_OTP_MEM_PGM_POS UINT8_C(0x3) +#define BMM350_OTP_MEM_RE_MSK UINT8_C(0x10) +#define BMM350_OTP_MEM_RE_POS UINT8_C(0x4) +#define BMM350_SAMPLE_RDATA_PLS_MSK UINT8_C(0x80) +#define BMM350_SAMPLE_RDATA_PLS_POS UINT8_C(0x7) +#define BMM350_CFG_FW_MSK UINT8_C(0x1) +#define BMM350_CFG_FW_POS UINT8_C(0x0) +#define BMM350_EN_BR_X_MSK UINT8_C(0x2) +#define BMM350_EN_BR_X_POS UINT8_C(0x1) +#define BMM350_EN_BR_Y_MSK UINT8_C(0x4) +#define BMM350_EN_BR_Y_POS UINT8_C(0x2) +#define BMM350_EN_BR_Z_MSK UINT8_C(0x8) +#define BMM350_EN_BR_Z_POS UINT8_C(0x3) +#define BMM350_CFG_PAUSE_TIME_MSK UINT8_C(0x30) +#define BMM350_CFG_PAUSE_TIME_POS UINT8_C(0x4) +#define BMM350_CFG_FGR_PLS_DUR_MSK UINT8_C(0xf) +#define BMM350_CFG_FGR_PLS_DUR_POS UINT8_C(0x0) +#define BMM350_CFG_BR_Z_ORDER_MSK UINT8_C(0x10) +#define BMM350_CFG_BR_Z_ORDER_POS UINT8_C(0x4) +#define BMM350_CFG_BR_XY_CHOP_MSK UINT8_C(0x20) +#define BMM350_CFG_BR_XY_CHOP_POS UINT8_C(0x5) +#define BMM350_CFG_BR_PLS_DUR_MSK UINT8_C(0xc0) +#define BMM350_CFG_BR_PLS_DUR_POS UINT8_C(0x6) +#define BMM350_ENABLE_BR_FGR_TEST_MSK UINT8_C(0x1) +#define BMM350_ENABLE_BR_FGR_TEST_POS UINT8_C(0x0) +#define BMM350_SEL_AXIS_MSK UINT8_C(0xe) +#define BMM350_SEL_AXIS_POS UINT8_C(0x1) +#define BMM350_TMR_CFG_TEST_CLK_EN_MSK UINT8_C(0x10) +#define BMM350_TMR_CFG_TEST_CLK_EN_POS UINT8_C(0x4) +#define BMM350_TEST_VAL_BITS_7DOWNTO0_MSK UINT8_C(0xff) +#define BMM350_TEST_VAL_BITS_7DOWNTO0_POS UINT8_C(0x0) +#define BMM350_TEST_VAL_BITS_8_MSK UINT8_C(0x1) +#define BMM350_TEST_VAL_BITS_8_POS UINT8_C(0x0) +#define BMM350_TEST_P_SAMPLE_MSK UINT8_C(0x2) +#define BMM350_TEST_P_SAMPLE_POS UINT8_C(0x1) +#define BMM350_TEST_N_SAMPLE_MSK UINT8_C(0x4) +#define BMM350_TEST_N_SAMPLE_POS UINT8_C(0x2) +#define BMM350_TEST_APPLY_TO_REM_MSK UINT8_C(0x10) +#define BMM350_TEST_APPLY_TO_REM_POS UINT8_C(0x4) +#define BMM350_UFO_TRM_OSC_RANGE_MSK UINT8_C(0xf) +#define BMM350_UFO_TRM_OSC_RANGE_POS UINT8_C(0x0) +#define BMM350_ISO_CHIP_ID_MSK UINT8_C(0x78) +#define BMM350_ISO_CHIP_ID_POS UINT8_C(0x3) +#define BMM350_ISO_I2C_DEV_ID_MSK UINT8_C(0x80) +#define BMM350_ISO_I2C_DEV_ID_POS UINT8_C(0x7) +#define BMM350_I3C_FREQ_BITS_1DOWNTO0_MSK UINT8_C(0xc) +#define BMM350_I3C_FREQ_BITS_1DOWNTO0_POS UINT8_C(0x2) +#define BMM350_I3C_IBI_MDB_SEL_MSK UINT8_C(0x10) +#define BMM350_I3C_IBI_MDB_SEL_POS UINT8_C(0x4) +#define BMM350_TC_ASYNC_EN_MSK UINT8_C(0x20) +#define BMM350_TC_ASYNC_EN_POS UINT8_C(0x5) +#define BMM350_TC_SYNC_EN_MSK UINT8_C(0x40) +#define BMM350_TC_SYNC_EN_POS UINT8_C(0x6) +#define BMM350_I3C_SCL_GATING_EN_MSK UINT8_C(0x80) +#define BMM350_I3C_SCL_GATING_EN_POS UINT8_C(0x7) +#define BMM350_I3C_INACCURACY_BITS_6DOWNTO0_MSK UINT8_C(0x7f) +#define BMM350_I3C_INACCURACY_BITS_6DOWNTO0_POS UINT8_C(0x0) +#define BMM350_EST_EN_X_MSK UINT8_C(0x1) +#define BMM350_EST_EN_X_POS UINT8_C(0x0) +#define BMM350_EST_EN_Y_MSK UINT8_C(0x2) +#define BMM350_EST_EN_Y_POS UINT8_C(0x1) +#define BMM350_CRST_DIS_MSK UINT8_C(0x4) +#define BMM350_CRST_DIS_POS UINT8_C(0x2) +#define BMM350_BR_TFALL_MSK UINT8_C(0x7) +#define BMM350_BR_TFALL_POS UINT8_C(0x0) +#define BMM350_BR_TRISE_MSK UINT8_C(0x70) +#define BMM350_BR_TRISE_POS UINT8_C(0x4) +#define BMM350_TMR_SOFT_START_DIS_MSK UINT8_C(0x80) +#define BMM350_TMR_SOFT_START_DIS_POS UINT8_C(0x7) +#define BMM350_FOSC_LOW_RANGE_MSK UINT8_C(0x80) +#define BMM350_FOSC_LOW_RANGE_POS UINT8_C(0x7) +#define BMM350_VCRST_TRIM_FG_MSK UINT8_C(0x3f) +#define BMM350_VCRST_TRIM_FG_POS UINT8_C(0x0) +#define BMM350_VCRST_TRIM_BR_MSK UINT8_C(0x3f) +#define BMM350_VCRST_TRIM_BR_POS UINT8_C(0x0) +#define BMM350_BG_TRIM_VRP_MSK UINT8_C(0xc0) +#define BMM350_BG_TRIM_VRP_POS UINT8_C(0x6) +#define BMM350_BG_TRIM_TC_MSK UINT8_C(0xf) +#define BMM350_BG_TRIM_TC_POS UINT8_C(0x0) +#define BMM350_BG_TRIM_VRA_MSK UINT8_C(0xf0) +#define BMM350_BG_TRIM_VRA_POS UINT8_C(0x4) +#define BMM350_BG_TRIM_VRD_MSK UINT8_C(0xf) +#define BMM350_BG_TRIM_VRD_POS UINT8_C(0x0) +#define BMM350_OVWR_REF_IB_EN_MSK UINT8_C(0x10) +#define BMM350_OVWR_REF_IB_EN_POS UINT8_C(0x4) +#define BMM350_OVWR_VDDA_EN_MSK UINT8_C(0x20) +#define BMM350_OVWR_VDDA_EN_POS UINT8_C(0x5) +#define BMM350_OVWR_VDDP_EN_MSK UINT8_C(0x40) +#define BMM350_OVWR_VDDP_EN_POS UINT8_C(0x6) +#define BMM350_OVWR_VDDS_EN_MSK UINT8_C(0x80) +#define BMM350_OVWR_VDDS_EN_POS UINT8_C(0x7) +#define BMM350_REF_IB_EN_MSK UINT8_C(0x10) +#define BMM350_REF_IB_EN_POS UINT8_C(0x4) +#define BMM350_VDDA_EN_MSK UINT8_C(0x20) +#define BMM350_VDDA_EN_POS UINT8_C(0x5) +#define BMM350_VDDP_EN_MSK UINT8_C(0x40) +#define BMM350_VDDP_EN_POS UINT8_C(0x6) +#define BMM350_VDDS_EN_MSK UINT8_C(0x80) +#define BMM350_VDDS_EN_POS UINT8_C(0x7) +#define BMM350_OVWR_OTP_PROG_VDD_SW_EN_MSK UINT8_C(0x8) +#define BMM350_OVWR_OTP_PROG_VDD_SW_EN_POS UINT8_C(0x3) +#define BMM350_OVWR_EN_MFE_BG_FILT_BYPASS_MSK UINT8_C(0x10) +#define BMM350_OVWR_EN_MFE_BG_FILT_BYPASS_POS UINT8_C(0x4) +#define BMM350_OTP_PROG_VDD_SW_EN_MSK UINT8_C(0x8) +#define BMM350_OTP_PROG_VDD_SW_EN_POS UINT8_C(0x3) +#define BMM350_CP_COMP_CRST_EN_TM_MSK UINT8_C(0x10) +#define BMM350_CP_COMP_CRST_EN_TM_POS UINT8_C(0x4) +#define BMM350_CP_COMP_VDD_EN_TM_MSK UINT8_C(0x20) +#define BMM350_CP_COMP_VDD_EN_TM_POS UINT8_C(0x5) +#define BMM350_CP_INTREFS_EN_TM_MSK UINT8_C(0x40) +#define BMM350_CP_INTREFS_EN_TM_POS UINT8_C(0x6) +#define BMM350_ADC_LOCAL_CHOP_EN_MSK UINT8_C(0x20) +#define BMM350_ADC_LOCAL_CHOP_EN_POS UINT8_C(0x5) +#define BMM350_INA_MODE_MSK UINT8_C(0x40) +#define BMM350_INA_MODE_POS UINT8_C(0x6) +#define BMM350_VDDD_EXT_EN_MSK UINT8_C(0x20) +#define BMM350_VDDD_EXT_EN_POS UINT8_C(0x5) +#define BMM350_VDDP_EXT_EN_MSK UINT8_C(0x80) +#define BMM350_VDDP_EXT_EN_POS UINT8_C(0x7) +#define BMM350_ADC_DSENS_EN_MSK UINT8_C(0x10) +#define BMM350_ADC_DSENS_EN_POS UINT8_C(0x4) +#define BMM350_DSENS_EN_MSK UINT8_C(0x20) +#define BMM350_DSENS_EN_POS UINT8_C(0x5) +#define BMM350_OTP_TM_CLVWR_EN_MSK UINT8_C(0x40) +#define BMM350_OTP_TM_CLVWR_EN_POS UINT8_C(0x6) +#define BMM350_OTP_VDDP_DIS_MSK UINT8_C(0x80) +#define BMM350_OTP_VDDP_DIS_POS UINT8_C(0x7) +#define BMM350_FORCE_HIGH_VREF_IREF_OK_MSK UINT8_C(0x10) +#define BMM350_FORCE_HIGH_VREF_IREF_OK_POS UINT8_C(0x4) +#define BMM350_FORCE_HIGH_FOSC_OK_MSK UINT8_C(0x20) +#define BMM350_FORCE_HIGH_FOSC_OK_POS UINT8_C(0x5) +#define BMM350_FORCE_HIGH_MFE_BG_RDY_MSK UINT8_C(0x40) +#define BMM350_FORCE_HIGH_MFE_BG_RDY_POS UINT8_C(0x6) +#define BMM350_FORCE_HIGH_MFE_VTMR_RDY_MSK UINT8_C(0x80) +#define BMM350_FORCE_HIGH_MFE_VTMR_RDY_POS UINT8_C(0x7) +#define BMM350_ERR_END_OF_RECHARGE_MSK UINT8_C(0x1) +#define BMM350_ERR_END_OF_RECHARGE_POS UINT8_C(0x0) +#define BMM350_ERR_END_OF_DISCHARGE_MSK UINT8_C(0x2) +#define BMM350_ERR_END_OF_DISCHARGE_POS UINT8_C(0x1) +#define BMM350_CP_TMX_DIGTP_SEL_MSK UINT8_C(0x7) +#define BMM350_CP_TMX_DIGTP_SEL_POS UINT8_C(0x0) +#define BMM350_CP_CPOSC_EN_TM_MSK UINT8_C(0x80) +#define BMM350_CP_CPOSC_EN_TM_POS UINT8_C(0x7) +#define BMM350_TST_ATM1_CFG_MSK UINT8_C(0x3f) +#define BMM350_TST_ATM1_CFG_POS UINT8_C(0x0) +#define BMM350_TST_TB1_EN_MSK UINT8_C(0x80) +#define BMM350_TST_TB1_EN_POS UINT8_C(0x7) +#define BMM350_TST_ATM2_CFG_MSK UINT8_C(0x1f) +#define BMM350_TST_ATM2_CFG_POS UINT8_C(0x0) +#define BMM350_TST_TB2_EN_MSK UINT8_C(0x80) +#define BMM350_TST_TB2_EN_POS UINT8_C(0x7) +#define BMM350_REG_DTB1X_SEL_MSK UINT8_C(0x7f) +#define BMM350_REG_DTB1X_SEL_POS UINT8_C(0x0) +#define BMM350_SEL_DTB1X_PAD_MSK UINT8_C(0x80) +#define BMM350_SEL_DTB1X_PAD_POS UINT8_C(0x7) +#define BMM350_REG_DTB2X_SEL_MSK UINT8_C(0x7f) +#define BMM350_REG_DTB2X_SEL_POS UINT8_C(0x0) +#define BMM350_TMR_TST_CFG_MSK UINT8_C(0x7f) +#define BMM350_TMR_TST_CFG_POS UINT8_C(0x0) +#define BMM350_TMR_TST_HIZ_VTMR_MSK UINT8_C(0x80) +#define BMM350_TMR_TST_HIZ_VTMR_POS UINT8_C(0x7) + +/****************************** OTP MACROS ***************************/ +#define BMM350_OTP_CMD_DIR_READ UINT8_C(0x20) +#define BMM350_OTP_CMD_DIR_PRGM_1B UINT8_C(0x40) +#define BMM350_OTP_CMD_DIR_PRGM UINT8_C(0x60) +#define BMM350_OTP_CMD_PWR_OFF_OTP UINT8_C(0x80) +#define BMM350_OTP_CMD_EXT_READ UINT8_C(0xA0) +#define BMM350_OTP_CMD_EXT_PRGM UINT8_C(0xE0) +#define BMM350_OTP_CMD_MSK UINT8_C(0xE0) +#define BMM350_OTP_WORD_ADDR_MSK UINT8_C(0x1F) + +#define BMM350_OTP_STATUS_ERROR_MSK UINT8_C(0xE0) +#define BMM350_OTP_STATUS_ERROR(val) (val & BMM350_OTP_STATUS_ERROR_MSK) +#define BMM350_OTP_STATUS_NO_ERROR UINT8_C(0x00) +#define BMM350_OTP_STATUS_BOOT_ERR UINT8_C(0x20) +#define BMM350_OTP_STATUS_PAGE_RD_ERR UINT8_C(0x40) +#define BMM350_OTP_STATUS_PAGE_PRG_ERR UINT8_C(0x60) +#define BMM350_OTP_STATUS_SIGN_ERR UINT8_C(0x80) +#define BMM350_OTP_STATUS_INV_CMD_ERR UINT8_C(0xA0) +#define BMM350_OTP_STATUS_CMD_DONE UINT8_C(0x01) + +/****************************** OTP indices ***************************/ +#define BMM350_TEMP_OFF_SENS UINT8_C(0x0D) + +#define BMM350_MAG_OFFSET_X UINT8_C(0x0E) +#define BMM350_MAG_OFFSET_Y UINT8_C(0x0F) +#define BMM350_MAG_OFFSET_Z UINT8_C(0x10) + +#define BMM350_MAG_SENS_X UINT8_C(0x10) +#define BMM350_MAG_SENS_Y UINT8_C(0x11) +#define BMM350_MAG_SENS_Z UINT8_C(0x11) + +#define BMM350_MAG_TCO_X UINT8_C(0x12) +#define BMM350_MAG_TCO_Y UINT8_C(0x13) +#define BMM350_MAG_TCO_Z UINT8_C(0x14) + +#define BMM350_MAG_TCS_X UINT8_C(0x12) +#define BMM350_MAG_TCS_Y UINT8_C(0x13) +#define BMM350_MAG_TCS_Z UINT8_C(0x14) + +#define BMM350_MAG_DUT_T_0 UINT8_C(0x18) + +#define BMM350_CROSS_X_Y UINT8_C(0x15) +#define BMM350_CROSS_Y_X UINT8_C(0x15) +#define BMM350_CROSS_Z_X UINT8_C(0x16) +#define BMM350_CROSS_Z_Y UINT8_C(0x16) + +#define BMM350_SENS_CORR_Y (0.01f) +#define BMM350_TCS_CORR_Z (0.0001f) + +/**************************** Signed bit macros **********************/ +#define BMM350_SIGNED_8_BIT UINT8_C(8) +#define BMM350_SIGNED_12_BIT UINT8_C(12) +#define BMM350_SIGNED_16_BIT UINT8_C(16) +#define BMM350_SIGNED_21_BIT UINT8_C(21) +#define BMM350_SIGNED_24_BIT UINT8_C(24) + +/**************************** Self-test macros **********************/ +#define BMM350_SELF_TEST_DISABLE UINT8_C(0x00) +#define BMM350_SELF_TEST_POS_X UINT8_C(0x0D) +#define BMM350_SELF_TEST_NEG_X UINT8_C(0x0B) +#define BMM350_SELF_TEST_POS_Y UINT8_C(0x15) +#define BMM350_SELF_TEST_NEG_Y UINT8_C(0x13) + +#define BMM350_X_FM_XP_UST_MAX_LIMIT INT16_C(150) +#define BMM350_X_FM_XP_UST_MIN_LIMIT INT16_C(50) + +#define BMM350_X_FM_XN_UST_MAX_LIMIT INT16_C(-50) +#define BMM350_X_FM_XN_UST_MIN_LIMIT INT16_C(-150) + +#define BMM350_Y_FM_YP_UST_MAX_LIMIT INT16_C(150) +#define BMM350_Y_FM_YP_UST_MIN_LIMIT INT16_C(50) + +#define BMM350_Y_FM_YN_UST_MAX_LIMIT INT16_C(-50) +#define BMM350_Y_FM_YN_UST_MIN_LIMIT INT16_C(-150) + +/**************************** PMU command status 0 macros **********************/ +#define BMM350_PMU_CMD_STATUS_0_SUS UINT8_C(0x00) +#define BMM350_PMU_CMD_STATUS_0_NM UINT8_C(0x01) +#define BMM350_PMU_CMD_STATUS_0_UPD_OAE UINT8_C(0x02) +#define BMM350_PMU_CMD_STATUS_0_FM UINT8_C(0x03) +#define BMM350_PMU_CMD_STATUS_0_FM_FAST UINT8_C(0x04) +#define BMM350_PMU_CMD_STATUS_0_FGR UINT8_C(0x05) +#define BMM350_PMU_CMD_STATUS_0_FGR_FAST UINT8_C(0x06) +#define BMM350_PMU_CMD_STATUS_0_BR UINT8_C(0x07) +#define BMM350_PMU_CMD_STATUS_0_BR_FAST UINT8_C(0x07) + + +/**************************** PRESET MODE DEFINITIONS **********************/ +#define BMM350_PRESETMODE_LOWPOWER UINT8_C(0x01) +#define BMM350_PRESETMODE_REGULAR UINT8_C(0x02) +#define BMM350_PRESETMODE_HIGHACCURACY UINT8_C(0x03) +#define BMM350_PRESETMODE_ENHANCED UINT8_C(0x04) + +#define LOW_THRESHOLD_INTERRUPT 0 +#define HIGH_THRESHOLD_INTERRUPT 1 +#define INTERRUPT_X_ENABLE 0 +#define INTERRUPT_Y_ENABLE 0 +#define INTERRUPT_Z_ENABLE 0 +#define INTERRUPT_X_DISABLE 1 +#define INTERRUPT_Y_DISABLE 1 +#define INTERRUPT_Z_DISABLE 1 +#define ENABLE_INTERRUPT_PIN 1 +#define DISABLE_INTERRUPT_PIN 0 +#define NO_DATA -32768 + +#define I2C_ADDRESS 0x14 + +/****************************** Enumerators ***************************/ +enum eBmm350InterruptEnableDisable_t { + BMM350_DISABLE_INTERRUPT = BMM350_DISABLE, + BMM350_ENABLE_INTERRUPT = BMM350_ENABLE +}; + +enum eBmm350PowerModes_t { + eBmm350SuspendMode = BMM350_PMU_CMD_SUS, + eBmm350NormalMode = BMM350_PMU_CMD_NM, + eBmm350ForcedMode = BMM350_PMU_CMD_FM, + eBmm350ForcedModeFast = BMM350_PMU_CMD_FM_FAST +}; + +enum eBmm350DataRates_t { + BMM350_DATA_RATE_400HZ = BMM350_ODR_400HZ, + BMM350_DATA_RATE_200HZ = BMM350_ODR_200HZ, + BMM350_DATA_RATE_100HZ = BMM350_ODR_100HZ, + BMM350_DATA_RATE_50HZ = BMM350_ODR_50HZ, + BMM350_DATA_RATE_25HZ = BMM350_ODR_25HZ, + BMM350_DATA_RATE_12_5HZ = BMM350_ODR_12_5HZ, + BMM350_DATA_RATE_6_25HZ = BMM350_ODR_6_25HZ, + BMM350_DATA_RATE_3_125HZ = BMM350_ODR_3_125HZ, + BMM350_DATA_RATE_1_5625HZ = BMM350_ODR_1_5625HZ +}; + +enum bmm350_magreset_type { + BMM350_FLUXGUIDE_9MS = BMM350_PMU_CMD_FGR, + BMM350_FLUXGUIDE_FAST = BMM350_PMU_CMD_FGR_FAST, + BMM350_BITRESET_9MS = BMM350_PMU_CMD_BR, + BMM350_BITRESET_FAST = BMM350_PMU_CMD_BR_FAST, + BMM350_NOMAGRESET = UINT8_C(127) +}; + +enum bmm350_intr_en_dis { + BMM350_INTR_DISABLE = BMM350_DISABLE, + BMM350_INTR_ENABLE = BMM350_ENABLE +}; + +enum bmm350_intr_map { + BMM350_UNMAP_FROM_PIN = BMM350_DISABLE, + BMM350_MAP_TO_PIN = BMM350_ENABLE +}; +enum bmm350_intr_latch { + BMM350_PULSED = BMM350_INT_MODE_PULSED, + BMM350_LATCHED = BMM350_INT_MODE_LATCHED +}; + +enum eBmm350IntrPolarity_t { + BMM350_ACTIVE_LOW = BMM350_INT_POL_ACTIVE_LOW, + BMM350_ACTIVE_HIGH = BMM350_INT_POL_ACTIVE_HIGH +}; + +enum bmm350_intr_drive { + BMM350_INTR_OPEN_DRAIN = BMM350_INT_OD_OPENDRAIN, + BMM350_INTR_PUSH_PULL = BMM350_INT_OD_PUSHPULL +}; + +enum bmm350_drdy_int_map_to_ibi { + BMM350_IBI_DISABLE = BMM350_DISABLE, + BMM350_IBI_ENABLE = BMM350_ENABLE +}; + +enum bmm350_clear_drdy_int_status_upon_ibi { + BMM350_NOCLEAR_ON_IBI = BMM350_DISABLE, + BMM350_CLEAR_ON_IBI = BMM350_ENABLE +}; + +enum bmm350_i2c_wdt_en { + BMM350_I2C_WDT_DIS = BMM350_DISABLE, + BMM350_I2C_WDT_EN = BMM350_ENABLE +}; + +enum bmm350_i2c_wdt_sel { + BMM350_I2C_WDT_SEL_SHORT = BMM350_DISABLE, + BMM350_I2C_WDT_SEL_LONG = BMM350_ENABLE +}; + +enum bmm350_performance_parameters { + BMM350_NO_AVERAGING = BMM350_AVG_NO_AVG, + BMM350_AVERAGING_2 = BMM350_AVG_2, + BMM350_AVERAGING_4 = BMM350_AVG_4, + BMM350_AVERAGING_8 = BMM350_AVG_8, + /*lint -e849*/ + BMM350_ULTRALOWNOISE = BMM350_AVG_8, + BMM350_LOWNOISE = BMM350_AVG_4, + BMM350_REGULARPOWER = BMM350_AVG_2, + BMM350_LOWPOWER = BMM350_AVG_NO_AVG +}; + +enum bmm350_st_igen_en { + BMM350_ST_IGEN_DIS = BMM350_DISABLE, + BMM350_ST_IGEN_EN = BMM350_ENABLE +}; + +enum bmm350_st_n { + BMM350_ST_N_DIS = BMM350_DISABLE, + BMM350_ST_N_EN = BMM350_ENABLE +}; + +enum bmm350_st_p { + BMM350_ST_P_DIS = BMM350_DISABLE, + BMM350_ST_P_EN = BMM350_ENABLE +}; + +enum bmm350_ist_en_x { + BMM350_IST_X_DIS = BMM350_DISABLE, + BMM350_IST_X_EN = BMM350_ENABLE +}; + +enum bmm350_ist_en_y { + BMM350_IST_Y_DIS = BMM350_DISABLE, + BMM350_IST_Y_EN = BMM350_ENABLE +}; + +enum bmm350_ctrl_user { + BMM350_CFG_SENS_TIM_AON_DIS = BMM350_DISABLE, + BMM350_CFG_SENS_TIM_AON_EN = BMM350_ENABLE +}; + +enum eBmm350XAxisEnDis_t { + BMM350_X_DIS = BMM350_DISABLE, + BMM350_X_EN = BMM350_ENABLE +}; + +enum eBmm350YAxisEnDis_t { + BMM350_Y_DIS = BMM350_DISABLE, + BMM350_Y_EN = BMM350_ENABLE +}; + +enum eBmm350ZAxisEnDis_t { + BMM350_Z_DIS = BMM350_DISABLE, + BMM350_Z_EN = BMM350_ENABLE +}; + +/******************************************************************************/ +/*! @name Function Pointers */ +/******************************************************************************/ + +/*! + * @brief Bus communication function pointer which should be mapped to + * the platform specific read functions of the user + * + * @param[in] reg_addr : Register address from which data is read. + * @param[out] reg_data : Pointer to data buffer where read data is stored. + * @param[in] len : Number of bytes of data to be read. + * @param[in, out] intfPtr : Void pointer that can enable the linking of descriptors + * for interface related call backs. + * + * retval = 0 -> Success + * retval < 0 -> Failure + * + */ +typedef BMM350_INTF_RET_TYPE (*pBmm350ReadFptr_t)(uint8_t reg_addr, uint8_t *reg_data, uint32_t len, void *intfPtr); + +/*! + * @brief Bus communication function pointer which should be mapped to + * the platform specific write functions of the user + * + * @param[in] reg_addr : Register address to which the data is written. + * @param[in] reg_data : Pointer to data buffer in which data to be written + * is stored. + * @param[in] len : Number of bytes of data to be written. + * @param[in, out] intfPtr : Void pointer that can enable the linking of descriptors + * for interface related call backs + * + * retval = 0 -> Success + * retval < 0 -> Failure + * + */ +typedef BMM350_INTF_RET_TYPE (*pBmm350WriteFptr_t)(uint8_t reg_addr, const uint8_t *reg_data, uint32_t len, + void *intfPtr); + +/*! + * @brief Delay function pointer which should be mapped to + * delay function of the user + * + * @param[in] period : Delay in microseconds. + * @param[in, out] intfPtr : Void pointer that can enable the linking of descriptors + * for interface related call backs + * + */ +typedef void (*pBmm350DelayUsFptr_t)(uint32_t period, void *intfPtr); + +/* Pre-declaration */ +struct bmm350_dev; + +/*! + * @brief Function pointer for the magnetic reset and wait override + * + * @param[in] dev : Structure instance of bmm350_dev. + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +typedef int8_t (*bmm350_mraw_override_t)(struct bmm350_dev *dev); + +/************************* STRUCTURE DEFINITIONS *************************/ + +/*! + * @brief bmm350 un-compensated (raw) magnetometer data, signed integer + */ +struct bmm350_raw_mag_data +{ + /*! Raw mag X data */ + int32_t raw_xdata; + + /*! Raw mag Y data */ + int32_t raw_ydata; + + /*! Raw mag Z data */ + int32_t raw_zdata; + + /*! Raw mag temperature value */ + int32_t raw_data_t; +}; + +/*! + * @brief bmm350 compensated magnetometer data and temperature data + */ +struct sBmm350MagTempData_t +{ + /*! Compensated mag X data */ + float x; + + /*! Compensated mag Y data */ + float y; + + /*! Compensated mag Z data */ + float z; + + /*! Temperature */ + float temperature; +}; + +/*! + * @brief bmm350 magnetometer dut offset coefficient structure + */ +struct bmm350_dut_offset_coef +{ + /*! Temperature offset */ + float t_offs; + + /*! Offset x-axis */ + float offset_x; + + /*! Offset y-axis */ + float offset_y; + + /*! Offset z-axis */ + float offset_z; +}; + +/*! + * @brief bmm350 magnetometer dut sensitivity coefficient structure + */ +struct bmm350_dut_sensit_coef +{ + /*! Temperature sensitivity */ + float t_sens; + + /*! Sensitivity x-axis */ + float sens_x; + + /*! Sensitivity y-axis */ + float sens_y; + + /*! Sensitivity z-axis */ + float sens_z; +}; + +/*! + * @brief bmm350 magnetometer dut tco structure + */ +struct bmm350_dut_tco +{ + float tco_x; + float tco_y; + float tco_z; +}; + +/*! + * @brief bmm350 magnetometer dut tcs structure + */ +struct bmm350_dut_tcs +{ + float tcs_x; + float tcs_y; + float tcs_z; +}; + +/*! + * @brief bmm350 magnetometer cross axis compensation structure + */ +struct bmm350_cross_axis +{ + float cross_x_y; + float cross_y_x; + float cross_z_x; + float cross_z_y; +}; + +/*! + * @brief bmm350 magnetometer compensate structure + */ +struct bmm350_mag_compensate +{ + /*! Structure to store dut offset coefficient */ + struct bmm350_dut_offset_coef dut_offset_coef; + + /*! Structure to store dut sensitivity coefficient */ + struct bmm350_dut_sensit_coef dut_sensit_coef; + + /*! Structure to store dut tco */ + struct bmm350_dut_tco dut_tco; + + /*! Structure to store dut tcs */ + struct bmm350_dut_tcs dut_tcs; + + /*! Initialize T0_reading parameter */ + float dut_t0; + + /*! Structure to define cross axis compensation */ + struct bmm350_cross_axis cross_axis; +}; + +/*! + * @brief bmm350 device structure + */ +struct bmm350_dev +{ + /*! + * The interface pointer is used to enable the user + * to link their interface descriptors for reference during the + * implementation of the read and write interfaces to the + * hardware. + */ + void* intfPtr; + + /*! Chip Id of BMM350 */ + uint8_t chipId; + + /*! Bus read function pointer */ + pBmm350ReadFptr_t read; + + /*! Bus write function pointer */ + pBmm350WriteFptr_t write; + + /*! delay(in us) function pointer */ + pBmm350DelayUsFptr_t delayUs; + + /*! To store interface pointer error */ + BMM350_INTF_RET_TYPE intf_rslt; + + /*! Variable to store status of axes enabled */ + uint8_t axisEn; + + /*! Structure for mag compensate */ + struct bmm350_mag_compensate mag_comp; + + /*! Array to store OTP data */ + uint16_t otp_data[BMM350_OTP_DATA_LENGTH]; + + /*! Variant ID */ + uint8_t var_id; + + /*! Magnetic reset and wait override */ + bmm350_mraw_override_t mraw_override; + + /*! power mode */ + uint8_t powerMode; +}; + +/*! + * @brief bmm350 self-test structure + */ +struct sBmm350SelfTest_t +{ + /* Variable to store self-test data on x-axis */ + float out_ust_x; + + /* Variable to store self-test data on y-axis */ + float out_ust_y; +}; + +/*! + * @brief bmm350 PMU command status 0 structure + */ +struct bmm350_pmu_cmd_status_0 +{ + /*! The previous PMU CMD is still in processing */ + uint8_t pmu_cmd_busy; + + /*! The previous PMU_CMD_AGGR_SET.odr has been overwritten */ + uint8_t odr_ovwr; + + /*! The previous PMU_CMD_AGGR_SET.avg has been overwritten */ + uint8_t avr_ovwr; + + /*! The chip is in normal power mode */ + uint8_t pwr_mode_is_normal; + + /*! CMD value is not allowed */ + uint8_t cmd_is_illegal; + + /*! Stores the latest PMU_CMD code processed */ + uint8_t pmu_cmd_value; +}; + +/** + * @brief bmm350 compensated magnetometer data in int16_t format + */ +typedef struct{ + int32_t x; /**< compensated mag X data */ + int32_t y; /**< compensated mag Y data */ + int32_t z; /**< compensated mag Z data */ + int32_t temperature; /**< compensated temperature data */ + float float_x; + float float_y; + float float_z; + float float_temperature; +}sBmm350MagData_t; + +typedef struct{ + int16_t mag_x; /**< mag X data */ + int16_t mag_y; /**< mag Y data */ + int16_t mag_z; /**< mag Z data */ + uint8_t interrupt_x; /**< X-axis interrupt trigger flag*/ + uint8_t interrupt_y; /**< Y-axis interrupt trigger flag*/ + uint8_t interrupt_z; /**< Z-axis interrupt trigger flag*/ +}sBmm350ThresholdData_t; + +#endif /* _BMM350_DEFS_H */ diff --git a/lib/DFRobot_BMM350/src/bmm350_oor.c b/lib/DFRobot_BMM350/src/bmm350_oor.c new file mode 100644 index 0000000..c587891 --- /dev/null +++ b/lib/DFRobot_BMM350/src/bmm350_oor.c @@ -0,0 +1,329 @@ +/** +* Copyright (c) 2023 Bosch Sensortec GmbH. All rights reserved. +* +* BSD-3-Clause +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* 1. Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* +* 2. Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the distribution. +* +* 3. Neither the name of the copyright holder nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, +* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING +* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* @file bmm350_oor.c +* @date 2023-05-26 +* @version v1.4.0 +* +*/ + +#include "bmm350_oor.h" + +#ifdef BMM350_OOR_HALF_SELF_TEST + +/*! + * @brief This internal API is used to trigger half self-test + */ +static int8_t trigger_half_selftest(struct bmm350_oor_params *oor, struct bmm350_dev *dev) +{ + int8_t rslt = BMM350_OK; + + oor->st_cmd = BMM350_SELF_TEST_DISABLE; + + /* Trigger a self-test on every alternate measurement if needed */ + if (oor->enable_selftest) + { + oor->st_counter++; + + switch (oor->st_counter) + { + case 1: + oor->st_cmd = BMM350_SELF_TEST_POS_X; + break; + case 2: + oor->st_cmd = BMM350_SELF_TEST_DISABLE; + break; + case 3: + oor->st_cmd = BMM350_SELF_TEST_POS_Y; + break; + case 4: + oor->st_cmd = BMM350_SELF_TEST_DISABLE; + break; + + default: + oor->st_counter = 0; + oor->st_cmd = BMM350_SELF_TEST_DISABLE; + break; + } + + rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, &(oor->st_cmd), 1, dev); + } + else + { + if (oor->last_st_cmd != BMM350_SELF_TEST_DISABLE) + { + rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, &(oor->st_cmd), 1, dev); + oor->st_counter = 0; + } + } + + return rslt; +} + +/*! + * @brief This internal API is used to validate half self-test + */ +static void validate_half_selftest(const struct sBmm350MagTempData_t *data, struct bmm350_oor_params *oor) +{ + switch (oor->last_st_cmd) + { + case BMM350_SELF_TEST_DISABLE: + oor->mag_xn = data->x; + oor->mag_yn = data->y; + break; + + case BMM350_SELF_TEST_POS_X: + oor->mag_xp = data->x; + oor->x_failed = (oor->mag_xp - oor->mag_xn) < BMM350_HALF_ST_THRESHOLD ? true : false; + break; + + case BMM350_SELF_TEST_POS_Y: + oor->mag_yp = data->y; + oor->y_failed = (oor->mag_yp - oor->mag_yn) < BMM350_HALF_ST_THRESHOLD ? true : false; + break; + + default: + break; + } +} +#else + +/*! + * @brief This internal API is used to trigger full self-test + */ +static int8_t trigger_full_selftest(struct bmm350_oor_params *oor, struct bmm350_dev *dev) +{ + int8_t rslt = BMM350_OK; + + oor->st_cmd = BMM350_SELF_TEST_DISABLE; + + /* Trigger a self-test on every alternate measurement if needed */ + if (oor->enable_selftest) + { + oor->st_counter++; + + switch (oor->st_counter) + { + case 1: + oor->st_cmd = BMM350_SELF_TEST_POS_X; + break; + case 2: + oor->st_cmd = BMM350_SELF_TEST_NEG_X; + break; + case 3: + oor->st_cmd = BMM350_SELF_TEST_POS_Y; + break; + case 4: + oor->st_cmd = BMM350_SELF_TEST_NEG_Y; + break; + + default: + oor->st_counter = 0; + oor->st_cmd = BMM350_SELF_TEST_DISABLE; + break; + } + + rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, &(oor->st_cmd), 1, dev); + } + else + { + if (oor->last_st_cmd != BMM350_SELF_TEST_DISABLE) + { + rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, &(oor->st_cmd), 1, dev); + oor->st_counter = 0; + } + } + + return rslt; +} + +/*! + * @brief This internal API is used to validate full self-test + */ +static void validate_full_selftest(const struct sBmm350MagTempData_t *data, struct bmm350_oor_params *oor) +{ + switch (oor->last_st_cmd) + { + case BMM350_SELF_TEST_POS_X: + oor->mag_xp = data->x; + break; + + case BMM350_SELF_TEST_NEG_X: + oor->mag_xn = data->x; + oor->x_failed = (oor->mag_xp - oor->mag_xn) < BMM350_FULL_ST_THRESHOLD ? true : false; + break; + + case BMM350_SELF_TEST_POS_Y: + oor->mag_yp = data->y; + break; + + case BMM350_SELF_TEST_NEG_Y: + oor->mag_yn = data->y; + oor->y_failed = (oor->mag_yp - oor->mag_yn) < BMM350_FULL_ST_THRESHOLD ? true : false; + break; + + default: + break; + } +} +#endif + +/*! + * @brief This internal API is used to validate out of range. + */ +static void validate_out_of_range(bool *out_of_range, + const struct sBmm350MagTempData_t *data, + struct bmm350_oor_params *oor) +{ + float field_str = 0.0f; + + /* Threshold to start out of range detection */ + float threshold = BMM350_OUT_OF_RANGE_THRESHOLD; + + /* Threshold to start self-tests */ + float st_threshold = BMM350_SELF_TEST_THRESHOLD; + + /* If either self-test failed, alert that the sensor is out of range and continue self-tests */ + if (oor->x_failed || oor->y_failed) + { + *out_of_range = true; + oor->enable_selftest = true; + } + else + { + field_str = sqrtf((data->x * data->x) + (data->y * data->y) + (data->z * data->z)); + + /* Check for the self-test threshold and perform self-tests to catch if the sensor is out of range */ + if ((fabsf(data->x) >= st_threshold) || (fabsf(data->y) >= st_threshold) || (fabsf(data->z) >= st_threshold) || + (field_str >= st_threshold)) + { + oor->enable_selftest = true; + } + else if (oor->st_counter == 0) /* If a self-test procedure has started, wait for it to complete */ + { + oor->enable_selftest = false; + } + + /* If out of range was previously detected, reduce the threshold to get back in range, + * effectively preventing hysteresis. Selecting 400uT */ + if (*out_of_range) + { + threshold = BMM350_IN_RANGE_THRESHOLD; + } + + /* Check if X or Y or Z > the threshold or the magnitude of all 3 is greater */ + if ((fabsf(data->x) >= threshold) || (fabsf(data->y) >= threshold) || (fabsf(data->z) >= threshold) || + (field_str >= threshold)) + { + *out_of_range = true; + } + else if (oor->st_counter == 0) /* If a self-test procedure has started, wait for it to complete */ + { + *out_of_range = false; + } + } +} + +/*! + * @brief This API is used to perform reset sequence in forced mode. + */ +int8_t bmm350_oor_perform_reset_sequence_forced(struct bmm350_oor_params *oor, struct bmm350_dev *dev) +{ + int8_t rslt = 0; + uint8_t pmu_cmd = 0; + + oor->reset_counter++; + + switch (oor->reset_counter) + { + case 1: /* Trigger the Bit reset fast */ + pmu_cmd = BMM350_PMU_CMD_BR_FAST; + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); + break; + + case 2: /* Trigger Flux Guide reset */ + pmu_cmd = BMM350_PMU_CMD_FGR; + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); + break; + + case 3: /* Flux Guide dummy */ + break; + + default: /* Default acts like the Flux guide reset dummy */ + oor->reset_counter = 0; + oor->trigger_reset = false; + break; + } + + return rslt; +} + +/*! + * @brief This API is used to read out of range in half or full self-test. + */ +int8_t bmm350_oor_read(bool *out_of_range, + struct sBmm350MagTempData_t *data, + struct bmm350_oor_params *oor, + struct bmm350_dev *dev) +{ + int8_t rslt = 0; + uint8_t pmu_cmd = BMM350_PMU_CMD_SUS; + +#ifdef BMM350_OOR_HALF_SELF_TEST + rslt = trigger_half_selftest(oor, dev); +#else + rslt = trigger_full_selftest(oor, dev); +#endif + + if (rslt == BMM350_OK) + { + pmu_cmd = BMM350_PMU_CMD_FM_FAST; + rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); + + if (rslt == BMM350_OK) + { + rslt = bmm350GetCompensatedMagXYZTempData(data, dev); + } + } + +#ifdef BMM350_OOR_HALF_SELF_TEST + validate_half_selftest(data, oor); +#else + validate_full_selftest(data, oor); +#endif + + validate_out_of_range(out_of_range, data, oor); + + oor->last_st_cmd = oor->st_cmd; + + return rslt; +} diff --git a/lib/DFRobot_BMM350/src/bmm350_oor.h b/lib/DFRobot_BMM350/src/bmm350_oor.h new file mode 100644 index 0000000..41b3eb7 --- /dev/null +++ b/lib/DFRobot_BMM350/src/bmm350_oor.h @@ -0,0 +1,136 @@ +/** +* Copyright (c) 2023 Bosch Sensortec GmbH. All rights reserved. +* +* BSD-3-Clause +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* 1. Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* +* 2. Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the distribution. +* +* 3. Neither the name of the copyright holder nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, +* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING +* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* @file bmm350_oor.h +* @date 2023-05-26 +* @version v1.4.0 +* +*/ + +#ifndef _BMM350_OOR_H +#define _BMM350_OOR_H + +#include +#include + +#include "bmm350.h" + +/*! CPP guard */ +#ifdef __cplusplus +extern "C" { +#endif + +/******************************************************************************/ +/*! @name General Macro Definitions */ +/******************************************************************************/ + +/*! Macro to define half self-test for out of range + * NOTE: Comment this to use both positive and negative self tests */ +#define BMM350_OOR_HALF_SELF_TEST + +/*! Macro to define mag data minimum and maximum range in uT */ +#define BMM350_HALF_ST_THRESHOLD (130.0f) +#define BMM350_FULL_ST_THRESHOLD (300.0f) + +/*! Macro to define threshold values of in range, out of range and self-test */ +#define BMM350_IN_RANGE_THRESHOLD (2000.0f) +#define BMM350_OUT_OF_RANGE_THRESHOLD (2400.0f) +#define BMM350_SELF_TEST_THRESHOLD (2600.0f) + +/************************* Structure definitions *************************/ + +/*! + * @brief Structure to define bmm350 out of range parameters + */ +struct bmm350_oor_params +{ + /*! Counter to track what self test to trigger */ + uint8_t st_counter; + + /*! Current self-test command */ + uint8_t st_cmd; + + /*! Stores the last applied self test configuration */ + uint8_t last_st_cmd; + + /*! Store the last measurements for comparing against the self-test */ + float mag_xp, mag_xn, mag_yp, mag_yn; + + /*! Flags to track if the test failed to redo it */ + bool x_failed, y_failed; + + /*! Flags to enable self-test */ + bool enable_selftest; + + /*! Flags to trigger reset */ + bool trigger_reset; + + /*! Variable to store reset counter value */ + uint8_t reset_counter; +}; + +/******************* Function prototype declarations ********************/ + +/*! + * @brief Function to read data and validate if the sensor is out of range + * + * @param[in,out] out_of_range : Flag that indicates that the sensor is out of range + * @param[out] data : Sensor data + * @param[out] oor : Structure that stores the state of the out of range detector + * @param[in,out] dev : Device structure of the BMM350 + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +int8_t bmm350_oor_read(bool *out_of_range, + struct sBmm350MagTempData_t *data, + struct bmm350_oor_params *oor, + struct bmm350_dev *dev); + +/*! + * @brief Function to perform reset sequence in forced mode. + * + * @param[in,out] oor : Structure that stores the state of the out of range detector + * @param[in,out] dev : Structure instance of bmm350_dev. + * + * @return Result of API execution status + * @retval = 0 -> Success + * @retval < 0 -> Error + */ +int8_t bmm350_oor_perform_reset_sequence_forced(struct bmm350_oor_params *oor, struct bmm350_dev *dev); + +#ifdef __cplusplus +} +#endif /* End of CPP guard */ + +#endif /* _BMM350_OOR_H */ diff --git a/pid_test.csv b/pid_test.csv index 11adc7a..84b9113 100644 --- a/pid_test.csv +++ b/pid_test.csv @@ -1,755 +1,727 @@ -EncoderLeft,EncoderRight,DesiredVelocityLeft,DesiredVelocityRight,CurrentVelocityLeft,CurrentVelocityRight,LeftPower,RightPower,EncoderTargetLeft,EncoderTargetRight -0,0,100.00,100.00,0.00,0.00,0.21,0.19,120000,120000 -6,5,400.00,350.00,300.00,250.00,0.21,0.19,120000,120000 -18,14,700.00,550.00,600.00,450.00,0.21,0.19,120000,120000 -26,16,500.00,200.00,400.00,100.00,0.21,0.19,120000,120000 -39,16,750.00,100.00,650.00,0.00,0.21,0.19,120000,120000 -86,16,2450.00,100.00,2350.00,0.00,0.21,0.19,120000,120000 -134,16,2500.00,100.00,2400.00,0.00,0.21,0.19,120000,120000 -191,17,2950.00,150.00,2850.00,50.00,0.21,0.19,120000,120000 -264,17,3750.00,100.00,3650.00,0.00,0.21,0.19,120000,120000 -343,17,4000.00,100.00,3950.00,0.00,0.10,0.19,120000,120000 -420,17,3950.00,100.00,3850.00,0.00,0.21,0.19,120000,120000 -487,17,3450.00,100.00,3350.00,0.00,0.21,0.19,120000,120000 -570,17,4000.00,100.00,4150.00,0.00,-0.31,0.19,120000,120000 -624,18,2800.00,150.00,2700.00,50.00,0.21,0.19,120000,120000 -616,18,-300.00,100.00,-400.00,0.00,0.21,0.19,120000,120000 -618,19,200.00,150.00,100.00,50.00,0.21,0.19,120000,120000 -619,19,150.00,100.00,50.00,0.00,0.21,0.19,120000,120000 -621,19,200.00,100.00,100.00,0.00,0.21,0.19,120000,120000 -625,19,300.00,100.00,200.00,0.00,0.21,0.19,120000,120000 -635,19,600.00,100.00,500.00,0.00,0.21,0.19,120000,120000 -675,19,2100.00,100.00,2000.00,0.00,0.21,0.19,120000,120000 -726,19,2650.00,100.00,2550.00,0.00,0.21,0.19,120000,120000 -787,20,3150.00,150.00,3050.00,50.00,0.21,0.19,120000,120000 -857,21,3600.00,150.00,3500.00,50.00,0.21,0.19,120000,120000 -933,21,3900.00,100.00,3800.00,0.00,0.21,0.19,120000,120000 -1018,21,4000.00,100.00,4250.00,0.00,-0.52,0.19,120000,120000 -1066,23,2500.00,200.00,2400.00,100.00,0.21,0.19,120000,120000 -1049,25,-750.00,200.00,-850.00,100.00,0.21,0.19,120000,120000 -1074,32,1350.00,450.00,1250.00,350.00,0.21,0.19,120000,120000 -1098,55,1300.00,1250.00,1200.00,1150.00,0.21,0.19,120000,120000 -1141,96,2250.00,2150.00,2150.00,2050.00,0.21,0.19,120000,120000 -1196,145,2850.00,2550.00,2750.00,2450.00,0.21,0.19,120000,120000 -1260,197,3300.00,2700.00,3200.00,2600.00,0.21,0.19,120000,120000 -1338,267,4000.00,3600.00,3900.00,3500.00,0.21,0.19,120000,120000 -1419,337,4000.00,3600.00,4050.00,3500.00,-0.10,0.19,120000,120000 -1502,415,4000.00,4000.00,4150.00,3900.00,-0.31,0.19,120000,120000 -1550,496,2500.00,4000.00,2400.00,4050.00,0.21,-0.10,120000,120000 -1535,580,-650.00,4000.00,-750.00,4200.00,0.21,-0.38,120000,120000 -1546,613,650.00,1750.00,550.00,1650.00,0.21,0.19,120000,120000 -1553,579,450.00,-1600.00,350.00,-1700.00,0.21,0.19,120000,120000 -1556,597,250.00,1000.00,150.00,900.00,0.21,0.19,120000,120000 -1559,632,250.00,1850.00,150.00,1750.00,0.21,0.19,120000,120000 -1568,684,550.00,2700.00,450.00,2600.00,0.21,0.19,120000,120000 -1600,739,1700.00,2850.00,1600.00,2750.00,0.21,0.19,120000,120000 -1644,805,2300.00,3400.00,2200.00,3300.00,0.21,0.19,120000,120000 -1702,875,3000.00,3600.00,2900.00,3500.00,0.21,0.19,120000,120000 -1770,956,3500.00,4000.00,3400.00,4050.00,0.21,-0.10,120000,120000 -1847,1035,3950.00,4000.00,3850.00,3950.00,0.21,0.10,120000,120000 -1934,1100,4000.00,3350.00,4350.00,3250.00,-0.72,0.19,120000,120000 -1960,1156,1400.00,2900.00,1300.00,2800.00,0.21,0.19,120000,120000 -1880,1223,-4000.00,3450.00,-4000.00,3350.00,0.00,0.19,120000,120000 -1838,1297,-2000.00,3800.00,-2100.00,3700.00,0.21,0.19,120000,120000 -1820,1373,-800.00,3900.00,-900.00,3800.00,0.21,0.19,120000,120000 -1823,1458,250.00,4000.00,150.00,4250.00,0.21,-0.48,120000,120000 -1840,1506,950.00,2500.00,850.00,2400.00,0.21,0.19,120000,120000 -1882,1473,2200.00,-1550.00,2100.00,-1650.00,0.21,0.19,120000,120000 -1934,1466,2700.00,-250.00,2600.00,-350.00,0.21,0.19,120000,120000 -1993,1481,3050.00,850.00,2950.00,750.00,0.21,0.19,120000,120000 -2065,1492,3700.00,650.00,3600.00,550.00,0.21,0.19,120000,120000 -2144,1505,4000.00,750.00,3950.00,650.00,0.10,0.19,120000,120000 -2226,1541,4000.00,1900.00,4100.00,1800.00,-0.21,0.19,120000,120000 -2281,1585,2850.00,2300.00,2750.00,2200.00,0.21,0.19,120000,120000 -2290,1639,550.00,2800.00,450.00,2700.00,0.21,0.19,120000,120000 -2304,1707,800.00,3500.00,700.00,3400.00,0.21,0.19,120000,120000 -2341,1776,1950.00,3550.00,1850.00,3450.00,0.21,0.19,120000,120000 -2388,1852,2450.00,3900.00,2350.00,3800.00,0.21,0.19,120000,120000 -2447,1937,3050.00,4000.00,2950.00,4250.00,0.21,-0.48,120000,120000 -2514,1980,3450.00,2250.00,3350.00,2150.00,0.21,0.19,120000,120000 -2593,1956,4000.00,-1100.00,3950.00,-1200.00,0.10,0.19,120000,120000 -2678,1953,4000.00,-50.00,4250.00,-150.00,-0.52,0.19,120000,120000 -2700,1961,1200.00,500.00,1100.00,400.00,0.21,0.19,120000,120000 -2642,1983,-2800.00,1200.00,-2900.00,1100.00,0.21,0.19,120000,120000 -2646,2028,300.00,2350.00,200.00,2250.00,0.21,0.19,120000,120000 -2686,2077,2100.00,2550.00,2000.00,2450.00,0.21,0.19,120000,120000 -2736,2134,2600.00,2950.00,2500.00,2850.00,0.21,0.19,120000,120000 -2797,2205,3150.00,3650.00,3050.00,3550.00,0.21,0.19,120000,120000 -2868,2279,3650.00,3800.00,3550.00,3700.00,0.21,0.19,120000,120000 -2948,2361,4000.00,4000.00,4000.00,4100.00,0.00,-0.19,120000,120000 -3027,2425,4000.00,3300.00,3950.00,3200.00,0.10,0.19,120000,120000 -3097,2450,3600.00,1350.00,3500.00,1250.00,0.21,0.19,120000,120000 -3157,2490,3100.00,2100.00,3000.00,2000.00,0.21,0.19,120000,120000 -3239,2549,4000.00,3050.00,4100.00,2950.00,-0.21,0.19,120000,120000 -3294,2604,2850.00,2850.00,2750.00,2750.00,0.21,0.19,120000,120000 -3307,2673,750.00,3550.00,650.00,3450.00,0.21,0.19,120000,120000 -3348,2744,2150.00,3650.00,2050.00,3550.00,0.21,0.19,120000,120000 -3390,2825,2200.00,4000.00,2100.00,4050.00,0.21,-0.10,120000,120000 -3458,2905,3500.00,4000.00,3400.00,4000.00,0.21,0.00,120000,120000 -3534,2970,3900.00,3350.00,3800.00,3250.00,0.21,0.19,120000,120000 -3615,3026,4000.00,2900.00,4050.00,2800.00,-0.10,0.19,120000,120000 -3696,3094,4000.00,3500.00,4050.00,3400.00,-0.10,0.19,120000,120000 -3762,3167,3400.00,3750.00,3300.00,3650.00,0.21,0.19,120000,120000 -3821,3243,3050.00,3900.00,2950.00,3800.00,0.21,0.19,120000,120000 -3896,3327,3850.00,4000.00,3750.00,4200.00,0.21,-0.38,120000,120000 -3974,3374,4000.00,2450.00,3900.00,2350.00,0.21,0.19,120000,120000 -4056,3363,4000.00,-450.00,4100.00,-550.00,-0.21,0.19,120000,120000 -4126,3371,3600.00,500.00,3500.00,400.00,0.21,0.19,120000,120000 -4159,3405,1750.00,1800.00,1650.00,1700.00,0.21,0.19,120000,120000 -4202,3447,2250.00,2200.00,2150.00,2100.00,0.21,0.19,120000,120000 -4251,3504,2550.00,2950.00,2450.00,2850.00,0.21,0.19,120000,120000 -4322,3571,3650.00,3450.00,3550.00,3350.00,0.21,0.19,120000,120000 -4396,3643,3800.00,3700.00,3700.00,3600.00,0.21,0.19,120000,120000 -4478,3722,4000.00,4000.00,4100.00,3950.00,-0.21,0.10,120000,120000 -4544,3797,3400.00,3850.00,3300.00,3750.00,0.21,0.19,120000,120000 -4566,3863,1200.00,3400.00,1100.00,3300.00,0.21,0.19,120000,120000 -4602,3941,1900.00,4000.00,1800.00,3900.00,0.21,0.19,120000,120000 -4652,4021,2600.00,4000.00,2500.00,4000.00,0.21,0.00,120000,120000 -4718,4101,3400.00,4000.00,3300.00,4000.00,0.21,0.00,120000,120000 -4790,4164,3700.00,3250.00,3600.00,3150.00,0.21,0.19,120000,120000 -4870,4220,4000.00,2900.00,4000.00,2800.00,0.00,0.19,120000,120000 -4952,4291,4000.00,3650.00,4100.00,3550.00,-0.21,0.19,120000,120000 -5005,4361,2750.00,3600.00,2650.00,3500.00,0.21,0.19,120000,120000 -5021,4441,900.00,4000.00,800.00,4000.00,0.21,0.00,120000,120000 -5038,4520,950.00,4000.00,850.00,3950.00,0.21,0.10,120000,120000 -5081,4585,2250.00,3350.00,2150.00,3250.00,0.21,0.19,120000,120000 -5135,4643,2800.00,3000.00,2700.00,2900.00,0.21,0.19,120000,120000 -5196,4709,3150.00,3400.00,3050.00,3300.00,0.21,0.19,120000,120000 -5267,4781,3650.00,3700.00,3550.00,3600.00,0.21,0.19,120000,120000 -5346,4857,4000.00,3900.00,3950.00,3800.00,0.10,0.19,120000,120000 -5426,4940,4000.00,4000.00,4000.00,4150.00,0.00,-0.29,120000,120000 -5493,4999,3450.00,3050.00,3350.00,2950.00,0.21,0.19,120000,120000 -5555,5005,3200.00,400.00,3100.00,300.00,0.21,0.19,120000,120000 -5628,5011,3750.00,400.00,3650.00,300.00,0.21,0.19,120000,120000 -5704,5013,3900.00,200.00,3800.00,100.00,0.21,0.19,120000,120000 -5789,5013,4000.00,100.00,4250.00,0.00,-0.52,0.19,120000,120000 -5831,5013,2200.00,100.00,2100.00,0.00,0.21,0.19,120000,120000 -5785,5015,-2200.00,200.00,-2300.00,100.00,0.21,0.19,120000,120000 -5792,5017,450.00,200.00,350.00,100.00,0.21,0.19,120000,120000 -5826,5023,1800.00,400.00,1700.00,300.00,0.21,0.19,120000,120000 -5875,5041,2550.00,1000.00,2450.00,900.00,0.21,0.19,120000,120000 -5934,5083,3050.00,2200.00,2950.00,2100.00,0.21,0.19,120000,120000 -6003,5134,3550.00,2650.00,3450.00,2550.00,0.21,0.19,120000,120000 -6082,5190,4000.00,2900.00,3950.00,2800.00,0.10,0.19,120000,120000 -6160,5261,4000.00,3650.00,3900.00,3550.00,0.21,0.19,120000,120000 -6231,5333,3650.00,3700.00,3550.00,3600.00,0.21,0.19,120000,120000 -6309,5413,4000.00,4000.00,3900.00,4000.00,0.21,0.00,120000,120000 -6395,5493,4000.00,4000.00,4300.00,4000.00,-0.62,0.00,120000,120000 -6430,5559,1850.00,3400.00,1750.00,3300.00,0.21,0.19,120000,120000 -6362,5618,-3300.00,3050.00,-3400.00,2950.00,0.21,0.19,120000,120000 -6336,5685,-1200.00,3450.00,-1300.00,3350.00,0.21,0.19,120000,120000 -6343,5755,450.00,3600.00,350.00,3500.00,0.21,0.19,120000,120000 -6354,5832,650.00,3950.00,550.00,3850.00,0.21,0.19,120000,120000 -6366,5917,700.00,4000.00,600.00,4250.00,0.21,-0.48,120000,120000 -6400,5960,1800.00,2250.00,1700.00,2150.00,0.21,0.19,120000,120000 -6442,5916,2200.00,-2100.00,2100.00,-2200.00,0.21,0.19,120000,120000 -6504,5924,3200.00,500.00,3100.00,400.00,0.21,0.19,120000,120000 -6570,5957,3400.00,1750.00,3300.00,1650.00,0.21,0.19,120000,120000 -6650,6000,4000.00,2250.00,4000.00,2150.00,0.00,0.19,120000,120000 -6732,6052,4000.00,2700.00,4100.00,2600.00,-0.21,0.19,120000,120000 -6780,6110,2500.00,3000.00,2400.00,2900.00,0.21,0.19,120000,120000 -6813,6179,1750.00,3550.00,1650.00,3450.00,0.21,0.19,120000,120000 -6846,6253,1750.00,3800.00,1650.00,3700.00,0.21,0.19,120000,120000 -6898,6333,2700.00,4000.00,2600.00,4000.00,0.21,0.00,120000,120000 -6959,6415,3150.00,4000.00,3050.00,4100.00,0.21,-0.19,120000,120000 -7031,6465,3700.00,2600.00,3600.00,2500.00,0.21,0.19,120000,120000 -7114,6483,4000.00,1000.00,4150.00,900.00,-0.31,0.19,120000,120000 -7172,6501,3000.00,1000.00,2900.00,900.00,0.21,0.19,120000,120000 -7175,6535,250.00,1800.00,150.00,1700.00,0.21,0.19,120000,120000 -7218,6585,2250.00,2600.00,2150.00,2500.00,0.21,0.19,120000,120000 -7259,6639,2150.00,2800.00,2050.00,2700.00,0.21,0.19,120000,120000 -7319,6704,3100.00,3350.00,3000.00,3250.00,0.21,0.19,120000,120000 -7386,6773,3450.00,3550.00,3350.00,3450.00,0.21,0.19,120000,120000 -7462,6847,3900.00,3800.00,3800.00,3700.00,0.21,0.19,120000,120000 -7550,6929,4000.00,4000.00,4400.00,4100.00,-0.83,-0.19,120000,120000 -7586,7000,1900.00,3650.00,1800.00,3550.00,0.21,0.19,120000,120000 -7504,7029,-4000.00,1550.00,-4100.00,1450.00,0.21,0.19,120000,120000 -7475,7076,-1350.00,2450.00,-1450.00,2350.00,0.21,0.19,120000,120000 -7476,7123,150.00,2450.00,50.00,2350.00,0.21,0.19,120000,120000 -7484,7182,500.00,3050.00,400.00,2950.00,0.21,0.19,120000,120000 -7494,7247,600.00,3350.00,500.00,3250.00,0.21,0.19,120000,120000 -7513,7318,1050.00,3650.00,950.00,3550.00,0.21,0.19,120000,120000 -7558,7400,2350.00,4000.00,2250.00,4100.00,0.21,-0.19,120000,120000 -7612,7463,2800.00,3250.00,2700.00,3150.00,0.21,0.19,120000,120000 -7677,7491,3350.00,1500.00,3250.00,1400.00,0.21,0.19,120000,120000 -7748,7525,3650.00,1800.00,3550.00,1700.00,0.21,0.19,120000,120000 -7826,7563,4000.00,2000.00,3900.00,1900.00,0.21,0.19,120000,120000 -7914,7614,4000.00,2650.00,4400.00,2550.00,-0.83,0.19,120000,120000 -7937,7675,1250.00,3150.00,1150.00,3050.00,0.21,0.19,120000,120000 -7840,7735,-4000.00,3100.00,-4850.00,3000.00,1.00,0.19,120000,120000 -7846,7806,400.00,3650.00,300.00,3550.00,0.21,0.19,120000,120000 -8014,7886,4000.00,4000.00,8400.00,4000.00,-1.00,0.00,120000,120000 -8110,7957,4000.00,3650.00,4800.00,3550.00,-1.00,0.19,120000,120000 -7954,8021,-4000.00,3300.00,-7800.00,3200.00,1.00,0.19,120000,120000 -7718,8092,-4000.00,3650.00,-11800.00,3550.00,1.00,0.19,120000,120000 -7768,8165,2600.00,3750.00,2500.00,3650.00,0.21,0.19,120000,120000 -7988,8235,4000.00,3600.00,11000.00,3500.00,-1.00,0.19,120000,120000 -8138,8314,4000.00,4000.00,7500.00,3950.00,-1.00,0.10,120000,120000 -8031,8387,-4000.00,3750.00,-5350.00,3650.00,1.00,0.19,120000,120000 -7839,8452,-4000.00,3350.00,-9600.00,3250.00,1.00,0.19,120000,120000 -7924,8520,4000.00,3500.00,4250.00,3400.00,-0.52,0.19,120000,120000 -8117,8590,4000.00,3600.00,9650.00,3500.00,-1.00,0.19,120000,120000 -8118,8661,150.00,3650.00,50.00,3550.00,0.21,0.19,120000,120000 -7970,8739,-4000.00,4000.00,-7400.00,3900.00,1.00,0.19,120000,120000 -7938,8822,-1500.00,4000.00,-1600.00,4150.00,0.21,-0.29,120000,120000 -8074,8876,4000.00,2800.00,6800.00,2700.00,-1.00,0.19,120000,120000 -8148,8873,3800.00,-50.00,3700.00,-150.00,0.21,0.19,120000,120000 -8062,8872,-4000.00,50.00,-4300.00,-50.00,0.62,0.19,120000,120000 -8067,8877,350.00,350.00,250.00,250.00,0.21,0.19,120000,120000 -8170,8879,4000.00,200.00,5150.00,100.00,-1.00,0.19,120000,120000 -8212,8880,2200.00,150.00,2100.00,50.00,0.21,0.19,120000,120000 -8096,8880,-4000.00,100.00,-5800.00,0.00,1.00,0.19,120000,120000 -8082,8882,-600.00,200.00,-700.00,100.00,0.21,0.19,120000,120000 -8227,8883,4000.00,150.00,7250.00,50.00,-1.00,0.19,120000,120000 -8304,8885,3950.00,200.00,3850.00,100.00,0.21,0.19,120000,120000 -8214,8890,-4000.00,350.00,-4500.00,250.00,1.00,0.19,120000,120000 -8224,8904,600.00,800.00,500.00,700.00,0.21,0.19,120000,120000 -8382,8936,4000.00,1700.00,7900.00,1600.00,-1.00,0.19,120000,120000 -8477,8971,4000.00,1850.00,4750.00,1750.00,-1.00,0.19,120000,120000 -8339,9017,-4000.00,2400.00,-6900.00,2300.00,1.00,0.19,120000,120000 -8138,9067,-4000.00,2600.00,-10050.00,2500.00,1.00,0.19,120000,120000 -8188,9121,2600.00,2800.00,2500.00,2700.00,0.21,0.19,120000,120000 -8405,9174,4000.00,2750.00,10850.00,2650.00,-1.00,0.19,120000,120000 -8550,9237,4000.00,3250.00,7250.00,3150.00,-1.00,0.19,120000,120000 -8443,9301,-4000.00,3300.00,-5350.00,3200.00,1.00,0.19,120000,120000 -8266,9366,-4000.00,3350.00,-8850.00,3250.00,1.00,0.19,120000,120000 -8338,9433,3700.00,3450.00,3600.00,3350.00,0.21,0.19,120000,120000 -8566,9505,4000.00,3700.00,11400.00,3600.00,-1.00,0.19,120000,120000 -8712,9577,4000.00,3700.00,7300.00,3600.00,-1.00,0.19,120000,120000 -8604,9653,-4000.00,3900.00,-5400.00,3800.00,1.00,0.19,120000,120000 -8417,9729,-4000.00,3900.00,-9350.00,3800.00,1.00,0.19,120000,120000 -8464,9805,2450.00,3900.00,2350.00,3800.00,0.21,0.19,120000,120000 -8672,9883,4000.00,4000.00,10400.00,3900.00,-1.00,0.19,120000,120000 -8810,9965,4000.00,4000.00,6900.00,4100.00,-1.00,-0.19,120000,120000 -8700,10033,-4000.00,3500.00,-5500.00,3400.00,1.00,0.19,120000,120000 -8513,10069,-4000.00,1900.00,-9350.00,1800.00,1.00,0.19,120000,120000 -8599,10111,4000.00,2200.00,4300.00,2100.00,-0.62,0.19,120000,120000 -8786,10158,4000.00,2450.00,9350.00,2350.00,-1.00,0.19,120000,120000 -8775,10207,-450.00,2550.00,-550.00,2450.00,0.21,0.19,120000,120000 -8630,10265,-4000.00,3000.00,-7250.00,2900.00,1.00,0.19,120000,120000 -8602,10326,-1300.00,3150.00,-1400.00,3050.00,0.21,0.19,120000,120000 -8745,10397,4000.00,3650.00,7150.00,3550.00,-1.00,0.19,120000,120000 -8819,10467,3800.00,3600.00,3700.00,3500.00,0.21,0.19,120000,120000 -8734,10542,-4000.00,3850.00,-4250.00,3750.00,0.52,0.19,120000,120000 -8730,10629,-100.00,4000.00,-200.00,4350.00,0.21,-0.67,120000,120000 -8829,10653,4000.00,1300.00,4950.00,1200.00,-1.00,0.19,120000,120000 -8860,10560,1650.00,-4000.00,1550.00,-4650.00,0.21,1.00,120000,120000 -8747,10551,-4000.00,-350.00,-5650.00,-450.00,1.00,0.19,120000,120000 -8735,10714,-500.00,4000.00,-600.00,8150.00,0.21,-1.00,120000,120000 -8894,10809,4000.00,4000.00,7950.00,4750.00,-1.00,-1.00,120000,120000 -8995,10665,4000.00,-4000.00,5050.00,-7200.00,-1.00,1.00,120000,120000 -8913,10491,-4000.00,-4000.00,-4100.00,-8700.00,0.21,1.00,120000,120000 -8746,10551,-4000.00,3100.00,-8350.00,3000.00,1.00,0.19,120000,120000 -8696,10783,-2400.00,4000.00,-2500.00,11600.00,0.21,-1.00,120000,120000 -8819,10939,4000.00,4000.00,6150.00,7800.00,-1.00,-1.00,120000,120000 -8894,10854,3850.00,-4000.00,3750.00,-4250.00,0.21,0.48,120000,120000 -8832,10711,-3000.00,-4000.00,-3100.00,-7150.00,0.21,1.00,120000,120000 -8808,10761,-1100.00,2600.00,-1200.00,2500.00,0.21,0.19,120000,120000 -8808,10988,100.00,4000.00,0.00,11350.00,0.21,-1.00,120000,120000 -8817,11141,550.00,4000.00,450.00,7650.00,0.21,-1.00,120000,120000 -8817,11034,100.00,-4000.00,0.00,-5350.00,0.21,1.00,120000,120000 -8817,10849,100.00,-4000.00,0.00,-9250.00,0.21,1.00,120000,120000 -8816,10945,50.00,4000.00,-50.00,4800.00,0.21,-1.00,120000,120000 -8817,11133,150.00,4000.00,50.00,9400.00,0.21,-1.00,120000,120000 -8816,11078,50.00,-2650.00,-50.00,-2750.00,0.21,0.19,120000,120000 -8819,10877,250.00,-4000.00,150.00,-10050.00,0.21,1.00,120000,120000 -8824,10807,350.00,-3400.00,250.00,-3500.00,0.21,0.19,120000,120000 -8828,10923,300.00,4000.00,200.00,5800.00,0.21,-1.00,120000,120000 -8846,10984,1000.00,3150.00,900.00,3050.00,0.21,0.19,120000,120000 -8886,10890,2100.00,-4000.00,2000.00,-4700.00,0.21,1.00,120000,120000 -8932,10893,2400.00,250.00,2300.00,150.00,0.21,0.19,120000,120000 -8984,11074,2700.00,4000.00,2600.00,9050.00,0.21,-1.00,120000,120000 -9045,11186,3150.00,4000.00,3050.00,5600.00,0.21,-1.00,120000,120000 -9114,11052,3550.00,-4000.00,3450.00,-6700.00,0.21,1.00,120000,120000 -9186,10851,3700.00,-4000.00,3600.00,-10050.00,0.21,1.00,120000,120000 -9262,10923,3900.00,3700.00,3800.00,3600.00,0.21,0.19,120000,120000 -9338,11161,3900.00,4000.00,3800.00,11900.00,0.21,-1.00,120000,120000 -9420,11330,4000.00,4000.00,4100.00,8450.00,-0.21,-1.00,120000,120000 -9489,11253,3550.00,-3750.00,3450.00,-3850.00,0.21,0.19,120000,120000 -9525,11045,1900.00,-4000.00,1800.00,-10400.00,0.21,1.00,120000,120000 -9570,10975,2350.00,-3400.00,2250.00,-3500.00,0.21,0.19,120000,120000 -9625,11112,2850.00,4000.00,2750.00,6850.00,0.21,-1.00,120000,120000 -9686,11191,3150.00,4000.00,3050.00,3950.00,0.21,0.10,120000,120000 -9756,11097,3600.00,-4000.00,3500.00,-4700.00,0.21,1.00,120000,120000 -9833,11068,3950.00,-1350.00,3850.00,-1450.00,0.21,0.19,120000,120000 -9914,11211,4000.00,4000.00,4050.00,7150.00,-0.10,-1.00,120000,120000 -9996,11294,4000.00,4000.00,4100.00,4150.00,-0.21,-0.29,120000,120000 -10050,11179,2800.00,-4000.00,2700.00,-5750.00,0.21,1.00,120000,120000 -10078,11110,1500.00,-3350.00,1400.00,-3450.00,0.21,0.19,120000,120000 -10096,11246,1000.00,4000.00,900.00,6800.00,0.21,-1.00,120000,120000 -10124,11327,1500.00,4000.00,1400.00,4050.00,0.21,-0.10,120000,120000 -10166,11234,2200.00,-4000.00,2100.00,-4650.00,0.21,1.00,120000,120000 -10223,11200,2950.00,-1600.00,2850.00,-1700.00,0.21,0.19,120000,120000 -10287,11356,3300.00,4000.00,3200.00,7800.00,0.21,-1.00,120000,120000 -10356,11443,3550.00,4000.00,3450.00,4350.00,0.21,-0.67,120000,120000 -10427,11307,3650.00,-4000.00,3550.00,-6800.00,0.21,1.00,120000,120000 -10509,11145,4000.00,-4000.00,4100.00,-8100.00,-0.21,1.00,120000,120000 -10570,11255,3150.00,4000.00,3050.00,5500.00,0.21,-1.00,120000,120000 -10610,11451,2100.00,4000.00,2000.00,9800.00,0.21,-1.00,120000,120000 -10642,11389,1700.00,-3000.00,1600.00,-3100.00,0.21,0.19,120000,120000 -10697,11189,2850.00,-4000.00,2750.00,-10000.00,0.21,1.00,120000,120000 -10756,11123,3050.00,-3200.00,2950.00,-3300.00,0.21,0.19,120000,120000 -10819,11267,3250.00,4000.00,3150.00,7200.00,0.21,-1.00,120000,120000 -10890,11352,3650.00,4000.00,3550.00,4250.00,0.21,-0.48,120000,120000 -10964,11226,3800.00,-4000.00,3700.00,-6300.00,0.21,1.00,120000,120000 -11050,11113,4000.00,-4000.00,4300.00,-5650.00,-0.62,1.00,120000,120000 -11094,11265,2300.00,4000.00,2200.00,7600.00,0.21,-1.00,120000,120000 -11052,11478,-2000.00,4000.00,-2100.00,10650.00,0.21,-1.00,120000,120000 -11058,11420,400.00,-2800.00,300.00,-2900.00,0.21,0.19,120000,120000 -11088,11223,1600.00,-4000.00,1500.00,-9850.00,0.21,1.00,120000,120000 -11122,11159,1800.00,-3100.00,1700.00,-3200.00,0.21,0.19,120000,120000 -11166,11292,2300.00,4000.00,2200.00,6650.00,0.21,-1.00,120000,120000 -11221,11375,2850.00,4000.00,2750.00,4150.00,0.21,-0.29,120000,120000 -11277,11261,2900.00,-4000.00,2800.00,-5700.00,0.21,1.00,120000,120000 -11350,11189,3750.00,-3500.00,3650.00,-3600.00,0.21,0.19,120000,120000 -11421,11315,3650.00,4000.00,3550.00,6300.00,0.21,-1.00,120000,120000 -11498,11381,3950.00,3400.00,3850.00,3300.00,0.21,0.19,120000,120000 -11579,11293,4000.00,-4000.00,4050.00,-4400.00,-0.10,0.76,120000,120000 -11668,11291,4000.00,0.00,4450.00,-100.00,-0.93,0.19,120000,120000 -11664,11424,-100.00,4000.00,-200.00,6650.00,0.21,-1.00,120000,120000 -11504,11493,-4000.00,3550.00,-8000.00,3450.00,1.00,0.19,120000,120000 -11478,11371,-1200.00,-4000.00,-1300.00,-6100.00,0.21,1.00,120000,120000 -11606,11346,4000.00,-1150.00,6400.00,-1250.00,-1.00,0.19,120000,120000 -11672,11489,3400.00,4000.00,3300.00,7150.00,0.21,-1.00,120000,120000 -11580,11572,-4000.00,4000.00,-4600.00,4150.00,1.00,-0.29,120000,120000 -11586,11459,400.00,-4000.00,300.00,-5650.00,0.21,1.00,120000,120000 -11736,11395,4000.00,-3100.00,7500.00,-3200.00,-1.00,0.19,120000,120000 -11823,11528,4000.00,4000.00,4350.00,6650.00,-0.72,-1.00,120000,120000 -11699,11605,-4000.00,3950.00,-6200.00,3850.00,1.00,0.19,120000,120000 -11588,11541,-4000.00,-3100.00,-5550.00,-3200.00,1.00,0.19,120000,120000 -11697,11505,4000.00,-1700.00,5450.00,-1800.00,-1.00,0.19,120000,120000 -11882,11521,4000.00,900.00,9250.00,800.00,-1.00,0.19,120000,120000 -11805,11553,-3750.00,1700.00,-3850.00,1600.00,0.21,0.19,120000,120000 -11585,11585,-4000.00,1700.00,-11000.00,1600.00,1.00,0.19,120000,120000 -11506,11640,-3850.00,2850.00,-3950.00,2750.00,0.21,0.19,120000,120000 -11622,11693,4000.00,2750.00,5800.00,2650.00,-1.00,0.19,120000,120000 -11676,11754,2800.00,3150.00,2700.00,3050.00,0.21,0.19,120000,120000 -11586,11817,-4000.00,3250.00,-4500.00,3150.00,1.00,0.19,120000,120000 -11608,11886,1200.00,3550.00,1100.00,3450.00,0.21,0.19,120000,120000 -11766,11957,4000.00,3650.00,7900.00,3550.00,-1.00,0.19,120000,120000 -11868,12035,4000.00,4000.00,5100.00,3900.00,-1.00,0.19,120000,120000 -11744,12111,-4000.00,3900.00,-6200.00,3800.00,1.00,0.19,120000,120000 -11548,12195,-4000.00,4000.00,-9800.00,4200.00,1.00,-0.38,120000,120000 -11588,12247,2100.00,2700.00,2000.00,2600.00,0.21,0.19,120000,120000 -11779,12265,4000.00,1000.00,9550.00,900.00,-1.00,0.19,120000,120000 -11898,12286,4000.00,1150.00,5950.00,1050.00,-1.00,0.19,120000,120000 -11760,12298,-4000.00,700.00,-6900.00,600.00,1.00,0.19,120000,120000 -11559,12325,-4000.00,1450.00,-10050.00,1350.00,1.00,0.19,120000,120000 -11592,12355,1750.00,1600.00,1650.00,1500.00,0.21,0.19,120000,120000 -11787,12384,4000.00,1550.00,9750.00,1450.00,-1.00,0.19,120000,120000 -11909,12435,4000.00,2650.00,6100.00,2550.00,-1.00,0.19,120000,120000 -11780,12485,-4000.00,2600.00,-6450.00,2500.00,1.00,0.19,120000,120000 -11581,12541,-4000.00,2900.00,-9950.00,2800.00,1.00,0.19,120000,120000 -11634,12591,2750.00,2600.00,2650.00,2500.00,0.21,0.19,120000,120000 -11846,12653,4000.00,3200.00,10600.00,3100.00,-1.00,0.19,120000,120000 -11993,12727,4000.00,3800.00,7350.00,3700.00,-1.00,0.19,120000,120000 -11906,12795,-4000.00,3500.00,-4350.00,3400.00,0.72,0.19,120000,120000 -11724,12873,-4000.00,4000.00,-9100.00,3900.00,1.00,0.19,120000,120000 -11774,12952,2600.00,4000.00,2500.00,3950.00,0.21,0.10,120000,120000 -11986,13021,4000.00,3550.00,10600.00,3450.00,-1.00,0.19,120000,120000 -12126,13083,4000.00,3200.00,7000.00,3100.00,-1.00,0.19,120000,120000 -12029,13151,-4000.00,3500.00,-4850.00,3400.00,1.00,0.19,120000,120000 -11856,13221,-4000.00,3600.00,-8650.00,3500.00,1.00,0.19,120000,120000 -11930,13293,3800.00,3700.00,3700.00,3600.00,0.21,0.19,120000,120000 -12163,13364,4000.00,3650.00,11650.00,3550.00,-1.00,0.19,120000,120000 -12320,13439,4000.00,3850.00,7850.00,3750.00,-1.00,0.19,120000,120000 -12229,13521,-4000.00,4000.00,-4550.00,4100.00,1.00,-0.19,120000,120000 -12056,13588,-4000.00,3450.00,-8650.00,3350.00,1.00,0.19,120000,120000 -12136,13625,4000.00,1950.00,4000.00,1850.00,0.00,0.19,120000,120000 -12362,13662,4000.00,1950.00,11300.00,1850.00,-1.00,0.19,120000,120000 -12488,13702,4000.00,2100.00,6300.00,2000.00,-1.00,0.19,120000,120000 -12360,13755,-4000.00,2750.00,-6400.00,2650.00,1.00,0.19,120000,120000 -12166,13811,-4000.00,2900.00,-9700.00,2800.00,1.00,0.19,120000,120000 -12214,13869,2500.00,3000.00,2400.00,2900.00,0.21,0.19,120000,120000 -12422,13928,4000.00,3050.00,10400.00,2950.00,-1.00,0.19,120000,120000 -12553,13993,4000.00,3350.00,6550.00,3250.00,-1.00,0.19,120000,120000 -12436,14059,-4000.00,3400.00,-5850.00,3300.00,1.00,0.19,120000,120000 -12250,14130,-4000.00,3650.00,-9300.00,3550.00,1.00,0.19,120000,120000 -12314,14204,3300.00,3800.00,3200.00,3700.00,0.21,0.19,120000,120000 -12540,14277,4000.00,3750.00,11300.00,3650.00,-1.00,0.19,120000,120000 -12690,14353,4000.00,3900.00,7500.00,3800.00,-1.00,0.19,120000,120000 -12580,14433,-4000.00,4000.00,-5500.00,4000.00,1.00,0.00,120000,120000 -12384,14513,-4000.00,4000.00,-9800.00,4000.00,1.00,0.00,120000,120000 -12454,14577,3600.00,3300.00,3500.00,3200.00,0.21,0.19,120000,120000 -12686,14632,4000.00,2850.00,11600.00,2750.00,-1.00,0.19,120000,120000 -12845,14697,4000.00,3350.00,7950.00,3250.00,-1.00,0.19,120000,120000 -12731,14761,-4000.00,3300.00,-5700.00,3200.00,1.00,0.19,120000,120000 -12538,14832,-4000.00,3650.00,-9650.00,3550.00,1.00,0.19,120000,120000 -12590,14900,2700.00,3500.00,2600.00,3400.00,0.21,0.19,120000,120000 -12806,14970,4000.00,3600.00,10800.00,3500.00,-1.00,0.19,120000,120000 -12950,15046,4000.00,3900.00,7200.00,3800.00,-1.00,0.19,120000,120000 -12830,15125,-4000.00,4000.00,-6000.00,3950.00,1.00,0.10,120000,120000 -12639,15201,-4000.00,3900.00,-9550.00,3800.00,1.00,0.19,120000,120000 -12716,15264,3950.00,3250.00,3850.00,3150.00,0.21,0.19,120000,120000 -12953,15333,4000.00,3550.00,11850.00,3450.00,-1.00,0.19,120000,120000 -13110,15401,4000.00,3500.00,7850.00,3400.00,-1.00,0.19,120000,120000 -12972,15487,-4000.00,4000.00,-6900.00,4300.00,1.00,-0.57,120000,120000 -12747,15531,-4000.00,2300.00,-11250.00,2200.00,1.00,0.19,120000,120000 -12766,15521,1050.00,-400.00,950.00,-500.00,0.21,0.19,120000,120000 -12954,15539,4000.00,1000.00,9400.00,900.00,-1.00,0.19,120000,120000 -13074,15564,4000.00,1350.00,6000.00,1250.00,-1.00,0.19,120000,120000 -12963,15596,-4000.00,1700.00,-5550.00,1600.00,1.00,0.19,120000,120000 -12782,15633,-4000.00,1950.00,-9050.00,1850.00,1.00,0.19,120000,120000 -12857,15677,3850.00,2300.00,3750.00,2200.00,0.21,0.19,120000,120000 -13090,15721,4000.00,2300.00,11650.00,2200.00,-1.00,0.19,120000,120000 -13252,15776,4000.00,2850.00,8100.00,2750.00,-1.00,0.19,120000,120000 -13162,15833,-4000.00,2950.00,-4500.00,2850.00,1.00,0.19,120000,120000 -12999,15895,-4000.00,3200.00,-8150.00,3100.00,1.00,0.19,120000,120000 -13060,15955,3150.00,3100.00,3050.00,3000.00,0.21,0.19,120000,120000 -13286,16021,4000.00,3400.00,11300.00,3300.00,-1.00,0.19,120000,120000 -13426,16087,4000.00,3400.00,7000.00,3300.00,-1.00,0.19,120000,120000 -13313,16159,-4000.00,3700.00,-5650.00,3600.00,1.00,0.19,120000,120000 -13118,16232,-4000.00,3750.00,-9750.00,3650.00,1.00,0.19,120000,120000 -13185,16304,3450.00,3700.00,3350.00,3600.00,0.21,0.19,120000,120000 -13422,16381,4000.00,3950.00,11850.00,3850.00,-1.00,0.19,120000,120000 -13578,16464,4000.00,4000.00,7800.00,4150.00,-1.00,-0.29,120000,120000 -13478,16524,-4000.00,3100.00,-5000.00,3000.00,1.00,0.19,120000,120000 -13307,16545,-4000.00,1150.00,-8550.00,1050.00,1.00,0.19,120000,120000 -13376,16548,3550.00,250.00,3450.00,150.00,0.21,0.19,120000,120000 -13602,16546,4000.00,0.00,11300.00,-100.00,-1.00,0.19,120000,120000 -13754,16545,4000.00,50.00,7600.00,-50.00,-1.00,0.19,120000,120000 -13646,16542,-4000.00,-50.00,-5400.00,-150.00,1.00,0.19,120000,120000 -13454,16541,-4000.00,50.00,-9600.00,-50.00,1.00,0.19,120000,120000 -13514,16541,3100.00,100.00,3000.00,0.00,0.21,0.19,120000,120000 -13731,16543,4000.00,200.00,10850.00,100.00,-1.00,0.19,120000,120000 -13874,16543,4000.00,100.00,7150.00,0.00,-1.00,0.19,120000,120000 -13784,16541,-4000.00,0.00,-4500.00,-100.00,1.00,0.19,120000,120000 -13610,16541,-4000.00,100.00,-8700.00,0.00,1.00,0.19,120000,120000 -13666,16541,2900.00,100.00,2800.00,0.00,0.21,0.19,120000,120000 -13878,16543,4000.00,200.00,10600.00,100.00,-1.00,0.19,120000,120000 -14018,16544,4000.00,150.00,7000.00,50.00,-1.00,0.19,120000,120000 -13902,16542,-4000.00,0.00,-5800.00,-100.00,1.00,0.19,120000,120000 -13702,16542,-4000.00,100.00,-10000.00,0.00,1.00,0.19,120000,120000 -13765,16541,3250.00,50.00,3150.00,-50.00,0.21,0.19,120000,120000 -13988,16543,4000.00,200.00,11150.00,100.00,-1.00,0.19,120000,120000 -14141,16544,4000.00,150.00,7650.00,50.00,-1.00,0.19,120000,120000 -14046,16542,-4000.00,0.00,-4750.00,-100.00,1.00,0.19,120000,120000 -13871,16541,-4000.00,50.00,-8750.00,-50.00,1.00,0.19,120000,120000 -13924,16541,2750.00,100.00,2650.00,0.00,0.21,0.19,120000,120000 -14144,16544,4000.00,250.00,11000.00,150.00,-1.00,0.19,120000,120000 -14287,16545,4000.00,150.00,7150.00,50.00,-1.00,0.19,120000,120000 -14170,16542,-4000.00,-50.00,-5850.00,-150.00,1.00,0.19,120000,120000 -13970,16542,-4000.00,100.00,-10000.00,0.00,1.00,0.19,120000,120000 -14023,16541,2750.00,50.00,2650.00,-50.00,0.21,0.19,120000,120000 -14239,16543,4000.00,200.00,10800.00,100.00,-1.00,0.19,120000,120000 -14388,16544,4000.00,150.00,7450.00,50.00,-1.00,0.19,120000,120000 -14301,16542,-4000.00,0.00,-4350.00,-100.00,0.72,0.19,120000,120000 -14130,16543,-4000.00,150.00,-8550.00,50.00,1.00,0.19,120000,120000 -14167,16543,1950.00,100.00,1850.00,0.00,0.21,0.19,120000,120000 -14362,16543,4000.00,100.00,9750.00,0.00,-1.00,0.19,120000,120000 -14489,16544,4000.00,150.00,6350.00,50.00,-1.00,0.19,120000,120000 -14357,16542,-4000.00,0.00,-6600.00,-100.00,1.00,0.19,120000,120000 -14154,16542,-4000.00,100.00,-10150.00,0.00,1.00,0.19,120000,120000 -14198,16542,2300.00,100.00,2200.00,0.00,0.21,0.19,120000,120000 -14410,16543,4000.00,150.00,10600.00,50.00,-1.00,0.19,120000,120000 -14546,16544,4000.00,150.00,6800.00,50.00,-1.00,0.19,120000,120000 -14428,16542,-4000.00,0.00,-5900.00,-100.00,1.00,0.19,120000,120000 -14232,16542,-4000.00,100.00,-9800.00,0.00,1.00,0.19,120000,120000 -14291,16541,3050.00,50.00,2950.00,-50.00,0.21,0.19,120000,120000 -14520,16543,4000.00,200.00,11450.00,100.00,-1.00,0.19,120000,120000 -14674,16544,4000.00,150.00,7700.00,50.00,-1.00,0.19,120000,120000 -14584,16542,-4000.00,0.00,-4500.00,-100.00,1.00,0.19,120000,120000 -14418,16542,-4000.00,100.00,-8300.00,0.00,1.00,0.19,120000,120000 -14489,16541,3650.00,50.00,3550.00,-50.00,0.21,0.19,120000,120000 -14726,16544,4000.00,250.00,11850.00,150.00,-1.00,0.19,120000,120000 -14884,16544,4000.00,100.00,7900.00,0.00,-1.00,0.19,120000,120000 -14786,16542,-4000.00,0.00,-4900.00,-100.00,1.00,0.19,120000,120000 -14612,16541,-4000.00,50.00,-8700.00,-50.00,1.00,0.19,120000,120000 -14676,16541,3300.00,100.00,3200.00,0.00,0.21,0.19,120000,120000 -14904,16544,4000.00,250.00,11400.00,150.00,-1.00,0.19,120000,120000 -15054,16544,4000.00,100.00,7500.00,0.00,-1.00,0.19,120000,120000 -14966,16541,-4000.00,-50.00,-4400.00,-150.00,0.83,0.19,120000,120000 -14782,16542,-4000.00,150.00,-9200.00,50.00,1.00,0.19,120000,120000 -14877,16542,4000.00,100.00,4750.00,0.00,-1.00,0.19,120000,120000 -15055,16541,4000.00,50.00,8900.00,-50.00,-1.00,0.19,120000,120000 -15002,16541,-2550.00,100.00,-2650.00,0.00,0.21,0.19,120000,120000 -14822,16544,-4000.00,250.00,-9000.00,150.00,1.00,0.19,120000,120000 -14766,16545,-2700.00,150.00,-2800.00,50.00,0.21,0.19,120000,120000 -14878,16544,4000.00,50.00,5600.00,-50.00,-1.00,0.19,120000,120000 -14934,16545,2900.00,150.00,2800.00,50.00,0.21,0.19,120000,120000 -14846,16544,-4000.00,50.00,-4400.00,-50.00,0.83,0.19,120000,120000 -14863,16545,950.00,150.00,850.00,50.00,0.21,0.19,120000,120000 -14993,16546,4000.00,150.00,6500.00,50.00,-1.00,0.19,120000,120000 -15071,16545,4000.00,50.00,3900.00,-50.00,0.21,0.19,120000,120000 -15000,16545,-3450.00,100.00,-3550.00,0.00,0.21,0.19,120000,120000 -14987,16548,-550.00,250.00,-650.00,150.00,0.21,0.19,120000,120000 -15018,16549,1650.00,150.00,1550.00,50.00,0.21,0.19,120000,120000 -15063,16549,2350.00,100.00,2250.00,0.00,0.21,0.19,120000,120000 -15122,16551,3050.00,200.00,2950.00,100.00,0.21,0.19,120000,120000 -15194,16551,3700.00,100.00,3600.00,0.00,0.21,0.19,120000,120000 -15275,16552,4000.00,150.00,4050.00,50.00,-0.10,0.19,120000,120000 -15360,16553,4000.00,150.00,4250.00,50.00,-0.52,0.19,120000,120000 -15394,16555,1800.00,200.00,1700.00,100.00,0.21,0.19,120000,120000 -15378,16555,-700.00,100.00,-800.00,0.00,0.21,0.19,120000,120000 -15406,16557,1500.00,200.00,1400.00,100.00,0.21,0.19,120000,120000 -15442,16558,1900.00,150.00,1800.00,50.00,0.21,0.19,120000,120000 -15494,16564,2700.00,400.00,2600.00,300.00,0.21,0.19,120000,120000 -15558,16585,3300.00,1150.00,3200.00,1050.00,0.21,0.19,120000,120000 -15632,16629,3800.00,2300.00,3700.00,2200.00,0.21,0.19,120000,120000 -15710,16681,4000.00,2700.00,3900.00,2600.00,0.21,0.19,120000,120000 -15800,16742,4000.00,3150.00,4500.00,3050.00,-1.00,0.19,120000,120000 -15826,16813,1400.00,3650.00,1300.00,3550.00,0.21,0.19,120000,120000 -15720,16882,-4000.00,3550.00,-5300.00,3450.00,1.00,0.19,120000,120000 -15727,16962,450.00,4000.00,350.00,4000.00,0.21,0.00,120000,120000 -15897,17035,4000.00,3750.00,8500.00,3650.00,-1.00,0.19,120000,120000 -16003,17101,4000.00,3400.00,5300.00,3300.00,-1.00,0.19,120000,120000 -15880,17167,-4000.00,3400.00,-6150.00,3300.00,1.00,0.19,120000,120000 -15691,17233,-4000.00,3400.00,-9450.00,3300.00,1.00,0.19,120000,120000 -15740,17303,2550.00,3600.00,2450.00,3500.00,0.21,0.19,120000,120000 -15951,17373,4000.00,3600.00,10550.00,3500.00,-1.00,0.19,120000,120000 -16086,17447,4000.00,3800.00,6750.00,3700.00,-1.00,0.19,120000,120000 -15962,17528,-4000.00,4000.00,-6200.00,4050.00,1.00,-0.10,120000,120000 -15756,17604,-4000.00,3900.00,-10300.00,3800.00,1.00,0.19,120000,120000 -15806,17668,2600.00,3300.00,2500.00,3200.00,0.21,0.19,120000,120000 -16029,17740,4000.00,3700.00,11150.00,3600.00,-1.00,0.19,120000,120000 -16172,17816,4000.00,3900.00,7150.00,3800.00,-1.00,0.19,120000,120000 -16051,17888,-4000.00,3700.00,-6050.00,3600.00,1.00,0.19,120000,120000 -15850,17964,-4000.00,3900.00,-10050.00,3800.00,1.00,0.19,120000,120000 -15916,18037,3400.00,3750.00,3300.00,3650.00,0.21,0.19,120000,120000 -16142,18114,4000.00,3950.00,11300.00,3850.00,-1.00,0.19,120000,120000 -16300,18195,4000.00,4000.00,7900.00,4050.00,-1.00,-0.10,120000,120000 -16187,18273,-4000.00,4000.00,-5650.00,3900.00,1.00,0.19,120000,120000 -15996,18339,-4000.00,3400.00,-9550.00,3300.00,1.00,0.19,120000,120000 -16058,18408,3200.00,3550.00,3100.00,3450.00,0.21,0.19,120000,120000 -16284,18474,4000.00,3400.00,11300.00,3300.00,-1.00,0.19,120000,120000 -16438,18549,4000.00,3850.00,7700.00,3750.00,-1.00,0.19,120000,120000 -16326,18621,-4000.00,3700.00,-5600.00,3600.00,1.00,0.19,120000,120000 -16145,18696,-4000.00,3850.00,-9050.00,3750.00,1.00,0.19,120000,120000 -16198,18772,2750.00,3900.00,2650.00,3800.00,0.21,0.19,120000,120000 -16410,18846,4000.00,3800.00,10600.00,3700.00,-1.00,0.19,120000,120000 -16553,18929,4000.00,4000.00,7150.00,4150.00,-1.00,-0.29,120000,120000 -16442,18987,-4000.00,3000.00,-5550.00,2900.00,1.00,0.19,120000,120000 -16256,19008,-4000.00,1150.00,-9300.00,1050.00,1.00,0.19,120000,120000 -16328,19018,3700.00,600.00,3600.00,500.00,0.21,0.19,120000,120000 -16554,19025,4000.00,450.00,11300.00,350.00,-1.00,0.19,120000,120000 -16702,19042,4000.00,950.00,7400.00,850.00,-1.00,0.19,120000,120000 -16595,19080,-4000.00,2000.00,-5350.00,1900.00,1.00,0.19,120000,120000 -16415,19115,-4000.00,1850.00,-9000.00,1750.00,1.00,0.19,120000,120000 -16473,19159,3000.00,2300.00,2900.00,2200.00,0.21,0.19,120000,120000 -16686,19205,4000.00,2400.00,10650.00,2300.00,-1.00,0.19,120000,120000 -16828,19255,4000.00,2600.00,7100.00,2500.00,-1.00,0.19,120000,120000 -16710,19310,-4000.00,2850.00,-5900.00,2750.00,1.00,0.19,120000,120000 -16511,19375,-4000.00,3350.00,-9950.00,3250.00,1.00,0.19,120000,120000 -16571,19435,3100.00,3100.00,3000.00,3000.00,0.21,0.19,120000,120000 -16794,19499,4000.00,3300.00,11150.00,3200.00,-1.00,0.19,120000,120000 -16945,19570,4000.00,3650.00,7550.00,3550.00,-1.00,0.19,120000,120000 -16838,19641,-4000.00,3650.00,-5350.00,3550.00,1.00,0.19,120000,120000 -16651,19715,-4000.00,3800.00,-9350.00,3700.00,1.00,0.19,120000,120000 -16768,19802,4000.00,4000.00,5850.00,4350.00,-1.00,-0.67,120000,120000 -16976,19833,4000.00,1650.00,10400.00,1550.00,-1.00,0.19,120000,120000 -16958,19797,-800.00,-1700.00,-900.00,-1800.00,0.21,0.19,120000,120000 -16799,19794,-4000.00,-50.00,-7950.00,-150.00,1.00,0.19,120000,120000 -16761,19817,-1800.00,1250.00,-1900.00,1150.00,0.21,0.19,120000,120000 -16887,19834,4000.00,950.00,6300.00,850.00,-1.00,0.19,120000,120000 -16952,19873,3350.00,2050.00,3250.00,1950.00,0.21,0.19,120000,120000 -16857,19912,-4000.00,2050.00,-4750.00,1950.00,1.00,0.19,120000,120000 -16876,19968,1050.00,2900.00,950.00,2800.00,0.21,0.19,120000,120000 -17036,20023,4000.00,2850.00,8000.00,2750.00,-1.00,0.19,120000,120000 -17141,20085,4000.00,3200.00,5250.00,3100.00,-1.00,0.19,120000,120000 -17004,20150,-4000.00,3350.00,-6850.00,3250.00,1.00,0.19,120000,120000 -16795,20219,-4000.00,3550.00,-10450.00,3450.00,1.00,0.19,120000,120000 -16854,20288,3050.00,3550.00,2950.00,3450.00,0.21,0.19,120000,120000 -17074,20355,4000.00,3450.00,11000.00,3350.00,-1.00,0.19,120000,120000 -17223,20428,4000.00,3750.00,7450.00,3650.00,-1.00,0.19,120000,120000 -17119,20498,-4000.00,3600.00,-5200.00,3500.00,1.00,0.19,120000,120000 -16934,20576,-4000.00,4000.00,-9250.00,3900.00,1.00,0.19,120000,120000 -16990,20651,2900.00,3850.00,2800.00,3750.00,0.21,0.19,120000,120000 -17202,20726,4000.00,3850.00,10600.00,3750.00,-1.00,0.19,120000,120000 -17341,20807,4000.00,4000.00,6950.00,4050.00,-1.00,-0.10,120000,120000 -17241,20881,-4000.00,3800.00,-5000.00,3700.00,1.00,0.19,120000,120000 -17056,20947,-4000.00,3400.00,-9250.00,3300.00,1.00,0.19,120000,120000 -17128,21016,3700.00,3550.00,3600.00,3450.00,0.21,0.19,120000,120000 -17354,21089,4000.00,3750.00,11300.00,3650.00,-1.00,0.19,120000,120000 -17509,21163,4000.00,3800.00,7750.00,3700.00,-1.00,0.19,120000,120000 -17404,21240,-4000.00,3950.00,-5250.00,3850.00,1.00,0.19,120000,120000 -17218,21318,-4000.00,4000.00,-9300.00,3900.00,1.00,0.19,120000,120000 -17278,21398,3100.00,4000.00,3000.00,4000.00,0.21,0.00,120000,120000 -17506,21472,4000.00,3800.00,11400.00,3700.00,-1.00,0.19,120000,120000 -17651,21533,4000.00,3150.00,7250.00,3050.00,-1.00,0.19,120000,120000 -17557,21595,-4000.00,3200.00,-4700.00,3100.00,1.00,0.19,120000,120000 -17379,21665,-4000.00,3600.00,-8900.00,3500.00,1.00,0.19,120000,120000 -17456,21734,3950.00,3550.00,3850.00,3450.00,0.21,0.19,120000,120000 -17698,21804,4000.00,3600.00,12100.00,3500.00,-1.00,0.19,120000,120000 -17857,21878,4000.00,3800.00,7950.00,3700.00,-1.00,0.19,120000,120000 -17786,21950,-3450.00,3700.00,-3550.00,3600.00,0.21,0.19,120000,120000 -17594,22027,-4000.00,3950.00,-9600.00,3850.00,1.00,0.19,120000,120000 -17531,22106,-3050.00,4000.00,-3150.00,3950.00,0.21,0.10,120000,120000 -17642,22185,4000.00,4000.00,5550.00,3950.00,-1.00,0.10,120000,120000 -17692,22245,2600.00,3100.00,2500.00,3000.00,0.21,0.19,120000,120000 -17598,22302,-4000.00,2950.00,-4700.00,2850.00,1.00,0.19,120000,120000 -17614,22373,900.00,3650.00,800.00,3550.00,0.21,0.19,120000,120000 -17783,22441,4000.00,3500.00,8450.00,3400.00,-1.00,0.19,120000,120000 -17885,22513,4000.00,3700.00,5100.00,3600.00,-1.00,0.19,120000,120000 -17752,22585,-4000.00,3700.00,-6650.00,3600.00,1.00,0.19,120000,120000 -17542,22662,-4000.00,3950.00,-10500.00,3850.00,1.00,0.19,120000,120000 -17577,22741,1850.00,4000.00,1750.00,3950.00,0.21,0.10,120000,120000 -17773,22813,4000.00,3700.00,9800.00,3600.00,-1.00,0.19,120000,120000 -17900,22871,4000.00,3000.00,6350.00,2900.00,-1.00,0.19,120000,120000 -17772,22937,-4000.00,3400.00,-6400.00,3300.00,1.00,0.19,120000,120000 -17571,23009,-4000.00,3700.00,-10050.00,3600.00,1.00,0.19,120000,120000 -17632,23079,3150.00,3600.00,3050.00,3500.00,0.21,0.19,120000,120000 -17852,23149,4000.00,3600.00,11000.00,3500.00,-1.00,0.19,120000,120000 -18000,23223,4000.00,3800.00,7400.00,3700.00,-1.00,0.19,120000,120000 -17910,23299,-4000.00,3900.00,-4500.00,3800.00,1.00,0.19,120000,120000 -17748,23377,-4000.00,4000.00,-8100.00,3900.00,1.00,0.19,120000,120000 -17815,23458,3450.00,4000.00,3350.00,4050.00,0.21,-0.10,120000,120000 -18048,23533,4000.00,3850.00,11650.00,3750.00,-1.00,0.19,120000,120000 -18202,23597,4000.00,3300.00,7700.00,3200.00,-1.00,0.19,120000,120000 -18106,23663,-4000.00,3400.00,-4800.00,3300.00,1.00,0.19,120000,120000 -17930,23736,-4000.00,3750.00,-8800.00,3650.00,1.00,0.19,120000,120000 -18004,23801,3800.00,3350.00,3700.00,3250.00,0.21,0.19,120000,120000 -18231,23873,4000.00,3700.00,11350.00,3600.00,-1.00,0.19,120000,120000 -18391,23950,4000.00,3950.00,8000.00,3850.00,-1.00,0.19,120000,120000 -18307,24028,-4000.00,4000.00,-4200.00,3900.00,0.41,0.19,120000,120000 -18106,24110,-4000.00,4000.00,-10050.00,4100.00,1.00,-0.19,120000,120000 -18079,24177,-1250.00,3450.00,-1350.00,3350.00,0.21,0.19,120000,120000 -18222,24222,4000.00,2350.00,7150.00,2250.00,-1.00,0.19,120000,120000 -18298,24273,3900.00,2650.00,3800.00,2550.00,0.21,0.19,120000,120000 -18208,24324,-4000.00,2650.00,-4500.00,2550.00,1.00,0.19,120000,120000 -18223,24389,850.00,3350.00,750.00,3250.00,0.21,0.19,120000,120000 -18382,24454,4000.00,3350.00,7950.00,3250.00,-1.00,0.19,120000,120000 -18479,24525,4000.00,3650.00,4850.00,3550.00,-1.00,0.19,120000,120000 -18342,24599,-4000.00,3800.00,-6850.00,3700.00,1.00,0.19,120000,120000 -18132,24677,-4000.00,4000.00,-10500.00,3900.00,1.00,0.19,120000,120000 -18221,24772,4000.00,4000.00,4450.00,4750.00,-0.93,-1.00,120000,120000 -18418,24798,4000.00,1400.00,9850.00,1300.00,-1.00,0.19,120000,120000 -18396,24720,-1000.00,-3800.00,-1100.00,-3900.00,0.21,0.19,120000,120000 -18228,24689,-4000.00,-1450.00,-8400.00,-1550.00,1.00,0.19,120000,120000 -18188,24685,-1900.00,-100.00,-2000.00,-200.00,0.21,0.19,120000,120000 -18322,24687,4000.00,200.00,6700.00,100.00,-1.00,0.19,120000,120000 -18397,24689,3850.00,200.00,3750.00,100.00,0.21,0.19,120000,120000 -18328,24692,-3350.00,250.00,-3450.00,150.00,0.21,0.19,120000,120000 -18317,24704,-450.00,700.00,-550.00,600.00,0.21,0.19,120000,120000 -18350,24742,1750.00,2000.00,1650.00,1900.00,0.21,0.19,120000,120000 -18397,24787,2450.00,2350.00,2350.00,2250.00,0.21,0.19,120000,120000 -18458,24850,3150.00,3250.00,3050.00,3150.00,0.21,0.19,120000,120000 -18531,24917,3750.00,3450.00,3650.00,3350.00,0.21,0.19,120000,120000 -18612,24997,4000.00,4000.00,4050.00,4000.00,-0.10,0.00,120000,120000 -18696,25076,4000.00,4000.00,4200.00,3950.00,-0.41,0.10,120000,120000 -18738,25139,2200.00,3250.00,2100.00,3150.00,0.21,0.19,120000,120000 -18725,25193,-550.00,2800.00,-650.00,2700.00,0.21,0.19,120000,120000 -18748,25261,1250.00,3500.00,1150.00,3400.00,0.21,0.19,120000,120000 -18766,25334,1000.00,3750.00,900.00,3650.00,0.21,0.19,120000,120000 -18809,25418,2250.00,4000.00,2150.00,4200.00,0.21,-0.38,120000,120000 -18856,25472,2450.00,2800.00,2350.00,2700.00,0.21,0.19,120000,120000 -18919,25463,3250.00,-350.00,3150.00,-450.00,0.21,0.19,120000,120000 -18994,25478,3850.00,850.00,3750.00,750.00,0.21,0.19,120000,120000 -19078,25496,4000.00,1000.00,4200.00,900.00,-0.41,0.19,120000,120000 -19133,25525,2850.00,1550.00,2750.00,1450.00,0.21,0.19,120000,120000 -19134,25566,150.00,2150.00,50.00,2050.00,0.21,0.19,120000,120000 -19150,25622,900.00,2900.00,800.00,2800.00,0.21,0.19,120000,120000 -19162,25688,700.00,3400.00,600.00,3300.00,0.21,0.19,120000,120000 -19191,25759,1550.00,3650.00,1450.00,3550.00,0.21,0.19,120000,120000 -19240,25839,2550.00,4000.00,2450.00,4000.00,0.21,0.00,120000,120000 -19298,25922,3000.00,4000.00,2900.00,4150.00,0.21,-0.29,120000,120000 -19368,25963,3600.00,2150.00,3500.00,2050.00,0.21,0.19,120000,120000 -19450,25956,4000.00,-250.00,4100.00,-350.00,-0.21,0.19,120000,120000 -19519,25965,3550.00,550.00,3450.00,450.00,0.21,0.19,120000,120000 -19556,25995,1950.00,1600.00,1850.00,1500.00,0.21,0.19,120000,120000 -19594,26042,2000.00,2450.00,1900.00,2350.00,0.21,0.19,120000,120000 -19648,26099,2800.00,2950.00,2700.00,2850.00,0.21,0.19,120000,120000 -19711,26166,3250.00,3450.00,3150.00,3350.00,0.21,0.19,120000,120000 -19790,26241,4000.00,3850.00,3950.00,3750.00,0.10,0.19,120000,120000 -19867,26322,3950.00,4000.00,3850.00,4050.00,0.21,-0.10,120000,120000 -19942,26409,3850.00,4000.00,3750.00,4350.00,0.21,-0.67,120000,120000 -20028,26427,4000.00,1000.00,4300.00,900.00,-0.62,0.19,120000,120000 -20064,26325,1900.00,-4000.00,1800.00,-5100.00,0.21,1.00,120000,120000 -20008,26342,-2700.00,950.00,-2800.00,850.00,0.21,0.19,120000,120000 -19992,26544,-700.00,4000.00,-800.00,10100.00,0.21,-1.00,120000,120000 -20015,26679,1250.00,4000.00,1150.00,6750.00,0.21,-1.00,120000,120000 -20030,26561,850.00,-4000.00,750.00,-5900.00,0.21,1.00,120000,120000 -20054,26371,1300.00,-4000.00,1200.00,-9500.00,0.21,1.00,120000,120000 -20090,26454,1900.00,4000.00,1800.00,4150.00,0.21,-0.29,120000,120000 -20121,26679,1650.00,4000.00,1550.00,11250.00,0.21,-1.00,120000,120000 -20174,26742,2750.00,3250.00,2650.00,3150.00,0.21,0.19,120000,120000 -20232,26635,3000.00,-4000.00,2900.00,-5350.00,0.21,1.00,120000,120000 -20302,26631,3600.00,-100.00,3500.00,-200.00,0.21,0.19,120000,120000 -20375,26806,3750.00,4000.00,3650.00,8750.00,0.21,-1.00,120000,120000 -20454,26921,4000.00,4000.00,3950.00,5750.00,0.10,-1.00,120000,120000 -20530,26793,3900.00,-4000.00,3800.00,-6400.00,0.21,1.00,120000,120000 -20595,26592,3350.00,-4000.00,3250.00,-10050.00,0.21,1.00,120000,120000 -20670,26662,3850.00,3600.00,3750.00,3500.00,0.21,0.19,120000,120000 -20747,26909,3950.00,4000.00,3850.00,12350.00,0.21,-1.00,120000,120000 -20828,27080,4000.00,4000.00,4050.00,8550.00,-0.10,-1.00,120000,120000 -20903,26981,3850.00,-4000.00,3750.00,-4950.00,0.21,1.00,120000,120000 -20968,26804,3350.00,-4000.00,3250.00,-8850.00,0.21,1.00,120000,120000 -21040,26869,3700.00,3350.00,3600.00,3250.00,0.21,0.19,120000,120000 -21114,27099,3800.00,4000.00,3700.00,11500.00,0.21,-1.00,120000,120000 -21198,27260,4000.00,4000.00,4200.00,8050.00,-0.41,-1.00,120000,120000 -21250,27173,2700.00,-4000.00,2600.00,-4350.00,0.21,0.67,120000,120000 -21264,27001,800.00,-4000.00,700.00,-8600.00,0.21,1.00,120000,120000 -21288,27047,1300.00,2400.00,1200.00,2300.00,0.21,0.19,120000,120000 -21295,27268,450.00,4000.00,350.00,11050.00,0.21,-1.00,120000,120000 -21323,27418,1500.00,4000.00,1400.00,7500.00,0.21,-1.00,120000,120000 -21358,27301,1850.00,-4000.00,1750.00,-5850.00,0.21,1.00,120000,120000 -21395,27104,1950.00,-4000.00,1850.00,-9850.00,0.21,1.00,120000,120000 -21446,27178,2650.00,3800.00,2550.00,3700.00,0.21,0.19,120000,120000 -21502,27411,2900.00,4000.00,2800.00,11650.00,0.21,-1.00,120000,120000 -21568,27578,3400.00,4000.00,3300.00,8350.00,0.21,-1.00,120000,120000 -21634,27487,3400.00,-4000.00,3300.00,-4550.00,0.21,1.00,120000,120000 -21724,27306,4000.00,-4000.00,4500.00,-9050.00,-1.00,1.00,120000,120000 -21739,27428,850.00,4000.00,750.00,6100.00,0.21,-1.00,120000,120000 -21648,27589,-4000.00,4000.00,-4550.00,8050.00,1.00,-1.00,120000,120000 -21636,27513,-500.00,-3700.00,-600.00,-3800.00,0.21,0.19,120000,120000 -21749,27341,4000.00,-4000.00,5650.00,-8600.00,-1.00,1.00,120000,120000 -21815,27290,3400.00,-2450.00,3300.00,-2550.00,0.21,0.19,120000,120000 -21764,27385,-2450.00,4000.00,-2550.00,4750.00,0.21,-1.00,120000,120000 -21754,27425,-400.00,2100.00,-500.00,2000.00,0.21,0.19,120000,120000 -21755,27313,150.00,-4000.00,50.00,-5600.00,0.21,1.00,120000,120000 -21765,27307,600.00,-200.00,500.00,-300.00,0.21,0.19,120000,120000 -21788,27481,1250.00,4000.00,1150.00,8700.00,0.21,-1.00,120000,120000 -21834,27593,2400.00,4000.00,2300.00,5600.00,0.21,-1.00,120000,120000 -21887,27465,2750.00,-4000.00,2650.00,-6400.00,0.21,1.00,120000,120000 -21944,27261,2950.00,-4000.00,2850.00,-10200.00,0.21,1.00,120000,120000 -22002,27325,3000.00,3300.00,2900.00,3200.00,0.21,0.19,120000,120000 -22064,27551,3200.00,4000.00,3100.00,11300.00,0.21,-1.00,120000,120000 -22141,27707,3950.00,4000.00,3850.00,7800.00,0.21,-1.00,120000,120000 -22217,27600,3900.00,-4000.00,3800.00,-5350.00,0.21,1.00,120000,120000 -22298,27412,4000.00,-4000.00,4050.00,-9400.00,-0.10,1.00,120000,120000 -22370,27481,3700.00,3550.00,3600.00,3450.00,0.21,0.19,120000,120000 -22435,27709,3350.00,4000.00,3250.00,11400.00,0.21,-1.00,120000,120000 -22515,27869,4000.00,4000.00,4000.00,8000.00,0.00,-1.00,120000,120000 -22584,27779,3550.00,-4000.00,3450.00,-4500.00,0.21,0.95,120000,120000 -22649,27610,3350.00,-4000.00,3250.00,-8450.00,0.21,1.00,120000,120000 -22722,27676,3750.00,3400.00,3650.00,3300.00,0.21,0.19,120000,120000 -22796,27897,3800.00,4000.00,3700.00,11050.00,0.21,-1.00,120000,120000 -22878,28043,4000.00,4000.00,4100.00,7300.00,-0.21,-1.00,120000,120000 -22940,27945,3200.00,-4000.00,3100.00,-4900.00,0.21,1.00,120000,120000 -22970,27765,1600.00,-4000.00,1500.00,-9000.00,0.21,1.00,120000,120000 -23009,27848,2050.00,4000.00,1950.00,4150.00,0.21,-0.29,120000,120000 -23046,28053,1950.00,4000.00,1850.00,10250.00,0.21,-1.00,120000,120000 -23099,28108,2750.00,2850.00,2650.00,2750.00,0.21,0.19,120000,120000 -23159,28021,3100.00,-4000.00,3000.00,-4350.00,0.21,0.67,120000,120000 -23230,28012,3650.00,-350.00,3550.00,-450.00,0.21,0.19,120000,120000 -23302,28124,3700.00,4000.00,3600.00,5600.00,0.21,-1.00,120000,120000 -23382,28184,4000.00,3100.00,4000.00,3000.00,0.00,0.19,120000,120000 -23460,28100,4000.00,-4000.00,3900.00,-4200.00,0.21,0.38,120000,120000 -23532,28076,3700.00,-1100.00,3600.00,-1200.00,0.21,0.19,120000,120000 -23614,28116,4000.00,2100.00,4100.00,2000.00,-0.21,0.19,120000,120000 -23678,28177,3300.00,3150.00,3200.00,3050.00,0.21,0.19,120000,120000 -23694,28248,900.00,3650.00,800.00,3550.00,0.21,0.19,120000,120000 -23725,28325,1650.00,3950.00,1550.00,3850.00,0.21,0.19,120000,120000 -23769,28411,2300.00,4000.00,2200.00,4300.00,0.21,-0.57,120000,120000 -23830,28452,3150.00,2150.00,3050.00,2050.00,0.21,0.19,120000,120000 -23897,28407,3450.00,-2150.00,3350.00,-2250.00,0.21,0.19,120000,120000 -23978,28398,4000.00,-350.00,4050.00,-450.00,-0.10,0.19,120000,120000 -24056,28417,4000.00,1050.00,3900.00,950.00,0.21,0.19,120000,120000 -24127,28431,3650.00,800.00,3550.00,700.00,0.21,0.19,120000,120000 -24212,28464,4000.00,1750.00,4250.00,1650.00,-0.52,0.19,120000,120000 -24262,28507,2600.00,2250.00,2500.00,2150.00,0.21,0.19,120000,120000 -24248,28565,-600.00,3000.00,-700.00,2900.00,0.21,0.19,120000,120000 -24277,28631,1550.00,3400.00,1450.00,3300.00,0.21,0.19,120000,120000 -24303,28701,1400.00,3600.00,1300.00,3500.00,0.21,0.19,120000,120000 -24355,28778,2700.00,3950.00,2600.00,3850.00,0.21,0.19,120000,120000 -24413,28862,3000.00,4000.00,2900.00,4200.00,0.21,-0.38,120000,120000 -24482,28911,3550.00,2550.00,3450.00,2450.00,0.21,0.19,120000,120000 -24560,28908,4000.00,-50.00,3900.00,-150.00,0.21,0.19,120000,120000 -24650,28937,4000.00,1550.00,4500.00,1450.00,-1.00,0.19,120000,120000 -24669,28971,1050.00,1800.00,950.00,1700.00,0.21,0.19,120000,120000 -24544,29019,-4000.00,2500.00,-6250.00,2400.00,1.00,0.19,120000,120000 -24535,29076,-350.00,2950.00,-450.00,2850.00,0.21,0.19,120000,120000 -24694,29137,4000.00,3150.00,7950.00,3050.00,-1.00,0.19,120000,120000 -24786,29201,4000.00,3300.00,4600.00,3200.00,-1.00,0.19,120000,120000 -24650,29273,-4000.00,3700.00,-6800.00,3600.00,1.00,0.19,120000,120000 -24437,29346,-4000.00,3750.00,-10650.00,3650.00,1.00,0.19,120000,120000 -24488,29417,2650.00,3650.00,2550.00,3550.00,0.21,0.19,120000,120000 \ No newline at end of file +LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError,HeadingVelocityCorrection,HeadingSetpoint,Heading +0.00,0.00,0.00,0.00,0.00,0.00,-98.20,86.00,87.89 +0.00,0.00,0.00,0.00,0.00,0.00,-98.20,86.00,87.89 +Changing encoder PID setpoint! +-4200.00,0.00,-4200.00,-4200.00,0.00,-4200.00,-105.38,86.00,88.03 +-9450.00,-685.71,-8764.29,-9450.00,-771.43,-8678.57,0.00,86.00,86.68 +-13950.00,-3766.67,-10183.33,-13950.00,-4066.67,-9883.33,0.00,86.00,85.10 +-18900.00,-9787.88,-9112.12,-18900.00,-9848.48,-9051.52,707.72,86.00,72.39 +-24150.00,-15114.29,-9035.71,-24150.00,-15314.29,-8835.71,590.48,86.00,74.64 +-29100.00,-20333.33,-8766.67,-29100.00,-19484.85,-9615.15,590.48,86.00,74.64 +-30000.00,-24558.82,-5441.18,-30000.00,-23264.71,-6735.29,535.15,86.00,75.71 +-30000.00,-28636.36,-1363.64,-30000.00,-27242.42,-2757.58,497.01,86.00,76.44 +-30000.00,-31312.50,1312.50,-30000.00,-29937.50,-62.50,260.93,86.00,80.98 +-30000.00,-31870.97,1870.97,-30000.00,-30774.19,774.19,-204.30,86.00,89.93 +-30000.00,-31037.04,1037.04,-30000.00,-30444.44,444.44,-204.30,86.00,89.93 +-30000.00,-29903.23,-96.77,-30000.00,-29935.48,-64.52,-230.62,86.00,90.44 +-30000.00,-29612.90,-387.10,-30000.00,-29870.97,-129.03,-117.44,86.00,88.26 +-30000.00,-29781.25,-218.75,-30000.00,-29812.50,-187.50,0.00,86.00,86.76 +-30000.00,-30187.50,187.50,-30000.00,-29812.50,-187.50,0.00,86.00,86.76 +-30000.00,-29870.97,-129.03,-30000.00,-29645.16,-354.84,-103.95,86.00,88.00 +-30000.00,-29625.00,-375.00,-30000.00,-29468.75,-531.25,0.00,86.00,86.83 +-30000.00,-29838.71,-161.29,-30000.00,-29677.42,-322.58,0.00,86.00,86.48 +-30000.00,-29838.71,-161.29,-30000.00,-29677.42,-322.58,0.00,86.00,86.94 +-30000.00,-29843.75,-156.25,-30000.00,-29906.25,-93.75,0.00,86.00,86.94 +-30000.00,-30096.77,96.77,-30000.00,-29903.23,-96.77,-73.01,86.00,87.40 +-30000.00,-30290.32,290.32,-30000.00,-29806.45,-193.55,-101.54,86.00,87.95 +-30000.00,-30096.77,96.77,-30000.00,-29967.74,-32.26,-94.20,86.00,87.81 +-30000.00,-29774.19,-225.81,-30000.00,-29806.45,-193.55,-94.20,86.00,87.81 +-30000.00,-29687.50,-312.50,-30000.00,-29843.75,-156.25,-114.45,86.00,88.20 +-30000.00,-30093.75,93.75,-30000.00,-29843.75,-156.25,-60.25,86.00,87.16 +-30000.00,-30187.50,187.50,-30000.00,-29843.75,-156.25,0.00,86.00,86.71 +-30000.00,-30258.06,258.06,-30000.00,-29774.19,-225.81,0.00,86.00,86.93 +-30000.00,-29870.97,-129.03,-30000.00,-29709.68,-290.32,0.00,86.00,86.93 +-30000.00,-29843.75,-156.25,-30000.00,-29531.25,-468.75,0.00,86.00,86.99 +-30000.00,-29843.75,-156.25,-30000.00,-29718.75,-281.25,0.00,86.00,85.66 +-30000.00,-29812.50,-187.50,-30000.00,-29875.00,-125.00,0.00,86.00,86.33 +-30000.00,-30064.52,64.52,-30000.00,-29870.97,-129.03,-85.40,86.00,87.64 +-30000.00,-30193.55,193.55,-30000.00,-29903.23,-96.77,-85.40,86.00,87.64 +-30000.00,-30343.75,343.75,-30000.00,-29968.75,-31.25,-106.50,86.00,88.05 +-30000.00,-29838.71,-161.29,-30000.00,-29967.74,-32.26,-86.19,86.00,87.66 +-30000.00,-29781.25,-218.75,-30000.00,-29937.50,-62.50,-78.01,86.00,87.50 +-30000.00,-29781.25,-218.75,-30000.00,-29906.25,-93.75,-80.36,86.00,87.55 +-30000.00,-29906.25,-93.75,-30000.00,-29843.75,-156.25,-80.36,86.00,87.55 +-30000.00,-30218.75,218.75,-30000.00,-29687.50,-312.50,-75.29,86.00,87.45 +-30000.00,-30096.77,96.77,-30000.00,-29774.19,-225.81,0.00,86.00,86.30 +-30000.00,-29838.71,-161.29,-30000.00,-29677.42,-322.58,0.00,86.00,86.50 +-30000.00,-30032.26,32.26,-30000.00,-29483.87,-516.13,0.00,86.00,86.50 +-30000.00,-29935.48,-64.52,-30000.00,-29838.71,-161.29,0.00,86.00,86.94 +-30000.00,-29812.50,-187.50,-30000.00,-29781.25,-218.75,0.00,86.00,86.89 +-30000.00,-29903.23,-96.77,-30000.00,-29870.97,-129.03,0.00,86.00,86.63 +-30000.00,-30483.87,483.87,-30000.00,-29741.94,-258.06,-72.93,86.00,87.40 +-30000.00,-30258.06,258.06,-30000.00,-29967.74,-32.26,-72.93,86.00,87.40 +-30000.00,-29937.50,-62.50,-30000.00,-30187.50,187.50,-118.13,86.00,88.27 +-30000.00,-29656.25,-343.75,-30000.00,-29937.50,-62.50,-62.22,86.00,87.20 +-30000.00,-29935.48,-64.52,-30000.00,-30129.03,129.03,0.00,86.00,86.90 +-30000.00,-30225.81,225.81,-30000.00,-29741.94,-258.06,0.00,86.00,86.90 +-30000.00,-30375.00,375.00,-30000.00,-29750.00,-250.00,-85.50,86.00,87.64 +-30000.00,-30064.52,64.52,-30000.00,-29870.97,-129.03,-84.18,86.00,87.62 +-30000.00,-29774.19,-225.81,-30000.00,-29838.71,-161.29,0.00,86.00,86.46 +-30000.00,-29870.97,-129.03,-30000.00,-29741.94,-258.06,0.00,86.00,86.67 +-30000.00,-29906.25,-93.75,-30000.00,-29781.25,-218.75,0.00,86.00,86.67 +-30000.00,-29838.71,-161.29,-30000.00,-29709.68,-290.32,-55.93,86.00,87.08 +-30000.00,-30064.52,64.52,-30000.00,-29870.97,-129.03,-80.12,86.00,87.54 +-30000.00,-30290.32,290.32,-30000.00,-30064.52,64.52,-75.31,86.00,87.45 +-30000.00,-30193.55,193.55,-30000.00,-30064.52,64.52,-97.21,86.00,87.87 +-30000.00,-29709.68,-290.32,-30000.00,-30000.00,0.00,-97.21,86.00,87.87 +-30000.00,-29875.00,-125.00,-30000.00,-29843.75,-156.25,-97.89,86.00,87.88 +-30000.00,-29968.75,-31.25,-30000.00,-29968.75,-31.25,-82.81,86.00,87.59 +-30000.00,-30258.06,258.06,-30000.00,-29741.94,-258.06,0.00,86.00,86.57 +-30000.00,-30250.00,250.00,-30000.00,-29722.22,-277.78,-102.55,86.00,87.97 +-30000.00,-30064.52,64.52,-30000.00,-29870.97,-129.03,-102.55,86.00,87.97 +-30000.00,-29838.71,-161.29,-30000.00,-29870.97,-129.03,-61.23,86.00,87.18 +-30000.00,-29709.68,-290.32,-30000.00,-29838.71,-161.29,0.00,86.00,86.82 +-30000.00,-29806.45,-193.55,-30000.00,-29774.19,-225.81,0.00,86.00,86.30 +-30000.00,-30032.26,32.26,-30000.00,-29838.71,-161.29,0.00,86.00,86.30 +-30000.00,-30258.06,258.06,-30000.00,-29806.45,-193.55,-96.61,86.00,87.86 +-30000.00,-30387.10,387.10,-30000.00,-29903.23,-96.77,-80.30,86.00,87.54 +-30000.00,-30064.52,64.52,-30000.00,-30000.00,0.00,-125.15,86.00,88.41 +-30000.00,-29774.19,-225.81,-30000.00,-29935.48,-64.52,-55.63,86.00,87.07 +-30000.00,-29870.97,-129.03,-29195.00,-30129.03,934.03,-55.63,86.00,87.07 +-26400.00,-30000.00,3600.00,-24545.00,-29935.48,5390.48,-96.43,86.00,87.85 +-21750.00,-29645.16,7895.16,-19895.00,-28516.13,8621.13,-281.31,86.00,91.41 +-17100.00,-26000.00,8900.00,-15245.00,-24580.65,9335.65,-1253.50,86.00,110.11 +-12450.00,-19451.61,7001.61,-10595.00,-17741.94,7146.94,-1253.50,86.00,110.11 +-7950.00,-14233.33,6283.33,-6095.00,-12766.67,6671.67,-841.06,86.00,102.17 +-3450.00,-10700.00,7250.00,-1595.00,-9366.67,7771.67,-414.06,86.00,93.96 +0.00,-7166.67,7166.67,0.00,-6133.33,6133.33,-810.11,86.00,101.58 +0.00,-1068.97,1068.97,0.00,-137.93,137.93,-810.11,86.00,101.58 +0.00,2758.62,-2758.62,0.00,2000.00,-2000.00,-279.77,86.00,91.38 +0.00,2448.28,-2448.28,0.00,1448.28,-1448.28,147.08,86.00,83.17 +0.00,1862.07,-1862.07,0.00,310.34,-310.34,121.99,86.00,83.65 +0.00,1068.97,-1068.97,0.00,34.48,-34.48,121.99,86.00,83.65 +0.00,1214.29,-1214.29,0.00,0.00,0.00,-172.96,86.00,89.33 +0.00,310.34,-310.34,0.00,0.00,0.00,81.99,86.00,84.42 +0.00,-642.86,642.86,0.00,0.00,0.00,81.99,86.00,84.42 +0.00,-107.14,107.14,0.00,0.00,0.00,0.00,86.00,85.28 +0.00,250.00,-250.00,0.00,0.00,0.00,0.00,86.00,85.30 +0.00,-107.14,107.14,0.00,0.00,0.00,79.59,86.00,84.47 +0.00,0.00,0.00,0.00,0.00,0.00,79.59,86.00,84.47 +0.00,0.00,0.00,0.00,0.00,0.00,69.07,86.00,84.67 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,86.00,85.02 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,86.00,85.02 +0.00,0.00,0.00,0.00,0.00,0.00,71.06,86.00,84.63 +0.00,0.00,0.00,0.00,0.00,0.00,61.76,86.00,84.81 +0.00,0.00,0.00,0.00,0.00,0.00,61.76,86.00,84.81 +0.00,0.00,0.00,0.00,0.00,0.00,55.68,86.00,84.93 +0.00,0.00,0.00,0.00,0.00,0.00,57.12,86.00,84.90 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,86.00,85.02 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,86.00,85.02 +0.00,0.00,0.00,0.00,0.00,0.00,69.50,86.00,84.66 +0.00,0.00,0.00,0.00,0.00,0.00,68.31,86.00,84.69 +0.00,0.00,0.00,0.00,0.00,0.00,68.31,86.00,84.69 +0.00,0.00,0.00,0.00,0.00,0.00,71.05,86.00,84.63 +0.00,0.00,0.00,0.00,0.00,0.00,74.74,86.00,84.56 +0.00,0.00,0.00,0.00,0.00,0.00,74.74,86.00,84.56 +0.00,0.00,0.00,0.00,0.00,0.00,80.50,86.00,84.45 +0.00,0.00,0.00,0.00,0.00,0.00,59.94,86.00,84.85 +0.00,0.00,0.00,0.00,0.00,0.00,75.89,86.00,84.54 +0.00,0.00,0.00,0.00,0.00,0.00,75.89,86.00,84.54 +0.00,0.00,0.00,0.00,0.00,0.00,69.06,86.00,84.67 +0.00,0.00,0.00,0.00,0.00,0.00,68.52,86.00,84.68 +0.00,0.00,0.00,0.00,0.00,0.00,68.52,86.00,84.68 +0.00,0.00,0.00,0.00,0.00,0.00,68.92,86.00,84.67 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,86.00,85.15 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,86.00,85.15 +0.00,0.00,0.00,0.00,0.00,0.00,70.30,86.00,84.65 +0.00,0.00,0.00,0.00,0.00,0.00,78.96,86.00,84.48 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,86.00,85.06 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,86.00,85.06 +0.00,0.00,0.00,0.00,0.00,0.00,56.18,86.00,84.92 +0.00,0.00,0.00,0.00,0.00,0.00,64.23,86.00,84.76 +0.00,0.00,0.00,0.00,0.00,0.00,64.23,86.00,84.76 +0.00,0.00,0.00,0.00,0.00,0.00,56.41,86.00,84.92 +0.00,0.00,0.00,0.00,0.00,0.00,53.36,86.00,84.97 +0.00,0.00,0.00,0.00,0.00,0.00,53.36,86.00,84.97 +0.00,0.00,0.00,0.00,0.00,0.00,66.83,86.00,84.71 +0.00,0.00,0.00,0.00,0.00,0.00,68.37,86.00,84.69 +0.00,0.00,0.00,0.00,0.00,0.00,76.06,86.00,84.54 +0.00,0.00,0.00,0.00,0.00,0.00,76.06,86.00,84.54 +0.00,0.00,0.00,0.00,0.00,0.00,71.78,86.00,84.62 +0.00,0.00,0.00,0.00,0.00,0.00,52.86,86.00,84.98 +0.00,0.00,0.00,0.00,0.00,0.00,52.86,86.00,84.98 +0.00,0.00,0.00,0.00,0.00,0.00,71.69,86.00,84.62 +0.00,0.00,0.00,0.00,0.00,0.00,73.86,86.00,84.58 +0.00,0.00,0.00,0.00,0.00,0.00,65.27,86.00,84.74 +0.00,0.00,0.00,0.00,0.00,0.00,65.27,86.00,84.74 +0.00,0.00,0.00,0.00,0.00,0.00,75.43,86.00,84.55 +0.00,0.00,0.00,0.00,0.00,0.00,85.19,86.00,84.36 +0.00,0.00,0.00,0.00,0.00,0.00,85.19,86.00,84.36 +0.00,0.00,0.00,0.00,0.00,0.00,68.13,86.00,84.69 +0.00,0.00,0.00,0.00,0.00,0.00,93.52,86.00,84.20 +0.00,0.00,0.00,0.00,0.00,0.00,93.52,86.00,84.20 +0.00,0.00,0.00,0.00,0.00,0.00,79.34,86.00,84.47 +0.00,0.00,0.00,0.00,0.00,0.00,67.36,86.00,84.70 +0.00,0.00,0.00,0.00,0.00,0.00,70.72,86.00,84.64 +0.00,0.00,0.00,0.00,0.00,0.00,70.72,86.00,84.64 +0.00,0.00,0.00,0.00,0.00,0.00,73.75,86.00,84.58 +0.00,0.00,0.00,0.00,0.00,0.00,62.40,86.00,84.80 +0.00,0.00,0.00,0.00,0.00,0.00,62.40,86.00,84.80 +0.00,0.00,0.00,0.00,0.00,0.00,88.94,86.00,84.29 +0.00,0.00,0.00,0.00,0.00,0.00,74.48,86.00,84.57 +0.00,0.00,0.00,0.00,0.00,0.00,74.48,86.00,84.57 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,86.00,85.08 +0.00,0.00,0.00,0.00,0.00,0.00,53.59,86.00,84.97 +0.00,0.00,0.00,0.00,0.00,0.00,68.31,86.00,84.69 +0.00,0.00,0.00,0.00,0.00,0.00,68.31,86.00,84.69 +0.00,0.00,0.00,0.00,0.00,0.00,75.59,86.00,84.55 +0.00,0.00,0.00,0.00,0.00,0.00,73.07,86.00,84.60 +0.00,0.00,0.00,0.00,0.00,0.00,73.07,86.00,84.60 +0.00,0.00,0.00,0.00,0.00,0.00,62.58,86.00,84.80 +0.00,0.00,0.00,0.00,0.00,0.00,55.37,86.00,84.94 +0.00,0.00,0.00,0.00,0.00,0.00,55.37,86.00,84.94 +0.00,0.00,0.00,0.00,0.00,0.00,52.76,86.00,84.99 +0.00,0.00,0.00,0.00,0.00,0.00,60.35,86.00,84.84 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,86.00,85.12 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,86.00,85.12 +0.00,0.00,0.00,0.00,0.00,0.00,61.77,86.00,84.81 +0.00,0.00,0.00,0.00,0.00,0.00,64.03,86.00,84.77 +0.00,0.00,0.00,0.00,0.00,0.00,64.03,86.00,84.77 +0.00,0.00,0.00,0.00,0.00,0.00,80.78,86.00,84.45 +0.00,0.00,0.00,0.00,0.00,0.00,69.44,86.00,84.66 +0.00,0.00,0.00,0.00,0.00,0.00,69.44,86.00,84.66 +0.00,0.00,0.00,0.00,0.00,0.00,68.19,86.00,84.69 +0.00,0.00,0.00,0.00,0.00,0.00,54.27,86.00,84.96 +0.00,0.00,0.00,0.00,0.00,0.00,72.12,86.00,84.61 +0.00,0.00,0.00,0.00,0.00,0.00,72.12,86.00,84.61 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,86.00,85.13 +0.00,0.00,0.00,0.00,0.00,0.00,57.46,86.00,84.90 +0.00,0.00,0.00,0.00,0.00,0.00,57.46,86.00,84.90 +0.00,0.00,0.00,0.00,0.00,0.00,70.05,86.00,84.65 +0.00,0.00,0.00,0.00,0.00,0.00,58.23,86.00,84.88 +0.00,0.00,0.00,0.00,0.00,0.00,58.23,86.00,84.88 +0.00,0.00,0.00,0.00,0.00,0.00,58.08,86.00,84.88 +0.00,0.00,0.00,0.00,0.00,0.00,72.22,86.00,84.61 +0.00,0.00,0.00,0.00,0.00,0.00,65.26,86.00,84.75 +0.00,0.00,0.00,0.00,0.00,0.00,65.26,86.00,84.75 +0.00,0.00,0.00,0.00,0.00,0.00,71.35,86.00,84.63 +0.00,0.00,0.00,0.00,0.00,0.00,70.17,86.00,84.65 +0.00,0.00,0.00,0.00,0.00,0.00,70.17,86.00,84.65 +0.00,0.00,0.00,0.00,0.00,0.00,60.80,86.00,84.83 +0.00,0.00,0.00,0.00,0.00,0.00,56.56,86.00,84.91 +0.00,0.00,0.00,0.00,0.00,0.00,56.56,86.00,84.91 +0.00,0.00,0.00,0.00,0.00,0.00,66.97,86.00,84.71 +0.00,0.00,0.00,0.00,0.00,0.00,67.70,86.00,84.70 +0.00,0.00,0.00,0.00,0.00,0.00,59.34,86.00,84.86 +0.00,0.00,0.00,0.00,0.00,0.00,59.34,86.00,84.86 +0.00,0.00,0.00,0.00,0.00,0.00,0.00,86.00,85.01 +0.00,0.00,0.00,0.00,0.00,0.00,53.18,86.00,84.98 +Changing encoder PID setpoint! +4200.00,0.00,4200.00,4200.00,0.00,4200.00,53.18,86.00,84.98 +8550.00,620.69,7929.31,8550.00,896.55,7653.45,77.58,86.00,84.51 +12900.00,4068.97,8831.03,12900.00,4241.38,8658.62,-547.49,86.00,96.53 +18150.00,9542.86,8607.14,18150.00,9400.00,8750.00,-914.44,86.00,103.59 +22950.00,15718.75,7231.25,22950.00,14218.75,8731.25,-554.10,86.00,96.66 +27750.00,20656.25,7093.75,27750.00,17750.00,10000.00,-554.10,86.00,96.66 +30000.00,24343.75,5656.25,30000.00,22468.75,7531.25,-500.50,86.00,95.63 +30000.00,27181.82,2818.18,30000.00,26909.09,3090.91,-451.72,86.00,94.69 +30000.00,29774.19,225.81,30000.00,30258.06,-258.06,-162.53,86.00,89.13 +30000.00,30870.97,-870.97,30000.00,31258.06,-1258.06,-162.53,86.00,89.13 +30000.00,30741.94,-741.94,30000.00,30548.39,-548.39,66.45,86.00,84.72 +30000.00,30322.58,-322.58,30000.00,30000.00,0.00,62.79,86.00,84.79 +30000.00,29967.74,32.26,30000.00,29870.97,129.03,0.00,86.00,86.59 +30000.00,29903.23,96.77,30000.00,29677.42,322.58,0.00,86.00,86.85 +30000.00,29733.33,266.67,30000.00,30066.67,-66.67,0.00,86.00,86.85 +30000.00,29766.67,233.33,30000.00,29900.00,100.00,0.00,86.00,86.79 +30000.00,29516.13,483.87,30000.00,29677.42,322.58,0.00,86.00,86.79 +30000.00,29666.67,333.33,30000.00,30000.00,0.00,-74.83,86.00,87.44 +30000.00,29967.74,32.26,30000.00,30096.77,-96.77,-74.83,86.00,87.44 +30000.00,30064.52,-64.52,30000.00,30000.00,0.00,0.00,86.00,86.28 +30000.00,29935.48,64.52,30000.00,29645.16,354.84,0.00,86.00,86.92 +30000.00,29866.67,133.33,30000.00,30166.67,-166.67,-75.22,86.00,87.45 +30000.00,29774.19,225.81,30000.00,30129.03,-129.03,-75.22,86.00,87.45 +30000.00,30096.77,-96.77,30000.00,29741.94,258.06,0.00,86.00,86.70 +30000.00,30100.00,-100.00,30000.00,29733.33,266.67,-71.61,86.00,87.38 +30000.00,29838.71,161.29,30000.00,30000.00,0.00,0.00,86.00,86.76 +30000.00,29774.19,225.81,30000.00,29935.48,64.52,0.00,86.00,86.95 +30000.00,29967.74,32.26,30000.00,29967.74,32.26,0.00,86.00,86.95 +30000.00,30096.77,-96.77,30000.00,29612.90,387.10,0.00,86.00,86.87 +30000.00,29677.42,322.58,30000.00,29967.74,32.26,0.00,86.00,86.40 +30000.00,29774.19,225.81,30000.00,29967.74,32.26,-60.21,86.00,87.16 +30000.00,29903.23,96.77,30000.00,29967.74,32.26,-60.21,86.00,87.16 +30000.00,30096.77,-96.77,30000.00,29741.94,258.06,0.00,86.00,86.65 +30000.00,30200.00,-200.00,30000.00,29966.67,33.33,0.00,86.00,86.55 +30000.00,30100.00,-100.00,30000.00,30100.00,-100.00,-72.65,86.00,87.40 +30000.00,29870.97,129.03,30000.00,30225.81,-225.81,-72.65,86.00,87.40 +30000.00,29838.71,161.29,30000.00,30096.77,-96.77,0.00,86.00,86.13 +30000.00,30096.77,-96.77,30000.00,29548.39,451.61,0.00,86.00,86.75 +30000.00,29935.48,64.52,30000.00,29677.42,322.58,0.00,86.00,86.70 +30000.00,29833.33,166.67,30000.00,29966.67,33.33,-68.54,86.00,87.32 +30000.00,29933.33,66.67,30000.00,30433.33,-433.33,-68.54,86.00,87.32 +30000.00,30193.55,-193.55,30000.00,29935.48,64.52,0.00,86.00,85.76 +30000.00,30032.26,-32.26,30000.00,29677.42,322.58,0.00,86.00,85.59 +30000.00,29741.94,258.06,30000.00,29870.97,129.03,0.00,86.00,86.25 +30000.00,29870.97,129.03,30000.00,30193.55,-193.55,0.00,86.00,86.25 +30000.00,30000.00,0.00,30000.00,29838.71,161.29,0.00,86.00,85.85 +30000.00,29966.67,33.33,30000.00,29900.00,100.00,0.00,86.00,86.72 +30000.00,30096.77,-96.77,30000.00,30193.55,-193.55,0.00,86.00,86.92 +30000.00,30129.03,-129.03,30000.00,29838.71,161.29,0.00,86.00,86.92 +30000.00,29933.33,66.67,30000.00,29666.67,333.33,0.00,86.00,86.24 +30000.00,29866.67,133.33,30000.00,30133.33,-133.33,-79.67,86.00,87.53 +30000.00,29806.45,193.55,30000.00,30064.52,-64.52,0.00,86.00,86.75 +30000.00,29833.33,166.67,30000.00,30066.67,-66.67,0.00,86.00,86.75 +30000.00,30066.67,-66.67,30000.00,29833.33,166.67,0.00,86.00,85.88 +30000.00,30064.52,-64.52,30000.00,29774.19,225.81,0.00,86.00,86.01 +30000.00,30000.00,0.00,30000.00,30096.77,-96.77,0.00,86.00,86.27 +30000.00,29766.67,233.33,30000.00,30333.33,-333.33,0.00,86.00,86.12 +30000.00,29806.45,193.55,30000.00,30129.03,-129.03,0.00,86.00,86.12 +30000.00,30000.00,0.00,30000.00,30233.33,-233.33,0.00,86.00,85.53 +30000.00,29838.71,161.29,30000.00,30096.77,-96.77,0.00,86.00,85.15 +30000.00,30033.33,-33.33,30000.00,29866.67,133.33,-60.84,86.00,87.17 +30000.00,30300.00,-300.00,30000.00,29666.67,333.33,-60.84,86.00,87.17 +30000.00,30066.67,-66.67,30000.00,29733.33,266.67,0.00,86.00,86.86 +30000.00,30100.00,-100.00,30000.00,29766.67,233.33,-95.73,86.00,87.84 +30000.00,29709.68,290.32,30000.00,29774.19,225.81,0.00,86.00,86.72 +30000.00,30066.67,-66.67,30000.00,30200.00,-200.00,0.00,86.00,86.72 +30000.00,30129.03,-129.03,30000.00,30193.55,-193.55,0.00,86.00,86.70 +30000.00,30193.55,-193.55,30000.00,29935.48,64.52,0.00,86.00,86.98 +30000.00,29916.67,83.33,30000.00,29777.78,222.22,0.00,86.00,85.97 +30000.00,29800.00,200.00,30000.00,29966.67,33.33,0.00,86.00,86.37 +30000.00,29838.71,161.29,30000.00,30161.29,-161.29,0.00,86.00,86.37 +30000.00,30100.00,-100.00,30000.00,30066.67,-66.67,0.00,86.00,86.20 +30000.00,29900.00,100.00,30000.00,30000.00,0.00,0.00,86.00,86.16 +30000.00,30133.33,-133.33,30000.00,30266.67,-266.67,0.00,86.00,86.57 +30000.00,30033.33,-33.33,30000.00,30066.67,-66.67,0.00,86.00,86.57 +30000.00,29966.67,33.33,30000.00,29900.00,100.00,0.00,86.00,86.04 +30000.00,30000.00,0.00,30000.00,29838.71,161.29,0.00,86.00,86.76 +27860.00,29900.00,-2040.00,26680.00,29733.33,-3053.33,-79.95,86.00,87.54 +23360.00,29566.67,-6206.67,22180.00,29500.00,-7320.00,-79.95,86.00,87.54 +18710.00,27903.23,-9193.23,17530.00,26741.94,-9211.94,150.63,86.00,83.10 +14210.00,23400.00,-9190.00,13030.00,19433.33,-6403.33,387.39,86.00,78.55 +9710.00,17733.33,-8023.33,8530.00,14033.33,-5503.33,256.88,86.00,81.06 +5210.00,13066.67,-7856.67,4030.00,10300.00,-6270.00,256.88,86.00,81.06 +710.00,9066.67,-8356.67,0.00,7100.00,-7100.00,0.00,86.00,85.14 +0.00,2482.76,-2482.76,0.00,2275.86,-2275.86,571.02,86.00,75.02 +0.00,-1925.93,1925.93,0.00,-962.96,962.96,-526.54,86.00,96.13 +0.00,-1655.17,1655.17,0.00,-137.93,137.93,-526.54,86.00,96.13 +0.00,-551.72,551.72,0.00,0.00,0.00,-517.20,86.00,95.95 +0.00,-34.48,34.48,0.00,0.00,0.00,-667.26,86.00,98.83 +0.00,0.00,0.00,0.00,0.00,0.00,-667.26,86.00,98.83 +0.00,0.00,0.00,0.00,0.00,0.00,-654.14,86.00,98.58 +0.00,0.00,0.00,0.00,0.00,0.00,-689.17,86.00,99.25 +0.00,0.00,0.00,0.00,0.00,0.00,-675.88,86.00,99.00 +0.00,0.00,0.00,0.00,0.00,0.00,-675.88,86.00,99.00 +0.00,0.00,0.00,0.00,0.00,0.00,-662.41,86.00,98.74 +0.00,0.00,0.00,0.00,0.00,0.00,-670.17,86.00,98.89 +0.00,0.00,0.00,0.00,0.00,0.00,-670.17,86.00,98.89 +0.00,0.00,0.00,0.00,0.00,0.00,-670.09,86.00,98.89 +0.00,0.00,0.00,0.00,0.00,0.00,-649.70,86.00,98.49 +0.00,0.00,0.00,0.00,0.00,0.00,-649.70,86.00,98.49 +0.00,0.00,0.00,0.00,0.00,0.00,-658.46,86.00,98.66 +0.00,0.00,0.00,0.00,0.00,0.00,-684.96,86.00,99.17 +0.00,0.00,0.00,0.00,0.00,0.00,-701.31,86.00,99.49 +0.00,0.00,0.00,0.00,0.00,0.00,-701.31,86.00,99.49 +0.00,0.00,0.00,0.00,0.00,0.00,-661.94,86.00,98.73 +0.00,0.00,0.00,0.00,0.00,0.00,-660.23,86.00,98.70 +0.00,0.00,0.00,0.00,0.00,0.00,-660.23,86.00,98.70 +0.00,0.00,0.00,0.00,0.00,0.00,-697.65,86.00,99.42 +0.00,0.00,0.00,0.00,0.00,0.00,-662.31,86.00,98.74 +0.00,0.00,0.00,0.00,0.00,0.00,-662.31,86.00,98.74 +0.00,0.00,0.00,0.00,0.00,0.00,-680.61,86.00,99.09 +0.00,0.00,0.00,0.00,0.00,0.00,-667.61,86.00,98.84 +0.00,0.00,0.00,0.00,0.00,0.00,-656.55,86.00,98.63 +0.00,0.00,0.00,0.00,0.00,0.00,-656.55,86.00,98.63 +0.00,0.00,0.00,0.00,0.00,0.00,-667.36,86.00,98.83 +0.00,0.00,0.00,0.00,0.00,0.00,-652.73,86.00,98.55 +0.00,0.00,0.00,0.00,0.00,0.00,-652.73,86.00,98.55 +0.00,0.00,0.00,0.00,0.00,0.00,-676.32,86.00,99.01 +0.00,0.00,0.00,0.00,0.00,0.00,-665.64,86.00,98.80 +0.00,0.00,0.00,0.00,0.00,0.00,-665.64,86.00,98.80 +0.00,0.00,0.00,0.00,0.00,0.00,-641.47,86.00,98.34 +0.00,0.00,0.00,0.00,0.00,0.00,-666.99,86.00,98.83 +0.00,0.00,0.00,0.00,0.00,0.00,-669.35,86.00,98.87 +0.00,0.00,0.00,0.00,0.00,0.00,-669.35,86.00,98.87 +0.00,0.00,0.00,0.00,0.00,0.00,-664.70,86.00,98.78 +0.00,0.00,0.00,0.00,0.00,0.00,-665.24,86.00,98.79 +0.00,0.00,0.00,0.00,0.00,0.00,-665.24,86.00,98.79 +0.00,0.00,0.00,0.00,0.00,0.00,-662.90,86.00,98.75 +0.00,0.00,0.00,0.00,0.00,0.00,-635.90,86.00,98.23 +0.00,0.00,0.00,0.00,0.00,0.00,-635.90,86.00,98.23 +0.00,0.00,0.00,0.00,0.00,0.00,-629.01,86.00,98.10 +0.00,0.00,0.00,0.00,0.00,0.00,-616.29,86.00,97.85 +0.00,0.00,0.00,0.00,0.00,0.00,-587.72,86.00,97.30 +0.00,0.00,0.00,0.00,0.00,0.00,-587.72,86.00,97.30 +0.00,0.00,0.00,0.00,0.00,0.00,-633.14,86.00,98.18 +0.00,0.00,0.00,0.00,0.00,0.00,-664.02,86.00,98.77 +0.00,0.00,0.00,0.00,0.00,0.00,-664.02,86.00,98.77 +0.00,0.00,0.00,0.00,0.00,0.00,-643.33,86.00,98.37 +0.00,0.00,0.00,0.00,0.00,0.00,-665.67,86.00,98.80 +0.00,0.00,0.00,0.00,0.00,0.00,-643.49,86.00,98.38 +0.00,0.00,0.00,0.00,0.00,0.00,-643.49,86.00,98.38 +0.00,0.00,0.00,0.00,0.00,0.00,-635.15,86.00,98.21 +0.00,0.00,0.00,0.00,0.00,0.00,-628.68,86.00,98.09 +0.00,0.00,0.00,0.00,0.00,0.00,-628.68,86.00,98.09 +0.00,0.00,0.00,0.00,0.00,0.00,-640.34,86.00,98.31 +0.00,0.00,0.00,0.00,0.00,0.00,-656.65,86.00,98.63 +0.00,0.00,0.00,0.00,0.00,0.00,-656.65,86.00,98.63 +0.00,0.00,0.00,0.00,0.00,0.00,-607.44,86.00,97.68 +0.00,0.00,0.00,0.00,0.00,0.00,-602.86,86.00,97.59 +0.00,0.00,0.00,0.00,0.00,0.00,-648.08,86.00,98.46 +0.00,0.00,0.00,0.00,0.00,0.00,-648.08,86.00,98.46 +0.00,0.00,0.00,0.00,0.00,0.00,-624.76,86.00,98.01 +0.00,0.00,0.00,0.00,0.00,0.00,-642.59,86.00,98.36 +0.00,0.00,0.00,0.00,0.00,0.00,-642.59,86.00,98.36 +0.00,0.00,0.00,0.00,0.00,0.00,-641.05,86.00,98.33 +0.00,0.00,0.00,0.00,0.00,0.00,-658.02,86.00,98.65 +0.00,0.00,0.00,0.00,0.00,0.00,-658.02,86.00,98.65 +0.00,0.00,0.00,0.00,0.00,0.00,-632.97,86.00,98.17 +0.00,0.00,0.00,0.00,0.00,0.00,-608.01,86.00,97.69 +0.00,0.00,0.00,0.00,0.00,0.00,-653.31,86.00,98.56 +0.00,0.00,0.00,0.00,0.00,0.00,-653.31,86.00,98.56 +0.00,0.00,0.00,0.00,0.00,0.00,-646.50,86.00,98.43 +0.00,0.00,0.00,0.00,0.00,0.00,-622.67,86.00,97.97 +0.00,0.00,0.00,0.00,0.00,0.00,-622.67,86.00,97.97 +0.00,0.00,0.00,0.00,0.00,0.00,-614.63,86.00,97.82 +0.00,0.00,0.00,0.00,0.00,0.00,-605.76,86.00,97.65 +0.00,0.00,0.00,0.00,0.00,0.00,-605.76,86.00,97.65 +0.00,0.00,0.00,0.00,0.00,0.00,-616.21,86.00,97.85 +0.00,0.00,0.00,0.00,0.00,0.00,-613.68,86.00,97.80 +0.00,0.00,0.00,0.00,0.00,0.00,-635.73,86.00,98.23 +0.00,0.00,0.00,0.00,0.00,0.00,-635.73,86.00,98.23 +0.00,0.00,0.00,0.00,0.00,0.00,-621.09,86.00,97.94 +0.00,0.00,0.00,0.00,0.00,0.00,-637.73,86.00,98.26 +0.00,0.00,0.00,0.00,0.00,0.00,-637.73,86.00,98.26 +0.00,0.00,0.00,0.00,0.00,0.00,-641.94,86.00,98.35 +0.00,0.00,0.00,0.00,0.00,0.00,-649.27,86.00,98.49 +0.00,0.00,0.00,0.00,0.00,0.00,-649.27,86.00,98.49 +0.00,0.00,0.00,0.00,0.00,0.00,-623.67,86.00,97.99 +0.00,0.00,0.00,0.00,0.00,0.00,-629.29,86.00,98.10 +0.00,0.00,0.00,0.00,0.00,0.00,-639.36,86.00,98.30 +0.00,0.00,0.00,0.00,0.00,0.00,-639.36,86.00,98.30 +0.00,0.00,0.00,0.00,0.00,0.00,-618.36,86.00,97.89 +0.00,0.00,0.00,0.00,0.00,0.00,-636.39,86.00,98.24 +0.00,0.00,0.00,0.00,0.00,0.00,-636.39,86.00,98.24 +0.00,0.00,0.00,0.00,0.00,0.00,-627.53,86.00,98.07 +0.00,0.00,0.00,0.00,0.00,0.00,-613.00,86.00,97.79 +0.00,0.00,0.00,0.00,0.00,0.00,-613.00,86.00,97.79 +0.00,0.00,0.00,0.00,0.00,0.00,-628.23,86.00,98.08 +0.00,0.00,0.00,0.00,0.00,0.00,-608.60,86.00,97.70 +0.00,0.00,0.00,0.00,0.00,0.00,-610.41,86.00,97.74 +0.00,0.00,0.00,0.00,0.00,0.00,-610.41,86.00,97.74 +0.00,0.00,0.00,0.00,0.00,0.00,-627.82,86.00,98.07 +0.00,0.00,0.00,0.00,0.00,0.00,-608.53,86.00,97.70 +0.00,0.00,0.00,0.00,0.00,0.00,-608.53,86.00,97.70 +0.00,0.00,0.00,0.00,0.00,0.00,-624.78,86.00,98.02 +0.00,0.00,0.00,0.00,0.00,0.00,-620.07,86.00,97.92 +0.00,0.00,0.00,0.00,0.00,0.00,-620.07,86.00,97.92 +0.00,0.00,0.00,0.00,0.00,0.00,-616.00,86.00,97.85 +0.00,0.00,0.00,0.00,0.00,0.00,-619.39,86.00,97.91 +0.00,0.00,0.00,0.00,0.00,0.00,-653.83,86.00,98.57 +0.00,0.00,0.00,0.00,0.00,0.00,-653.83,86.00,98.57 +0.00,0.00,0.00,0.00,0.00,0.00,-640.59,86.00,98.32 +0.00,0.00,0.00,0.00,0.00,0.00,-657.35,86.00,98.64 +0.00,0.00,0.00,0.00,0.00,0.00,-657.35,86.00,98.64 +0.00,0.00,0.00,0.00,0.00,0.00,-651.52,86.00,98.53 +0.00,0.00,0.00,0.00,0.00,0.00,-668.59,86.00,98.86 +Changing encoder PID setpoint! +-4200.00,0.00,-4200.00,-4200.00,0.00,-4200.00,-668.59,86.00,98.86 +-8550.00,-620.69,-7929.31,-8550.00,-965.52,-7584.48,-680.33,86.00,99.08 +-12900.00,-3551.72,-9348.28,-12900.00,-4724.14,-8175.86,311.86,86.00,80.00 +-17700.00,-8468.75,-9231.25,-17700.00,-10281.25,-7418.75,678.53,86.00,72.95 +-23400.00,-14657.89,-8742.11,-23400.00,-14710.53,-8689.47,650.45,86.00,73.49 +-28350.00,-20454.55,-7895.45,-28350.00,-18484.85,-9865.15,650.45,86.00,73.49 +-30000.00,-24060.61,-5939.39,-30000.00,-22545.45,-7454.55,632.53,86.00,73.84 +-30000.00,-27411.76,-2588.24,-30000.00,-26882.35,-3117.65,539.60,86.00,75.62 +-30000.00,-31125.00,1125.00,-30000.00,-29687.50,-312.50,402.54,86.00,78.26 +-30000.00,-32354.84,2354.84,-30000.00,-30580.65,580.65,-52.56,86.00,87.01 +-30000.00,-31516.13,1516.13,-30000.00,-30258.06,258.06,-52.56,86.00,87.01 +-30000.00,-30032.26,32.26,-30000.00,-30096.77,96.77,-203.04,86.00,89.90 +-30000.00,-29580.65,-419.35,-30000.00,-30000.00,0.00,-128.58,86.00,88.47 +-30000.00,-29781.25,-218.75,-30000.00,-29625.00,-375.00,0.00,86.00,86.43 +-30000.00,-30214.29,214.29,-30000.00,-29642.86,-357.14,0.00,86.00,86.63 +-30000.00,-30064.52,64.52,-30000.00,-29741.94,-258.06,0.00,86.00,86.63 +-30000.00,-29548.39,-451.61,-30000.00,-29580.65,-419.35,-62.06,86.00,87.19 +-30000.00,-29645.16,-354.84,-30000.00,-29645.16,-354.84,0.00,86.00,86.10 +-30000.00,-29781.25,-218.75,-30000.00,-29875.00,-125.00,0.00,86.00,86.28 +-30000.00,-29937.50,-62.50,-30000.00,-29812.50,-187.50,0.00,86.00,86.28 +-30000.00,-30250.00,250.00,-30000.00,-29687.50,-312.50,-85.88,86.00,87.65 +-30000.00,-30437.50,437.50,-30000.00,-29875.00,-125.00,-81.94,86.00,87.58 +-30000.00,-30031.25,31.25,-30000.00,-29875.00,-125.00,-61.65,86.00,87.19 +-30000.00,-29687.50,-312.50,-30000.00,-29937.50,-62.50,0.00,86.00,86.52 +-30000.00,-29718.75,-281.25,-30000.00,-29875.00,-125.00,0.00,86.00,86.52 +-30000.00,-29968.75,-31.25,-30000.00,-29843.75,-156.25,-57.26,86.00,87.10 +-30000.00,-30312.50,312.50,-30000.00,-29718.75,-281.25,-66.08,86.00,87.27 +-30000.00,-30281.25,281.25,-30000.00,-29687.50,-312.50,0.00,86.00,86.20 +-30000.00,-30000.00,0.00,-30000.00,-29709.68,-290.32,0.00,86.00,86.95 +-30000.00,-29733.33,-266.67,-30000.00,-29500.00,-500.00,0.00,86.00,86.95 +-30000.00,-29935.48,-64.52,-30000.00,-29677.42,-322.58,0.00,86.00,86.84 +-30000.00,-29781.25,-218.75,-30000.00,-29750.00,-250.00,0.00,86.00,85.77 +-30000.00,-30161.29,161.29,-30000.00,-29870.97,-129.03,0.00,86.00,86.29 +-30000.00,-30312.50,312.50,-30000.00,-29937.50,-62.50,-82.61,86.00,87.59 +-30000.00,-30225.81,225.81,-30000.00,-29935.48,-64.52,-82.61,86.00,87.59 +-30000.00,-29812.50,-187.50,-30000.00,-29875.00,-125.00,-115.43,86.00,88.22 +-30000.00,-29625.00,-375.00,-30000.00,-29781.25,-218.75,-66.34,86.00,87.28 +-30000.00,-29903.23,-96.77,-30000.00,-29903.23,-96.77,0.00,86.00,86.84 +-30000.00,-30032.26,32.26,-30000.00,-29935.48,-64.52,0.00,86.00,86.84 +-30000.00,-30129.03,129.03,-30000.00,-29903.23,-96.77,-97.97,86.00,87.88 +-30000.00,-30064.52,64.52,-30000.00,-29838.71,-161.29,-109.34,86.00,88.10 +-30000.00,-29774.19,-225.81,-30000.00,-29645.16,-354.84,0.00,86.00,86.72 +-30000.00,-29750.00,-250.00,-30000.00,-29718.75,-281.25,0.00,86.00,86.53 +-30000.00,-29781.25,-218.75,-30000.00,-29750.00,-250.00,0.00,86.00,86.53 +-30000.00,-29903.23,-96.77,-30000.00,-29677.42,-322.58,-58.20,86.00,87.12 +-30000.00,-30031.25,31.25,-30000.00,-29937.50,-62.50,0.00,86.00,86.53 +-30000.00,-30451.61,451.61,-30000.00,-29903.23,-96.77,-52.15,86.00,87.00 +-30000.00,-30218.75,218.75,-30000.00,-29968.75,-31.25,-88.33,86.00,87.70 +-30000.00,-29774.19,-225.81,-30000.00,-29870.97,-129.03,-88.33,86.00,87.70 +-30000.00,-29781.25,-218.75,-30000.00,-30093.75,93.75,-100.27,86.00,87.93 +-30000.00,-30096.77,96.77,-30000.00,-30161.29,161.29,0.00,86.00,86.90 +-30000.00,-30322.58,322.58,-30000.00,-30032.26,32.26,-87.90,86.00,87.69 +-30000.00,-30225.81,225.81,-30000.00,-29709.68,-290.32,-87.90,86.00,87.69 +-30000.00,-30032.26,32.26,-30000.00,-29645.16,-354.84,-92.55,86.00,87.78 +-30000.00,-29838.71,-161.29,-30000.00,-29774.19,-225.81,0.00,86.00,85.94 +-30000.00,-29774.19,-225.81,-30000.00,-29709.68,-290.32,0.00,86.00,86.42 +-30000.00,-29741.94,-258.06,-30000.00,-29806.45,-193.55,0.00,86.00,86.80 +-30000.00,-29937.50,-62.50,-30000.00,-29843.75,-156.25,0.00,86.00,86.80 +-30000.00,-30290.32,290.32,-30000.00,-29967.74,-32.26,-86.64,86.00,87.67 +-30000.00,-30451.61,451.61,-30000.00,-30096.77,96.77,-58.90,86.00,87.13 +-30000.00,-30156.25,156.25,-30000.00,-30187.50,187.50,-98.06,86.00,87.89 +-30000.00,-29838.71,-161.29,-30000.00,-30129.03,129.03,-98.06,86.00,87.89 +-30000.00,-29677.42,-322.58,-30000.00,-30000.00,0.00,-92.49,86.00,87.78 +-30000.00,-29903.23,-96.77,-30000.00,-30096.77,96.77,-90.75,86.00,87.75 +-30000.00,-30156.25,156.25,-30000.00,-29968.75,-31.25,-82.92,86.00,87.59 +-30000.00,-30281.25,281.25,-30000.00,-29718.75,-281.25,0.00,86.00,86.88 +-30000.00,-29967.74,-32.26,-30000.00,-29709.68,-290.32,0.00,86.00,86.88 +-30000.00,-29677.42,-322.58,-30000.00,-29677.42,-322.58,-59.75,86.00,87.15 +-30000.00,-29783.78,-216.22,-30000.00,-29729.73,-270.27,0.00,86.00,86.92 +-30000.00,-29741.94,-258.06,-30000.00,-29548.39,-451.61,0.00,86.00,86.38 +-30000.00,-30032.26,32.26,-30000.00,-29935.48,-64.52,0.00,86.00,86.26 +-30000.00,-30354.84,354.84,-30000.00,-29838.71,-161.29,0.00,86.00,86.26 +-30000.00,-30354.84,354.84,-30000.00,-29935.48,-64.52,-118.88,86.00,88.29 +-30000.00,-29935.48,-64.52,-30000.00,-30032.26,32.26,-78.05,86.00,87.50 +-30000.00,-29677.42,-322.58,-30000.00,-29935.48,-64.52,0.00,86.00,86.51 +-30000.00,-29843.75,-156.25,-28740.00,-30031.25,1291.25,0.00,86.00,85.87 +-25490.00,-30290.32,4800.32,-24090.00,-29903.23,5813.23,0.00,86.00,85.87 +-20840.00,-29645.16,8805.16,-19440.00,-28290.32,8850.32,-172.81,86.00,89.32 +-16190.00,-25612.90,9422.90,-14790.00,-24354.84,9564.84,-708.80,86.00,99.63 +-11540.00,-19064.52,7524.52,-10140.00,-17451.61,7311.61,-968.82,86.00,104.63 +-7040.00,-14066.67,7026.67,-5640.00,-12533.33,6893.33,-968.82,86.00,104.63 +-2540.00,-9766.67,7226.67,-1140.00,-9266.67,8126.67,-472.80,86.00,95.09 +0.00,-3466.67,3466.67,0.00,-5900.00,5900.00,-453.75,86.00,94.73 +0.00,896.55,-896.55,0.00,275.86,-275.86,-422.63,86.00,94.13 +0.00,1586.21,-1586.21,0.00,2448.28,-2448.28,-422.63,86.00,94.13 +0.00,862.07,-862.07,0.00,1758.62,-1758.62,284.75,86.00,80.52 +0.00,-379.31,379.31,0.00,1275.86,-1275.86,266.82,86.00,80.87 +0.00,-758.62,758.62,0.00,34.48,-34.48,220.53,86.00,81.76 +0.00,310.34,-310.34,0.00,-551.72,551.72,220.53,86.00,81.76 +0.00,-35.71,35.71,0.00,-285.71,285.71,282.59,86.00,80.57 +0.00,-34.48,34.48,0.00,137.93,-137.93,252.72,86.00,81.14 +0.00,0.00,0.00,0.00,0.00,0.00,252.72,86.00,81.14 +0.00,0.00,0.00,0.00,0.00,0.00,277.73,86.00,80.66 +0.00,0.00,0.00,0.00,0.00,0.00,294.53,86.00,80.34 +0.00,0.00,0.00,0.00,0.00,0.00,294.53,86.00,80.34 +0.00,0.00,0.00,0.00,0.00,0.00,294.29,86.00,80.34 +0.00,0.00,0.00,0.00,0.00,0.00,292.15,86.00,80.38 +0.00,0.00,0.00,0.00,0.00,0.00,277.82,86.00,80.66 +0.00,0.00,0.00,0.00,0.00,0.00,277.82,86.00,80.66 +0.00,0.00,0.00,0.00,0.00,0.00,302.92,86.00,80.17 +0.00,0.00,0.00,0.00,0.00,0.00,306.66,86.00,80.10 +0.00,0.00,0.00,0.00,0.00,0.00,306.66,86.00,80.10 +0.00,0.00,0.00,0.00,0.00,0.00,308.58,86.00,80.07 +0.00,0.00,0.00,0.00,0.00,0.00,296.20,86.00,80.30 +0.00,0.00,0.00,0.00,0.00,0.00,325.04,86.00,79.75 +0.00,0.00,0.00,0.00,0.00,0.00,325.04,86.00,79.75 +0.00,0.00,0.00,0.00,0.00,0.00,311.52,86.00,80.01 +0.00,0.00,0.00,0.00,0.00,0.00,319.25,86.00,79.86 +0.00,0.00,0.00,0.00,0.00,0.00,319.25,86.00,79.86 +0.00,0.00,0.00,0.00,0.00,0.00,325.43,86.00,79.74 +0.00,0.00,0.00,0.00,0.00,0.00,334.53,86.00,79.57 +0.00,0.00,0.00,0.00,0.00,0.00,334.53,86.00,79.57 +0.00,0.00,0.00,0.00,0.00,0.00,309.20,86.00,80.05 +0.00,0.00,0.00,0.00,0.00,0.00,313.17,86.00,79.98 +0.00,0.00,0.00,0.00,0.00,0.00,310.64,86.00,80.03 +0.00,0.00,0.00,0.00,0.00,0.00,310.64,86.00,80.03 +0.00,0.00,0.00,0.00,0.00,0.00,312.86,86.00,79.98 +0.00,0.00,0.00,0.00,0.00,0.00,297.14,86.00,80.29 +0.00,0.00,0.00,0.00,0.00,0.00,297.14,86.00,80.29 +0.00,0.00,0.00,0.00,0.00,0.00,336.51,86.00,79.53 +0.00,0.00,0.00,0.00,0.00,0.00,338.43,86.00,79.49 +0.00,0.00,0.00,0.00,0.00,0.00,338.43,86.00,79.49 +0.00,0.00,0.00,0.00,0.00,0.00,353.28,86.00,79.21 +0.00,0.00,0.00,0.00,0.00,0.00,331.10,86.00,79.63 +0.00,0.00,0.00,0.00,0.00,0.00,331.10,86.00,79.63 +0.00,0.00,0.00,0.00,0.00,0.00,314.31,86.00,79.96 +0.00,0.00,0.00,0.00,0.00,0.00,320.74,86.00,79.83 +0.00,0.00,0.00,0.00,0.00,0.00,334.10,86.00,79.58 +0.00,0.00,0.00,0.00,0.00,0.00,334.10,86.00,79.58 +0.00,0.00,0.00,0.00,0.00,0.00,316.46,86.00,79.91 +0.00,0.00,0.00,0.00,0.00,0.00,310.70,86.00,80.03 +0.00,0.00,0.00,0.00,0.00,0.00,310.70,86.00,80.03 +0.00,0.00,0.00,0.00,0.00,0.00,308.98,86.00,80.06 +0.00,0.00,0.00,0.00,0.00,0.00,304.29,86.00,80.15 +0.00,0.00,0.00,0.00,0.00,0.00,304.29,86.00,80.15 +0.00,0.00,0.00,0.00,0.00,0.00,313.84,86.00,79.96 +0.00,0.00,0.00,0.00,0.00,0.00,293.98,86.00,80.35 +0.00,0.00,0.00,0.00,0.00,0.00,314.06,86.00,79.96 +0.00,0.00,0.00,0.00,0.00,0.00,314.06,86.00,79.96 +0.00,0.00,0.00,0.00,0.00,0.00,304.17,86.00,80.15 +0.00,0.00,0.00,0.00,0.00,0.00,287.63,86.00,80.47 +0.00,0.00,0.00,0.00,0.00,0.00,287.63,86.00,80.47 +0.00,0.00,0.00,0.00,0.00,0.00,308.40,86.00,80.07 +0.00,0.00,0.00,0.00,0.00,0.00,307.85,86.00,80.08 +0.00,0.00,0.00,0.00,0.00,0.00,299.37,86.00,80.24 +0.00,0.00,0.00,0.00,0.00,0.00,299.37,86.00,80.24 +0.00,0.00,0.00,0.00,0.00,0.00,302.74,86.00,80.18 +0.00,0.00,0.00,0.00,0.00,0.00,322.91,86.00,79.79 +0.00,0.00,0.00,0.00,0.00,0.00,322.91,86.00,79.79 +0.00,0.00,0.00,0.00,0.00,0.00,309.56,86.00,80.05 +0.00,0.00,0.00,0.00,0.00,0.00,290.33,86.00,80.42 +0.00,0.00,0.00,0.00,0.00,0.00,290.33,86.00,80.42 +0.00,0.00,0.00,0.00,0.00,0.00,287.52,86.00,80.47 +0.00,0.00,0.00,0.00,0.00,0.00,318.42,86.00,79.88 +0.00,0.00,0.00,0.00,0.00,0.00,309.59,86.00,80.05 +0.00,0.00,0.00,0.00,0.00,0.00,309.59,86.00,80.05 +0.00,0.00,0.00,0.00,0.00,0.00,302.46,86.00,80.18 +0.00,0.00,0.00,0.00,0.00,0.00,280.42,86.00,80.61 +0.00,0.00,0.00,0.00,0.00,0.00,280.42,86.00,80.61 +0.00,0.00,0.00,0.00,0.00,0.00,293.67,86.00,80.35 +0.00,0.00,0.00,0.00,0.00,0.00,319.96,86.00,79.85 +0.00,0.00,0.00,0.00,0.00,0.00,319.96,86.00,79.85 +0.00,0.00,0.00,0.00,0.00,0.00,308.39,86.00,80.07 +0.00,0.00,0.00,0.00,0.00,0.00,305.32,86.00,80.13 +0.00,0.00,0.00,0.00,0.00,0.00,304.54,86.00,80.14 +0.00,0.00,0.00,0.00,0.00,0.00,304.54,86.00,80.14 +0.00,0.00,0.00,0.00,0.00,0.00,322.69,86.00,79.79 +0.00,0.00,0.00,0.00,0.00,0.00,297.32,86.00,80.28 +0.00,0.00,0.00,0.00,0.00,0.00,297.32,86.00,80.28 +0.00,0.00,0.00,0.00,0.00,0.00,299.95,86.00,80.23 +0.00,0.00,0.00,0.00,0.00,0.00,289.47,86.00,80.43 +0.00,0.00,0.00,0.00,0.00,0.00,289.47,86.00,80.43 +0.00,0.00,0.00,0.00,0.00,0.00,292.39,86.00,80.38 +0.00,0.00,0.00,0.00,0.00,0.00,291.22,86.00,80.40 +0.00,0.00,0.00,0.00,0.00,0.00,308.42,86.00,80.07 +0.00,0.00,0.00,0.00,0.00,0.00,308.42,86.00,80.07 +0.00,0.00,0.00,0.00,0.00,0.00,296.98,86.00,80.29 +0.00,0.00,0.00,0.00,0.00,0.00,299.60,86.00,80.24 +0.00,0.00,0.00,0.00,0.00,0.00,299.60,86.00,80.24 +0.00,0.00,0.00,0.00,0.00,0.00,303.34,86.00,80.17 +0.00,0.00,0.00,0.00,0.00,0.00,291.07,86.00,80.40 +0.00,0.00,0.00,0.00,0.00,0.00,291.07,86.00,80.40 +0.00,0.00,0.00,0.00,0.00,0.00,297.31,86.00,80.28 +0.00,0.00,0.00,0.00,0.00,0.00,270.28,86.00,80.80 +0.00,0.00,0.00,0.00,0.00,0.00,285.23,86.00,80.51 +0.00,0.00,0.00,0.00,0.00,0.00,285.23,86.00,80.51 +0.00,0.00,0.00,0.00,0.00,0.00,300.84,86.00,80.21 +0.00,0.00,0.00,0.00,0.00,0.00,315.09,86.00,79.94 +0.00,0.00,0.00,0.00,0.00,0.00,315.09,86.00,79.94 +0.00,0.00,0.00,0.00,0.00,0.00,326.42,86.00,79.72 +0.00,0.00,0.00,0.00,0.00,0.00,300.18,86.00,80.23 +0.00,0.00,0.00,0.00,0.00,0.00,300.18,86.00,80.23 +0.00,0.00,0.00,0.00,0.00,0.00,299.72,86.00,80.24 +0.00,0.00,0.00,0.00,0.00,0.00,316.21,86.00,79.92 +0.00,0.00,0.00,0.00,0.00,0.00,316.21,86.00,79.92 +0.00,0.00,0.00,0.00,0.00,0.00,305.35,86.00,80.13 +0.00,0.00,0.00,0.00,0.00,0.00,304.00,86.00,80.15 +0.00,0.00,0.00,0.00,0.00,0.00,292.78,86.00,80.37 +0.00,0.00,0.00,0.00,0.00,0.00,292.78,86.00,80.37 +0.00,0.00,0.00,0.00,0.00,0.00,298.45,86.00,80.26 +0.00,0.00,0.00,0.00,0.00,0.00,301.49,86.00,80.20 +0.00,0.00,0.00,0.00,0.00,0.00,301.49,86.00,80.20 +0.00,0.00,0.00,0.00,0.00,0.00,294.78,86.00,80.33 +0.00,0.00,0.00,0.00,0.00,0.00,296.26,86.00,80.30 +0.00,0.00,0.00,0.00,0.00,0.00,296.26,86.00,80.30 +Changing encoder PID setpoint! +4200.00,0.00,4200.00,4200.00,0.00,4200.00,288.25,86.00,80.46 +8400.00,535.71,7864.29,8400.00,785.71,7614.29,108.05,86.00,83.92 +12600.00,3535.71,9064.29,12600.00,3857.14,8742.86,108.05,86.00,83.92 +17100.00,8533.33,8566.67,17100.00,9200.00,7900.00,-1443.62,86.00,113.76 +21900.00,13843.75,8056.25,21900.00,13562.50,8337.50,-646.47,86.00,98.43 +27450.00,19891.89,7558.11,27450.00,17351.35,10098.65,-383.60,86.00,93.38 +30000.00,24281.25,5718.75,30000.00,21062.50,8937.50,-495.16,86.00,95.52 +30000.00,26878.79,3121.21,30000.00,25454.55,4545.45,-368.11,86.00,93.08 +30000.00,29406.25,593.75,30000.00,30500.00,-500.00,-368.11,86.00,93.08 +30000.00,30774.19,-774.19,30000.00,31741.94,-1741.94,-98.67,86.00,87.90 +30000.00,30741.94,-741.94,30000.00,30838.71,-838.71,66.89,86.00,84.71 +30000.00,30290.32,-290.32,30000.00,30064.52,-64.52,0.00,86.00,85.16 +30000.00,29935.48,64.52,30000.00,29645.16,354.84,0.00,86.00,85.16 +30000.00,29966.67,33.33,30000.00,29433.33,566.67,0.00,86.00,86.55 +30000.00,29533.33,466.67,30000.00,30066.67,-66.67,0.00,86.00,86.94 +30000.00,29677.42,322.58,30000.00,30064.52,-64.52,-63.63,86.00,87.22 +30000.00,29967.74,32.26,30000.00,29967.74,32.26,0.00,86.00,86.91 +30000.00,29774.19,225.81,30000.00,29806.45,193.55,0.00,86.00,86.91 +30000.00,29806.45,193.55,30000.00,29774.19,225.81,0.00,86.00,86.69 +30000.00,30000.00,0.00,30000.00,29766.67,233.33,0.00,86.00,86.21 +30000.00,30033.33,-33.33,30000.00,30066.67,-66.67,0.00,86.00,86.56 +30000.00,29766.67,233.33,30000.00,30033.33,-33.33,0.00,86.00,86.56 +30000.00,29741.94,258.06,30000.00,30193.55,-193.55,0.00,86.00,86.19 +30000.00,29800.00,200.00,30000.00,30000.00,0.00,0.00,86.00,86.40 +30000.00,30000.00,0.00,30000.00,30000.00,0.00,0.00,86.00,86.95 +30000.00,29933.33,66.67,30000.00,29766.67,233.33,0.00,86.00,86.95 +30000.00,29833.33,166.67,30000.00,29766.67,233.33,0.00,86.00,86.87 +30000.00,29833.33,166.67,30000.00,30100.00,-100.00,-75.84,86.00,87.46 +30000.00,29870.97,129.03,30000.00,30000.00,0.00,-74.83,86.00,87.44 +30000.00,30064.52,-64.52,30000.00,30032.26,-32.26,-74.83,86.00,87.44 +30000.00,29741.94,258.06,30000.00,30000.00,0.00,0.00,86.00,85.36 +30000.00,29833.33,166.67,30000.00,29866.67,133.33,0.00,86.00,86.37 +30000.00,29866.67,133.33,30000.00,29966.67,33.33,0.00,86.00,86.04 +30000.00,30100.00,-100.00,30000.00,30166.67,-166.67,0.00,86.00,86.04 +30000.00,29838.71,161.29,30000.00,30193.55,-193.55,0.00,86.00,85.75 +30000.00,29870.97,129.03,30000.00,29806.45,193.55,0.00,86.00,87.00 +30000.00,30032.26,-32.26,30000.00,29935.48,64.52,0.00,86.00,86.57 +30000.00,30000.00,0.00,30000.00,30033.33,-33.33,0.00,86.00,86.57 +30000.00,29967.74,32.26,30000.00,29741.94,258.06,0.00,86.00,86.28 +30000.00,29709.68,290.32,30000.00,29838.71,161.29,0.00,86.00,86.20 +30000.00,29833.33,166.67,30000.00,30000.00,0.00,-74.30,86.00,87.43 +30000.00,30066.67,-66.67,30000.00,30066.67,-66.67,0.00,86.00,85.96 +30000.00,30064.52,-64.52,30000.00,30258.06,-258.06,0.00,86.00,85.96 +30000.00,29677.42,322.58,30000.00,30225.81,-225.81,0.00,86.00,85.81 +30000.00,29806.45,193.55,30000.00,29838.71,161.29,0.00,86.00,85.29 +30000.00,29966.67,33.33,30000.00,30066.67,-66.67,0.00,86.00,85.30 +30000.00,30064.52,-64.52,30000.00,29870.97,129.03,0.00,86.00,85.30 +30000.00,29709.68,290.32,30000.00,30000.00,0.00,0.00,86.00,85.06 +30000.00,29838.71,161.29,30000.00,30064.52,-64.52,0.00,86.00,85.78 +30000.00,30133.33,-133.33,30000.00,30000.00,0.00,0.00,86.00,86.44 +30000.00,29866.67,133.33,30000.00,30133.33,-133.33,0.00,86.00,86.44 +30000.00,29586.21,413.79,30000.00,29586.21,413.79,0.00,86.00,85.90 +30000.00,29741.94,258.06,30000.00,29838.71,161.29,0.00,86.00,86.15 +30000.00,29935.48,64.52,30000.00,30258.06,-258.06,-64.28,86.00,87.24 +30000.00,30032.26,-32.26,30000.00,29967.74,32.26,-64.28,86.00,87.24 +30000.00,30129.03,-129.03,30000.00,30129.03,-129.03,0.00,86.00,85.14 +30000.00,29966.67,33.33,30000.00,30133.33,-133.33,0.00,86.00,85.38 +30000.00,29774.19,225.81,30000.00,30064.52,-64.52,0.00,86.00,85.39 +30000.00,29741.94,258.06,30000.00,29935.48,64.52,0.00,86.00,86.18 +30000.00,30066.67,-66.67,30000.00,30200.00,-200.00,0.00,86.00,86.18 +30000.00,29966.67,33.33,30000.00,30200.00,-200.00,0.00,86.00,85.20 +30000.00,29966.67,33.33,30000.00,29900.00,100.00,0.00,86.00,85.71 +30000.00,29933.33,66.67,30000.00,30166.67,-166.67,0.00,86.00,85.62 +30000.00,30033.33,-33.33,30000.00,30000.00,0.00,0.00,86.00,85.62 +30000.00,29967.74,32.26,30000.00,29741.94,258.06,0.00,86.00,85.76 +30000.00,29866.67,133.33,30000.00,29633.33,366.67,0.00,86.00,85.67 +30000.00,29633.33,366.67,30000.00,29966.67,33.33,0.00,86.00,86.83 +30000.00,29866.67,133.33,30000.00,30066.67,-66.67,0.00,86.00,86.83 +30000.00,30096.77,-96.77,30000.00,30258.06,-258.06,0.00,86.00,85.78 +30000.00,29838.71,161.29,30000.00,29870.97,129.03,0.00,86.00,85.51 +30000.00,29774.19,225.81,30000.00,30129.03,-129.03,0.00,86.00,86.00 +30000.00,29944.44,55.56,30000.00,30055.56,-55.56,0.00,86.00,85.10 +30000.00,30100.00,-100.00,30000.00,30066.67,-66.67,0.00,86.00,85.10 +30000.00,29800.00,200.00,30000.00,30133.33,-133.33,0.00,86.00,85.70 +30000.00,29800.00,200.00,30000.00,29933.33,66.67,-56.45,86.00,87.09 +30000.00,29838.71,161.29,30000.00,30000.00,0.00,0.00,86.00,86.36 +30000.00,29966.67,33.33,30000.00,30100.00,-100.00,0.00,86.00,86.36 +30000.00,30064.52,-64.52,28380.00,29903.23,-1523.23,0.00,86.00,85.92 +25560.00,29741.94,-4181.94,23730.00,29516.13,-5786.13,0.00,86.00,86.49 +21360.00,28928.57,-7568.57,19530.00,27964.29,-8434.29,250.96,86.00,81.17 +16710.00,25354.84,-8644.84,14880.00,24129.03,-9249.03,250.96,86.00,81.17 +12060.00,19096.77,-7036.77,10230.00,17612.90,-7382.90,431.65,86.00,77.70 +7410.00,14129.03,-6719.03,5580.00,12548.39,-6968.39,204.14,86.00,82.07 +2910.00,10666.67,-7756.67,1080.00,8566.67,-7486.67,239.26,86.00,81.40 +0.00,7137.93,-7137.93,0.00,3172.41,-3172.41,239.26,86.00,81.40 +0.00,1137.93,-1137.93,0.00,-482.76,482.76,420.99,86.00,77.90 +0.00,-2068.97,2068.97,0.00,241.38,-241.38,-635.86,86.00,98.23 +0.00,-1620.69,1620.69,0.00,275.86,-275.86,-512.85,86.00,95.86 +0.00,-1275.86,1275.86,0.00,0.00,0.00,-512.85,86.00,95.86 +0.00,-620.69,620.69,0.00,0.00,0.00,-539.09,86.00,96.37 +0.00,-892.86,892.86,0.00,0.00,0.00,-243.08,86.00,90.67 +0.00,142.86,-142.86,0.00,0.00,0.00,-243.08,86.00,90.67 +0.00,68.97,-68.97,0.00,0.00,0.00,-136.52,86.00,88.63 +0.00,0.00,0.00,0.00,0.00,0.00,-128.41,86.00,88.47 +0.00,0.00,0.00,0.00,0.00,0.00,-111.77,86.00,88.15 +0.00,0.00,0.00,0.00,0.00,0.00,-111.77,86.00,88.15 +0.00,0.00,0.00,0.00,0.00,0.00,-126.20,86.00,88.43 +0.00,0.00,0.00,0.00,0.00,0.00,-127.95,86.00,88.46 +0.00,0.00,0.00,0.00,0.00,0.00,-127.95,86.00,88.46 +0.00,0.00,0.00,0.00,0.00,0.00,-118.92,86.00,88.29 +0.00,0.00,0.00,0.00,0.00,0.00,-123.96,86.00,88.38 +0.00,0.00,0.00,0.00,0.00,0.00,-123.96,86.00,88.38 +0.00,0.00,0.00,0.00,0.00,0.00,-118.56,86.00,88.28 +0.00,0.00,0.00,0.00,0.00,0.00,-123.68,86.00,88.38 +0.00,0.00,0.00,0.00,0.00,0.00,-125.11,86.00,88.41 diff --git a/pid_vis.py b/pid_vis.py index da21df8..0490878 100644 --- a/pid_vis.py +++ b/pid_vis.py @@ -2,37 +2,72 @@ import csv from collections import defaultdict from matplotlib import pyplot as plt +import numpy as np with Path('pid_test.csv').open('r') as f: reader = csv.DictReader(filter(lambda line: not line.startswith('#'), f)) + lists = defaultdict(list) - header = "EncoderLeft,EncoderRight,DesiredVelocityLeft,DesiredVelocityRight,CurrentVelocityLeft,CurrentVelocityRight,LeftPower,RightPower,EncoderTargetLeft,EncoderTargetRight" + # header = "EncoderLeft,EncoderRight,DesiredVelocityLeft,DesiredVelocityRight,CurrentVelocityLeft,CurrentVelocityRight,LeftPower,RightPower,EncoderTargetLeft,EncoderTargetRight" + header = "LeftSetpoint,LeftVelocity,LeftError,RightSetpoint,RightVelocity,RightError,HeadingVelocityCorrection,HeadingSetpoint,Heading" keys = header.split(",") for row in reader: + if row["LeftSetpoint"].startswith("Changing"): + continue for k in keys: val = int(row[k]) if "." not in row[k] else float(row[k]) - if "Left" in k: - val *= -1 # Correct for rotation test + # if "Left" in k: + # val *= -1 # Correct for rotation test lists[k].append(val) + lists = {k: np.array(v) for k, v in lists.items()} + +# power_deadzone = [0.15] * len(lists["EncoderLeft"]) +# neg_power_deadzone = [-0.15] * len(lists["EncoderLeft"]) + +# ax_enc.set_title("Encoder Values") +# ax_enc.plot( +# lists["EncoderLeft"], "-b", +# lists["EncoderRight"], "-r", +# lists["EncoderTargetLeft"], "--c", +# lists["EncoderTargetRight"], "--m", +# ) +# ax_vel.set_title("Velocity Values") +# ax_vel.plot( +# lists["CurrentVelocityLeft"], "-b", +# lists["CurrentVelocityRight"], "-r", +# lists["DesiredVelocityLeft"], "--c", +# lists["DesiredVelocityRight"], "--m", +# ) +# ax_pow.set_title("Motor Powers") +# ax_pow.plot(power_deadzone, "--k", neg_power_deadzone, "--k", lists["LeftPower"], "-g", lists["RightPower"], "-y") +# plt.show() + +fig = plt.figure(figsize=(15, 8)) + +# Velocity plot (top left) +ax_vel = plt.subplot2grid((2, 2), (0, 0)) +ax_vel.set_title("Velocity Values") +ax_vel.plot(lists["LeftSetpoint"]-lists["HeadingVelocityCorrection"], "--m", lists["LeftVelocity"], "-r", lists["LeftError"], "--g", + lists["RightSetpoint"]+lists["HeadingVelocityCorrection"], "--c", lists["RightVelocity"], "-b", lists["RightError"], "--y", + lists["HeadingVelocityCorrection"], "-.k") +ax_vel.legend(["Left Setpoint", "Left Velocity", "Left Error", "Right Setpoint", "Right Velocity", "Right Error", "Heading Velocity Correction"]) + +# Heading plot (bottom left) +ax_heading = plt.subplot2grid((2, 2), (1, 0), sharex=ax_vel) +ax_heading.set_title("Heading") +ax_heading.plot(lists["Heading"], "-k") +ax_heading.plot(lists["HeadingSetpoint"], "--c") +ax_heading.legend(["Heading", "Heading Setpoint"]) +ax_heading.set_xlabel("Time (index)") + +# Polar plot (right, spans both rows) +ax_polar = plt.subplot2grid((2, 2), (0, 1), rowspan=2, projection='polar') +ax_polar.set_title("Heading (Polar)") +theta = np.deg2rad(lists["Heading"]) +r = np.arange(len(theta)) +ax_polar.plot(theta, r, color="purple") +ax_polar.plot(np.deg2rad(lists["HeadingSetpoint"]), r, "--", color="cyan") +ax_polar.set_rticks([]) # Hide radial ticks for clarity - power_deadzone = [0.15] * len(lists["EncoderLeft"]) - neg_power_deadzone = [-0.15] * len(lists["EncoderLeft"]) - - fig, (ax_enc, ax_vel, ax_pow) = plt.subplots(3, 1) - ax_enc.set_title("Encoder Values") - ax_enc.plot( - lists["EncoderLeft"], "-b", - lists["EncoderRight"], "-r", - lists["EncoderTargetLeft"], "--c", - lists["EncoderTargetRight"], "--m", - ) - ax_vel.set_title("Velocity Values") - ax_vel.plot( - lists["CurrentVelocityLeft"], "-b", - lists["CurrentVelocityRight"], "-r", - lists["DesiredVelocityLeft"], "--c", - lists["DesiredVelocityRight"], "--m", - ) - ax_pow.set_title("Motor Powers") - ax_pow.plot(power_deadzone, "--k", neg_power_deadzone, "--k", lists["LeftPower"], "-g", lists["RightPower"], "-y") - plt.show() +plt.tight_layout() +plt.show() diff --git a/src/calibrate.cpp.bak b/src/calibrate.cpp.bak new file mode 100644 index 0000000..c42fae7 --- /dev/null +++ b/src/calibrate.cpp.bak @@ -0,0 +1,93 @@ +/*! + * @file getGeomagneticData.ino + * @brief Get the calibration data + * @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north + * @n Experimental phenomenon: serial print the geomagnetic data of x-axis, y-axis and z-axis and the compass degree + * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + * @license The MIT License (MIT) + * @author [GDuang](yonglei.ren@dfrobot.com) + * @version V1.0.0 + * @date 2024-05-06 + * @url https://github.com/DFRobot/DFRobot_BMM350/ + */ + +// ======================================================= +// 请先阅读项目 https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration +// Please read https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration +// 包含使用说明、校准步骤。 +// It contains usage instructions, calibration steps. +// ======================================================= +#include "DFRobot_BMM350.h" + +DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); +void setup() { + Serial.begin(115200); + while (!Serial) + ; + Wire.begin(8, 9); + while (bmm350.begin()) { + Serial.println("bmm350 init failed, Please try again!"); + delay(1000); + } + Serial.println("bmm350 init success!"); + + /** + * Set sensor operation mode + * opMode: + * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, + * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. + * eBmm350NormalMode // normal mode Get geomagnetic data normally. + * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. + * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. + */ + bmm350.setOperationMode(eBmm350NormalMode); + /** + * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) + * presetMode: + * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. + * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. + * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. + * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. + * rate: + * BMM350_DATA_RATE_1_5625HZ + * BMM350_DATA_RATE_3_125HZ + * BMM350_DATA_RATE_6_25HZ + * BMM350_DATA_RATE_12_5HZ (default rate) + * BMM350_DATA_RATE_25HZ + * BMM350_DATA_RATE_50HZ + * BMM350_DATA_RATE_100HZ + * BMM350_DATA_RATE_200HZ + * BMM350_DATA_RATE_400HZ + */ + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); + + /** + * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. + * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. + */ + bmm350.setMeasurementXYZ(); +} + +void loop() { + sBmm350MagData_t magData = bmm350.getGeomagneticData(); + Serial.print("Raw:"); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(0); + Serial.print(','); + Serial.print(magData.x*10); + Serial.print(','); + Serial.print(magData.y*10); + Serial.print(','); + Serial.print(magData.z*10); + Serial.println(); + delay(100); +} diff --git a/src/main.cpp b/src/main.cpp index 279268d..eb17f22 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -16,10 +16,12 @@ #include "robot/encoder.h" #include "../env.h" #include "robot/pidController.h" +#include "robot/magnet.h" //alright SCREW YOU serial monitor i won't print every frame then if you wanna play that game const int8_t PRINT_INTERVAL = 60; int8_t framesUntilPrint = 60; +unsigned long previousTime = 0; // For loop timing // Setup gets run at startup void setup() { @@ -29,7 +31,6 @@ void setup() { delay(STARTUP_DELAY); serialLogln("Finished Delay!", 2); - // Any setup needed to get bot ready setupBot(); @@ -44,6 +45,8 @@ void setup() { if (DO_DRIVE_TICKS_TEST) driveTicks(20000, "NULL"); if (DO_HARDWARE_TEST) timerDelay(5000, &startMotorAndEncoderTest); + + previousTime = millis() - loopDelayMilliseconds; } // After setup gets run, loop is run over and over as fast ass possible @@ -68,7 +71,10 @@ void loop() { } // Run control loop - controlLoop(loopDelayMilliseconds, framesUntilPrint); + // TODO change time parameter to be actual delta time, not just delay between loops + unsigned long deltaTime = millis() - previousTime; + previousTime = millis(); + controlLoop(deltaTime, framesUntilPrint); // This delay determines how often the code in loop is run // (Forcefully pauses the thread for about the amount of milliseconds passed in) diff --git a/src/robot/control.cpp b/src/robot/control.cpp index 5631c5a..887485a 100644 --- a/src/robot/control.cpp +++ b/src/robot/control.cpp @@ -3,7 +3,6 @@ // Associated Header File #include "robot/control.h" -#include "robot/trapezoidalProfile.h" // Built-In Libraries #include "Arduino.h" @@ -24,9 +23,23 @@ #include #include "utils/functions.h" -//PLEASE ONLY USE CHESSBOT #4 FOR TESTING -PIDController encoderAVelocityController(0.00008, 0.0000035, 0.000001, -1, +1); //Blue -PIDController encoderBVelocityController(0.00008, 0.0000035, 0.000001, -1, +1); //Red +#include "robot/profiledPIDController.h" +#include "robot/trapezoidalProfileNew.h" +#include "robot/magnet.h" + + +Magnet *magnet = nullptr; // Declare a pointer to Magnet + +// pid constants +TrapezoidProfile::Constraints profileConstraints(VELOCITY_LIMIT_TPS, ACCELERATION_LIMIT_TPSPS); +TrapezoidProfile xProfile(profileConstraints); +TrapezoidProfile yProfile(profileConstraints); +TrapezoidProfile aProfile(profileConstraints); +TrapezoidProfile::State xSetpoint, ySetpoint, aSetpoint; +PIDController XVelocityController(0.000009, 0.000035, 0.000000000001, -1, +1, 10); +PIDController YVelocityController(0.0000005, 0.000035, 0.000000000001, -1, +1, 10); +PIDController AVelocityController(0.000012, 0.00000, 0.0000000000000, -1, +1, 10); //angular velocity used for turns +ContinuousPIDController headingController(0.21, 0.000001, 0.000000000001, -1, +1, 0.1, -180, 180); // input degrees, output duty cycle //put this in manually for each bot. Dist between the two front encoders, or the two back encoders. In meters. const float lightDist = 0.07; @@ -46,8 +59,20 @@ const uint8_t Bottom_Right_Encoder_Index = 3; boolean testEncoderPID_value = false; //determines the encoder values the iteration right before -int prevPositionA = 0; -int prevPositionB = 0; +int prevPositionL = 0; +int prevPositionR = 0; +int timeMs = 0; + +//robot rotation in radians +double prevRotation = 0; + +//calculated previous X and Y values +double prevX = 0; +double prevY = 0; + +bool runningPID = false; +bool runningTurn = false; +double average[50]; //when moving to a different target, this is the encoder position we started from int startEncoderAPos = -1; @@ -113,29 +138,45 @@ void testEncoderPID() if (!testEncoderPID_value) { testEncoderPID_value = true; - setLeftMotorControl({POSITION, (float)TICKS_PER_ROTATION * 5}); - setRightMotorControl({POSITION, (float)TICKS_PER_ROTATION * 5}); + setXControl({POSITION, (float)TICKS_PER_ROTATION * 6}); + setYControl({POSITION, 0.0f}); + runningPID = true; } else { testEncoderPID_value = false; - setLeftMotorControl({POSITION, 0.0f}); - setRightMotorControl({POSITION, 0.0f}); + setXControl({POSITION, 0.0f}); + setYControl({POSITION, 0.0f}); + runningPID = true; } updateCritRange(); } +/** + * get PID ready for the next iteration + */ +void resetPID(){ + prevPositionL = readLeftEncoder(); + prevPositionR = readRightEncoder(); + prevX = 0; + prevY = 0; + prevRotation = 0; + timeMs = 0; + for (int x = 0; x < 50; x++) average[x] = 100; +} + + //crit range is basically getting distance we go until we are halfway to target. By the end of this range, //we're at our max speed and are sure we aren't at a low speed just cause we're speeding up void updateCritRange() { //want to record the values before we move now - startEncoderAPos = profileA.currentPosition; - startEncoderBPos = profileB.currentPosition; + startEncoderAPos = profileX.currentPosition; + startEncoderBPos = profileY.currentPosition; - profileA.criticalRange = fabs(profileA.targetPosition - startEncoderAPos) / 2; - profileB.criticalRange = fabs(profileB.targetPosition - startEncoderBPos) / 2; + profileX.criticalRange = fabs(profileX.targetPosition - startEncoderAPos) / 2; + profileY.criticalRange = fabs(profileY.targetPosition - startEncoderBPos) / 2; //update it so that time since start is now equal to this. Only really care about this value after turns though timeSinceTurn = millis(); @@ -175,16 +216,28 @@ void setupBot() { setupMotors(); setupIR(); setupEncodersNew(); + magnet = new Magnet(); + if (!magnet->isActive()) { + serialLogln("Magnetometer not responding!", 0); + } else { + serialLogln("Magnetometer ready!", 2); + headingTarget = magnet->readDegrees(); + } serialLogln("Bot Set Up!", 2); - encoderAVelocityController.Reset(); - encoderBVelocityController.Reset(); + XVelocityController.Reset(); + YVelocityController.Reset(); + AVelocityController.Reset(); + headingController.Reset(); + resetPID(); + if (DO_PID_TEST) { + setHeadingTarget(magnet->readDegrees()); testEncoderPID(); - timerInterval(12000, &testEncoderPID); + timerInterval(8000, &testEncoderPID); } - + if (DO_TURN_TEST) { angle = 30; testTurn(); @@ -230,99 +283,198 @@ void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { } if (DO_ENCODER_TEST) encoderLoop(); - - if (DO_PID) { - double loopDelaySeconds = ((double) loopDelayMs) / 1000; - - int currentPositionEncoderA = readLeftEncoder(); - int currentPositionEncoderB = readRightEncoder(); - double currentVelocityA = (currentPositionEncoderA - prevPositionA) / loopDelaySeconds; - double currentVelocityB = (currentPositionEncoderB - prevPositionB) / loopDelaySeconds; - - profileA.currentPosition = currentPositionEncoderA; - profileA.currentVelocity = currentVelocityA; - profileB.currentPosition = currentPositionEncoderB; - profileB.currentVelocity = currentVelocityB; - - double desiredVelocityA, desiredVelocityB; - - if (getLeftMotorControl().mode == POSITION) { - desiredVelocityA = updateTrapezoidalProfile(profileA, loopDelaySeconds, framesUntilPrint); - } else { - desiredVelocityA = getLeftMotorControl().value; - } - if (getRightMotorControl().mode == POSITION) { - desiredVelocityB = updateTrapezoidalProfile(profileB, loopDelaySeconds, framesUntilPrint); - } else { - desiredVelocityB = getRightMotorControl().value; + + if (DO_PID){ + double trackWidth = TRACK_WIDTH_INCHES/39.37; + if(runningPID){ + + double lDist = (double)(readLeftEncoder()-prevPositionL)/TICKS_PER_ROTATION*2*PI; + double rDist = (double)(readRightEncoder()-prevPositionR)/TICKS_PER_ROTATION*2*PI; + + prevPositionL = readLeftEncoder(); + prevPositionR = readRightEncoder(); + + double angleDist = (rDist - lDist)*TIRE_RADIUS/trackWidth; + + double currentRot = prevRotation + angleDist; + + double currentX; + double deltaX; + double currentY; + double deltaY; + if(angleDist != 0){ + double temp = (trackWidth*(rDist+lDist))/(2*(rDist-lDist)); + deltaX = temp * (sin(currentRot) - sin(prevRotation)); + deltaY = temp * (cos(prevRotation) - cos(currentRot)); + currentX = prevX + deltaX; + currentY = prevY + deltaY; + + } else { + double totalDist = TIRE_RADIUS*(lDist + rDist)/2; + deltaX = totalDist * cos(currentRot); + deltaY = totalDist * sin(currentRot); + currentX = prevX + deltaX; + currentY = prevY + deltaY; + } + prevX = currentX; + prevY = currentY; + prevRotation = currentRot; + + double loopDelaySeconds = ((double) timeMs) / 1000; + profileX.currentPosition = currentX / TICK_TO_METERS; + profileX.currentVelocity = deltaX==0?0:deltaX / TICK_TO_METERS /loopDelaySeconds; + xSetpoint = xProfile.calculate(loopDelaySeconds, + TrapezoidProfile::State(profileX.currentPosition, profileX.currentVelocity), + TrapezoidProfile::State(getLeftMotorControl().value, 0.0)); + + double velocity = XVelocityController.Compute(xSetpoint.velocity, profileX.currentVelocity, loopDelaySeconds); + double aVel = headingController.Compute(headingTarget, currentRot*RAD_TO_DEG, loopDelaySeconds); + + profileY.currentPosition = currentY / TICK_TO_METERS; + profileY.currentVelocity = deltaY==0?0:deltaY / TICK_TO_METERS /loopDelaySeconds; + ySetpoint = yProfile.calculate(loopDelayMs/1000, + TrapezoidProfile::State(profileY.currentPosition, profileY.currentVelocity), + TrapezoidProfile::State(getRightMotorControl().value, 0.0)); + double yVel = YVelocityController.Compute(ySetpoint.velocity, profileY.currentVelocity, loopDelaySeconds); + + aVel += yVel; + + double lMotorPower = fmap((velocity-8*aVel*trackWidth/2)/TIRE_RADIUS, -25, 25, -1, 1); + double rMotorPower = fmap((velocity+8*aVel*trackWidth/2)/TIRE_RADIUS, -25, 25, -1, 1); + + if (fabs(lMotorPower) < MIN_MOTOR_POWER) lMotorPower = 0; + if (fabs(rMotorPower) < MIN_MOTOR_POWER) rMotorPower = 0; + + + serialLog("vel ", 3); + serialLog(velocity, 3); + serialLog(" yvel ", 3); + serialLog(yVel, 3); + serialLog(" avel ", 3); + serialLog(aVel, 3); + + serialLog(" lpower ", 3); + serialLog(lMotorPower, 3); + serialLog(" rpower ", 3); + serialLog(rMotorPower, 3); + serialLog(" xpos ", 3); + serialLog(currentX, 3); + serialLog(" ypos ", 3); + serialLogln(currentY, 3); + + setLeftPower(lMotorPower); + setRightPower(rMotorPower); + + double sum = 0; + for(int x = 49; x >= 0; x--) { + average[x+1] = average[x]; + sum += fabs(average[x+1]); + } + average[0] = lMotorPower; + sum += fabs(average[0]); + timeMs += loopDelayMs; + if (sum/50 < 0.01){ + serialLogln(sum/50,3); + serialLogln(runningPID,3); + runningPID = false; + setLeftPower(0); + setRightPower(0); + + sendActionSuccess("move done"); + resetPID(); + + } else { + runningPID = true; + } } + if(runningTurn){ - prevPositionA = currentPositionEncoderA; - prevPositionB = currentPositionEncoderB; - - double leftFeedForward = desiredVelocityA / MAX_VELOCITY_TPS; - double rightFeedForward = desiredVelocityB / MAX_VELOCITY_TPS; - double leftMotorPower = encoderAVelocityController.Compute(desiredVelocityA, currentVelocityA, loopDelaySeconds) + leftFeedForward; - double rightMotorPower = encoderBVelocityController.Compute(desiredVelocityB, currentVelocityB, loopDelaySeconds) + rightFeedForward; + double lDist = (double)(readLeftEncoder()-prevPositionL)/TICKS_PER_ROTATION*2*PI; + double rDist = (double)(readRightEncoder()-prevPositionR)/TICKS_PER_ROTATION*2*PI; - if (leftMotorPower > 1) leftMotorPower = 1; - if (leftMotorPower < -1) leftMotorPower = -1; - if (rightMotorPower > 1) rightMotorPower = 1; - if (rightMotorPower < -1) rightMotorPower = -1; + prevPositionL = readLeftEncoder(); + prevPositionR = readRightEncoder(); - //using macros this code isn't uploaded if not proper loging levels - #if LOGGING_LEVEL >= 4 - - if(framesUntilPrint == 0) - { - serialLog("Current encoder A pos: ", 2); - serialLog(currentEncoderA, 2); - serialLog(", ", 2); - serialLog("Current encoder B pos: ", 2); - serialLog(currentEncoderB, 2); - serialLog(", ", 2); - serialLog("Desired encoder A speed: ", 2); - serialLog(desiredVelocityA, 2); - serialLog(", ", 2); - serialLog("Desired encoder B speed: ", 2); - serialLog(desiredVelocityB, 2); - serialLog(", ", 2); - serialLog("current encoder a speed: ", 2); - serialLog(currentVelocityA, 2); - serialLog(", ", 2); - serialLog("current encoder b speed: ", 2); - serialLog(currentVelocityB, 2); - serialLog(", ", 2); - serialLog("current left motor power: ", 2); - serialLog(leftMotorPower, 2); - serialLog(", ", 2); - serialLog("current right motor power: ", 2); - serialLog(rightMotorPower, 2); - serialLog(", ", 2); - serialLog("current encoder a target: ", 2); - serialLog(leftMotorControl.mode == POSITION ? leftMotorControl.value : 0, 2); - serialLog(", ", 2); - serialLog("current encoder b target: ", 2); - serialLog(rightMotorControl.mode == POSITION ? rightMotorControl.value : 0, 2); // TODO log results of trapezoidal profile into csv (on motor value graph) - serialLog(", ", 2); - serialLog("is robot pid at target? ", 2); - serialLog(isRobotPidAtTarget(), 2); - serialLog(", ", 2); - serialLogln(loopDelaySeconds, 2); - } - - #endif + double angleDist = (rDist - lDist)*TIRE_RADIUS/trackWidth; - drive( - leftMotorPower, // leftMotorPower, - rightMotorPower, // rightMotorPower, - "NULL" - ); + double currentRot = prevRotation + angleDist; - // serialLogln(leftMotorPower, 3); + double currentX; + double deltaX; + double currentY; + double deltaY; + if(angleDist != 0){ + double temp = (trackWidth*(rDist+lDist))/(2*(rDist-lDist)); + deltaX = temp * (sin(currentRot) - sin(prevRotation)); + deltaY = temp * (cos(prevRotation) - cos(currentRot)); + currentX = prevX + deltaX; + currentY = prevY + deltaY; + + } else { + double totalDist = TIRE_RADIUS*(lDist + rDist)/2; + deltaX = totalDist * cos(currentRot); + deltaY = totalDist * sin(currentRot); + currentX = prevX + deltaX; + currentY = prevY + deltaY; + } + prevX = currentX; + prevY = currentY; + + prevRotation = currentRot; + + double loopDelaySeconds = ((double) timeMs) / 1000; + profileA.currentPosition = currentRot*10 / TICK_TO_METERS; + profileA.currentVelocity = angleDist==0?0:angleDist*10 / TICK_TO_METERS /loopDelaySeconds; + aSetpoint = aProfile.calculate(loopDelaySeconds, + TrapezoidProfile::State(profileA.currentPosition, profileA.currentVelocity), + TrapezoidProfile::State(getHeadingTarget()*10/TICK_TO_METERS, 0.0)); + + double velocity = AVelocityController.Compute(aSetpoint.velocity, profileA.currentVelocity, loopDelaySeconds); + + double lMotorPower = fmap((-8*velocity*trackWidth/2)/TIRE_RADIUS, -11, 11, -1, 1); + double rMotorPower = fmap((8*velocity*trackWidth/2)/TIRE_RADIUS, -11, 11, -1, 1); + + if (fabs(lMotorPower) < MIN_MOTOR_POWER) lMotorPower = 0; + if (fabs(rMotorPower) < MIN_MOTOR_POWER) rMotorPower = 0; + + setLeftPower(lMotorPower); + setRightPower(rMotorPower); + + serialLog("vels ", 3); + serialLog(xSetpoint.velocity, 3); + serialLog("vel ", 3); + serialLog(velocity, 3); + serialLog(" lpower ", 3); + serialLog(lMotorPower, 3); + serialLog(" rpower ", 3); + serialLog(rMotorPower, 3); + serialLog(" angle ", 3); + serialLogln(currentRot*10, 3); + - // turn(M_PI / 2, "NULL"); + double sum = 0; + for(int x = 49; x >= 0; x--) { + average[x+1] = average[x]; + sum += fabs(average[x+1]); + } + average[0] = lMotorPower; + sum += fabs(average[0]); + timeMs += loopDelayMs; + if (sum/50 < 0.01){ + serialLogln(sum/50,3); + serialLogln(runningPID,3); + runningPID = false; + setLeftPower(0); + setRightPower(0); + + sendActionSuccess("turn done"); + resetPID(); + + } else { + runningTurn = true; + } + } } } @@ -374,8 +526,8 @@ void determineNextAction() else if(forwardAligning) { //if going forward, store the current encoder value so we can see the full encoder length of the tiles - encoderAHalfwayDist = profileA.currentPosition; - encoderBHalfwayDist = profileB.currentPosition; + encoderAHalfwayDist = profileX.currentPosition; + encoderBHalfwayDist = profileY.currentPosition; //swap to going back forwardAligning = !forwardAligning; //set that new drive @@ -383,9 +535,9 @@ void determineNextAction() centeringStatus = 'E'; serialLog((char*)"Current encoder A: ", 2); - serialLogln(profileA.currentPosition, 2); + serialLogln(profileX.currentPosition, 2); serialLog((char*)"Current encoder B: ", 2); - serialLogln(profileB.currentPosition, 2); + serialLogln(profileY.currentPosition, 2); serialLog((char*)"Target encoder A: ", 2); serialLogln(leftMotorControl.mode == POSITION ? leftMotorControl.value : 0, 2); serialLog((char*)"Target encoder B: ", 2); @@ -400,8 +552,8 @@ void determineNextAction() //since we always go forward first and then backwards, the current value of encoderHalfwayDist > currentEncoder always //what we're doing is currently, "encoderAHalfwayDist" just stores the value of the other edge in encoder ticks, now we're //finding the difference between them. And of course divide by 2 as want half that distance - encoderAHalfwayDist = (encoderAHalfwayDist - profileA.currentPosition) / 2; - encoderBHalfwayDist = (encoderBHalfwayDist - profileB.currentPosition) / 2; + encoderAHalfwayDist = (encoderAHalfwayDist - profileX.currentPosition) / 2; + encoderBHalfwayDist = (encoderBHalfwayDist - profileY.currentPosition) / 2; //decide that we take average of encoder A and B's distances, since ideally we want both to travel the same amount int totalHalfwayDistance = (encoderAHalfwayDist + encoderBHalfwayDist) / 2; @@ -459,15 +611,15 @@ void updateCentering() //checks if we're done moving to our target when either moving half a tile's length or turning bool checkMoveFinished() { - //first, checks like "fabs(profileA.currentVelocity) < 2" see if we're slowing down or not. + //first, checks like "fabs(profileX.currentVelocity) < 2" see if we're slowing down or not. //then, something like "fabs(currentEncoderA - encoderATarget) < criticalRangeA" is making sure //the reason our speed is slow is specifically because we're slowing down and not because we're //beginning to speed up. //do this by seeing if the distance remaining is less than the midpoint distance from start to end, as by then we're at our max speed. - bool encoderAChecks = fabs(profileA.currentPosition - profileA.targetPosition) < profileA.criticalRange && fabs(profileA.currentVelocity) < 3; - bool encoderBChecks = fabs(profileB.currentPosition - profileB.targetPosition) < profileB.criticalRange && fabs(profileB.currentVelocity) < 3; + bool encoderAChecks = fabs(profileX.currentPosition - profileX.targetPosition) < profileX.criticalRange && fabs(profileX.currentVelocity) < 3; + bool encoderBChecks = fabs(profileY.currentPosition - profileY.targetPosition) < profileY.criticalRange && fabs(profileY.currentVelocity) < 3; //check if we've been stalling too long, for 8 seconds. If we're over time, that's bad, and means we should declare the movement finished. bool timerCheck = millis() - timeSinceTurn > 8000; @@ -478,23 +630,29 @@ bool checkMoveFinished() //like the one above but just seeing if we can keep moving or not bool checkIfCanUpdateMovement() { - return fabs(profileA.currentPosition - profileA.targetPosition) < profileA.criticalRange && fabs(profileB.currentPosition - profileB.targetPosition) < profileB.criticalRange; + return fabs(profileX.currentPosition - profileX.targetPosition) < profileX.criticalRange && fabs(profileY.currentPosition - profileY.targetPosition) < profileY.criticalRange; } -void setLeftMotorControl(ControlSetting control) { +void setXControl(ControlSetting control) { leftMotorControl = control; + xSetpoint = TrapezoidProfile::State(readLeftEncoder(), profileX.currentVelocity); if (control.mode == POSITION) - profileA.targetPosition = control.value; + profileX.targetPosition = control.value; else - profileA.targetVelocity = control.value; + profileX.targetVelocity = control.value; } -void setRightMotorControl(ControlSetting control) { +void setYControl(ControlSetting control) { rightMotorControl = control; + ySetpoint = TrapezoidProfile::State(readRightEncoder(), profileY.currentVelocity); if (control.mode == POSITION) - profileB.targetPosition = control.value; + profileY.targetPosition = control.value; else - profileB.targetVelocity = control.value; + profileY.targetVelocity = control.value; +} + +void setHeadingTarget(double target) { + headingTarget = target; } ControlSetting getLeftMotorControl() { @@ -505,6 +663,10 @@ ControlSetting getRightMotorControl() { return rightMotorControl; } +double getHeadingTarget() { + return headingTarget; +} + void drive(float tiles, std::string id) { if (!getStoppedStatus()) { const float TILE_SIZE_INCHES = 24; @@ -521,9 +683,10 @@ void driveTicks(int tickDistance, std::string id) { if (!getStoppedStatus()) { resetSpeed(); - setLeftMotorControl({POSITION, (float)(readLeftEncoder() + tickDistance)}); - setRightMotorControl({POSITION, (float)(readRightEncoder() + tickDistance)}); + setXControl({POSITION, (float)tickDistance}); + setYControl({POSITION, 0}); updateCritRange(); + runningPID = true; if (id != "NULL") { sendPacketOnPidComplete(id); @@ -535,10 +698,9 @@ void driveTicks(int tickDistance, std::string id) void drive(float leftPower, float rightPower, std::string id) { if (!getStoppedStatus()) { // TODO: maybe move to motor.cpp? - float minPower = 0.16; - if (leftPower < minPower && leftPower > -minPower) { + if (leftPower < MIN_MOTOR_POWER && leftPower > -MIN_MOTOR_POWER) { leftPower = 0; - } if (rightPower < minPower && rightPower > -minPower) { + } if (rightPower < MIN_MOTOR_POWER && rightPower > -MIN_MOTOR_POWER) { rightPower = 0; } @@ -551,23 +713,18 @@ void drive(float leftPower, float rightPower, std::string id) { } } -//turns the given amount in radians +//turns the given amount in radians, CCW void turn(float angleRadians, std::string id) { + serialLogln("Turning", 3); serialLogln(angleRadians, 3); - int offsetTicks = radiansToTicks(angleRadians); - if (getLeftMotorControl().mode == POSITION) { - setLeftMotorControl({POSITION, getLeftMotorControl().value - offsetTicks}); - } else { - setLeftMotorControl({POSITION, (float)(readLeftEncoder() - offsetTicks)}); - } - if (getRightMotorControl().mode == POSITION) { - setRightMotorControl({POSITION, getRightMotorControl().value + offsetTicks}); - } else { - setRightMotorControl({POSITION, (float)(readRightEncoder() + offsetTicks)}); - } + setXControl({POSITION, 0}); + setYControl({POSITION, 0}); + updateCritRange(); + setHeadingTarget(angleRadians*0.95); + runningTurn = true; if (id != "NULL") { @@ -592,39 +749,39 @@ boolean isRobotPidAtTarget() { if (getLeftMotorControl().mode == POSITION) { - leftAtTarget = approxEquals(getLeftMotorControl().value, profileA.currentPosition, PID_POSITION_TOLERANCE) - && approxEquals(profileA.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE); + leftAtTarget = approxEquals(getLeftMotorControl().value, profileX.currentPosition, PID_POSITION_TOLERANCE) + && approxEquals(profileX.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE); serialLog("Left Position: ", 3); - serialLog(profileA.currentPosition, 3); + serialLog(profileX.currentPosition, 3); serialLog(", Target: ", 3); serialLog(getLeftMotorControl().value, 3); serialLog(", Velocity: ", 3); - serialLog(profileA.currentVelocity, 3); + serialLog(profileX.currentVelocity, 3); serialLog(", At Target: ", 3); serialLogln(leftAtTarget, 3); } else { - leftAtTarget = approxEquals(getLeftMotorControl().value, profileA.currentVelocity, PID_VELOCITY_TOLERANCE); + leftAtTarget = approxEquals(getLeftMotorControl().value, profileX.currentVelocity, PID_VELOCITY_TOLERANCE); } if (getRightMotorControl().mode == POSITION) { - rightAtTarget = approxEquals(getRightMotorControl().value, profileB.currentPosition, PID_POSITION_TOLERANCE) - && approxEquals(profileB.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE); + rightAtTarget = approxEquals(getRightMotorControl().value, profileY.currentPosition, PID_POSITION_TOLERANCE) + && approxEquals(profileY.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE); serialLog("Right Position: ", 3); - serialLog(profileB.currentPosition, 3); + serialLog(profileY.currentPosition, 3); serialLog(", Target: ", 3); serialLog(getRightMotorControl().value, 3); serialLog(", Velocity: ", 3); - serialLog(profileB.currentVelocity, 3); + serialLog(profileY.currentVelocity, 3); serialLog(", At Target: ", 3); serialLogln(rightAtTarget, 3); } else { - rightAtTarget = approxEquals(getRightMotorControl().value, profileB.currentVelocity, PID_VELOCITY_TOLERANCE); + rightAtTarget = approxEquals(getRightMotorControl().value, profileY.currentVelocity, PID_VELOCITY_TOLERANCE); } return leftAtTarget && rightAtTarget; @@ -657,8 +814,8 @@ void readLight(int loopDelayMs) { void resetSpeed() { - profileA.targetVelocity = 0; - profileB.targetVelocity = 0; + profileX.targetVelocity = 0; + profileY.targetVelocity = 0; } // Test motor and encoder synchronization @@ -669,7 +826,7 @@ void startMotorAndEncoderTest() { // Tests the motors. This turns the motors on. void startDriveTest() { drive(0.5f, 0.5f, "NULL"); - timerDelay(2000, &driveTestOff); + //timerDelay(2000, &driveTestOff); } //updates us to the next distance we're traveling @@ -677,10 +834,10 @@ void updateToNextDistance() { //this way if we're reversing, we're actually subtracting. if going forward was 0, then 0 * 2 - 1 = -1. //if going forward was 1, 1 * 2 - 1 = 1. - float encTargetA = (float)profileA.currentPosition + 2500 * (forwardAligning * 2 - 1); - float encTargetB = (float)profileB.currentPosition + 2500 * (forwardAligning * 2 - 1); - setLeftMotorControl({POSITION, encTargetA}); - setRightMotorControl({POSITION, encTargetB}); + float encTargetA = (float)profileX.currentPosition + 2500 * (forwardAligning * 2 - 1); + float encTargetB = (float)profileY.currentPosition + 2500 * (forwardAligning * 2 - 1); + setXControl({POSITION, encTargetA}); + setYControl({POSITION, encTargetB}); #if LOGGING_LEVEL >= 3 serialLogln("changing direction!", 3); serialLogln(encTargetA, 3); @@ -743,19 +900,19 @@ uint8_t driveUntilNewTile() uint8_t status = 0; if(leadingEncoder != 0) { - setLeftMotorControl({POSITION, (float)profileA.currentPosition}); - setRightMotorControl({POSITION, (float)profileB.currentPosition}); + setXControl({POSITION, (float)profileX.currentPosition}); + setYControl({POSITION, (float)profileY.currentPosition}); //first get the encoder that we're comparing to get the distance. If leading encoder is 1 and we were moving forward, or if //leading encoder is 2 but we were moving backward, then the back encoder is b, otherwise it's A - double encoderChosen = (leadingEncoder == 1 && forwardAligning || leadingEncoder == 2 && !forwardAligning) ? profileB.currentPosition : profileA.currentPosition; + double encoderChosen = (leadingEncoder == 1 && forwardAligning || leadingEncoder == 2 && !forwardAligning) ? profileY.currentPosition : profileX.currentPosition; //now, the distance we traveled is the difference between the encoders double backEncoderDist = fabs(encoderChosen - backPrevDistance); #if LOGGING_LEVEL >= 3 serialLog("Begin encoder is: ", 2); serialLogln(backPrevDistance, 2); serialLog("End encoder is: ", 2); - serialLogln((leadingEncoder == 1) ? profileA.currentPosition : profileB.currentPosition, 2); + serialLogln((leadingEncoder == 1) ? profileX.currentPosition : profileY.currentPosition, 2); #endif //now convert difference in ticks to meter value backEncoderDist *= TICK_TO_METERS; @@ -816,7 +973,7 @@ uint8_t driveUntilNewTile() leadingEncoder = leftEncoderChange ? 1 : 2; //this makes sense as if the left encoder first crossed but we're going backwards, that's encoder A that's behind. Meanwhile if the right //encoder crossed first and we're going forwards, its encoder A that's behind too. In all other cases, its encoder B - backPrevDistance = (leftEncoderChange && !forwardAligning || rightEncoderChange && forwardAligning) ? profileA.currentPosition : profileB.currentPosition; + backPrevDistance = (leftEncoderChange && !forwardAligning || rightEncoderChange && forwardAligning) ? profileX.currentPosition : profileY.currentPosition; } } return 1; diff --git a/src/robot/driveTest.cpp b/src/robot/driveTest.cpp index 35f6115..0ce6739 100644 --- a/src/robot/driveTest.cpp +++ b/src/robot/driveTest.cpp @@ -148,10 +148,11 @@ void MotorEncoderTest::checkEncoderVelocity() { int encA = readLeftEncoder(); int encB = readRightEncoder(); - float encAVel = (encA - prevEncA) / (float) 0.02; - float encBVel = (encB - prevEncB) / (float) 0.02; - float encAAccel = (encAVel - prevEncVelA); // Am I miscalculating acceleration? Should be change in velocity over change in time, but I'm not dividing by time here - float encBAccel = (encBVel - prevEncVelB); + float timeDiff = (millis() - prevTime) / 1000.0; // in seconds + float encAVel = (encA - prevEncA) / timeDiff; + float encBVel = (encB - prevEncB) / timeDiff; + float encAAccel = (encAVel - prevEncVelA) / timeDiff; // Am I miscalculating acceleration? Should be change in velocity over change in time, but I'm not dividing by time here + float encBAccel = (encBVel - prevEncVelB) / timeDiff; if (abs(encAVel) > maxEncoderVelocity) maxEncoderVelocity = abs(encAVel); if (abs(encBVel) > maxEncoderVelocity) maxEncoderVelocity = abs(encBVel); if (abs(encAAccel) > maxEncoderAccel) maxEncoderAccel = abs(encAAccel); @@ -160,6 +161,7 @@ void MotorEncoderTest::checkEncoderVelocity() prevEncB = encB; prevEncVelA = encAVel; prevEncVelB = encBVel; + prevTime = millis(); } void MotorEncoderTest::testDriveForward() @@ -168,6 +170,7 @@ void MotorEncoderTest::testDriveForward() prevEncB = readRightEncoder(); prevEncVelA = 0; prevEncVelB = 0; + prevTime = millis(); serialLogln("Setting motors to go 'forward' for 5 seconds...", 2); setLeftPower(1); setRightPower(1); diff --git a/src/robot/magnet.cpp b/src/robot/magnet.cpp new file mode 100644 index 0000000..96f00e7 --- /dev/null +++ b/src/robot/magnet.cpp @@ -0,0 +1,125 @@ +#include "DFRobot_BMM350.h" +#include "robot/magnet.h" +#include "utils/logging.h" + +#define SDA_PIN 8 +#define SCL_PIN 9 + +Magnet::Magnet() + : bmm350(&Wire, 0x14) +{ + Wire.begin(SDA_PIN, SCL_PIN); + int maxTries = 6; + int errorCode = -1; + while (maxTries-- > 0 && (errorCode=bmm350.begin())) + { + delay(500); + serialLog("Retrying BMM350 connection... (error code ", 1); + serialLog(errorCode, 1); + serialLogln(")", 1); + } + if (errorCode > 0) { + serialLogln("BMM350 not detected at default I2C address. Check wiring.", 1); + return; + } else { + serialLogln("BMM350 detected.", 1); + } + bmm350.setOperationMode(eBmm350NormalMode); + bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY, BMM350_DATA_RATE_25HZ); + bmm350.setMeasurementXYZ(); + activeFlag = true; + // bmm350.setDataReadyPin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW); + // pinMode(/*Pin */ 13, INPUT_PULLUP); + // maxTries = 5; + // bool dataReady = false; + // while (maxTries-- > 0 && !(dataReady=bmm350.getDataReadyState())) { + // delay(100); + // } + // if (dataReady) { + // serialLogln("BMM350 data ready interrupt enabled.", 1); + // activeFlag = true; + // } else { + // serialLogln("BMM350 data ready interrupt not detected. Check wiring.", 1); + // } +} + +bool Magnet::isActive() { + return activeFlag; +} + +bool Magnet::isDataReady() { + return bmm350.getDataReadyState(); +} + +void Magnet::set_hard_iron_offset(float x, float y, float z) { + hard_iron_offset[0] = x; + hard_iron_offset[1] = y; + hard_iron_offset[2] = z; +} + +void Magnet::set_soft_iron_matrix(float matrix[3][3]) { + for (int i = 0; i < 3; i++) { + for (int j = 0; j < 3; j++) { + soft_iron_matrix[i][j] = matrix[i][j]; + } + } +} + +MagnetReading Magnet::read_calibrated_data() { + sBmm350MagData_t sensor_mag_data = bmm350.getGeomagneticData(); + float hi_data[3]; + float mag_data[3]; + + hi_data[0] = sensor_mag_data.float_x - hard_iron_offset[0]; + hi_data[1] = sensor_mag_data.float_y - hard_iron_offset[1]; + hi_data[2] = sensor_mag_data.float_z - hard_iron_offset[2]; + + for (int i = 0; i < 3; i++) { + mag_data[i] = (soft_iron_matrix[i][0] * hi_data[0]) + (soft_iron_matrix[i][1] * hi_data[1]) + (soft_iron_matrix[i][2] * hi_data[2]); + } + + MagnetReading calibrated_data = { mag_data[0], mag_data[1], mag_data[2] }; + return calibrated_data; +} + +float Magnet::getCompassDegree(MagnetReading mag) { + float compass = 0.0; + compass = atan2(mag.x, mag.y); + if (compass < 0) { + compass += 2 * PI; + } + if (compass > 2 * PI) { + compass -= 2 * PI; + } + return compass * 180 / M_PI; +} + +float Magnet::readDegreesRaw() { + MagnetReading mag = read_calibrated_data(); + return getCompassDegree(mag); +} + +float Magnet::readDegrees() { + // // Only works if data ready interrupt is enabled + // if (previousReading >= 0 && !bmm350.getDataReadyState()) { + // return previousReading; // Return the last reading if data is not ready and previousReading is valid + // } + float currentReading = readDegreesRaw(); + // Handle first reading + if (previousReading < 0) { + previousReading = currentReading; + return currentReading; + } + // Handle wrap-around + if (currentReading - previousReading > 180) { + previousReading += 360; + } else if (currentReading - previousReading < -180) { + previousReading -= 360; + } + // Simple low-pass filter + // currentReading = previousReading * 0.8 + currentReading * 0.2; + if (currentReading >= 360) currentReading -= 360; + else if (currentReading < 0) currentReading += 360; + previousReading = currentReading; + return currentReading; +} diff --git a/src/robot/pidController.cpp b/src/robot/pidController.cpp index 2c74fba..293a06a 100644 --- a/src/robot/pidController.cpp +++ b/src/robot/pidController.cpp @@ -9,9 +9,9 @@ double PIDController::Compute(double setpoint, double actual_value, double dt) { // Calculate error - double error = setpoint - actual_value; + double error = this->getError(setpoint, actual_value); - if (abs(error) < 100) { + if (abs(error) < errorTolerance) { return 0; } diff --git a/src/robot/splines.cpp b/src/robot/splines.cpp index 706f4d0..a7c17cd 100644 --- a/src/robot/splines.cpp +++ b/src/robot/splines.cpp @@ -27,8 +27,8 @@ void velocityUpdateTimerFunction(std::string id) float desiredVelocityLeft, desiredVelocityRight; std::tie(desiredVelocityLeft, desiredVelocityRight) = timeSlicesToExecute.front(); - setLeftMotorControl({VELOCITY, desiredVelocityLeft}); - setRightMotorControl({VELOCITY, desiredVelocityRight}); + setXControl({VELOCITY, desiredVelocityLeft}); + setYControl({VELOCITY, desiredVelocityRight}); timeSlicesToExecute.pop(); // 1ms delay ensures the function will run in the next loop @@ -244,8 +244,8 @@ void customMotionProfileTimerFunction(MotionProfile &customProfileA, MotionProfi float desiredVelocityLeft = updateTrapezoidalProfile(customProfileA, dt, 0); float desiredVelocityRight = updateTrapezoidalProfile(customProfileB, dt, 0); - setLeftMotorControl({VELOCITY, desiredVelocityLeft}); - setRightMotorControl({VELOCITY, desiredVelocityRight}); + setXControl({VELOCITY, desiredVelocityLeft}); + setYControl({VELOCITY, desiredVelocityRight}); timerDelay(1, [&customProfileA, &customProfileB, dt, id](){ customMotionProfileTimerFunction(customProfileA, customProfileB, dt, id); }); } diff --git a/src/robot/trapezoidalProfileNew.cpp b/src/robot/trapezoidalProfileNew.cpp new file mode 100644 index 0000000..8dae385 --- /dev/null +++ b/src/robot/trapezoidalProfileNew.cpp @@ -0,0 +1,107 @@ +#include "robot/trapezoidalProfileNew.h" +#include "utils/config.h" +#include "utils/logging.h" +#include + +TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State ¤t, const State &goal) +{ + int m_direction = shouldFlipAcceleration(current, goal) ? -1 : 1; + State m_current = direct(current, m_direction); + State goalDir = direct(goal, m_direction); + + if (m_current.velocity > m_constraints.maxVelocity) + { + m_current.velocity = m_constraints.maxVelocity; + } + else if (m_current.velocity < -m_constraints.maxVelocity) + { + m_current.velocity = -m_constraints.maxVelocity; + } + + double cutoffBegin = m_current.velocity / m_constraints.maxAcceleration; + double cutoffDistBegin = cutoffBegin * cutoffBegin * m_constraints.maxAcceleration / 2.0; + + double cutoffEnd = max((goalDir.velocity - MIN_MOTOR_VELOCITY_TPS), 0.0) / m_constraints.maxAcceleration; + double cutoffDistEnd = cutoffEnd * cutoffEnd * m_constraints.maxAcceleration / 2.0; + + double fullTrapezoidDist = cutoffDistBegin + (goalDir.position - m_current.position) + cutoffDistEnd; + double accelerationTime = m_constraints.maxVelocity / m_constraints.maxAcceleration; + + double fullSpeedDist = fullTrapezoidDist - accelerationTime * accelerationTime * m_constraints.maxAcceleration; + + if (fullSpeedDist < 0) + { + accelerationTime = std::sqrt(fullTrapezoidDist / m_constraints.maxAcceleration); + fullSpeedDist = 0; + } + + State result(m_current.position, m_current.velocity); + + double dist = fabs(m_current.position - goalDir.position); + + double accelDist = (pow(m_constraints.maxVelocity,2) - pow(m_current.velocity,2)) / (2*m_constraints.maxAcceleration); //dist to/from max vel + double fastDist = dist - 2*accelDist; + + if(m_current.position < accelDist){ + result.velocity += t * m_constraints.maxAcceleration; + + } + + else if(dist > accelDist+100){ + result.velocity = m_constraints.maxVelocity; + serialLogln(result.velocity,3); + } + else if (dist > 10){ + result.velocity = m_current.velocity - min(sqrt(m_constraints.maxAcceleration*fabs(accelDist-dist))*.250,m_current.velocity*0.99); + serialLog("slowing ", 3); + serialLogln(result.velocity,3); + } + else + { + result = goalDir; + } + + /* + double m_endAccel = accelerationTime - cutoffBegin; + double m_endFullSpeed = m_endAccel + fullSpeedDist / m_constraints.maxVelocity; + double m_endDecel = m_endFullSpeed + accelerationTime - cutoffEnd; + State result(m_current.position, m_current.velocity); + + if (t < m_endAccel) + { + result.velocity += t * m_constraints.maxAcceleration; + if (abs(result.velocity) < MIN_MOTOR_VELOCITY_TPS) { + result.velocity = MIN_MOTOR_VELOCITY_TPS; + } + result.position += (m_current.velocity + t * m_constraints.maxAcceleration / 2.0) * t; + serialLog("accelerating ", 3); + serialLogln(result.velocity,3); + } + else if (t < m_endFullSpeed) + { + result.velocity = m_constraints.maxVelocity; + result.position += + (m_current.velocity + m_endAccel * m_constraints.maxAcceleration / 2.0) * m_endAccel + + m_constraints.maxVelocity * (t - m_endAccel); + serialLog("holding ", 3); + serialLogln(result.velocity,3); + } + else if (t <= m_endDecel) + { + double timeLeft = m_endDecel - t; + result.velocity = goalDir.velocity + timeLeft * m_constraints.maxAcceleration; + result.position = goalDir.position - (goalDir.velocity * timeLeft) - (timeLeft * timeLeft * m_constraints.maxAcceleration / 2.0); + serialLog("slowing ", 3); + serialLogln(result.velocity,3); + } + else + { + result = goalDir; + } + */ + if (abs(result.position - goalDir.position) <= 10) { + result.velocity = 0; + } + + return direct(result, m_direction); +} diff --git a/src/utils/config.cpp b/src/utils/config.cpp index 6049e39..6779e66 100644 --- a/src/utils/config.cpp +++ b/src/utils/config.cpp @@ -37,10 +37,16 @@ gpio_num_t BATTERY_VOLTAGE_PIN = GPIO_NUM_10; int TICKS_PER_ROTATION = 12000; float TRACK_WIDTH_INCHES = 8.29; float WHEEL_DIAMETER_INCHES = 4.75; -float MAX_VELOCITY_TPS = 39000; -float MAX_ACCELERATION_TPSPS = 5000; +float THEORETICAL_MAX_VELOCITY_TPS = 52000; +float THEORETICAL_MAX_ACCELERATION_TPSPS = 252000; +float VELOCITY_LIMIT_TPS = 30000; +float ACCELERATION_LIMIT_TPSPS = 125000; +float MIN_MOTOR_POWER = 0.15; // Minimum motor power to elicit motor response, empirically determined +float MIN_MOTOR_VELOCITY_TPS = 5000; float TILES_TO_TICKS = 2*12*TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); +int MAGNET_CCW_IS_POSITIVE = 1; // Set to 1 if counterclockwise rotation is positive, -1 if clockwise rotation is positive + float PID_POSITION_TOLERANCE = 100; float PID_VELOCITY_TOLERANCE = 6000; @@ -68,8 +74,12 @@ void setConfig(JsonObject config) { if (config["TICKS_PER_ROTATION"].is()) TICKS_PER_ROTATION = config["TICKS_PER_ROTATION"]; if (config["TRACK_WIDTH_INCHES"].is()) TRACK_WIDTH_INCHES = config["TRACK_WIDTH_INCHES"]; if (config["WHEEL_DIAMETER_INCHES"].is()) WHEEL_DIAMETER_INCHES = config["WHEEL_DIAMETER_INCHES"]; - if (config["MAX_VELOCITY_TPS"].is()) MAX_VELOCITY_TPS = config["MAX_VELOCITY_TPS"]; - if (config["MAX_ACCELERATION_TPSPS"].is()) MAX_ACCELERATION_TPSPS = config["MAX_ACCELERATION_TPSPS"]; + if (config["THEORETICAL_MAX_VELOCITY_TPS"].is()) THEORETICAL_MAX_VELOCITY_TPS = config["THEORETICAL_MAX_VELOCITY_TPS"]; + if (config["THEORETICAL_MAX_ACCELERATION_TPSPS"].is()) THEORETICAL_MAX_ACCELERATION_TPSPS = config["THEORETICAL_MAX_ACCELERATION_TPSPS"]; + if (config["MIN_MOTOR_POWER"].is()) MIN_MOTOR_POWER = config["MIN_MOTOR_POWER"]; + if (config["MIN_MOTOR_VELOCITY_TPS"].is()) MIN_MOTOR_VELOCITY_TPS = config["MIN_MOTOR_VELOCITY_TPS"]; + + if (config["MAGNET_CCW_IS_POSITIVE"].is()) MAGNET_CCW_IS_POSITIVE = config["MAGNET_CCW_IS_POSITIVE"]; serialLogln("Config Set!", 2); } diff --git a/src/utils/logging.cpp b/src/utils/logging.cpp index 58ffb88..56baaa0 100644 --- a/src/utils/logging.cpp +++ b/src/utils/logging.cpp @@ -55,6 +55,12 @@ void serialLogln(double value, int serialLoggingLevel) Serial.println(value); } +void serialLogln(float value, int serialLoggingLevel) +{ + if (serialLoggingLevel <= LOGGING_LEVEL) + Serial.println(value); +} + void serialLogln(std::string value, int serialLoggingLevel) { serialLogln(value.c_str(), serialLoggingLevel); diff --git a/src/wifi/packet.cpp b/src/wifi/packet.cpp index f69a964..e19f21f 100644 --- a/src/wifi/packet.cpp +++ b/src/wifi/packet.cpp @@ -39,6 +39,7 @@ const char* ESTOP = "ESTOP"; const char* CUBIC = "DRIVE_CUBIC_SPLINE"; const char* QUADRATIC = "DRIVE_QUADRATIC_SPLINE"; const char* SPIN_RADIANS = "SPIN_RADIANS"; +const char* BS_MOVE = "BS_MOVE"; // Takes a packet a does specific things based on the type void handlePacket(JsonDocument packet) { @@ -77,7 +78,7 @@ void handlePacket(JsonDocument packet) { drive(packet["tiles"], packet["packetId"]); } else if (packet["type"] == PING_SEND) { sendPingResponse(); - } + } } // This creates the handshake packet sent to the server when this bot connects to it From 9fd4364a35700a45f76582976e5ef1d1ffca57f1 Mon Sep 17 00:00:00 2001 From: Siddharth Narayan Date: Tue, 31 Mar 2026 14:02:36 -0500 Subject: [PATCH 02/12] Refactoring baseline commit This commit is the *starting point* for refactoring. It does not compile. Changes made: - Added Robot, Motor and Light classes - Refactored quite a bit of control.cpp to make it much clearer - Moved control related code into the `control` folder - Started using enums for centering status instead of unkown sentinel values - Changed up the frame system for printing every `n` frames - Moved tests into their own file and separated them from the rest of the code - Moved Encoder code to the Motor class - Added serial_printf to more easily debug - Started centering refactor in center_tick - Started work on pid_tick - And more A lot of functionality was removed. Tests were commented out to get code to compile at some points during development --- .vscode/extensions.json | 10 - include/robot/battery.h | 6 - include/robot/control.h | 59 -- include/robot/control/lights.h | 23 + include/robot/{ => control}/magnet.h | 0 include/robot/control/motor.h | 41 ++ include/robot/control/robot.h | 120 ++++ include/robot/encoder.h | 11 - include/robot/lightSensor.h | 14 - include/robot/motor.h | 8 - include/robot/trapezoidalProfile.h | 2 +- include/robot/trapezoidalProfileNew.h | 1 + include/utils/config.h | 3 + include/wifi/connection.h | 2 +- platformio.ini | 3 + src/main.cpp | 31 +- src/robot/battery.cpp | 19 - src/robot/control.cpp | 988 -------------------------- src/robot/control/lights.cpp | 63 ++ src/robot/{ => control}/magnet.cpp | 3 +- src/robot/control/motor.cpp | 57 ++ src/robot/control/robot.cpp | 874 +++++++++++++++++++++++ src/robot/driveTest.cpp | 389 +++++----- src/robot/encoder.cpp | 50 -- src/robot/lightSensor.cpp | 122 ---- src/robot/motor.cpp | 67 -- src/robot/splines.cpp | 7 +- src/robot/trapezoidalProfile.cpp | 39 +- src/robot/trapezoidalProfileNew.cpp | 2 +- src/tests/tests.cpp | 20 + src/utils/config.cpp | 2 + src/utils/logging.cpp | 25 + src/wifi/connection.cpp | 18 +- src/wifi/packet.cpp | 50 +- src/wifi/wireless.cpp | 2 +- 35 files changed, 1499 insertions(+), 1632 deletions(-) delete mode 100644 .vscode/extensions.json delete mode 100644 include/robot/battery.h delete mode 100644 include/robot/control.h create mode 100644 include/robot/control/lights.h rename include/robot/{ => control}/magnet.h (100%) create mode 100644 include/robot/control/motor.h create mode 100644 include/robot/control/robot.h delete mode 100644 include/robot/encoder.h delete mode 100644 include/robot/lightSensor.h delete mode 100644 include/robot/motor.h delete mode 100644 src/robot/battery.cpp delete mode 100644 src/robot/control.cpp create mode 100644 src/robot/control/lights.cpp rename src/robot/{ => control}/magnet.cpp (99%) create mode 100644 src/robot/control/motor.cpp create mode 100644 src/robot/control/robot.cpp delete mode 100644 src/robot/encoder.cpp delete mode 100644 src/robot/lightSensor.cpp delete mode 100644 src/robot/motor.cpp create mode 100644 src/tests/tests.cpp diff --git a/.vscode/extensions.json b/.vscode/extensions.json deleted file mode 100644 index 080e70d..0000000 --- a/.vscode/extensions.json +++ /dev/null @@ -1,10 +0,0 @@ -{ - // See http://go.microsoft.com/fwlink/?LinkId=827846 - // for the documentation about the extensions.json format - "recommendations": [ - "platformio.platformio-ide" - ], - "unwantedRecommendations": [ - "ms-vscode.cpptools-extension-pack" - ] -} diff --git a/include/robot/battery.h b/include/robot/battery.h deleted file mode 100644 index cd2e704..0000000 --- a/include/robot/battery.h +++ /dev/null @@ -1,6 +0,0 @@ -#ifndef CHESSBOT_BATTERY_H -#define CHESSBOT_BATTERY_H - -int getBatteryLevel(); - -#endif \ No newline at end of file diff --git a/include/robot/control.h b/include/robot/control.h deleted file mode 100644 index 28442f1..0000000 --- a/include/robot/control.h +++ /dev/null @@ -1,59 +0,0 @@ -#ifndef CHESSBOT_CONTROL_H -#define CHESSBOT_CONTROL_H - -#include "Arduino.h" -#include "utils/config.h" -#include "robot/trapezoidalProfile.h" - -enum OperatingMode -{ - POSITION, - VELOCITY -}; - -struct ControlSetting -{ - OperatingMode mode; - float value; -}; - -static ControlSetting leftMotorControl; -static ControlSetting rightMotorControl; -static double headingTarget = 0.0; - -static MotionProfile profileX = {THEORETICAL_MAX_VELOCITY_TPS, THEORETICAL_MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity -static MotionProfile profileY = {THEORETICAL_MAX_VELOCITY_TPS, THEORETICAL_MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity -static MotionProfile profileA = {THEORETICAL_MAX_VELOCITY_TPS, THEORETICAL_MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity - - -void setXControl(ControlSetting control); -void setYControl(ControlSetting control); -void setHeadingTarget(double target); -ControlSetting getLeftMotorControl(); -ControlSetting getRightMotorControl(); -double getHeadingTarget(); - -void setupBot(); -void drive(float tiles, std::string id); -void drive(float leftPower, float rightPower, std::string id); -void driveTicks(int tickDistance, std::string id); -void turn(float angleRadians, std::string id); -void stop(); -void sendPacketOnPidComplete(std::string id); -void readLight(int loopDelayMs); -void startMotorAndEncoderTest(); -bool checkMoveFinished(); -void startDriveTest(); -void startCentering(); -bool checkIfCanUpdateMovement(); -void resetSpeed(); -void createDriveUntilNewTile(); -void determineNextChoice(); -uint8_t driveUntilNewTile(); -void driveTestOff(); -boolean isRobotPidAtTarget(); -void updateCritRange(); -void controlLoop(int loopDelayMs, int8_t framesUntilPrint); -void updateCentering(); -void updateToNextDistance(); -#endif \ No newline at end of file diff --git a/include/robot/control/lights.h b/include/robot/control/lights.h new file mode 100644 index 0000000..23f792e --- /dev/null +++ b/include/robot/control/lights.h @@ -0,0 +1,23 @@ +#ifndef CHESSBOT_LIGHT_SENSOR_H +#define CHESSBOT_LIGHT_SENSOR_H + +// Built-In Libraries +#include "Arduino.h" + +class Light { + public: + void tick(); + short value(); + unsigned long last_changed_time(); + + private: + int pin; + short _value; + unsigned long _last_changed_time; +}; + +void setupIR(); +void activateIR(); +void deactivateIR(); + +#endif \ No newline at end of file diff --git a/include/robot/magnet.h b/include/robot/control/magnet.h similarity index 100% rename from include/robot/magnet.h rename to include/robot/control/magnet.h diff --git a/include/robot/control/motor.h b/include/robot/control/motor.h new file mode 100644 index 0000000..54ef708 --- /dev/null +++ b/include/robot/control/motor.h @@ -0,0 +1,41 @@ +#ifndef CHESSBOT_MOTOR_H +#define CHESSBOT_MOTOR_H + +#include "config.h" +#include "Encoder.h" + +//just measured, its 5.9 centimeters, or .059 meters +const float TIRE_RADIUS = 0.059; +//circumference equals pi * diameter. In meters +const float TIRE_CIRCUMFERENCE = M_PI * 2 * TIRE_RADIUS; + +class Motor { + public: + Motor(int pin_a, int pin_b); + + void tick(); + + // Sets the motor power + // power is a float between [-1, 1] + void power(float power); + void encoder_reset(); + + // The distance of the tire in cm + float dist(); + private: + int pin_a; + int pin_b; + + Encoder encoder; + + // The raw encoder value + float dist_raw(); + +}; + +// Encoder EncoderA(ENCODER_A_PIN1, ENCODER_A_PIN2); +// void setupMotors(); +// void setLeftPower(float power); +// void setRightPower(float power); + +#endif \ No newline at end of file diff --git a/include/robot/control/robot.h b/include/robot/control/robot.h new file mode 100644 index 0000000..b0e45bc --- /dev/null +++ b/include/robot/control/robot.h @@ -0,0 +1,120 @@ +#ifndef CHESSBOT_CONTROL_H +#define CHESSBOT_CONTROL_H + +#include "Arduino.h" +#include "utils/config.h" +#include "robot/trapezoidalProfile.h" +#include "robot/control/lights.h" +#include "robot/control/motor.h" + +enum OperatingMode +{ + POSITION, + VELOCITY +}; + +enum DriveStatus { + ONGOING, + + // The robot has reached its destination and is now reversing + REACHED_REVERSING, + + // The robot has reached its destination, and reversing is not necessary + REACHED +}; + +enum CenteringStatus { + NOT_CENTERING, + + // The robot has started centering + STARTED, + + // The robot has finished centering along axis 1, and is moving to an edge + EDGE, + + // The robot is moving by itself + MOVING +}; + +struct ControlSetting +{ + OperatingMode mode; + float value; +}; + +// Unused? +// static ControlSetting leftMotorControl; +// static ControlSetting rightMotorControl; +// static double headingTarget = 0.0; + +void setXControl(ControlSetting control); +void setYControl(ControlSetting control); +void setHeadingTarget(double target); +ControlSetting getLeftMotorControl(); +ControlSetting getRightMotorControl(); +double getHeadingTarget(); + +class Robot { + public: + Robot(); + + static int batteryLevel(); + + // Runs all the necessary processing for each tick of the global event loop + void tick(); + + void center(); + void drive(float tiles, std::string id); + void drive(float leftPower, float rightPower, std::string id); + void driveTicks(int tickDistance, std::string id); + enum DriveStatus driveUntilNewTile(); + + void turn(float angleRadians, std::string id); + + void stop(); + + private: + Motor left; + Motor right; + + Light left_light; + Light right_light; + + boolean stopped; + + CenteringStatus centeringStatus; + + MotionProfile profileX = {THEORETICAL_MAX_VELOCITY_TPS, THEORETICAL_MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity + MotionProfile profileY = {THEORETICAL_MAX_VELOCITY_TPS, THEORETICAL_MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity + MotionProfile profileA = {THEORETICAL_MAX_VELOCITY_TPS, THEORETICAL_MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity + + void center_tick(); + void turn_tick(); + void pid_tick(); + // void setLeftPower(leftPower); + // void setRightPower(rightPower); + +}; + +void setupBot(); + +void sendPacketOnPidComplete(std::string id); +void readLight(int loopDelayMs); +bool checkMoveFinished(); +void startCentering(); +bool checkIfCanUpdateMovement(); +void resetSpeed(); +void createDriveUntilNewTile(); +void determineNextChoice(); +uint8_t driveUntilNewTile(); +boolean isRobotPidAtTarget(); +void updateCritRange(); +void controlLoop(int loopDelayMs); +void updateCentering(); +void updateToNextDistance(); + +void startDriveTest(); +void driveTestOff(); +void startMotorAndEncoderTest(); + +#endif \ No newline at end of file diff --git a/include/robot/encoder.h b/include/robot/encoder.h deleted file mode 100644 index 743e3ce..0000000 --- a/include/robot/encoder.h +++ /dev/null @@ -1,11 +0,0 @@ -#ifndef CHESSBOT_ENCODER_H -#define CHESSBOT_ENCODER_H - -void setupEncodersNew(); -void resetEncoders(); -void encoderLoop(); - -int readLeftEncoder(); -int readRightEncoder(); - -#endif \ No newline at end of file diff --git a/include/robot/lightSensor.h b/include/robot/lightSensor.h deleted file mode 100644 index c2dc89e..0000000 --- a/include/robot/lightSensor.h +++ /dev/null @@ -1,14 +0,0 @@ -#ifndef CHESSBOT_LIGHT_SENSOR_H -#define CHESSBOT_LIGHT_SENSOR_H - -// Built-In Libraries -#include "Arduino.h" - -void setupIR(); -void readGarbageVals(); -void activateIR(); -void deactivateIR(); -void startLightReading(bool* onFirstTile, bool* waitingForLight); -void readLightLevels(); - -#endif \ No newline at end of file diff --git a/include/robot/motor.h b/include/robot/motor.h deleted file mode 100644 index 6a5d914..0000000 --- a/include/robot/motor.h +++ /dev/null @@ -1,8 +0,0 @@ -#ifndef CHESSBOT_MOTOR_H -#define CHESSBOT_MOTOR_H - -void setupMotors(); -void setLeftPower(float power); -void setRightPower(float power); - -#endif \ No newline at end of file diff --git a/include/robot/trapezoidalProfile.h b/include/robot/trapezoidalProfile.h index 24b1fde..6e81dfd 100644 --- a/include/robot/trapezoidalProfile.h +++ b/include/robot/trapezoidalProfile.h @@ -13,7 +13,7 @@ struct MotionProfile { double criticalRange; }; -double updateTrapezoidalProfile(MotionProfile &profile, double dt, int8_t framesUntilPrint); +double updateTrapezoidalProfile(MotionProfile &profile, double dt); template T clamp(T value, T minValue, T maxValue) { diff --git a/include/robot/trapezoidalProfileNew.h b/include/robot/trapezoidalProfileNew.h index 67e551b..41da6ff 100644 --- a/include/robot/trapezoidalProfileNew.h +++ b/include/robot/trapezoidalProfileNew.h @@ -35,6 +35,7 @@ class TrapezoidProfile bool operator==(const State& rhs) const { + // Don't use equals for floats? return position == rhs.position && velocity == rhs.velocity; } }; diff --git a/include/utils/config.h b/include/utils/config.h index a271251..aff232a 100644 --- a/include/utils/config.h +++ b/include/utils/config.h @@ -8,6 +8,7 @@ #include extern int loopDelayMilliseconds; +extern unsigned long frame; // These variables are declared here, and defined in config.cpp // config.cpp is the only file that should be modifying these values. Everything else is read-only @@ -28,6 +29,8 @@ extern gpio_num_t PHOTODIODE_C_PIN; extern gpio_num_t PHOTODIODE_D_PIN; extern gpio_num_t BATTERY_VOLTAGE_PIN; +extern int BATTERY_VOLTAGE_OFFSET; + extern gpio_num_t ONBOARD_LED_PIN; extern int TICKS_PER_ROTATION; diff --git a/include/wifi/connection.h b/include/wifi/connection.h index d151f05..98ff8ff 100644 --- a/include/wifi/connection.h +++ b/include/wifi/connection.h @@ -10,7 +10,7 @@ void reconnectServer(); bool checkServerConnection(); void initiateHandshake(); -void acceptData(); +JsonDocument acceptData(); void sendPacket(JsonDocument& packet); void sendActionSuccess(std::string messageId); void sendActionFail(std::string messageId); diff --git a/platformio.ini b/platformio.ini index f14403b..a05010e 100644 --- a/platformio.ini +++ b/platformio.ini @@ -13,6 +13,9 @@ platform = espressif32 board = lolin_s2_mini framework = arduino monitor_speed = 115200 +build_flags = + -Wall + -Wextra lib_deps = bblanchon/ArduinoJson@^7.2.0 paulstoffregen/Encoder@^1.4.4 diff --git a/src/main.cpp b/src/main.cpp index eb17f22..2bf62ee 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -12,17 +12,18 @@ #include "utils/status.h" #include "wifi/wireless.h" #include "wifi/connection.h" -#include "robot/control.h" -#include "robot/encoder.h" +#include "robot/control/robot.h" #include "../env.h" #include "robot/pidController.h" -#include "robot/magnet.h" +#include "robot/control/magnet.h" //alright SCREW YOU serial monitor i won't print every frame then if you wanna play that game const int8_t PRINT_INTERVAL = 60; -int8_t framesUntilPrint = 60; +unsigned long frame = 0; unsigned long previousTime = 0; // For loop timing +Robot robot = Robot(); + // Setup gets run at startup void setup() { // Serial port for debugging purposes @@ -37,14 +38,7 @@ void setup() { // Create a WiFi network for the laptop to connect to if (!RUN_OFFLINE) connectWiFI(); - if (DO_DRIVE_TEST) startDriveTest(); - - delay(2000); - - //start reading the light - if (DO_DRIVE_TICKS_TEST) driveTicks(20000, "NULL"); - if (DO_HARDWARE_TEST) timerDelay(5000, &startMotorAndEncoderTest); previousTime = millis() - loopDelayMilliseconds; } @@ -61,11 +55,6 @@ void loop() { // Checks whether bot is still connected to the server. Reconnect if not if (getServerConnectionStatus() && !checkServerConnection()) reconnectServer(); - // If the bot is connected to the server, check for received data, and accept it if available - if (getServerConnectionStatus()) acceptData(); - // Checks whether bot is still connected to the server. Reconnect if not - if (getServerConnectionStatus() && !checkServerConnection()) reconnectServer(); - // If the bot is connected to the server, check for received data, and accept it if available if (getServerConnectionStatus()) acceptData(); } @@ -74,16 +63,14 @@ void loop() { // TODO change time parameter to be actual delta time, not just delay between loops unsigned long deltaTime = millis() - previousTime; previousTime = millis(); - controlLoop(deltaTime, framesUntilPrint); + + controlLoop(deltaTime); // This delay determines how often the code in loop is run // (Forcefully pauses the thread for about the amount of milliseconds passed in) delay(loopDelayMilliseconds); - framesUntilPrint--; - if(framesUntilPrint < 0) - { - framesUntilPrint = PRINT_INTERVAL; - } + + frame++; } // This is used at the end of each file due to the name definition at the beginning diff --git a/src/robot/battery.cpp b/src/robot/battery.cpp deleted file mode 100644 index cb41b44..0000000 --- a/src/robot/battery.cpp +++ /dev/null @@ -1,19 +0,0 @@ -#ifndef CHESSBOT_BATTERY_CPP -#define CHESSBOT_BATTERY_CPP - -// Associated Header File -#include "robot/battery.h" - -// Built-In Libraries -#include "Arduino.h" - -// Custom Libraries -#include "utils/config.h" - -int batteryVoltageOffset = 100; - -int getBatteryLevel() { - return analogRead(BATTERY_VOLTAGE_PIN) - batteryVoltageOffset; -} - -#endif \ No newline at end of file diff --git a/src/robot/control.cpp b/src/robot/control.cpp deleted file mode 100644 index 887485a..0000000 --- a/src/robot/control.cpp +++ /dev/null @@ -1,988 +0,0 @@ -#ifndef CHESSBOT_CONTROL_CPP -#define CHESSBOT_CONTROL_CPP - -// Associated Header File -#include "robot/control.h" - -// Built-In Libraries -#include "Arduino.h" -#include - -// Custom Libraries -#include "utils/logging.h" -#include "utils/timer.h" -#include "utils/config.h" -#include "utils/status.h" -#include "robot/motor.h" -#include "robot/lightSensor.h" -#include "wifi/connection.h" -#include "robot/encoder.h" -#include "robot/pidController.h" -#include "robot/driveTest.h" -#include "../../env.h" -#include -#include "utils/functions.h" - -#include "robot/profiledPIDController.h" -#include "robot/trapezoidalProfileNew.h" -#include "robot/magnet.h" - - -Magnet *magnet = nullptr; // Declare a pointer to Magnet - -// pid constants -TrapezoidProfile::Constraints profileConstraints(VELOCITY_LIMIT_TPS, ACCELERATION_LIMIT_TPSPS); -TrapezoidProfile xProfile(profileConstraints); -TrapezoidProfile yProfile(profileConstraints); -TrapezoidProfile aProfile(profileConstraints); -TrapezoidProfile::State xSetpoint, ySetpoint, aSetpoint; -PIDController XVelocityController(0.000009, 0.000035, 0.000000000001, -1, +1, 10); -PIDController YVelocityController(0.0000005, 0.000035, 0.000000000001, -1, +1, 10); -PIDController AVelocityController(0.000012, 0.00000, 0.0000000000000, -1, +1, 10); //angular velocity used for turns -ContinuousPIDController headingController(0.21, 0.000001, 0.000000000001, -1, +1, 0.1, -180, 180); // input degrees, output duty cycle - -//put this in manually for each bot. Dist between the two front encoders, or the two back encoders. In meters. -const float lightDist = 0.07; - -//just measured, its 5.9 centimeters, or .059 meters -const float TIRE_RADIUS = 0.059; -//circumference equals pi * diameter. In meters -const float TIRE_CIRCUMFERENCE = M_PI * 2 * TIRE_RADIUS; -//multiply any ticks by this ratio to get distance in meters -const float TICK_TO_METERS = TIRE_CIRCUMFERENCE / TICKS_PER_ROTATION; - -const uint8_t Top_Left_Encoder_Index = 0; -const uint8_t Top_Right_Encoder_Index = 1; -const uint8_t Bottom_Left_Encoder_Index = 2; -const uint8_t Bottom_Right_Encoder_Index = 3; - -boolean testEncoderPID_value = false; - -//determines the encoder values the iteration right before -int prevPositionL = 0; -int prevPositionR = 0; -int timeMs = 0; - -//robot rotation in radians -double prevRotation = 0; - -//calculated previous X and Y values -double prevX = 0; -double prevY = 0; - -bool runningPID = false; -bool runningTurn = false; -double average[50]; - -//when moving to a different target, this is the encoder position we started from -int startEncoderAPos = -1; -int startEncoderBPos = -1; - -//the encoder distance to about halfway through the tile -int encoderAHalfwayDist = 0; -int encoderBHalfwayDist = 0; - -//when we receive a command from the website to center, set this from false to true, -//then when the code sets it back to false, that's when we know we're done centering -bool isCentering = false; - -//holds the current status representing the progress in centering. The different values -//are defined below -char centeringStatus = 'S'; - -//measures if the forward encoders are aligning on the edge or the back encoders -bool forwardAligning = true; - -//set this true when our robot is on an edge and is moving to the center from its given measured distance -bool movingCenter = false; - -//set this true when our robot is turning to align itself on the next axis -bool turningToNextAxis = false; - -//initially 0, once 2 means both axises aligned so we done -uint8_t axisesAligned = 0; - -float angle = 0; -unsigned long timeSinceTurn = 0; - -//the value of the encoder we're measuring in terms of its light value -bool firstEncoderVal = false; -bool secondEncoderVal = false; - -//represents which index is being referenced for the current encoders -uint8_t firstEncoderIndex = 0; -uint8_t secondEncoderIndex = 0; - -//Here are the possible values: - //0 = no encoder leading. - //1 = left encoder leading. - //2 = right encoder leading -uint8_t leadingEncoder = 0; - -//previous encoder distance, specifically the one that is lagging behind -float backPrevDistance = 0; - -//checks if the given encoders have changed tiles yet. -bool leftEncoderChange = false; -bool rightEncoderChange = false; - -//determines basically what tile each encoder is one. false is one tile, true is the opposite tile. -//it could be false = white and true = black, or false = black and white = true, doesn't really matter -bool onFirstTile[4] = {false, false, false, false}; - -bool waitingForLight = false; - -void testEncoderPID() -{ - serialLogln("Changing encoder PID setpoint!", 2); - if (!testEncoderPID_value) - { - testEncoderPID_value = true; - setXControl({POSITION, (float)TICKS_PER_ROTATION * 6}); - setYControl({POSITION, 0.0f}); - runningPID = true; - } - else - { - testEncoderPID_value = false; - setXControl({POSITION, 0.0f}); - setYControl({POSITION, 0.0f}); - runningPID = true; - } - - updateCritRange(); -} - -/** - * get PID ready for the next iteration - */ -void resetPID(){ - prevPositionL = readLeftEncoder(); - prevPositionR = readRightEncoder(); - prevX = 0; - prevY = 0; - prevRotation = 0; - timeMs = 0; - for (int x = 0; x < 50; x++) average[x] = 100; -} - - -//crit range is basically getting distance we go until we are halfway to target. By the end of this range, -//we're at our max speed and are sure we aren't at a low speed just cause we're speeding up -void updateCritRange() -{ - //want to record the values before we move now - startEncoderAPos = profileX.currentPosition; - startEncoderBPos = profileY.currentPosition; - - profileX.criticalRange = fabs(profileX.targetPosition - startEncoderAPos) / 2; - profileY.criticalRange = fabs(profileY.targetPosition - startEncoderBPos) / 2; - - //update it so that time since start is now equal to this. Only really care about this value after turns though - timeSinceTurn = millis(); -} - -void testTurn() -{ - resetSpeed(); - - serialLog("Changing destination angle to ", 2); - serialLog(angle, 2); - //simple maths - turn(M_PI / 180 * angle, "NULL"); - serialLog(" (", 2); - serialLog(getLeftMotorControl().value, 2); - serialLog(", ", 2); - serialLog(getRightMotorControl().value, 2); - serialLogln(")", 2); - - //compute the new crit range now that target and start encoder have changed - updateCritRange(); -} - -void testCentering() -{ - serialLogln("Running centering routine...", 2); - startCentering(); -} - -// Sets up all the aspects needed for the bot to work -void setupBot() { - serialLogln("Setting Up Bot...", 2); - - pinMode(ONBOARD_LED_PIN, OUTPUT); - digitalWrite(ONBOARD_LED_PIN, HIGH); - - setupMotors(); - setupIR(); - setupEncodersNew(); - magnet = new Magnet(); - if (!magnet->isActive()) { - serialLogln("Magnetometer not responding!", 0); - } else { - serialLogln("Magnetometer ready!", 2); - headingTarget = magnet->readDegrees(); - } - serialLogln("Bot Set Up!", 2); - - XVelocityController.Reset(); - YVelocityController.Reset(); - AVelocityController.Reset(); - headingController.Reset(); - resetPID(); - - - if (DO_PID_TEST) { - setHeadingTarget(magnet->readDegrees()); - testEncoderPID(); - timerInterval(8000, &testEncoderPID); - } - - if (DO_TURN_TEST) { - angle = 30; - testTurn(); - timerInterval(5000, testTurn); - } - - if (DO_CENTERING_TEST) { - testCentering(); - timerInterval(5000, &testCentering); - } -} - -// + (0.0001 * desiredVelocityA) -// Manages control loop (loopDelayMs is for reference) -void controlLoop(int loopDelayMs, int8_t framesUntilPrint) { - if (DO_LIGHT_SENSOR_TEST) - { - //read the light values. May actually.... not want to do this if not centering? Keeping it outside the if - //statement in case it'll be used for something else - readLight(loopDelayMs); - if(isCentering) - { - // TODO see if targetPosition needs to be updated in the middle of this method - doesn't look like it? - updateCentering(); - } - - // uint8_t status = driveUntilNewTile(onFirstTile); - - //this way we don't even upload the code if it's not being used - #if LOGGING_LEVEL >= 4 - //know our char will be 4 bits - char vals[5]; - //read the booleans as char - for(uint8_t i = 0; i < 4; i++) - { - vals[i] = onFirstTile[i] ? '1' : '0'; - } - //must null terminate - vals[4] = '\0'; - serialLog("Light statuses: ", 2); - serialLogln(vals, 2); - #endif - } - - if (DO_ENCODER_TEST) encoderLoop(); - - if (DO_PID){ - double trackWidth = TRACK_WIDTH_INCHES/39.37; - if(runningPID){ - - double lDist = (double)(readLeftEncoder()-prevPositionL)/TICKS_PER_ROTATION*2*PI; - double rDist = (double)(readRightEncoder()-prevPositionR)/TICKS_PER_ROTATION*2*PI; - - prevPositionL = readLeftEncoder(); - prevPositionR = readRightEncoder(); - - double angleDist = (rDist - lDist)*TIRE_RADIUS/trackWidth; - - double currentRot = prevRotation + angleDist; - - double currentX; - double deltaX; - double currentY; - double deltaY; - if(angleDist != 0){ - double temp = (trackWidth*(rDist+lDist))/(2*(rDist-lDist)); - deltaX = temp * (sin(currentRot) - sin(prevRotation)); - deltaY = temp * (cos(prevRotation) - cos(currentRot)); - currentX = prevX + deltaX; - currentY = prevY + deltaY; - - } else { - double totalDist = TIRE_RADIUS*(lDist + rDist)/2; - deltaX = totalDist * cos(currentRot); - deltaY = totalDist * sin(currentRot); - currentX = prevX + deltaX; - currentY = prevY + deltaY; - } - prevX = currentX; - prevY = currentY; - prevRotation = currentRot; - - double loopDelaySeconds = ((double) timeMs) / 1000; - profileX.currentPosition = currentX / TICK_TO_METERS; - profileX.currentVelocity = deltaX==0?0:deltaX / TICK_TO_METERS /loopDelaySeconds; - xSetpoint = xProfile.calculate(loopDelaySeconds, - TrapezoidProfile::State(profileX.currentPosition, profileX.currentVelocity), - TrapezoidProfile::State(getLeftMotorControl().value, 0.0)); - - double velocity = XVelocityController.Compute(xSetpoint.velocity, profileX.currentVelocity, loopDelaySeconds); - double aVel = headingController.Compute(headingTarget, currentRot*RAD_TO_DEG, loopDelaySeconds); - - profileY.currentPosition = currentY / TICK_TO_METERS; - profileY.currentVelocity = deltaY==0?0:deltaY / TICK_TO_METERS /loopDelaySeconds; - ySetpoint = yProfile.calculate(loopDelayMs/1000, - TrapezoidProfile::State(profileY.currentPosition, profileY.currentVelocity), - TrapezoidProfile::State(getRightMotorControl().value, 0.0)); - double yVel = YVelocityController.Compute(ySetpoint.velocity, profileY.currentVelocity, loopDelaySeconds); - - aVel += yVel; - - double lMotorPower = fmap((velocity-8*aVel*trackWidth/2)/TIRE_RADIUS, -25, 25, -1, 1); - double rMotorPower = fmap((velocity+8*aVel*trackWidth/2)/TIRE_RADIUS, -25, 25, -1, 1); - - if (fabs(lMotorPower) < MIN_MOTOR_POWER) lMotorPower = 0; - if (fabs(rMotorPower) < MIN_MOTOR_POWER) rMotorPower = 0; - - - serialLog("vel ", 3); - serialLog(velocity, 3); - serialLog(" yvel ", 3); - serialLog(yVel, 3); - serialLog(" avel ", 3); - serialLog(aVel, 3); - - serialLog(" lpower ", 3); - serialLog(lMotorPower, 3); - serialLog(" rpower ", 3); - serialLog(rMotorPower, 3); - serialLog(" xpos ", 3); - serialLog(currentX, 3); - serialLog(" ypos ", 3); - serialLogln(currentY, 3); - - setLeftPower(lMotorPower); - setRightPower(rMotorPower); - - double sum = 0; - for(int x = 49; x >= 0; x--) { - average[x+1] = average[x]; - sum += fabs(average[x+1]); - } - average[0] = lMotorPower; - sum += fabs(average[0]); - timeMs += loopDelayMs; - if (sum/50 < 0.01){ - serialLogln(sum/50,3); - serialLogln(runningPID,3); - runningPID = false; - setLeftPower(0); - setRightPower(0); - - sendActionSuccess("move done"); - resetPID(); - - } else { - runningPID = true; - } - } - if(runningTurn){ - - - double lDist = (double)(readLeftEncoder()-prevPositionL)/TICKS_PER_ROTATION*2*PI; - double rDist = (double)(readRightEncoder()-prevPositionR)/TICKS_PER_ROTATION*2*PI; - - prevPositionL = readLeftEncoder(); - prevPositionR = readRightEncoder(); - - double angleDist = (rDist - lDist)*TIRE_RADIUS/trackWidth; - - double currentRot = prevRotation + angleDist; - - double currentX; - double deltaX; - double currentY; - double deltaY; - if(angleDist != 0){ - double temp = (trackWidth*(rDist+lDist))/(2*(rDist-lDist)); - deltaX = temp * (sin(currentRot) - sin(prevRotation)); - deltaY = temp * (cos(prevRotation) - cos(currentRot)); - currentX = prevX + deltaX; - currentY = prevY + deltaY; - - } else { - double totalDist = TIRE_RADIUS*(lDist + rDist)/2; - deltaX = totalDist * cos(currentRot); - deltaY = totalDist * sin(currentRot); - currentX = prevX + deltaX; - currentY = prevY + deltaY; - } - prevX = currentX; - prevY = currentY; - - prevRotation = currentRot; - - double loopDelaySeconds = ((double) timeMs) / 1000; - profileA.currentPosition = currentRot*10 / TICK_TO_METERS; - profileA.currentVelocity = angleDist==0?0:angleDist*10 / TICK_TO_METERS /loopDelaySeconds; - aSetpoint = aProfile.calculate(loopDelaySeconds, - TrapezoidProfile::State(profileA.currentPosition, profileA.currentVelocity), - TrapezoidProfile::State(getHeadingTarget()*10/TICK_TO_METERS, 0.0)); - - double velocity = AVelocityController.Compute(aSetpoint.velocity, profileA.currentVelocity, loopDelaySeconds); - - double lMotorPower = fmap((-8*velocity*trackWidth/2)/TIRE_RADIUS, -11, 11, -1, 1); - double rMotorPower = fmap((8*velocity*trackWidth/2)/TIRE_RADIUS, -11, 11, -1, 1); - - if (fabs(lMotorPower) < MIN_MOTOR_POWER) lMotorPower = 0; - if (fabs(rMotorPower) < MIN_MOTOR_POWER) rMotorPower = 0; - - setLeftPower(lMotorPower); - setRightPower(rMotorPower); - - serialLog("vels ", 3); - serialLog(xSetpoint.velocity, 3); - serialLog("vel ", 3); - serialLog(velocity, 3); - serialLog(" lpower ", 3); - serialLog(lMotorPower, 3); - serialLog(" rpower ", 3); - serialLog(rMotorPower, 3); - serialLog(" angle ", 3); - serialLogln(currentRot*10, 3); - - - double sum = 0; - for(int x = 49; x >= 0; x--) { - average[x+1] = average[x]; - sum += fabs(average[x+1]); - } - average[0] = lMotorPower; - sum += fabs(average[0]); - timeMs += loopDelayMs; - if (sum/50 < 0.01){ - serialLogln(sum/50,3); - serialLogln(runningPID,3); - runningPID = false; - setLeftPower(0); - setRightPower(0); - - sendActionSuccess("turn done"); - resetPID(); - - } else { - runningTurn = true; - } - } - } -} - -// start centering process -void startCentering() -{ - if (!isCentering) - { - isCentering = true; - centeringStatus = 'S'; - } -} - -//this determines what our next action will be after an edge alignment, move to center, or axis turn. -void determineNextAction() -{ - //if we were previously turning to the next axis, and finished: - if(turningToNextAxis) - { - turningToNextAxis = false; - axisesAligned++; - //done centering yippee! - if(axisesAligned == 2) - { - axisesAligned = 0; - isCentering = false; - centeringStatus = 'F'; - } - //otherwise restart the whole process for this next axis - else - { - centeringStatus = 'S'; - } - } - //if previously moving to center for an axis, and finished: - else if(movingCenter) - { - //now, turn to next direction - movingCenter = false; - turningToNextAxis = true; - centeringStatus = 'M'; - //this way, if no axises aligned yet, angle = -90, and if one axis aligned, - //angle = 90, undoing the previous rotation. - angle = 90 * (axisesAligned * 2 - 1); - - testTurn(); - } - //if just aligned on a forward edge with the encoders in the front: - else if(forwardAligning) - { - //if going forward, store the current encoder value so we can see the full encoder length of the tiles - encoderAHalfwayDist = profileX.currentPosition; - encoderBHalfwayDist = profileY.currentPosition; - //swap to going back - forwardAligning = !forwardAligning; - //set that new drive - createDriveUntilNewTile(); - centeringStatus = 'E'; - - serialLog((char*)"Current encoder A: ", 2); - serialLogln(profileX.currentPosition, 2); - serialLog((char*)"Current encoder B: ", 2); - serialLogln(profileY.currentPosition, 2); - serialLog((char*)"Target encoder A: ", 2); - serialLogln(leftMotorControl.mode == POSITION ? leftMotorControl.value : 0, 2); - serialLog((char*)"Target encoder B: ", 2); - serialLogln(rightMotorControl.mode == POSITION ? rightMotorControl.value : 0, 2); - } - //if just aligned on a backward edge with the encoders in the back: - else - { - //swap to going forward now - forwardAligning = !forwardAligning; - - //since we always go forward first and then backwards, the current value of encoderHalfwayDist > currentEncoder always - //what we're doing is currently, "encoderAHalfwayDist" just stores the value of the other edge in encoder ticks, now we're - //finding the difference between them. And of course divide by 2 as want half that distance - encoderAHalfwayDist = (encoderAHalfwayDist - profileX.currentPosition) / 2; - encoderBHalfwayDist = (encoderBHalfwayDist - profileY.currentPosition) / 2; - - //decide that we take average of encoder A and B's distances, since ideally we want both to travel the same amount - int totalHalfwayDistance = (encoderAHalfwayDist + encoderBHalfwayDist) / 2; - driveTicks(totalHalfwayDistance, "NULL"); - centeringStatus = 'M'; - //now we moving to da center - movingCenter = true; - } -} - -//this updates our centering depending on the current status of it -void updateCentering() -{ - //what we do depend on the current status - switch(centeringStatus) - { - //What each status bit means: - // S means we just started centering on the current axis - // E means we are moving to an edge - // M means the bot is just moving by itself, whether that be to correct for a turn or to just get to the halfway point - case 'S': - //create the first drive - createDriveUntilNewTile(); - //now change it so we're driving forward - centeringStatus = 'E'; - break; - case 'E': - { - //continue driving forward - uint8_t driveStatus = driveUntilNewTile(); - //reminder status 3 = no leading encoders and driving finished - if(driveStatus == 3) - { - //meaning we can now go in opposite direction. - determineNextAction(); - } - //reminder status 2 = one leading encoder finished first, but driving is finished - else if(driveStatus == 2) - { - //mean we now begin correcting - centeringStatus = 'M'; - } - break; - } - case 'M': - //check if we're the moving we're doing is finished. If so, determine what we do next. - if(checkMoveFinished()) - { - determineNextAction(); - } - break; - } -} - -//checks if we're done moving to our target when either moving half a tile's length or turning -bool checkMoveFinished() -{ - //first, checks like "fabs(profileX.currentVelocity) < 2" see if we're slowing down or not. - - //then, something like "fabs(currentEncoderA - encoderATarget) < criticalRangeA" is making sure - //the reason our speed is slow is specifically because we're slowing down and not because we're - //beginning to speed up. - //do this by seeing if the distance remaining is less than the midpoint distance from start to end, as by then we're at our max speed. - - bool encoderAChecks = fabs(profileX.currentPosition - profileX.targetPosition) < profileX.criticalRange && fabs(profileX.currentVelocity) < 3; - bool encoderBChecks = fabs(profileY.currentPosition - profileY.targetPosition) < profileY.criticalRange && fabs(profileY.currentVelocity) < 3; - - //check if we've been stalling too long, for 8 seconds. If we're over time, that's bad, and means we should declare the movement finished. - bool timerCheck = millis() - timeSinceTurn > 8000; - - return ((encoderAChecks && encoderBChecks) || timerCheck); -} - -//like the one above but just seeing if we can keep moving or not -bool checkIfCanUpdateMovement() -{ - return fabs(profileX.currentPosition - profileX.targetPosition) < profileX.criticalRange && fabs(profileY.currentPosition - profileY.targetPosition) < profileY.criticalRange; -} - -void setXControl(ControlSetting control) { - leftMotorControl = control; - xSetpoint = TrapezoidProfile::State(readLeftEncoder(), profileX.currentVelocity); - if (control.mode == POSITION) - profileX.targetPosition = control.value; - else - profileX.targetVelocity = control.value; -} - -void setYControl(ControlSetting control) { - rightMotorControl = control; - ySetpoint = TrapezoidProfile::State(readRightEncoder(), profileY.currentVelocity); - if (control.mode == POSITION) - profileY.targetPosition = control.value; - else - profileY.targetVelocity = control.value; -} - -void setHeadingTarget(double target) { - headingTarget = target; -} - -ControlSetting getLeftMotorControl() { - return leftMotorControl; -} - -ControlSetting getRightMotorControl() { - return rightMotorControl; -} - -double getHeadingTarget() { - return headingTarget; -} - -void drive(float tiles, std::string id) { - if (!getStoppedStatus()) { - const float TILE_SIZE_INCHES = 24; - float distanceInches = tiles * TILE_SIZE_INCHES; - float ticksPerInch = TICKS_PER_ROTATION / (WHEEL_DIAMETER_INCHES * M_PI); - int tickDistance = (int)(distanceInches * ticksPerInch); - driveTicks(tickDistance, id); - } - -} - -//drives the given amount of ticks -void driveTicks(int tickDistance, std::string id) -{ - if (!getStoppedStatus()) { - resetSpeed(); - setXControl({POSITION, (float)tickDistance}); - setYControl({POSITION, 0}); - updateCritRange(); - runningPID = true; - - if (id != "NULL") { - sendPacketOnPidComplete(id); - } - } -} - -// Drives the wheels according to the powers set. Negative is backwards, Positive forwards -void drive(float leftPower, float rightPower, std::string id) { - if (!getStoppedStatus()) { - // TODO: maybe move to motor.cpp? - if (leftPower < MIN_MOTOR_POWER && leftPower > -MIN_MOTOR_POWER) { - leftPower = 0; - } if (rightPower < MIN_MOTOR_POWER && rightPower > -MIN_MOTOR_POWER) { - rightPower = 0; - } - - setLeftPower(leftPower); - setRightPower(rightPower); - - //we only send null as id during our test drive. The only other time this drive method is called will be - //when the server sends it, meaning it will have an id to send back. - if (id != "NULL") { sendActionSuccess(id); } - } -} - -//turns the given amount in radians, CCW -void turn(float angleRadians, std::string id) { - - - serialLogln("Turning", 3); - serialLogln(angleRadians, 3); - - setXControl({POSITION, 0}); - setYControl({POSITION, 0}); - updateCritRange(); - setHeadingTarget(angleRadians*0.95); - runningTurn = true; - - if (id != "NULL") - { - sendPacketOnPidComplete(id); - } -} - -// Stops the bot in its tracks -void stop() { - setStoppedStatus(true); - setLeftPower(0); - setRightPower(0); - - serialLogln("Bot Stopped!", 2); -} - -boolean isRobotPidAtTarget() { - if (!DO_PID) - return true; - - boolean leftAtTarget, rightAtTarget; - - if (getLeftMotorControl().mode == POSITION) - { - leftAtTarget = approxEquals(getLeftMotorControl().value, profileX.currentPosition, PID_POSITION_TOLERANCE) - && approxEquals(profileX.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE); - - serialLog("Left Position: ", 3); - serialLog(profileX.currentPosition, 3); - serialLog(", Target: ", 3); - serialLog(getLeftMotorControl().value, 3); - serialLog(", Velocity: ", 3); - serialLog(profileX.currentVelocity, 3); - serialLog(", At Target: ", 3); - serialLogln(leftAtTarget, 3); - } - else - { - leftAtTarget = approxEquals(getLeftMotorControl().value, profileX.currentVelocity, PID_VELOCITY_TOLERANCE); - } - if (getRightMotorControl().mode == POSITION) - { - rightAtTarget = approxEquals(getRightMotorControl().value, profileY.currentPosition, PID_POSITION_TOLERANCE) - && approxEquals(profileY.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE); - - serialLog("Right Position: ", 3); - serialLog(profileY.currentPosition, 3); - serialLog(", Target: ", 3); - serialLog(getRightMotorControl().value, 3); - serialLog(", Velocity: ", 3); - serialLog(profileY.currentVelocity, 3); - serialLog(", At Target: ", 3); - serialLogln(rightAtTarget, 3); - } - else - { - rightAtTarget = approxEquals(getRightMotorControl().value, profileY.currentVelocity, PID_VELOCITY_TOLERANCE); - } - - return leftAtTarget && rightAtTarget; -} - -void sendPacketOnPidComplete(std::string id) { - if (!DO_PID) - sendActionFail(id); - - if (isRobotPidAtTarget()) { - sendActionSuccess(id); - } else { - // Run on next loop - timerDelay(1, [id](){ sendPacketOnPidComplete(id); }); - } -} - -// Reads in the light value of all light sensors -void readLight(int loopDelayMs) { - //if we're still waiting to read, can't enter this statement. Kind of like a mutex lock - if(!waitingForLight) - { - waitingForLight = true; - // The Infrared Blaster must be activated first to get a clear reading - activateIR(); - //this way, we can pass in a parameter to timerDelay as well, but we don't have to - timerDelay(loopDelayMs, std::bind(startLightReading, onFirstTile, &waitingForLight)); - } -} - -void resetSpeed() -{ - profileX.targetVelocity = 0; - profileY.targetVelocity = 0; -} - -// Test motor and encoder synchronization -void startMotorAndEncoderTest() { - (new MotorEncoderTest())->startMotorAndEncoderTest(); -} - -// Tests the motors. This turns the motors on. -void startDriveTest() { - drive(0.5f, 0.5f, "NULL"); - //timerDelay(2000, &driveTestOff); -} - -//updates us to the next distance we're traveling -void updateToNextDistance() -{ - //this way if we're reversing, we're actually subtracting. if going forward was 0, then 0 * 2 - 1 = -1. - //if going forward was 1, 1 * 2 - 1 = 1. - float encTargetA = (float)profileX.currentPosition + 2500 * (forwardAligning * 2 - 1); - float encTargetB = (float)profileY.currentPosition + 2500 * (forwardAligning * 2 - 1); - setXControl({POSITION, encTargetA}); - setYControl({POSITION, encTargetB}); -#if LOGGING_LEVEL >= 3 - serialLogln("changing direction!", 3); - serialLogln(encTargetA, 3); - serialLogln(encTargetB, 3); -#endif - - //update crit range yessir - updateCritRange(); -} - -//creates a new drive until the next tile -void createDriveUntilNewTile() -{ - //set the next distance to travel - resetSpeed(); - updateToNextDistance(); - - //assign values here, will detect when they change - if(forwardAligning) - { - firstEncoderIndex = Top_Left_Encoder_Index; - secondEncoderIndex = Top_Right_Encoder_Index; - } - else - { - //from the robots perspective as it's going backwards, the encoder on the left is bottom right, - //while the encoder on the right is bottom left, so we just swap em - firstEncoderIndex = Bottom_Right_Encoder_Index; - secondEncoderIndex = Bottom_Left_Encoder_Index; - } - //now set the actual values with the indices - firstEncoderVal = onFirstTile[firstEncoderIndex]; - secondEncoderVal = onFirstTile[secondEncoderIndex]; -} - -//drives until the first two encoders are considered to hit a new value. -//Returns a status bit, with the corresponding values: - // 1 - drive is going - // 2 - just at this moment, we have reached our destination and are going to begin reversing now. - // 3 - just at this moment, we've reached our destination, but DON'T need to reverse. -uint8_t driveUntilNewTile() -{ - //if we do finish moving, update to a new distance. I think we have to move at intervals for it to work - if(checkIfCanUpdateMovement()) - { - updateToNextDistance(); - } - - //if we already changed it, don't change it back again - leftEncoderChange = leftEncoderChange || (onFirstTile[firstEncoderIndex] != firstEncoderVal); - rightEncoderChange = rightEncoderChange || (onFirstTile[secondEncoderIndex] != secondEncoderVal); - - //if either has changed - if(leftEncoderChange || rightEncoderChange) - { - //when both cross, we done. - if(leftEncoderChange && rightEncoderChange) - { - //if there had been a leading encoder, do the following: - uint8_t status = 0; - if(leadingEncoder != 0) - { - setXControl({POSITION, (float)profileX.currentPosition}); - setYControl({POSITION, (float)profileY.currentPosition}); - - //first get the encoder that we're comparing to get the distance. If leading encoder is 1 and we were moving forward, or if - //leading encoder is 2 but we were moving backward, then the back encoder is b, otherwise it's A - double encoderChosen = (leadingEncoder == 1 && forwardAligning || leadingEncoder == 2 && !forwardAligning) ? profileY.currentPosition : profileX.currentPosition; - //now, the distance we traveled is the difference between the encoders - double backEncoderDist = fabs(encoderChosen - backPrevDistance); -#if LOGGING_LEVEL >= 3 - serialLog("Begin encoder is: ", 2); - serialLogln(backPrevDistance, 2); - serialLog("End encoder is: ", 2); - serialLogln((leadingEncoder == 1) ? profileX.currentPosition : profileY.currentPosition, 2); -#endif - //now convert difference in ticks to meter value - backEncoderDist *= TICK_TO_METERS; -#if LOGGING_LEVEL >= 3 - serialLog(" Encoder in front is gonna be: ", 2); - serialLogln(leadingEncoder, 2); - serialLog("Total distance encoder was behind is: ", 2); - serialLogln(backEncoderDist, 2); -#endif - //reminder: angle = arctan(x/y), where x = backEncoderDist (like distance to our edge), and y = distance between two light sensors (put in manually) - - //idk why, but when dividing by 2 that gets us the true angle. The BackEncoderDist and lightDist seems to be correct vales, but the value we - //end up getting from it is double what it should be. Maybe there's an issue with how I did it. - float radAngle = atan(backEncoderDist / lightDist) / 2; - - //as a reminder, corresponding degrees = (pi/180) * x radians - float degreesAngle = 180 / M_PI * radAngle; - - serialLog("Angle is going to be: ", 2); - serialLog(degreesAngle, 2); - serialLogln(" degrees.", 2); - - //we know positive angle = turn left, negative angle means turn right. - //encoder 1 forward means turn left, encoder 2 forward means turn right. - //so 2 = -1, 1 = 1. If you plug those numbers in, that's what you get. - - int8_t degreesDirection = 3 - 2 * leadingEncoder; - serialLog("Sign is going to be: ", 2); - serialLogln(degreesDirection, 2); - - //now update the angle, and turn - angle = degreesAngle * degreesDirection; - testTurn(); - status = 2; - } - else - { - status = 3; - - //with the other one we set the crit range after calling the turn function. - //Here we don't, so we gotta do that - updateCritRange(); - } - - //reset all of our values - leadingEncoder = 0; - backPrevDistance = 0; - leftEncoderChange = false; - rightEncoderChange = false; - - //if the encoder returned 0, no need to reverse so skip to status 3. - return status; - } - //otherwise, want to see which one crossed. Can do this by seeing if we've updated backPrevDistance yet or not. - else if(backPrevDistance == 0) - { - //if left encoder changed, that's the leading encoder, otherwise 2nd is the leading encoder obviously. - leadingEncoder = leftEncoderChange ? 1 : 2; - //this makes sense as if the left encoder first crossed but we're going backwards, that's encoder A that's behind. Meanwhile if the right - //encoder crossed first and we're going forwards, its encoder A that's behind too. In all other cases, its encoder B - backPrevDistance = (leftEncoderChange && !forwardAligning || rightEncoderChange && forwardAligning) ? profileX.currentPosition : profileY.currentPosition; - } - } - return 1; -} - -// Tests the motors. This turns the motors off. -void driveTestOff() { - stop(); - timerDelay(2000, &startDriveTest); -} - -#endif \ No newline at end of file diff --git a/src/robot/control/lights.cpp b/src/robot/control/lights.cpp new file mode 100644 index 0000000..ad0a7f3 --- /dev/null +++ b/src/robot/control/lights.cpp @@ -0,0 +1,63 @@ +#ifndef CHESSBOT_LIGHT_SENSOR_CPP +#define CHESSBOT_LIGHT_SENSOR_CPP + +// Associated Header File +#include "robot/control/lights.h" +#include "../../../env.h" + +// Built-In Libraries +#include "Arduino.h" + +// Custom Libraries +#include "utils/logging.h" +#include "utils/config.h" + +void Light::tick() { + short prev = _value; + + _value = analogRead(pin); + + if (prev != _value) { + _last_changed_time = millis(); + } +} + +short Light::value() { + return _value; +} + +unsigned long Light::last_changed_time() { + return _last_changed_time; +} + +bool IR_activated = false; + +// Sets the IR (Infrared) Blaster to be able to output +void setupIR() { + serialLogln("Setting Up Light Sensors...", 2); + pinMode(RELAY_IR_LED_PIN, OUTPUT); + serialLogln("Light Sensors Setup!", 2); +} + +// Turns on the IR Blaster +// Does turning on and off the IR potentially take more energy than just leaving it on? +void activateIR() { + if (IR_activated) { + return; + } + + digitalWrite(RELAY_IR_LED_PIN, HIGH); + IR_activated = true; +} + +// Turns off the IR Blaster +void deactivateIR() { + if (!IR_activated) { + return; + } + + digitalWrite(RELAY_IR_LED_PIN, LOW); + IR_activated = false; +} + +#endif \ No newline at end of file diff --git a/src/robot/magnet.cpp b/src/robot/control/magnet.cpp similarity index 99% rename from src/robot/magnet.cpp rename to src/robot/control/magnet.cpp index 96f00e7..5936ab1 100644 --- a/src/robot/magnet.cpp +++ b/src/robot/control/magnet.cpp @@ -1,5 +1,6 @@ #include "DFRobot_BMM350.h" -#include "robot/magnet.h" + +#include "robot/control/magnet.h" #include "utils/logging.h" #define SDA_PIN 8 diff --git a/src/robot/control/motor.cpp b/src/robot/control/motor.cpp new file mode 100644 index 0000000..2c5601c --- /dev/null +++ b/src/robot/control/motor.cpp @@ -0,0 +1,57 @@ +#ifndef CHESSBOT_MOTOR_CPP +#define CHESSBOT_MOTOR_CPP + +// Associated Header File +#include "robot/control/motor.h" + +// Built-In Libraries +#include "Arduino.h" + +// Custom Libraries +#include "robot/pwm.h" +#include "utils/config.h" +#include "utils/logging.h" + +Motor::Motor(int motor_pin_a, int motor_pin_b, int enc_pin_a, int enc_pin_b) { + pin_a = _pin_a; + pin_b = _pin_b; + + setupPWM(pin_a); + setupPWM(pin_b); + + encoder(enc_pin_a, enc_pin_b); +} + +void Motor::tick() { + // Read from encoder and save its previous value +} + +// This will set how fast and what direction left motor will spin +// Value between [-1, 1] +// Negative is backwards, Positive is forwards +void Motor::power(float power) { + if (power > 0) { + writePWM(MOTOR_A_PIN2, 0); + writePWM(MOTOR_A_PIN1, mapPowerToDuty(power)); + } else { + writePWM(MOTOR_A_PIN1, 0); + writePWM(MOTOR_A_PIN2, mapPowerToDuty(-power)); + } + + serialLog("Motor Power: ", 4); + serialLogln(power, 4); +} + +void Motor::encoder_reset() { + encoder.readAndReset(); +} + +float Motor::dist_raw() { + return encoder.read(); +} + +float Motor::dist() { + return dist_raw() * TIRE_CIRCUMFERENCE; +} + +#endif \ No newline at end of file diff --git a/src/robot/control/robot.cpp b/src/robot/control/robot.cpp new file mode 100644 index 0000000..0e71a0b --- /dev/null +++ b/src/robot/control/robot.cpp @@ -0,0 +1,874 @@ +#ifndef CHESSBOT_CONTROL_CPP +#define CHESSBOT_CONTROL_CPP + +// Associated Header File +#include "robot/control/robot.h" + +// Built-In Libraries +#include "Arduino.h" +#include + +// Custom Libraries +#include "utils/logging.h" +#include "utils/timer.h" +#include "utils/config.h" +#include "utils/status.h" +#include "robot/control/motor.h" +#include "robot/control/lights.h" +#include "wifi/connection.h" +#include "robot/pidController.h" +#include "robot/driveTest.h" +#include "../../../env.h" +#include +#include "utils/functions.h" + +#include "robot/profiledPIDController.h" +#include "robot/trapezoidalProfileNew.h" + +// pid constants +TrapezoidProfile::Constraints profileConstraints(VELOCITY_LIMIT_TPS, ACCELERATION_LIMIT_TPSPS); +TrapezoidProfile xProfile(profileConstraints); +TrapezoidProfile yProfile(profileConstraints); +TrapezoidProfile aProfile(profileConstraints); +TrapezoidProfile::State xSetpoint, ySetpoint, aSetpoint; +PIDController XVelocityController(0.000009, 0.000035, 0.000000000001, -1, +1, 10); +PIDController YVelocityController(0.0000005, 0.000035, 0.000000000001, -1, +1, 10); +PIDController AVelocityController(0.000012, 0.00000, 0.0000000000000, -1, +1, 10); //angular velocity used for turns +ContinuousPIDController headingController(0.21, 0.000001, 0.000000000001, -1, +1, 0.1, -180, 180); // input degrees, output duty cycle + +//put this in manually for each bot. Dist between the two front encoders, or the two back encoders. In meters. +const float lightDist = 0.07; +//multiply any ticks by this ratio to get distance in meters +const float TICK_TO_METERS = TIRE_CIRCUMFERENCE / TICKS_PER_ROTATION; + +// const uint8_t Top_Left_Encoder_Index = 0; +// const uint8_t Top_Right_Encoder_Index = 1; +// const uint8_t Bottom_Left_Encoder_Index = 2; +// const uint8_t Bottom_Right_Encoder_Index = 3; + +// boolean testEncoderPID_value = false; + +// //determines the encoder values the iteration right before +// int prevPositionL = 0; +// int prevPositionR = 0; +// int timeMs = 0; + +// //robot rotation in radians +// double prevRotation = 0; + +// //calculated previous X and Y values +// double prevX = 0; +// double prevY = 0; + +// bool runningPID = false; +// bool runningTurn = false; +// double average[50]; + +// //when moving to a different target, this is the encoder position we started from +// int startEncoderAPos = -1; +// int startEncoderBPos = -1; + +// //the encoder distance to about halfway through the tile +// int encoderAHalfwayDist = 0; +// int encoderBHalfwayDist = 0; + +// //when we receive a command from the website to center, set this from false to true, +// //then when the code sets it back to false, that's when we know we're done centering +// bool isCentering = false; + +// //holds the current status representing the progress in centering. The different values +// //are defined below +// char centeringStatus = 'S'; + +// //measures if the forward encoders are aligning on the edge or the back encoders +// bool forwardAligning = true; + +// //set this true when our robot is on an edge and is moving to the center from its given measured distance +// bool movingCenter = false; + +// //set this true when our robot is turning to align itself on the next axis +// bool turningToNextAxis = false; + +// //initially 0, once 2 means both axises aligned so we done +// uint8_t axisesAligned = 0; + +// float angle = 0; +// unsigned long timeSinceTurn = 0; + +// //the value of the encoder we're measuring in terms of its light value +// bool firstEncoderVal = false; +// bool secondEncoderVal = false; + +// //represents which index is being referenced for the current encoders +// uint8_t firstEncoderIndex = 0; +// uint8_t secondEncoderIndex = 0; + +// //Here are the possible values: +// //0 = no encoder leading. +// //1 = left encoder leading. +// //2 = right encoder leading +// uint8_t leadingEncoder = 0; + +// //previous encoder distance, specifically the one that is lagging behind +// float backPrevDistance = 0; + +// //checks if the given encoders have changed tiles yet. +// bool leftEncoderChange = false; +// bool rightEncoderChange = false; + +// //determines basically what tile each encoder is one. false is one tile, true is the opposite tile. +// //it could be false = white and true = black, or false = black and white = true, doesn't really matter +// bool onFirstTile[4] = {false, false, false, false}; + +// bool waitingForLight = false; + +Robot::Robot() { + + } + +int Robot::batteryLevel() { + return analogRead(BATTERY_VOLTAGE_PIN) - BATTERY_VOLTAGE_OFFSET; + } + +void Robot::tick() { + center_tick(); + pid_tick(); + turn_tick(); +} + +void Robot::pid_tick() { + double lDist = (double)(readLeftEncoder()-prevPositionL)/TICKS_PER_ROTATION*2*PI; + double rDist = (double)(readRightEncoder()-prevPositionR)/TICKS_PER_ROTATION*2*PI; + + prevPositionL = readLeftEncoder(); + prevPositionR = readRightEncoder(); + + double angleDist = (rDist - lDist)*TIRE_RADIUS/trackWidth; + + double currentRot = prevRotation + angleDist; + + double currentX; + double deltaX; + double currentY; + double deltaY; + if(angleDist != 0){ + double temp = (trackWidth*(rDist+lDist))/(2*(rDist-lDist)); + deltaX = temp * (sin(currentRot) - sin(prevRotation)); + deltaY = temp * (cos(prevRotation) - cos(currentRot)); + currentX = prevX + deltaX; + currentY = prevY + deltaY; + + } else { + double totalDist = TIRE_RADIUS*(lDist + rDist)/2; + deltaX = totalDist * cos(currentRot); + deltaY = totalDist * sin(currentRot); + currentX = prevX + deltaX; + currentY = prevY + deltaY; + } + prevX = currentX; + prevY = currentY; + prevRotation = currentRot; + + double loopDelaySeconds = ((double) timeMs) / 1000; + profileX.currentPosition = currentX / TICK_TO_METERS; + profileX.currentVelocity = deltaX==0?0:deltaX / TICK_TO_METERS /loopDelaySeconds; + xSetpoint = xProfile.calculate(loopDelaySeconds, + TrapezoidProfile::State(profileX.currentPosition, profileX.currentVelocity), + TrapezoidProfile::State(getLeftMotorControl().value, 0.0)); + + double velocity = XVelocityController.Compute(xSetpoint.velocity, profileX.currentVelocity, loopDelaySeconds); + double aVel = headingController.Compute(0, currentRot*RAD_TO_DEG, loopDelaySeconds); + + profileY.currentPosition = currentY / TICK_TO_METERS; + profileY.currentVelocity = deltaY==0?0:deltaY / TICK_TO_METERS /loopDelaySeconds; + ySetpoint = yProfile.calculate(loopDelayMs/1000, + TrapezoidProfile::State(profileY.currentPosition, profileY.currentVelocity), + TrapezoidProfile::State(getRightMotorControl().value, 0.0)); + double yVel = YVelocityController.Compute(ySetpoint.velocity, profileY.currentVelocity, loopDelaySeconds); + + aVel += yVel; + + double lMotorPower = fmap((velocity-8*aVel*trackWidth/2)/TIRE_RADIUS, -25, 25, -1, 1); + double rMotorPower = fmap((velocity+8*aVel*trackWidth/2)/TIRE_RADIUS, -25, 25, -1, 1); + + if (fabs(lMotorPower) < MIN_MOTOR_POWER) lMotorPower = 0; + if (fabs(rMotorPower) < MIN_MOTOR_POWER) rMotorPower = 0; + + + serial_printf( + DebugLevel::DEBUG, + "vel %f yvel %f avel %f lpower %f rpower %f xpos %f ypos %f\n", + velocity, + yVel, + aVel, + lMotorPower, + rMotorPower, + currentX, + currentY + ); + + setLeftPower(lMotorPower); + setRightPower(rMotorPower); + + double sum = 0; + for(int x = 49; x >= 0; x--) { + average[x+1] = average[x]; + sum += fabs(average[x+1]); + } + average[0] = lMotorPower; + sum += fabs(average[0]); + timeMs += loopDelayMs; + if (sum/50 < 0.01){ + serialLogln(sum/50,3); + serialLogln(runningPID,3); + runningPID = false; + setLeftPower(0); + setRightPower(0); + + sendActionSuccess("move done"); + resetPID(); + + } else { + runningPID = true; + } +} + +void Robot::turn_tick() { + double lDist = left.dist(); + double rDist = right.dist(); + + prevPositionL = readLeftEncoder(); + prevPositionR = readRightEncoder(); + + double angleDist = (rDist - lDist)*TIRE_RADIUS/trackWidth; + + double currentRot = prevRotation + angleDist; + + double currentX; + double deltaX; + double currentY; + double deltaY; + if(angleDist != 0){ + double temp = (trackWidth*(rDist+lDist))/(2*(rDist-lDist)); + deltaX = temp * (sin(currentRot) - sin(prevRotation)); + deltaY = temp * (cos(prevRotation) - cos(currentRot)); + currentX = prevX + deltaX; + currentY = prevY + deltaY; + + } else { + double totalDist = TIRE_RADIUS*(lDist + rDist)/2; + deltaX = totalDist * cos(currentRot); + deltaY = totalDist * sin(currentRot); + currentX = prevX + deltaX; + currentY = prevY + deltaY; + } + prevX = currentX; + prevY = currentY; + + prevRotation = currentRot; + + double loopDelaySeconds = ((double) timeMs) / 1000; + profileA.currentPosition = currentRot*10 / TICK_TO_METERS; + profileA.currentVelocity = angleDist==0?0:angleDist*10 / TICK_TO_METERS /loopDelaySeconds; + aSetpoint = aProfile.calculate(loopDelaySeconds, + TrapezoidProfile::State(profileA.currentPosition, profileA.currentVelocity), + TrapezoidProfile::State(getHeadingTarget()*10/TICK_TO_METERS, 0.0)); + + double velocity = AVelocityController.Compute(aSetpoint.velocity, profileA.currentVelocity, loopDelaySeconds); + + double lMotorPower = fmap((-8*velocity*trackWidth/2)/TIRE_RADIUS, -11, 11, -1, 1); + double rMotorPower = fmap((8*velocity*trackWidth/2)/TIRE_RADIUS, -11, 11, -1, 1); + + if (fabs(lMotorPower) < MIN_MOTOR_POWER) lMotorPower = 0; + if (fabs(rMotorPower) < MIN_MOTOR_POWER) rMotorPower = 0; + + setLeftPower(lMotorPower); + setRightPower(rMotorPower); + + serialLog("vels ", 3); + serialLog(xSetpoint.velocity, 3); + serialLog("vel ", 3); + serialLog(velocity, 3); + serialLog(" lpower ", 3); + serialLog(lMotorPower, 3); + serialLog(" rpower ", 3); + serialLog(rMotorPower, 3); + serialLog(" angle ", 3); + serialLogln(currentRot*10, 3); + + + double sum = 0; + for(int x = 49; x >= 0; x--) { + average[x+1] = average[x]; + sum += fabs(average[x+1]); + } + average[0] = lMotorPower; + sum += fabs(average[0]); + timeMs += loopDelayMs; + if (sum/50 < 0.01){ + serialLogln(sum/50,3); + serialLogln(runningPID,3); + runningPID = false; + setLeftPower(0); + setRightPower(0); + + sendActionSuccess("turn done"); + resetPID(); + + } else { + runningTurn = true; + } +} + +void Robot::center() { + centeringStatus = STARTED; +} + +void Robot::drive(float tiles, std::string id) { + if (!getStoppedStatus()) { + const float TILE_SIZE_INCHES = 24; + float distanceInches = tiles * TILE_SIZE_INCHES; + float ticksPerInch = TICKS_PER_ROTATION / (WHEEL_DIAMETER_INCHES * M_PI); + int tickDistance = (int)(distanceInches * ticksPerInch); + driveTicks(tickDistance, id); + } +} + +// Drives the wheels according to the powers set. Negative is backwards, Positive forwards +void Robot::drive(float leftPower, float rightPower, std::string id) { + if (!getStoppedStatus()) { + if (leftPower < MIN_MOTOR_POWER && leftPower > -MIN_MOTOR_POWER) { + leftPower = 0; + } if (rightPower < MIN_MOTOR_POWER && rightPower > -MIN_MOTOR_POWER) { + rightPower = 0; + } + + setLeftPower(leftPower); + setRightPower(rightPower); + + //we only send null as id during our test drive. The only other time this drive method is called will be + //when the server sends it, meaning it will have an id to send back. + if (id != "NULL") { sendActionSuccess(id); } + } + } + +void Robot::driveTicks(int tickDistance, std::string id) { + if (stopped) { + resetSpeed(); + setXControl({POSITION, (float)tickDistance}); + setYControl({POSITION, 0}); + updateCritRange(); + runningPID = true; + + if (id != "NULL") { + sendPacketOnPidComplete(id); + } + } + } + +//turns the given amount in radians, CCW +void Robot::turn(float angleRadians, std::string id) { + serialLogln("Turning", 3); + serialLogln(angleRadians, 3); + + setXControl({POSITION, 0}); + setYControl({POSITION, 0}); + updateCritRange(); + setHeadingTarget(angleRadians*0.95); + runningTurn = true; + + if (id != "NULL") + { + sendPacketOnPidComplete(id); + } +} + +void Robot::stop() { + stopped = true; + + left.power(0); + right.power(0); + + serialLogln("Bot Stopped!", 2); +} + + + +/** + * get PID ready for the next iteration + */ +void resetPID(){ + prevPositionL = readLeftEncoder(); + prevPositionR = readRightEncoder(); + prevX = 0; + prevY = 0; + prevRotation = 0; + timeMs = 0; + for (int x = 0; x < 50; x++) average[x] = 100; +} + + +//crit range is basically getting distance we go until we are halfway to target. By the end of this range, +//we're at our max speed and are sure we aren't at a low speed just cause we're speeding up +void updateCritRange() +{ + //want to record the values before we move now + startEncoderAPos = profileX.currentPosition; + startEncoderBPos = profileY.currentPosition; + + profileX.criticalRange = fabs(profileX.targetPosition - startEncoderAPos) / 2; + profileY.criticalRange = fabs(profileY.targetPosition - startEncoderBPos) / 2; + + //update it so that time since start is now equal to this. Only really care about this value after turns though + timeSinceTurn = millis(); +} + + + + +// Sets up all the aspects needed for the bot to work +void setupBot() { + serialLogln("Setting Up Bot...", 2); + + pinMode(ONBOARD_LED_PIN, OUTPUT); + digitalWrite(ONBOARD_LED_PIN, HIGH); + + setupMotors(); + setupIR(); + setupEncodersNew(); + serialLogln("Bot Set Up!", 2); + + XVelocityController.Reset(); + YVelocityController.Reset(); + AVelocityController.Reset(); + headingController.Reset(); + resetPID(); + + + // if (DO_PID_TEST) { + // testEncoderPID(); + // timerInterval(8000, &testEncoderPID); + // } + + // if (DO_TURN_TEST) { + // angle = 30; + // testTurn(); + // timerInterval(5000, testTurn); + // } + + // if (DO_CENTERING_TEST) { + // testCentering(); + // timerInterval(5000, &testCentering); + // } +} + +//this determines what our next action will be after an edge alignment, move to center, or axis turn. +void nextAction() +{ + //if we were previously turning to the next axis, and finished: + if(turningToNextAxis) + { + turningToNextAxis = false; + axisesAligned++; + //done centering yippee! + if(axisesAligned == 2) + { + axisesAligned = 0; + isCentering = false; + centeringStatus = CenteringStatus::NOT_CENTERING; + } + //otherwise restart the whole process for this next axis + else + { + centeringStatus = CenteringStatus::STARTED; + } + } + //if previously moving to center for an axis, and finished: + else if(movingCenter) + { + //now, turn to next direction + movingCenter = false; + turningToNextAxis = true; + centeringStatus = CenteringStatus::MOVING; + //this way, if no axises aligned yet, angle = -90, and if one axis aligned, + //angle = 90, undoing the previous rotation. + angle = 90 * (axisesAligned * 2 - 1); + + // testTurn(); + } + //if just aligned on a forward edge with the encoders in the front: + else if(forwardAligning) + { + //if going forward, store the current encoder value so we can see the full encoder length of the tiles + encoderAHalfwayDist = profileX.currentPosition; + encoderBHalfwayDist = profileY.currentPosition; + //swap to going back + forwardAligning = !forwardAligning; + //set that new drive + createDriveUntilNewTile(); + centeringStatus = 'E'; + + serialLog((char*)"Current encoder A: ", 2); + serialLogln(profileX.currentPosition, 2); + serialLog((char*)"Current encoder B: ", 2); + serialLogln(profileY.currentPosition, 2); + serialLog((char*)"Target encoder A: ", 2); + // serialLogln(leftMotorControl.mode == POSITION ? leftMotorControl.value : 0, 2); + serialLog((char*)"Target encoder B: ", 2); + // serialLogln(rightMotorControl.mode == POSITION ? rightMotorControl.value : 0, 2); + } + //if just aligned on a backward edge with the encoders in the back: + else + { + //swap to going forward now + forwardAligning = !forwardAligning; + + //since we always go forward first and then backwards, the current value of encoderHalfwayDist > currentEncoder always + //what we're doing is currently, "encoderAHalfwayDist" just stores the value of the other edge in encoder ticks, now we're + //finding the difference between them. And of course divide by 2 as want half that distance + encoderAHalfwayDist = (encoderAHalfwayDist - profileX.currentPosition) / 2; + encoderBHalfwayDist = (encoderBHalfwayDist - profileY.currentPosition) / 2; + + //decide that we take average of encoder A and B's distances, since ideally we want both to travel the same amount + int totalHalfwayDistance = (encoderAHalfwayDist + encoderBHalfwayDist) / 2; + // driveTicks(totalHalfwayDistance, "NULL"); + centeringStatus = CenteringStatus::MOVING; + //now we moving to da center + movingCenter = true; + } +} + +//this updates our centering depending on the current status of it +void Robot::center_tick() +{ + //what we do depend on the current status + switch(centeringStatus) + { + case CenteringStatus::STARTED: + //create the first drive + createDriveUntilNewTile(); + //now change it so we're driving forward + centeringStatus = CenteringStatus::EDGE; + break; + case CenteringStatus::EDGE: + { + //continue driving forward + DriveStatus drive_status = driveUntilNewTile(); + //reminder status 3 = no leading encoders and driving finished + if(driveStatus == DriveStatus::REACHED) + { + //meaning we can now go in opposite direction. + nextAction(); + } + //reminder status 2 = one leading encoder finished first, but driving is finished + else if(driveStatus == == DriveStatus::REACHED_REVERSING) + { + //mean we now begin correcting + centeringStatus = CenteringStatus::MOVING; // ???? + } + break; + } + case CenteringStatus::MOVING: + //check if we're the moving we're doing is finished. If so, determine what we do next. + + // ??? + // if(checkMoveFinished()) + // { + // nextAction(); + // } + break; + } +} + +//checks if we're done moving to our target when either moving half a tile's length or turning +// bool checkMoveFinished() +// { +// //first, checks like "fabs(profileX.currentVelocity) < 2" see if we're slowing down or not. + +// //then, something like "fabs(currentEncoderA - encoderATarget) < criticalRangeA" is making sure +// //the reason our speed is slow is specifically because we're slowing down and not because we're +// //beginning to speed up. +// //do this by seeing if the distance remaining is less than the midpoint distance from start to end, as by then we're at our max speed. + +// bool encoderAChecks = fabs(profileX.currentPosition - profileX.targetPosition) < profileX.criticalRange && fabs(profileX.currentVelocity) < 3; +// bool encoderBChecks = fabs(profileY.currentPosition - profileY.targetPosition) < profileY.criticalRange && fabs(profileY.currentVelocity) < 3; + +// //check if we've been stalling too long, for 8 seconds. If we're over time, that's bad, and means we should declare the movement finished. +// bool timerCheck = millis() - timeSinceTurn > 8000; + +// return ((encoderAChecks && encoderBChecks) || timerCheck); +// } + +// //like the one above but just seeing if we can keep moving or not +// bool checkIfCanUpdateMovement() +// { +// return fabs(profileX.currentPosition - profileX.targetPosition) < profileX.criticalRange && fabs(profileY.currentPosition - profileY.targetPosition) < profileY.criticalRange; +// } + +boolean isRobotPidAtTarget() { + if (!DO_PID) + return true; + + boolean leftAtTarget, rightAtTarget; + + if (getLeftMotorControl().mode == POSITION) + { + leftAtTarget = approxEquals(getLeftMotorControl().value, profileX.currentPosition, PID_POSITION_TOLERANCE) + && approxEquals(profileX.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE); + + serialLog("Left Position: ", 3); + serialLog(profileX.currentPosition, 3); + serialLog(", Target: ", 3); + serialLog(getLeftMotorControl().value, 3); + serialLog(", Velocity: ", 3); + serialLog(profileX.currentVelocity, 3); + serialLog(", At Target: ", 3); + serialLogln(leftAtTarget, 3); + } + else + { + leftAtTarget = approxEquals(getLeftMotorControl().value, profileX.currentVelocity, PID_VELOCITY_TOLERANCE); + } + if (getRightMotorControl().mode == POSITION) + { + rightAtTarget = approxEquals(getRightMotorControl().value, profileY.currentPosition, PID_POSITION_TOLERANCE) + && approxEquals(profileY.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE); + + serialLog("Right Position: ", 3); + serialLog(profileY.currentPosition, 3); + serialLog(", Target: ", 3); + serialLog(getRightMotorControl().value, 3); + serialLog(", Velocity: ", 3); + serialLog(profileY.currentVelocity, 3); + serialLog(", At Target: ", 3); + serialLogln(rightAtTarget, 3); + } + else + { + rightAtTarget = approxEquals(getRightMotorControl().value, profileY.currentVelocity, PID_VELOCITY_TOLERANCE); + } + + return leftAtTarget && rightAtTarget; +} + +void sendPacketOnPidComplete(std::string id) { + if (!DO_PID) + sendActionFail(id); + + if (isRobotPidAtTarget()) { + sendActionSuccess(id); + } else { + // Run on next loop + timerDelay(1, [id](){ sendPacketOnPidComplete(id); }); + } +} + +// //updates us to the next distance we're traveling +// void updateToNextDistance() +// { +// //this way if we're reversing, we're actually subtracting. if going forward was 0, then 0 * 2 - 1 = -1. +// //if going forward was 1, 1 * 2 - 1 = 1. +// float encTargetA = (float)profileX.currentPosition + 2500 * (forwardAligning * 2 - 1); +// float encTargetB = (float)profileY.currentPosition + 2500 * (forwardAligning * 2 - 1); +// setXControl({POSITION, encTargetA}); +// setYControl({POSITION, encTargetB}); +// #if LOGGING_LEVEL >= 3 +// serialLogln("changing direction!", 3); +// serialLogln(encTargetA, 3); +// serialLogln(encTargetB, 3); +// #endif + +// //update crit range yessir +// updateCritRange(); +// } + +//creates a new drive until the next tile +// void createDriveUntilNewTile() +// { +// //set the next distance to travel +// resetSpeed(); +// updateToNextDistance(); + +// //assign values here, will detect when they change +// if(forwardAligning) +// { +// firstEncoderIndex = Top_Left_Encoder_Index; +// secondEncoderIndex = Top_Right_Encoder_Index; +// } +// else +// { +// //from the robots perspective as it's going backwards, the encoder on the left is bottom right, +// //while the encoder on the right is bottom left, so we just swap em +// firstEncoderIndex = Bottom_Right_Encoder_Index; +// secondEncoderIndex = Bottom_Left_Encoder_Index; +// } +// //now set the actual values with the indices +// firstEncoderVal = onFirstTile[firstEncoderIndex]; +// secondEncoderVal = onFirstTile[secondEncoderIndex]; +// } + +//drives until the first two encoders are considered to hit a new value. +//Returns a status bit, with the corresponding values: + // 1 - drive is going + // 2 - just at this moment, we have reached our destination and are going to begin reversing now. + // 3 - just at this moment, we've reached our destination, but DON'T need to reverse. +enum DriveStatus Robot::driveUntilNewTile() +{ + //if we do finish moving, update to a new distance. I think we have to move at intervals for it to work + if(checkIfCanUpdateMovement()) + { + updateToNextDistance(); + } + + //if we already changed it, don't change it back again + leftEncoderChange = leftEncoderChange || (onFirstTile[firstEncoderIndex] != firstEncoderVal); + rightEncoderChange = rightEncoderChange || (onFirstTile[secondEncoderIndex] != secondEncoderVal); + + if(!leftEncoderChange && !rightEncoderChange) { + return CenteringStatus::STARTED; + } + + //when both cross, we done. + if(leftEncoderChange && rightEncoderChange) + { + //if there had been a leading encoder, do the following: + uint8_t status = 0; + if(leadingEncoder != 0) + { + setXControl({POSITION, (float)profileX.currentPosition}); + setYControl({POSITION, (float)profileY.currentPosition}); + + //first get the encoder that we're comparing to get the distance. If leading encoder is 1 and we were moving forward, or if + //leading encoder is 2 but we were moving backward, then the back encoder is b, otherwise it's A + double encoderChosen = (leadingEncoder == 1 && forwardAligning || leadingEncoder == 2 && !forwardAligning) ? profileY.currentPosition : profileX.currentPosition; + //now, the distance we traveled is the difference between the encoders + double backEncoderDist = fabs(encoderChosen - backPrevDistance); + // serialLog("Begin encoder is: ", 3); + // serialLogln(backPrevDistance, 3); + // serialLog("End encoder is: ", 3); + // serialLogln((leadingEncoder == 1) ? profileX.currentPosition : profileY.currentPosition, 3); + //now convert difference in ticks to meter value + backEncoderDist *= TICK_TO_METERS; + // serialLog(" Encoder in front is gonna be: ", 3); + // serialLogln(leadingEncoder, 2); + // serialLog("Total distance encoder was behind is: ", 2); + // serialLogln(backEncoderDist, 2); + //reminder: angle = arctan(x/y), where x = backEncoderDist (like distance to our edge), and y = distance between two light sensors (put in manually) + + //idk why, but when dividing by 2 that gets us the true angle. The BackEncoderDist and lightDist seems to be correct vales, but the value we + //end up getting from it is double what it should be. Maybe there's an issue with how I did it. + float radAngle = atan(backEncoderDist / lightDist) / 2; + + //as a reminder, corresponding degrees = (pi/180) * x radians + float degreesAngle = 180 / M_PI * radAngle; + + serialLog("Angle is going to be: ", 2); + serialLog(degreesAngle, 2); + serialLogln(" degrees.", 2); + + //we know positive angle = turn left, negative angle means turn right. + //encoder 1 forward means turn left, encoder 2 forward means turn right. + //so 2 = -1, 1 = 1. If you plug those numbers in, that's what you get. + + int8_t degreesDirection = 3 - 2 * leadingEncoder; + serialLog("Sign is going to be: ", 2); + serialLogln(degreesDirection, 2); + + //now update the angle, and turn + angle = degreesAngle * degreesDirection; + // testTurn(); + status = 2; + } + else + { + status = 3; + + //with the other one we set the crit range after calling the turn function. + //Here we don't, so we gotta do that + updateCritRange(); + } + + //reset all of our values + leadingEncoder = 0; + backPrevDistance = 0; + leftEncoderChange = false; + rightEncoderChange = false; + + //if the encoder returned 0, no need to reverse so skip to status 3. + return status; + } + //otherwise, want to see which one crossed. Can do this by seeing if we've updated backPrevDistance yet or not. + else if(backPrevDistance == 0) + { + //if left encoder changed, that's the leading encoder, otherwise 2nd is the leading encoder obviously. + leadingEncoder = leftEncoderChange ? 1 : 2; + //this makes sense as if the left encoder first crossed but we're going backwards, that's encoder A that's behind. Meanwhile if the right + //encoder crossed first and we're going forwards, its encoder A that's behind too. In all other cases, its encoder B + backPrevDistance = (leftEncoderChange && !forwardAligning || rightEncoderChange && forwardAligning) ? profileX.currentPosition : profileY.currentPosition; + } + + return 1; +} + +// // Tests the motors. This turns the motors off. +// void driveTestOff() { +// stop(); +// timerDelay(2000, &startDriveTest); +// } + +// // Test motor and encoder synchronization +// void startMotorAndEncoderTest() { +// (new MotorEncoderTest())->startMotorAndEncoderTest(); +// } + +// // Tests the motors. This turns the motors on. +// void startDriveTest() { +// drive(0.5f, 0.5f, "NULL"); +// //timerDelay(2000, &driveTestOff); +// } + +// void testCentering() +// { +// serialLogln("Running centering routine...", 2); +// startCentering(); +// } + +// void testEncoderPID() +// { +// serialLogln("Changing encoder PID setpoint!", 2); +// if (!testEncoderPID_value) +// { +// testEncoderPID_value = true; +// setXControl({POSITION, (float)TICKS_PER_ROTATION * 6}); +// setYControl({POSITION, 0.0f}); +// runningPID = true; +// } +// else +// { +// testEncoderPID_value = false; +// setXControl({POSITION, 0.0f}); +// setYControl({POSITION, 0.0f}); +// runningPID = true; +// } + +// updateCritRange(); +// } + +// void testTurn() +// { +// resetSpeed(); + +// serialLog("Changing destination angle to ", 2); +// serialLog(angle, 2); +// //simple maths +// turn(M_PI / 180 * angle, "NULL"); +// serialLog(" (", 2); +// serialLog(getLeftMotorControl().value, 2); +// serialLog(", ", 2); +// serialLog(getRightMotorControl().value, 2); +// serialLogln(")", 2); + +// //compute the new crit range now that target and start encoder have changed +// updateCritRange(); +// } +#endif \ No newline at end of file diff --git a/src/robot/driveTest.cpp b/src/robot/driveTest.cpp index 0ce6739..fb9da45 100644 --- a/src/robot/driveTest.cpp +++ b/src/robot/driveTest.cpp @@ -1,195 +1,194 @@ -#ifndef CHESSBOT_DRIVETEST_CPP -#define CHESSBOT_DRIVETEST_CPP - -#include "robot/driveTest.h" -#include "Arduino.h" -#include "robot/motor.h" -#include "robot/encoder.h" -#include "utils/timer.h" -#include "utils/logging.h" - -void MotorEncoderTest::init() -{ - serialLogln("Starting Motor & Encoder Test", 2); - - this->testSuccessful = true; - - this->startEncoderA = readLeftEncoder(); - this->_startEncoderB = readRightEncoder(); - - setLeftPower(1); - setRightPower(0); - auto fp = std::bind(&MotorEncoderTest::testLeftMotor, this); - timerDelay(1000, fp); -} - -void MotorEncoderTest::testLeftMotor() -{ - int encoderAValue = readLeftEncoder(); - if (encoderAValue > (this->startEncoderA + this->ENCODER_TOLERANCE)) - { - serialLogln("Encoder A (lbl RightEncoder) is aligned with left motor (lbl M1). (Positive motor = positive encoder = CW from Motor POV)", 2); - } - else if (encoderAValue < (this->startEncoderA - this->ENCODER_TOLERANCE)) - { - serialLogln("[WARN] Encoder A (lbl RightEncoder) is inverted with left motor (lbl M1)!", 2); - this->testSuccessful = false; - } - else - { - serialLogln("[ERR] Encoder A (lbl RightEncoder) is not associated with left motor (lbl M1)!", 2); - this->testSuccessful = false; - } - setLeftPower(0); - setRightPower(0); - auto fp = std::bind(&MotorEncoderTest::testWait, this); - timerDelay(2000, fp); -} - -void MotorEncoderTest::testWait() -{ - this->startEncoderB = readRightEncoder(); - - setLeftPower(0); - setRightPower(1); - auto fp = std::bind(&MotorEncoderTest::testRightMotor, this); - timerDelay(1000, fp); -} - -void MotorEncoderTest::testRightMotor() -{ - int encoderBValue = readRightEncoder(); - if (encoderBValue > (this->startEncoderB + this->ENCODER_TOLERANCE)) - { - serialLogln("Encoder B (lbl LeftEncoder) is aligned with right motor (lbl M2). (Positive motor = positive encoder = CCW from Motor POV)", 2); - } - else if (encoderBValue < (this->startEncoderB - this->ENCODER_TOLERANCE)) - { - serialLogln("[WARN] Encoder B (lbl LeftEncoder) is inverted with right motor (lbl M2)!", 2); - this->testSuccessful = false; - } - else - { - serialLogln("[ERR] Encoder B (lbl LeftEncoder) is not associated with right motor (lbl M2)!", 2); - this->testSuccessful = false; - } - setRightPower(0); - if (this->testSuccessful) - { - serialLogln("Test successful!", 2); - serialLogln("To go forward, both left and right should be set positive.", 2); - auto fp = std::bind(&MotorEncoderTest::testMotorDeadzones, this); - timerDelay(2000, fp); - } - else - { - int encoderAValue = readLeftEncoder(); - if ((this->startEncoderA - this->ENCODER_TOLERANCE) <= encoderAValue && encoderAValue <= (this->startEncoderA + this->ENCODER_TOLERANCE)) { - serialLogln("[WARN] Encoder A (lbl RightEncoder) did not significantly change over the course of the test!", 2); - } - if ((this->_startEncoderB - this->ENCODER_TOLERANCE) <= encoderBValue && encoderBValue <= (this->_startEncoderB + this->ENCODER_TOLERANCE)) - { - serialLogln("[WARN] Encoder B (lbl LeftEncoder) did not significantly change over the course of the test!", 2); - } - serialLogln("Test failed for one or more reasons, listed above.", 2); - if (((this->startEncoderA - this->ENCODER_TOLERANCE) > encoderAValue || encoderAValue > (this->startEncoderA + this->ENCODER_TOLERANCE)) - && ((this->_startEncoderB - this->ENCODER_TOLERANCE) > encoderBValue || encoderBValue > (this->_startEncoderB + this->ENCODER_TOLERANCE))) { - serialLogln("Encoder A and B changed but did not have the correct associations. Maybe swap the motors or the encoders?", 2); - } - } -} - -void MotorEncoderTest::checkMotorDeadzone(bool leftMotor) -{ - serialLogln(leftMotor ? "Checking LEFT motor deadzone..." : "Checking RIGHT motor deadzone...", 2); - const float powerStep = 0.01f; - const float maxPower = 1.0f; - const int encoderThreshold = 200; // Minimum encoder ticks to consider as movement - int initialEncoder = leftMotor ? readLeftEncoder() : readRightEncoder(); - - for (float power = 0.0f; power <= maxPower; power += powerStep) - { - if (leftMotor) - { - setLeftPower(power); - setRightPower(0); - } - else - { - setLeftPower(0); - setRightPower(power); - } - delay(200); // Wait for motor to respond - - int currentEncoder = leftMotor ? readLeftEncoder() : readRightEncoder(); - if (abs(currentEncoder - initialEncoder) >= encoderThreshold) - { - serialLog("Deadzone crossed at power: ", 2); - serialLogln(power, 2); - break; - } - } - setLeftPower(0); - setRightPower(0); -} - -void MotorEncoderTest::testMotorDeadzones() -{ - delay(500); - checkMotorDeadzone(true); // Check left motor - delay(500); - checkMotorDeadzone(false); // Check right motor - serialLogln("Deadzone test complete!", 2); - auto fp = std::bind(&MotorEncoderTest::testDriveForward, this); - timerDelay(1000, fp); -} - -void MotorEncoderTest::checkEncoderVelocity() -{ - int encA = readLeftEncoder(); - int encB = readRightEncoder(); - float timeDiff = (millis() - prevTime) / 1000.0; // in seconds - float encAVel = (encA - prevEncA) / timeDiff; - float encBVel = (encB - prevEncB) / timeDiff; - float encAAccel = (encAVel - prevEncVelA) / timeDiff; // Am I miscalculating acceleration? Should be change in velocity over change in time, but I'm not dividing by time here - float encBAccel = (encBVel - prevEncVelB) / timeDiff; - if (abs(encAVel) > maxEncoderVelocity) maxEncoderVelocity = abs(encAVel); - if (abs(encBVel) > maxEncoderVelocity) maxEncoderVelocity = abs(encBVel); - if (abs(encAAccel) > maxEncoderAccel) maxEncoderAccel = abs(encAAccel); - if (abs(encBAccel) > maxEncoderAccel) maxEncoderAccel = abs(encBAccel); - prevEncA = encA; - prevEncB = encB; - prevEncVelA = encAVel; - prevEncVelB = encBVel; - prevTime = millis(); -} - -void MotorEncoderTest::testDriveForward() -{ - prevEncA = readLeftEncoder(); - prevEncB = readRightEncoder(); - prevEncVelA = 0; - prevEncVelB = 0; - prevTime = millis(); - serialLogln("Setting motors to go 'forward' for 5 seconds...", 2); - setLeftPower(1); - setRightPower(1); - auto fp2 = std::bind(&MotorEncoderTest::checkEncoderVelocity, this); - encoderCheckTimerId = timerInterval(20, fp2); - auto fp = std::bind(&MotorEncoderTest::testDriveDone, this); - timerDelay(5000, fp); -} - -void MotorEncoderTest::testDriveDone() -{ - serialLogln("Driving done!", 2); - serialLog("Max encoder velocity is ", 2); - serialLogln(maxEncoderVelocity, 2); - serialLog("Max encoder acceleration is ", 2); - serialLogln(maxEncoderAccel, 2); - timerCancel(encoderCheckTimerId); - setLeftPower(0); - setRightPower(0); -} - -#endif \ No newline at end of file +// #ifndef CHESSBOT_DRIVETEST_CPP +// #define CHESSBOT_DRIVETEST_CPP + +// #include "robot/driveTest.h" +// #include "Arduino.h" +// #include "robot/control/motor.h" +// #include "utils/timer.h" +// #include "utils/logging.h" + +// void MotorEncoderTest::init() +// { +// serialLogln("Starting Motor & Encoder Test", 2); + +// this->testSuccessful = true; + +// this->startEncoderA = readLeftEncoder(); +// this->_startEncoderB = readRightEncoder(); + +// setLeftPower(1); +// setRightPower(0); +// auto fp = std::bind(&MotorEncoderTest::testLeftMotor, this); +// timerDelay(1000, fp); +// } + +// void MotorEncoderTest::testLeftMotor() +// { +// int encoderAValue = readLeftEncoder(); +// if (encoderAValue > (this->startEncoderA + this->ENCODER_TOLERANCE)) +// { +// serialLogln("Encoder A (lbl RightEncoder) is aligned with left motor (lbl M1). (Positive motor = positive encoder = CW from Motor POV)", 2); +// } +// else if (encoderAValue < (this->startEncoderA - this->ENCODER_TOLERANCE)) +// { +// serialLogln("[WARN] Encoder A (lbl RightEncoder) is inverted with left motor (lbl M1)!", 2); +// this->testSuccessful = false; +// } +// else +// { +// serialLogln("[ERR] Encoder A (lbl RightEncoder) is not associated with left motor (lbl M1)!", 2); +// this->testSuccessful = false; +// } +// setLeftPower(0); +// setRightPower(0); +// auto fp = std::bind(&MotorEncoderTest::testWait, this); +// timerDelay(2000, fp); +// } + +// void MotorEncoderTest::testWait() +// { +// this->startEncoderB = readRightEncoder(); + +// setLeftPower(0); +// setRightPower(1); +// auto fp = std::bind(&MotorEncoderTest::testRightMotor, this); +// timerDelay(1000, fp); +// } + +// void MotorEncoderTest::testRightMotor() +// { +// int encoderBValue = readRightEncoder(); +// if (encoderBValue > (this->startEncoderB + this->ENCODER_TOLERANCE)) +// { +// serialLogln("Encoder B (lbl LeftEncoder) is aligned with right motor (lbl M2). (Positive motor = positive encoder = CCW from Motor POV)", 2); +// } +// else if (encoderBValue < (this->startEncoderB - this->ENCODER_TOLERANCE)) +// { +// serialLogln("[WARN] Encoder B (lbl LeftEncoder) is inverted with right motor (lbl M2)!", 2); +// this->testSuccessful = false; +// } +// else +// { +// serialLogln("[ERR] Encoder B (lbl LeftEncoder) is not associated with right motor (lbl M2)!", 2); +// this->testSuccessful = false; +// } +// setRightPower(0); +// if (this->testSuccessful) +// { +// serialLogln("Test successful!", 2); +// serialLogln("To go forward, both left and right should be set positive.", 2); +// auto fp = std::bind(&MotorEncoderTest::testMotorDeadzones, this); +// timerDelay(2000, fp); +// } +// else +// { +// int encoderAValue = readLeftEncoder(); +// if ((this->startEncoderA - this->ENCODER_TOLERANCE) <= encoderAValue && encoderAValue <= (this->startEncoderA + this->ENCODER_TOLERANCE)) { +// serialLogln("[WARN] Encoder A (lbl RightEncoder) did not significantly change over the course of the test!", 2); +// } +// if ((this->_startEncoderB - this->ENCODER_TOLERANCE) <= encoderBValue && encoderBValue <= (this->_startEncoderB + this->ENCODER_TOLERANCE)) +// { +// serialLogln("[WARN] Encoder B (lbl LeftEncoder) did not significantly change over the course of the test!", 2); +// } +// serialLogln("Test failed for one or more reasons, listed above.", 2); +// if (((this->startEncoderA - this->ENCODER_TOLERANCE) > encoderAValue || encoderAValue > (this->startEncoderA + this->ENCODER_TOLERANCE)) +// && ((this->_startEncoderB - this->ENCODER_TOLERANCE) > encoderBValue || encoderBValue > (this->_startEncoderB + this->ENCODER_TOLERANCE))) { +// serialLogln("Encoder A and B changed but did not have the correct associations. Maybe swap the motors or the encoders?", 2); +// } +// } +// } + +// void MotorEncoderTest::checkMotorDeadzone(bool leftMotor) +// { +// serialLogln(leftMotor ? "Checking LEFT motor deadzone..." : "Checking RIGHT motor deadzone...", 2); +// const float powerStep = 0.01f; +// const float maxPower = 1.0f; +// const int encoderThreshold = 200; // Minimum encoder ticks to consider as movement +// int initialEncoder = leftMotor ? readLeftEncoder() : readRightEncoder(); + +// for (float power = 0.0f; power <= maxPower; power += powerStep) +// { +// if (leftMotor) +// { +// setLeftPower(power); +// setRightPower(0); +// } +// else +// { +// setLeftPower(0); +// setRightPower(power); +// } +// delay(200); // Wait for motor to respond + +// int currentEncoder = leftMotor ? readLeftEncoder() : readRightEncoder(); +// if (abs(currentEncoder - initialEncoder) >= encoderThreshold) +// { +// serialLog("Deadzone crossed at power: ", 2); +// serialLogln(power, 2); +// break; +// } +// } +// setLeftPower(0); +// setRightPower(0); +// } + +// void MotorEncoderTest::testMotorDeadzones() +// { +// delay(500); +// checkMotorDeadzone(true); // Check left motor +// delay(500); +// checkMotorDeadzone(false); // Check right motor +// serialLogln("Deadzone test complete!", 2); +// auto fp = std::bind(&MotorEncoderTest::testDriveForward, this); +// timerDelay(1000, fp); +// } + +// void MotorEncoderTest::checkEncoderVelocity() +// { +// int encA = readLeftEncoder(); +// int encB = readRightEncoder(); +// float timeDiff = (millis() - prevTime) / 1000.0; // in seconds +// float encAVel = (encA - prevEncA) / timeDiff; +// float encBVel = (encB - prevEncB) / timeDiff; +// float encAAccel = (encAVel - prevEncVelA) / timeDiff; // Am I miscalculating acceleration? Should be change in velocity over change in time, but I'm not dividing by time here +// float encBAccel = (encBVel - prevEncVelB) / timeDiff; +// if (abs(encAVel) > maxEncoderVelocity) maxEncoderVelocity = abs(encAVel); +// if (abs(encBVel) > maxEncoderVelocity) maxEncoderVelocity = abs(encBVel); +// if (abs(encAAccel) > maxEncoderAccel) maxEncoderAccel = abs(encAAccel); +// if (abs(encBAccel) > maxEncoderAccel) maxEncoderAccel = abs(encBAccel); +// prevEncA = encA; +// prevEncB = encB; +// prevEncVelA = encAVel; +// prevEncVelB = encBVel; +// prevTime = millis(); +// } + +// void MotorEncoderTest::testDriveForward() +// { +// prevEncA = readLeftEncoder(); +// prevEncB = readRightEncoder(); +// prevEncVelA = 0; +// prevEncVelB = 0; +// prevTime = millis(); +// serialLogln("Setting motors to go 'forward' for 5 seconds...", 2); +// setLeftPower(1); +// setRightPower(1); +// auto fp2 = std::bind(&MotorEncoderTest::checkEncoderVelocity, this); +// encoderCheckTimerId = timerInterval(20, fp2); +// auto fp = std::bind(&MotorEncoderTest::testDriveDone, this); +// timerDelay(5000, fp); +// } + +// void MotorEncoderTest::testDriveDone() +// { +// serialLogln("Driving done!", 2); +// serialLog("Max encoder velocity is ", 2); +// serialLogln(maxEncoderVelocity, 2); +// serialLog("Max encoder acceleration is ", 2); +// serialLogln(maxEncoderAccel, 2); +// timerCancel(encoderCheckTimerId); +// setLeftPower(0); +// setRightPower(0); +// } + +// #endif \ No newline at end of file diff --git a/src/robot/encoder.cpp b/src/robot/encoder.cpp deleted file mode 100644 index fa46458..0000000 --- a/src/robot/encoder.cpp +++ /dev/null @@ -1,50 +0,0 @@ -#ifndef CHESSBOT_ENCODER_CPP -#define CHESSBOT_ENCODER_CPP - -#include "Encoder.h" -#include "robot/encoder.h" -#include "utils/config.h" -#include "utils/logging.h" - -Encoder EncoderA(ENCODER_A_PIN1, ENCODER_A_PIN2); // right -Encoder EncoderB(ENCODER_B_PIN1, ENCODER_B_PIN2); // left -int oldPositionA = -999; -int oldPositionB = -999; - - -void setupEncodersNew() { - serialLogln("Setting up encoder", 3); -} - -void resetEncoders() { - EncoderA.write(0); - EncoderB.write(0); -} - -void encoderLoop() { - int newPosition_EncA = readLeftEncoder(); - int newPosition_EncB = readRightEncoder(); - - if(oldPositionA != newPosition_EncA){ - oldPositionA = newPosition_EncA; - serialLog("Encoder A: ", 4); - serialLogln(newPosition_EncA, 4); - } - - if(oldPositionB != newPosition_EncB){ - oldPositionB = newPosition_EncB; - serialLog("Encoder B: ", 4); - serialLogln(newPosition_EncB, 4); - } -} - -int readLeftEncoder() { - // TODO swap encoders and rename debug logs - return EncoderA.read(); -} - -int readRightEncoder() { - return -EncoderB.read(); -} - -#endif \ No newline at end of file diff --git a/src/robot/lightSensor.cpp b/src/robot/lightSensor.cpp deleted file mode 100644 index 980165f..0000000 --- a/src/robot/lightSensor.cpp +++ /dev/null @@ -1,122 +0,0 @@ -#ifndef CHESSBOT_LIGHT_SENSOR_CPP -#define CHESSBOT_LIGHT_SENSOR_CPP - -// Associated Header File -#include "robot/lightSensor.h" -#include "../env.h" - -// Built-In Libraries -#include "Arduino.h" - -// Custom Libraries -#include "utils/logging.h" -#include "utils/config.h" -#include "utils/timer.h" - -short lightArray[4]; -float prevTickVals[4] = {-1, -1, -1, -1}; -const uint8_t DIFF_TICK = 2; -int8_t counter = 0; - -const short LIMIT_TO_CHANGE = 600; - -// Sets the IR (Infrared) Blaster to be able to output -void setupIR() { - serialLogln("Setting Up Light Sensors...", 2); - pinMode(RELAY_IR_LED_PIN, OUTPUT); - serialLogln("Light Sensors Setup!", 2); -} - -// Turns on the IR Blaster -void activateIR() { - digitalWrite(RELAY_IR_LED_PIN, HIGH); -} - -// Turns off the IR Blaster -void deactivateIR() { - digitalWrite(RELAY_IR_LED_PIN, LOW); -} - -//detects the light change. returns true if change, returns false otherwise -bool checkForLightChange(uint8_t i) -{ - //if difference too great and we're not at the start where prevTick is -1, declare that the encoder has changed color, and assign cooldown. - if(fabs(prevTickVals[i] - lightArray[i]) >= LIMIT_TO_CHANGE && (short) prevTickVals[i] != -1) - { - serialLog(prevTickVals[i], 3); - serialLogln((char*) "", 3); - serialLogln((char*) "THE DIFFERENCE IS BIG SO WE HAVE CHANGED COLOR GRAHH", 3); - return true; - } - return false; -} - -//updates counter value for us. -void updateCounter() { - counter++; - //on diff tick we check, so if we're now past diff tick we reset - if(counter == DIFF_TICK + 1) - { - counter = 0; - } -} - -void startLightReading(bool* onFirstTile, bool* waitingForLight) { - //for each tick, check if its previous value is too far from what it was before. If it is, consider that the encoder has changed color. - readLightLevels(); - *waitingForLight = false; - - for(uint8_t i = 0; i < 4; i++) - { - //if its time to change the tick - if(counter == DIFF_TICK) - { - //only print once - if(i == 0) - { - serialLogln((char*) "Checking tick values!", 4); - } - - if(checkForLightChange(i)) - { - //invert value - onFirstTile[i] = !onFirstTile[i]; - } - //reset the tick values - prevTickVals[i] = 0; - } - else - { - //do DIFF_TICK because if we change in say DIFF_TICK = 3, then 0, 1, and 2 are values we can get, so each is divided by 3. - prevTickVals[i] += (float) lightArray[i] / (DIFF_TICK); - } - } - //updating counter - updateCounter(); -} - -void readLightLevels() { - // Reads the values on the light sensor pins - lightArray[0] = analogRead(PHOTODIODE_A_PIN); - lightArray[1] = analogRead(PHOTODIODE_B_PIN); - lightArray[2] = analogRead(PHOTODIODE_C_PIN); - lightArray[3] = analogRead(PHOTODIODE_D_PIN); - - // Deactivates the IR Blaster after reading to save battery power - deactivateIR(); - - //Logs the values for debugging purposes. This way, if the logging level doesn't permit it, - //we don't ever get to this code as it's not flashed, which saved on time. -#if LOGGING_LEVEL >= 4 - serialLog("Light Levels: ", 2); - serialLog(lightArray[0], 2); - serialLog(" ", 2); - serialLog(lightArray[1], 2); - serialLog(" ", 2); - serialLog(lightArray[2], 2); - serialLog(" ", 2); - serialLogln(lightArray[3], 2); -#endif -} - -#endif \ No newline at end of file diff --git a/src/robot/motor.cpp b/src/robot/motor.cpp deleted file mode 100644 index 272c097..0000000 --- a/src/robot/motor.cpp +++ /dev/null @@ -1,67 +0,0 @@ -#ifndef CHESSBOT_MOTOR_CPP -#define CHESSBOT_MOTOR_CPP - -// Associated Header File -#include "robot/motor.h" - -// Built-In Libraries -#include "Arduino.h" - -// Custom Libraries -#include "utils/logging.h" -#include "utils/config.h" -#include "robot/pwm.h" - -// Sets up all the pins for the motors -void setupMotors() { - analogWriteResolution(12); - serialLogln("Setting Up Motors...", 2); - setupPWM(MOTOR_A_PIN1); - setupPWM(MOTOR_A_PIN2); - setupPWM(MOTOR_B_PIN1); - setupPWM(MOTOR_B_PIN2); - serialLogln("Motors Setup!", 2); -} - -// This will set how fast and what direction left motor will spin -// Value between [-1, 1] -// Negative is backwards, Positive is forwards -void setLeftPower(float power) { - // To spin the motor, you set one of the pins to 0, and the other to a PWM for speed. - // The pins you set to each determine the spin direction - if (power > 0) { - writePWM(MOTOR_A_PIN2, 0); - writePWM(MOTOR_A_PIN1, mapPowerToDuty(power)); - } else { - writePWM(MOTOR_A_PIN1, 0); - writePWM(MOTOR_A_PIN2, mapPowerToDuty(-power)); - } - - // Logs the power for debugging purposes - serialLog("Left Power: ", 4); - serialLogln(power, 4); -} - -// This will set how fast and what direction right motor will spin -// Value between [-1, 1] -// Negative is backwards, Positive is forwards -void setRightPower(float power) { - // To spin the motor, you set one of the pins to 0, and the other to a PWM for speed. - // The pins you set to each determine the spin direction - - // Invert power so sending (1,1) to drive results in robot moving forward - power *= -1; - if (power > 0) { - writePWM(MOTOR_B_PIN2, 0); - writePWM(MOTOR_B_PIN1, mapPowerToDuty(power)); - } else { - writePWM(MOTOR_B_PIN1, 0); - writePWM(MOTOR_B_PIN2, mapPowerToDuty(-power)); - } - - // Logs the power for debugging purposes - serialLog("Right Power: ", 4); - serialLogln(power, 4); -} - -#endif \ No newline at end of file diff --git a/src/robot/splines.cpp b/src/robot/splines.cpp index a7c17cd..c1fea2f 100644 --- a/src/robot/splines.cpp +++ b/src/robot/splines.cpp @@ -3,7 +3,7 @@ #include "robot/splines.h" #include "utils/logging.h" -#include "robot/control.h" +#include "robot/control/robot.h" #include "robot/trapezoidalProfile.h" #include "utils/timer.h" #include "wifi/connection.h" @@ -11,7 +11,6 @@ #include "utils/functions.h" #include #include -#include "robot/encoder.h" #include #include @@ -241,8 +240,8 @@ void customMotionProfileTimerFunction(MotionProfile &customProfileA, MotionProfi customProfileB.currentPosition = currentPositionEncoderB; customProfileB.currentVelocity = currentVelocityB; - float desiredVelocityLeft = updateTrapezoidalProfile(customProfileA, dt, 0); - float desiredVelocityRight = updateTrapezoidalProfile(customProfileB, dt, 0); + float desiredVelocityLeft = updateTrapezoidalProfile(customProfileA, dt); + float desiredVelocityRight = updateTrapezoidalProfile(customProfileB, dt); setXControl({VELOCITY, desiredVelocityLeft}); setYControl({VELOCITY, desiredVelocityRight}); diff --git a/src/robot/trapezoidalProfile.cpp b/src/robot/trapezoidalProfile.cpp index dbe3e84..8429398 100644 --- a/src/robot/trapezoidalProfile.cpp +++ b/src/robot/trapezoidalProfile.cpp @@ -11,7 +11,7 @@ using namespace std; -double updateTrapezoidalProfile(MotionProfile &profile, double dt, int8_t framesUntilPrint) { +double updateTrapezoidalProfile(MotionProfile &profile, double dt) { // distanceToGo = positive, you're still behind the target. || distanceToGo = negative, you're ahead. double distanceToGo = profile.targetPosition - profile.currentPosition; @@ -84,26 +84,23 @@ double updateTrapezoidalProfile(MotionProfile &profile, double dt, int8_t frames //use macros so that if we're not even logging, we won't even upload the code #if LOGGING_LEVEL >= 3 - if(framesUntilPrint == 0) - { - serialLog("Change in velocity was: ", 3); - serialLog(float(changeInVelocity), 3); - serialLog(", ", 3); - - serialLog("Motion profile is outputting: ", 3); - serialLog(float(profile.targetVelocity), 3); - serialLog(", ", 3); - - serialLog("Current Position: ", 3); - serialLog(float(profile.currentPosition), 3); - serialLog(", ", 3); - - serialLog("Target Position: ", 3); - serialLogln(float(profile.targetPosition), 3); - - // serialLog("Stopping position: ", 3); - // serialLogln(float(stoppingDistance), 3); - } + serialLog("Change in velocity was: ", 3); + serialLog(float(changeInVelocity), 3); + serialLog(", ", 3); + + serialLog("Motion profile is outputting: ", 3); + serialLog(float(profile.targetVelocity), 3); + serialLog(", ", 3); + + serialLog("Current Position: ", 3); + serialLog(float(profile.currentPosition), 3); + serialLog(", ", 3); + + serialLog("Target Position: ", 3); + serialLogln(float(profile.targetPosition), 3); + + // serialLog("Stopping position: ", 3); + // serialLogln(float(stoppingDistance), 3); #endif return profile.targetVelocity; diff --git a/src/robot/trapezoidalProfileNew.cpp b/src/robot/trapezoidalProfileNew.cpp index 8dae385..748764e 100644 --- a/src/robot/trapezoidalProfileNew.cpp +++ b/src/robot/trapezoidalProfileNew.cpp @@ -40,7 +40,7 @@ TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State &curre double dist = fabs(m_current.position - goalDir.position); double accelDist = (pow(m_constraints.maxVelocity,2) - pow(m_current.velocity,2)) / (2*m_constraints.maxAcceleration); //dist to/from max vel - double fastDist = dist - 2*accelDist; + //Unused double fastDist = dist - 2*accelDist; if(m_current.position < accelDist){ result.velocity += t * m_constraints.maxAcceleration; diff --git a/src/tests/tests.cpp b/src/tests/tests.cpp new file mode 100644 index 0000000..48ef3e5 --- /dev/null +++ b/src/tests/tests.cpp @@ -0,0 +1,20 @@ +// #include "config.h" + +// void do_tests() { +// if (DO_DRIVE_TEST) { +// startDriveTest(); +// } + +// delay(2000); + + +// if (DO_DRIVE_TICKS_TEST){ +// driveTicks(20000, "NULL"); +// } + +// delay(5000); + +// if (DO_HARDWARE_TEST) { +// startMotorAndEncoderTest(); +// } +// } diff --git a/src/utils/config.cpp b/src/utils/config.cpp index 6779e66..c841204 100644 --- a/src/utils/config.cpp +++ b/src/utils/config.cpp @@ -33,9 +33,11 @@ gpio_num_t PHOTODIODE_D_PIN = GPIO_NUM_6; gpio_num_t ONBOARD_LED_PIN = GPIO_NUM_15; gpio_num_t BATTERY_VOLTAGE_PIN = GPIO_NUM_10; +int BATTERY_VOLTAGE_OFFSET = 100; int TICKS_PER_ROTATION = 12000; float TRACK_WIDTH_INCHES = 8.29; +float TRACK_WIDTH_CM = TRACK_WIDTH_INCHES * 2.54; float WHEEL_DIAMETER_INCHES = 4.75; float THEORETICAL_MAX_VELOCITY_TPS = 52000; float THEORETICAL_MAX_ACCELERATION_TPSPS = 252000; diff --git a/src/utils/logging.cpp b/src/utils/logging.cpp index 56baaa0..c8d9370 100644 --- a/src/utils/logging.cpp +++ b/src/utils/logging.cpp @@ -1,6 +1,8 @@ #ifndef CHESSBOT_LOGGING_CPP #define CHESSBOT_LOGGING_CPP +#include + // Associated Header File #include "utils/logging.h" @@ -14,6 +16,29 @@ // Prints a value or message through Serial. (The console) // ln means it sends a new newline character +enum DebugLevel { + NONE, + INFO, + DEBUG, + TRACE, + RIDICULOUS, // Use if insane +}; + +void serial_printf(enum DebugLevel level, const char* fmt, ...) { + char buf[256]; + + if level > LOGGING_LEVEL { + return; + } + + va_list args; + va_start(args, fmt); + + vsnprintf(buf, sizeof(buf) fmt, args) + + Serial.print(buf) +} + void serialLog(const char *message, int serialLoggingLevel) { if (serialLoggingLevel <= LOGGING_LEVEL) diff --git a/src/wifi/connection.cpp b/src/wifi/connection.cpp index b2ced75..f681a0b 100644 --- a/src/wifi/connection.cpp +++ b/src/wifi/connection.cpp @@ -16,9 +16,9 @@ #include "utils/logging.h" #include "utils/timer.h" #include "utils/status.h" -#include "robot/control.h" +#include "robot/control/robot.h" -#include "../env.h" +#include "../../env.h" bool serverConnecting = false; bool pinging = false; @@ -78,7 +78,8 @@ void initiateHandshake() { // The buffer size is 500 characters. If there are issues right after // accepting a packet, the buffer size may be the culprit -void acceptData() { +JsonDocument acceptData() { + JsonDocument packet; if (client.available()) { // Allocates a buffer to hold the incoming packet char rawPacket[500]; @@ -87,7 +88,7 @@ void acceptData() { while (client.available() || !packetDone) { // Reads in a single character char data = client.read(); - if (data == ';') { + if (data == ';' || len > 499) { // If the delimiter character is encountered, the packet is done packetDone = true; } else { @@ -98,17 +99,16 @@ void acceptData() { } // The packet is in the form of a JSON. We use a library to handle them - JsonDocument packet; + // This turns the character buffer into a fully formed JSON object deserializeJson(packet, rawPacket); serialLog("Received Packet: ", 2); // This takes that JSON object and prints it to Serial (the console) for debugging purposes if (LOGGING_LEVEL >= 3) serializeJson(packet, Serial); serialLog("\n", 2); - - // Actually does something with the received packet - handlePacket(packet); } + + return packet; } // Sends a packet to the server @@ -144,7 +144,7 @@ void pingTimeout() { serialLogln((char*)" missed ping!", 2); if (missedPings >= PING_MAX_MISSES) { serialLogln((char*)"SERVER TIMED OUT!", 2); - stop(); + // TODO: stop(); pinging = false; } else { pingTimeoutTimer = timerDelay(PING_TIMEOUT, &pingTimeout); diff --git a/src/wifi/packet.cpp b/src/wifi/packet.cpp index e19f21f..277c2a8 100644 --- a/src/wifi/packet.cpp +++ b/src/wifi/packet.cpp @@ -16,9 +16,8 @@ #include "utils/status.h" #include "utils/functions.h" #include "utils/config.h" -#include "robot/control.h" +#include "robot/control/robot.h" #include "robot/splines.h" -#include "robot/battery.h" #include "wifi/connection.h" // These are the various different supported message types that can be sent over TCP @@ -42,7 +41,7 @@ const char* SPIN_RADIANS = "SPIN_RADIANS"; const char* BS_MOVE = "BS_MOVE"; // Takes a packet a does specific things based on the type -void handlePacket(JsonDocument packet) { +void handlePacket(Robot& r, JsonDocument packet) { // Sadly a switch case can't be used due to the packet type being a string. // We do this to allow the packets to be more readable when serialLogged if (packet["type"] == SERVER_HELLO) { @@ -51,36 +50,43 @@ void handlePacket(JsonDocument packet) { setConfig(packet["config"].as()); } else if (packet["type"] == DRIVE_TANK) { // This is received when the bot is being manually controlled via the debug page - drive(packet["left"], packet["right"], packet["packetId"]); + r.drive(packet["left"], packet["right"], packet["packetId"]); } else if (packet["type"] == DRIVE_TICKS){ - driveTicks(packet["tickDistance"], packet["packetId"]); + r.driveTicks(packet["tickDistance"], packet["packetId"]); } else if (packet["type"] == ESTOP) { - stop(); + r.stop(); } else if (packet["type"] == CUBIC) { - Point startPosition = {(float)packet["startPosition"]["x"]*TILES_TO_TICKS, (float)packet["startPosition"]["y"]*TILES_TO_TICKS}; - Point endPosition = {(float)packet["endPosition"]["x"]*TILES_TO_TICKS, (float)packet["endPosition"]["y"]*TILES_TO_TICKS}; - Point controlPositionA = {(float)packet["controlPositionA"]["x"]*TILES_TO_TICKS, (float)packet["controlPositionA"]["y"]*TILES_TO_TICKS}; - Point controlPositionB = {(float)packet["controlPositionB"]["x"]*TILES_TO_TICKS, (float)packet["controlPositionB"]["y"]*TILES_TO_TICKS}; - danceMonkeyCubic(packet["packetId"], startPosition, controlPositionA, controlPositionB, endPosition, packet["timeDeltaMs"]); + // Point startPosition = {(float)packet["startPosition"]["x"]*TILES_TO_TICKS, (float)packet["startPosition"]["y"]*TILES_TO_TICKS}; + // Point endPosition = {(float)packet["endPosition"]["x"]*TILES_TO_TICKS, (float)packet["endPosition"]["y"]*TILES_TO_TICKS}; + // Point controlPositionA = {(float)packet["controlPositionA"]["x"]*TILES_TO_TICKS, (float)packet["controlPositionA"]["y"]*TILES_TO_TICKS}; + // Point controlPositionB = {(float)packet["controlPositionB"]["x"]*TILES_TO_TICKS, (float)packet["controlPositionB"]["y"]*TILES_TO_TICKS}; + // danceMonkeyCubic(packet["packetId"], startPosition, controlPositionA, controlPositionB, endPosition, packet["timeDeltaMs"]); } else if (packet["type"] == QUADRATIC) { - serialLog("I have arrived!! at Quadratic", 3); - Point startPosition = {(float)packet["startPosition"]["x"]*TILES_TO_TICKS, (float)packet["startPosition"]["y"]*TILES_TO_TICKS}; - Point endPosition = {(float)packet["endPosition"]["x"]*TILES_TO_TICKS, (float)packet["endPosition"]["y"]*TILES_TO_TICKS}; - Point controlPosition = {(float)packet["controlPosition"]["x"]*TILES_TO_TICKS, (float)packet["controlPosition"]["y"]*TILES_TO_TICKS}; - danceMonkeyQuadratic(packet["packetId"], startPosition, controlPosition, endPosition, packet["timeDeltaMs"]); + // serialLog("I have arrived!! at Quadratic", 3); + // Point startPosition = {(float)packet["startPosition"]["x"]*TILES_TO_TICKS, (float)packet["startPosition"]["y"]*TILES_TO_TICKS}; + // Point endPosition = {(float)packet["endPosition"]["x"]*TILES_TO_TICKS, (float)packet["endPosition"]["y"]*TILES_TO_TICKS}; + // Point controlPosition = {(float)packet["controlPosition"]["x"]*TILES_TO_TICKS, (float)packet["controlPosition"]["y"]*TILES_TO_TICKS}; + // danceMonkeyQuadratic(packet["packetId"], startPosition, controlPosition, endPosition, packet["timeDeltaMs"]); } else if (packet["type"] == SPIN_RADIANS) { - serialLog("Going to spin!", 3); - int offsetTicks = radiansToTicks((float)packet["radians"]); - startCustomMotionProfileTimer(-offsetTicks, offsetTicks, (double)packet["timeDeltaMs"]/1000, packet["packetId"]); + // serialLog("Going to spin!", 3); + // int offsetTicks = radiansToTicks((float)packet["radians"]); + // startCustomMotionProfileTimer(-offsetTicks, offsetTicks, (double)packet["timeDeltaMs"]/1000, packet["packetId"]); } else if (packet["type"] == TURN_BY_ANGLE) { - turn(packet["deltaHeadingRadians"], packet["packetId"]); + r.turn(packet["deltaHeadingRadians"], packet["packetId"]); } else if (packet["type"] == DRIVE_TILES) { - drive(packet["tiles"], packet["packetId"]); + r.drive(packet["tiles"], packet["packetId"]); } else if (packet["type"] == PING_SEND) { sendPingResponse(); } } +enum ResponsePacketType { + Ping, + Hello, + Success, + Fail, +}; + // This creates the handshake packet sent to the server when this bot connects to it void constructHelloPacket(JsonDocument& packet) { packet["type"] = CLIENT_HELLO; @@ -107,7 +113,7 @@ void constructFailPacket(JsonDocument& packet, std::string messageId) { void constructPingPacket(JsonDocument& packet) { packet["type"] = PING_RESPONSE; - packet["batteryLevel"] = getBatteryLevel(); + packet["batteryLevel"] = Robot::batteryLevel(); } #endif \ No newline at end of file diff --git a/src/wifi/wireless.cpp b/src/wifi/wireless.cpp index 8f0c212..d1eff42 100644 --- a/src/wifi/wireless.cpp +++ b/src/wifi/wireless.cpp @@ -13,7 +13,7 @@ #include "utils/timer.h" #include "utils/status.h" #include "wifi/connection.h" -#include "../env.h" +#include "../../env.h" bool wifiConnecting = false; From 2b38667ed550ab92646e559401a6f5ec9eb52022 Mon Sep 17 00:00:00 2001 From: Siddharth Narayan Date: Wed, 1 Apr 2026 21:48:54 -0500 Subject: [PATCH 03/12] Further refactors - Changes were made for compilation success - Added geometry calculations for easier logic encapsulation - Refactor actual calculation code: centering, turning, and PID - Created MotionController class -- uses both PID and TrapezoidalProfile as used in previous controlLoop code. - Removed commented old code, was likely not usable - Remove old trapezoidalProfile code - Most of the PID stuff *should* be good to go - MotionController uses an updated PID strategy involving merging two distance/angle PID controllers - Finish PID aligning phase, fill in more centering steps, fill in old drive functions with new goal strategy --- include/robot/control/lights.h | 16 +- include/robot/control/motor.h | 25 +- include/robot/control/robot.h | 103 ++- include/robot/pidController.h | 6 +- include/robot/profiledPIDController.h | 2 +- include/robot/splines.h | 36 +- include/robot/trapezoidalProfile.h | 79 ++- include/robot/trapezoidalProfileNew.h | 64 -- include/utils/config.h | 2 + include/utils/geometry.h | 31 + include/utils/logging.h | 10 + platformio.ini | 2 + src/main.cpp | 47 +- src/robot/control/lights.cpp | 48 +- src/robot/control/motor.cpp | 61 +- src/robot/control/robot.cpp | 959 +++++--------------------- src/robot/pidController.cpp | 8 + src/robot/splines.cpp | 504 +++++++------- src/robot/trapezoidalProfile.cpp | 178 +++-- src/robot/trapezoidalProfileNew.cpp | 107 --- src/utils/config.cpp | 1 + src/utils/geometry.cpp | 67 ++ src/utils/logging.cpp | 21 +- src/wifi/packet.cpp | 4 +- 24 files changed, 910 insertions(+), 1471 deletions(-) delete mode 100644 include/robot/trapezoidalProfileNew.h create mode 100644 include/utils/geometry.h delete mode 100644 src/robot/trapezoidalProfileNew.cpp create mode 100644 src/utils/geometry.cpp diff --git a/include/robot/control/lights.h b/include/robot/control/lights.h index 23f792e..7cec383 100644 --- a/include/robot/control/lights.h +++ b/include/robot/control/lights.h @@ -6,13 +6,23 @@ class Light { public: + Light(gpio_num_t pin); + void tick(); - short value(); + + short raw_value(); + bool value(); + bool held_value(); + void reset(); + + bool changed_this_tick(); unsigned long last_changed_time(); private: - int pin; - short _value; + gpio_num_t pin; + short _raw_value; + bool _held_value; + bool _changed_this_tick; unsigned long _last_changed_time; }; diff --git a/include/robot/control/motor.h b/include/robot/control/motor.h index 54ef708..d09fb67 100644 --- a/include/robot/control/motor.h +++ b/include/robot/control/motor.h @@ -1,35 +1,42 @@ #ifndef CHESSBOT_MOTOR_H #define CHESSBOT_MOTOR_H -#include "config.h" +#include + +#include "utils/config.h" #include "Encoder.h" -//just measured, its 5.9 centimeters, or .059 meters -const float TIRE_RADIUS = 0.059; -//circumference equals pi * diameter. In meters +const float TIRE_RADIUS = 5.9; const float TIRE_CIRCUMFERENCE = M_PI * 2 * TIRE_RADIUS; class Motor { public: - Motor(int pin_a, int pin_b); + Motor(bool inverted, int motor_pin_a, int motor_pin_b, uint8_t enc_pin_a, uint8_t enc_pin_b); void tick(); // Sets the motor power // power is a float between [-1, 1] + float power(); void power(float power); void encoder_reset(); - // The distance of the tire in cm - float dist(); + double dist(); // Total distance in cm + double tick_dist(); // Distance this tick in cm + int32_t raw_dist(); // Read the raw encoder value in ticks private: int pin_a; int pin_b; + bool inverted; + + float _power; + + int32_t raw_enc_value; + int32_t prev_raw_enc_value; Encoder encoder; - // The raw encoder value - float dist_raw(); + }; diff --git a/include/robot/control/robot.h b/include/robot/control/robot.h index b0e45bc..d153913 100644 --- a/include/robot/control/robot.h +++ b/include/robot/control/robot.h @@ -3,9 +3,11 @@ #include "Arduino.h" #include "utils/config.h" +#include "utils/geometry.h" #include "robot/trapezoidalProfile.h" #include "robot/control/lights.h" #include "robot/control/motor.h" +#include "robot/pidController.h" enum OperatingMode { @@ -29,30 +31,41 @@ enum CenteringStatus { // The robot has started centering STARTED, - // The robot has finished centering along axis 1, and is moving to an edge - EDGE, + // Has hit the first edge, and is now aligning to it + ALIGNING_EDGE_1, - // The robot is moving by itself - MOVING -}; + ALIGNED_EDGE_1, -struct ControlSetting -{ - OperatingMode mode; - float value; + CENTERED_Y_AXIS, + + ALIGNED_EDGE_2, }; -// Unused? -// static ControlSetting leftMotorControl; -// static ControlSetting rightMotorControl; -// static double headingTarget = 0.0; +class MotionController { + public: + enum MotionPhase { + // Traveling to the destination + TRAVELLING, -void setXControl(ControlSetting control); -void setYControl(ControlSetting control); -void setHeadingTarget(double target); -ControlSetting getLeftMotorControl(); -ControlSetting getRightMotorControl(); -double getHeadingTarget(); + // Aligning to the correct rotation + ALIGNING + }; + + MotionController(); + + void set_goal(Coordinate2D goal_destination, double goal_angle); + std::tuple update_speeds(Coordinate2D position, double angle, double dt); + void print_status(); + void reset(); + private: + PIDController DistVelocityController; + PIDController AVelocityController; + + MotionPhase phase; + + double goal_angle; + Coordinate2D goal_position; +}; class Robot { public: @@ -61,60 +74,42 @@ class Robot { static int batteryLevel(); // Runs all the necessary processing for each tick of the global event loop - void tick(); + void tick(unsigned long frame, uint32_t delay); void center(); void drive(float tiles, std::string id); - void drive(float leftPower, float rightPower, std::string id); + void drive(Coordinate2D goal_pos, double goal_angle); + void drive(std::tuple& powers, std::string id); void driveTicks(int tickDistance, std::string id); enum DriveStatus driveUntilNewTile(); void turn(float angleRadians, std::string id); void stop(); + + void test(); private: + // Components Motor left; Motor right; - Light left_light; - Light right_light; + Light front_left_light; + Light front_right_light; + Light back_left_light; + Light back_right_light; - boolean stopped; + // State + double rotation; + Coordinate2D position; + MotionController motion_controller; CenteringStatus centeringStatus; - - MotionProfile profileX = {THEORETICAL_MAX_VELOCITY_TPS, THEORETICAL_MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity - MotionProfile profileY = {THEORETICAL_MAX_VELOCITY_TPS, THEORETICAL_MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity - MotionProfile profileA = {THEORETICAL_MAX_VELOCITY_TPS, THEORETICAL_MAX_ACCELERATION_TPSPS, 0, 0, 0, 0, 75.0}; // maxVelocity, maxAcceleration, currentPosition, currentVelocity, targetPosition, targetVelocity - void center_tick(); - void turn_tick(); - void pid_tick(); - // void setLeftPower(leftPower); - // void setRightPower(rightPower); + void center_tick(uint32_t delay); + void pid_tick(uint32_t delay); + void print_status(); }; -void setupBot(); - -void sendPacketOnPidComplete(std::string id); -void readLight(int loopDelayMs); -bool checkMoveFinished(); -void startCentering(); -bool checkIfCanUpdateMovement(); -void resetSpeed(); -void createDriveUntilNewTile(); -void determineNextChoice(); -uint8_t driveUntilNewTile(); -boolean isRobotPidAtTarget(); -void updateCritRange(); -void controlLoop(int loopDelayMs); -void updateCentering(); -void updateToNextDistance(); - -void startDriveTest(); -void driveTestOff(); -void startMotorAndEncoderTest(); - #endif \ No newline at end of file diff --git a/include/robot/pidController.h b/include/robot/pidController.h index 85f7a6c..92ce073 100644 --- a/include/robot/pidController.h +++ b/include/robot/pidController.h @@ -5,8 +5,7 @@ class PIDController { public: // PIDController(double kp, double ki, double kd, double min, double max); - PIDController(double kp, double ki, double kd, double min, double max, double errorTolerance) - : kp(kp), ki(ki), kd(kd), minOutput(min), maxOutput(max), errorTolerance(errorTolerance), prev_error(0), integral(0) {} + PIDController(double kp, double ki, double kd, double min, double max, double errorTolerance); double Compute(double setpoint, double actual_value, double dt); void Reset(); @@ -15,8 +14,9 @@ class PIDController double minOutput, maxOutput; // Output limits double prev_error, prev_velocity_error; // Previous error - double integral; // Integral accumulator double errorTolerance; // Allowed error before returning 0 + double integral; // Integral accumulator + protected: virtual double getError(double setpoint, double actual_value) { return setpoint - actual_value; } }; diff --git a/include/robot/profiledPIDController.h b/include/robot/profiledPIDController.h index b2a978d..e11cd0b 100644 --- a/include/robot/profiledPIDController.h +++ b/include/robot/profiledPIDController.h @@ -2,7 +2,7 @@ #define PROFILED_PID_CONTROLLER_H #include "robot/pidController.h" -#include "robot/trapezoidalProfileNew.h" +#include "robot/trapezoidalProfile.h" class ProfiledPIDController { public: diff --git a/include/robot/splines.h b/include/robot/splines.h index 67d5960..8cc6cd7 100644 --- a/include/robot/splines.h +++ b/include/robot/splines.h @@ -1,23 +1,23 @@ -#ifndef CHESSBOT_SPLINES_H -#define CHESSBOT_SPLINES_H +// #ifndef CHESSBOT_SPLINES_H +// #define CHESSBOT_SPLINES_H -#include -#include -#include -#include "wifi/packet.h" -#include "trapezoidalProfile.h" +// #include +// #include +// #include +// #include "wifi/packet.h" +// #include "trapezoidalProfile.h" -struct Point { - float x; - float y; -}; +// struct Point { +// float x; +// float y; +// }; -static std::queue> timeSlicesToExecute; +// static std::queue> timeSlicesToExecute; -void velocityUpdateTimerFunction(std::string id); -void danceMonkeyQuadratic(std::string id, Point start, Point control, Point end, float totalTime); -void danceMonkeyCubic(std::string id, Point start, Point control1, Point control2, Point end, float totalTime); -void startCustomMotionProfileTimer(int leftPositionTarget, int rightPositionTarget, double profileDuration, std::string id); -void customMotionProfileTimerFunction(MotionProfile &customProfileA, MotionProfile &customProfileB, double dt, std::string id); +// void velocityUpdateTimerFunction(std::string id); +// void danceMonkeyQuadratic(std::string id, Point start, Point control, Point end, float totalTime); +// void danceMonkeyCubic(std::string id, Point start, Point control1, Point control2, Point end, float totalTime); +// void startCustomMotionProfileTimer(int leftPositionTarget, int rightPositionTarget, double profileDuration, std::string id); +// void customMotionProfileTimerFunction(MotionProfile &customProfileA, MotionProfile &customProfileB, double dt, std::string id); -#endif \ No newline at end of file +// #endif \ No newline at end of file diff --git a/include/robot/trapezoidalProfile.h b/include/robot/trapezoidalProfile.h index 6e81dfd..41da6ff 100644 --- a/include/robot/trapezoidalProfile.h +++ b/include/robot/trapezoidalProfile.h @@ -1,23 +1,64 @@ -#ifndef CHESSBOT_TRAPEZOIDAL_PROFILE_H -#define CHESSBOT_TRAPEZOIDAL_PROFILE_H - -#include - -struct MotionProfile { - double maxVelocity; - double maxAcceleration; - double currentPosition; - double currentVelocity; - double targetPosition; - double targetVelocity; - double criticalRange; -}; +#ifndef TRAPEZOIDAL_PROFILE_NEW_H +#define TRAPEZOIDAL_PROFILE_NEW_H + +#include +#include + +class TrapezoidProfile +{ +public: + struct Constraints + { + double maxVelocity; + double maxAcceleration; + + Constraints(double maxVelocity, double maxAcceleration) + { + if (maxVelocity < 0.0 || maxAcceleration < 0.0) + { + throw std::runtime_error("Constraints must be non-negative"); + } + this->maxVelocity = maxVelocity; + this->maxAcceleration = maxAcceleration; + // Remove MathSharedStore.reportUsage for now (Java-specific) + } + }; + + struct State + { + double position = 0.0; + double velocity = 0.0; + + State() = default; + State(double position, double velocity) + : position(position), velocity(velocity) {} -double updateTrapezoidalProfile(MotionProfile &profile, double dt); + bool operator==(const State& rhs) const + { + // Don't use equals for floats? + return position == rhs.position && velocity == rhs.velocity; + } + }; -template -T clamp(T value, T minValue, T maxValue) { - return (value < minValue) ? minValue : (value > maxValue) ? maxValue : value; -} + TrapezoidProfile(const Constraints& constraints) + : m_constraints(constraints) {} + + State calculate(double t, const State& current, const State& goal); + + // bool isFinished(double t) const { return t >= totalTime(); } + +private: + static bool shouldFlipAcceleration(const State& initial, const State& goal) + { + return initial.position > goal.position; + } + + State direct(const State& in, int m_direction) const + { + return State(in.position * m_direction, in.velocity * m_direction); + } + + Constraints m_constraints; +}; #endif \ No newline at end of file diff --git a/include/robot/trapezoidalProfileNew.h b/include/robot/trapezoidalProfileNew.h deleted file mode 100644 index 41da6ff..0000000 --- a/include/robot/trapezoidalProfileNew.h +++ /dev/null @@ -1,64 +0,0 @@ -#ifndef TRAPEZOIDAL_PROFILE_NEW_H -#define TRAPEZOIDAL_PROFILE_NEW_H - -#include -#include - -class TrapezoidProfile -{ -public: - struct Constraints - { - double maxVelocity; - double maxAcceleration; - - Constraints(double maxVelocity, double maxAcceleration) - { - if (maxVelocity < 0.0 || maxAcceleration < 0.0) - { - throw std::runtime_error("Constraints must be non-negative"); - } - this->maxVelocity = maxVelocity; - this->maxAcceleration = maxAcceleration; - // Remove MathSharedStore.reportUsage for now (Java-specific) - } - }; - - struct State - { - double position = 0.0; - double velocity = 0.0; - - State() = default; - State(double position, double velocity) - : position(position), velocity(velocity) {} - - bool operator==(const State& rhs) const - { - // Don't use equals for floats? - return position == rhs.position && velocity == rhs.velocity; - } - }; - - TrapezoidProfile(const Constraints& constraints) - : m_constraints(constraints) {} - - State calculate(double t, const State& current, const State& goal); - - // bool isFinished(double t) const { return t >= totalTime(); } - -private: - static bool shouldFlipAcceleration(const State& initial, const State& goal) - { - return initial.position > goal.position; - } - - State direct(const State& in, int m_direction) const - { - return State(in.position * m_direction, in.velocity * m_direction); - } - - Constraints m_constraints; -}; - -#endif \ No newline at end of file diff --git a/include/utils/config.h b/include/utils/config.h index aff232a..86f932e 100644 --- a/include/utils/config.h +++ b/include/utils/config.h @@ -35,7 +35,9 @@ extern gpio_num_t ONBOARD_LED_PIN; extern int TICKS_PER_ROTATION; extern float TRACK_WIDTH_INCHES; +extern float TRACK_WIDTH_CM; extern float WHEEL_DIAMETER_INCHES; +extern float WHEEL_RADIUS_CM; extern float THEORETICAL_MAX_VELOCITY_TPS; extern float VELOCITY_LIMIT_TPS; extern float THEORETICAL_MAX_ACCELERATION_TPSPS; diff --git a/include/utils/geometry.h b/include/utils/geometry.h new file mode 100644 index 0000000..1217a29 --- /dev/null +++ b/include/utils/geometry.h @@ -0,0 +1,31 @@ +#pragma once + +class Coordinate2D { + public: + double x; + double y; + + Coordinate2D(); + + // Unit vector from angle + Coordinate2D(double angle); + Coordinate2D(double x, double y); + + // Transform (same as addition) + Coordinate2D transform(Coordinate2D offset) const; + + // Transform with polar coordinate + Coordinate2D transform(double theta, double distance) const; + + // Rotate around origin + Coordinate2D rotate(double theta) const; + // Scale (same as multiplication) + Coordinate2D scale(double theta) const; + + double distance_to(const Coordinate2D destination) const; + double angle_to(const Coordinate2D destination) const; + Coordinate2D vector_to(const Coordinate2D destination) const; + + double dot_product(const Coordinate2D other) const; + bool is_behind(double radians, Coordinate2D other) const; +}; \ No newline at end of file diff --git a/include/utils/logging.h b/include/utils/logging.h index 41ebcd7..2de56ae 100644 --- a/include/utils/logging.h +++ b/include/utils/logging.h @@ -4,6 +4,14 @@ // Built-In Libraries #include +enum DebugLevel { + NONE, + INFO, + DEBUG, + TRACE, + RIDICULOUS, // Use if insane +}; + void serialLog(const char *message, int serialLoggingLevel); void serialLog(int value, int serialLoggingLevel); void serialLog(double value, int serialLoggingLevel); @@ -17,4 +25,6 @@ void serialLogln(std::string value, int serialLoggingLevel); void serialLogError(char message[], int error); +void serial_printf(enum DebugLevel level, const char* fmt, ...); +void serial_clear(); #endif \ No newline at end of file diff --git a/platformio.ini b/platformio.ini index a05010e..f49fb9e 100644 --- a/platformio.ini +++ b/platformio.ini @@ -14,8 +14,10 @@ board = lolin_s2_mini framework = arduino monitor_speed = 115200 build_flags = + -O3 -Wall -Wextra lib_deps = bblanchon/ArduinoJson@^7.2.0 paulstoffregen/Encoder@^1.4.4 +monitor_raw = yes \ No newline at end of file diff --git a/src/main.cpp b/src/main.cpp index 2bf62ee..b66b085 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -1,9 +1,4 @@ -// Sets file name into memory (usually to avoid duplicate imports) -#ifndef CHESSBOT_MAIN_CPP -#define CHESSBOT_MAIN_CPP - -// Built-In Libraries -#include +#include "Arduino.h" // Custom Libraries #include "utils/config.h" @@ -17,8 +12,8 @@ #include "robot/pidController.h" #include "robot/control/magnet.h" -//alright SCREW YOU serial monitor i won't print every frame then if you wanna play that game -const int8_t PRINT_INTERVAL = 60; +void loop_test(); + unsigned long frame = 0; unsigned long previousTime = 0; // For loop timing @@ -32,15 +27,12 @@ void setup() { delay(STARTUP_DELAY); serialLogln("Finished Delay!", 2); - // Any setup needed to get bot ready - setupBot(); - // Create a WiFi network for the laptop to connect to if (!RUN_OFFLINE) connectWiFI(); - - previousTime = millis() - loopDelayMilliseconds; + + // robot.center(); } // After setup gets run, loop is run over and over as fast ass possible @@ -64,14 +56,29 @@ void loop() { unsigned long deltaTime = millis() - previousTime; previousTime = millis(); - controlLoop(deltaTime); - - // This delay determines how often the code in loop is run - // (Forcefully pauses the thread for about the amount of milliseconds passed in) - delay(loopDelayMilliseconds); + loop_test(); + robot.tick(frame, (uint32_t)deltaTime); frame++; } -// This is used at the end of each file due to the name definition at the beginning -#endif +void loop_test() { + unsigned long time_seconds = millis() / 1000; + + Coordinate2D goal; + double rotation = 0; + + if (time_seconds > 10) { + goal = Coordinate2D(100, 100); + } + + if (time_seconds > 20) { + goal = Coordinate2D(0, 0); + } + + if (time_seconds > 30) { + goal = Coordinate2D(500, 200); + } + + robot.drive(goal, rotation); +} \ No newline at end of file diff --git a/src/robot/control/lights.cpp b/src/robot/control/lights.cpp index ad0a7f3..2399fc8 100644 --- a/src/robot/control/lights.cpp +++ b/src/robot/control/lights.cpp @@ -12,18 +12,46 @@ #include "utils/logging.h" #include "utils/config.h" +static short LIGHT_RAW_VALUE_CUTOFF = 7600; +bool is_light_value_on(short value) { + return value < LIGHT_RAW_VALUE_CUTOFF; +} + +Light::Light(gpio_num_t _pin) { + pin = _pin; +} + void Light::tick() { - short prev = _value; + short prev = _raw_value; - _value = analogRead(pin); + _changed_this_tick = false; + _raw_value = analogRead(pin); + _held_value = _held_value || is_light_value_on(_raw_value); - if (prev != _value) { + if (prev != _raw_value) { + _changed_this_tick = true; _last_changed_time = millis(); } } -short Light::value() { - return _value; +short Light::raw_value() { + return _raw_value; +} + +bool Light::value() { + return is_light_value_on(_raw_value); +} + +bool Light::held_value() { + return _held_value; +} + +void Light::reset() { + _held_value = false; +} + +bool Light::changed_this_tick() { + return _changed_this_tick; } unsigned long Light::last_changed_time() { @@ -52,12 +80,12 @@ void activateIR() { // Turns off the IR Blaster void deactivateIR() { - if (!IR_activated) { - return; - } + // if (!IR_activated) { + // return; + // } - digitalWrite(RELAY_IR_LED_PIN, LOW); - IR_activated = false; + // digitalWrite(RELAY_IR_LED_PIN, LOW); + // IR_activated = false; } #endif \ No newline at end of file diff --git a/src/robot/control/motor.cpp b/src/robot/control/motor.cpp index 2c5601c..13c1d64 100644 --- a/src/robot/control/motor.cpp +++ b/src/robot/control/motor.cpp @@ -12,46 +12,77 @@ #include "utils/config.h" #include "utils/logging.h" -Motor::Motor(int motor_pin_a, int motor_pin_b, int enc_pin_a, int enc_pin_b) { - pin_a = _pin_a; - pin_b = _pin_b; +Motor::Motor(bool _inverted, int motor_pin_a, int motor_pin_b, uint8_t enc_pin_a, uint8_t enc_pin_b) + : inverted(_inverted), encoder(enc_pin_a, enc_pin_b) + { + pin_a = motor_pin_a; + pin_b = motor_pin_b; setupPWM(pin_a); setupPWM(pin_b); - - encoder(enc_pin_a, enc_pin_b); } void Motor::tick() { // Read from encoder and save its previous value + prev_raw_enc_value = raw_enc_value; + raw_enc_value = raw_dist(); +} + +// Returns the current power of the motor +float Motor::power() { + if (inverted) { + return -_power; + } + + return _power; } // This will set how fast and what direction left motor will spin // Value between [-1, 1] // Negative is backwards, Positive is forwards -void Motor::power(float power) { - if (power > 0) { - writePWM(MOTOR_A_PIN2, 0); - writePWM(MOTOR_A_PIN1, mapPowerToDuty(power)); +void Motor::power(float __power) { + if (inverted) { + __power = -__power; + } + + _power = __power; + + if (abs(_power) < MIN_MOTOR_POWER) { + _power = 0; + } + + + if (_power > 0) { + writePWM(pin_b, 0); + writePWM(pin_a, mapPowerToDuty(_power)); } else { - writePWM(MOTOR_A_PIN1, 0); - writePWM(MOTOR_A_PIN2, mapPowerToDuty(-power)); + writePWM(pin_a, 0); + writePWM(pin_b, mapPowerToDuty(-_power)); } serialLog("Motor Power: ", 4); - serialLogln(power, 4); + serialLogln(_power, 4); } void Motor::encoder_reset() { encoder.readAndReset(); } -float Motor::dist_raw() { +int32_t Motor::raw_dist() { + if (inverted) { + return -encoder.read(); + } + return encoder.read(); } -float Motor::dist() { - return dist_raw() * TIRE_CIRCUMFERENCE; +double Motor::dist() { + return ((double)raw_enc_value / TICKS_PER_ROTATION) * TIRE_CIRCUMFERENCE; +} + +double Motor::tick_dist() { + int32_t dist = raw_enc_value - prev_raw_enc_value; + return ((double)dist / TICKS_PER_ROTATION) * TIRE_CIRCUMFERENCE; } #endif \ No newline at end of file diff --git a/src/robot/control/robot.cpp b/src/robot/control/robot.cpp index 0e71a0b..726686f 100644 --- a/src/robot/control/robot.cpp +++ b/src/robot/control/robot.cpp @@ -1,17 +1,17 @@ -#ifndef CHESSBOT_CONTROL_CPP -#define CHESSBOT_CONTROL_CPP - // Associated Header File #include "robot/control/robot.h" // Built-In Libraries #include "Arduino.h" #include +#include // Custom Libraries #include "utils/logging.h" #include "utils/timer.h" #include "utils/config.h" +#include "utils/logging.h" +#include "utils/geometry.h" #include "utils/status.h" #include "robot/control/motor.h" #include "robot/control/lights.h" @@ -22,853 +22,228 @@ #include #include "utils/functions.h" -#include "robot/profiledPIDController.h" -#include "robot/trapezoidalProfileNew.h" - -// pid constants -TrapezoidProfile::Constraints profileConstraints(VELOCITY_LIMIT_TPS, ACCELERATION_LIMIT_TPSPS); -TrapezoidProfile xProfile(profileConstraints); -TrapezoidProfile yProfile(profileConstraints); -TrapezoidProfile aProfile(profileConstraints); -TrapezoidProfile::State xSetpoint, ySetpoint, aSetpoint; -PIDController XVelocityController(0.000009, 0.000035, 0.000000000001, -1, +1, 10); -PIDController YVelocityController(0.0000005, 0.000035, 0.000000000001, -1, +1, 10); -PIDController AVelocityController(0.000012, 0.00000, 0.0000000000000, -1, +1, 10); //angular velocity used for turns -ContinuousPIDController headingController(0.21, 0.000001, 0.000000000001, -1, +1, 0.1, -180, 180); // input degrees, output duty cycle - -//put this in manually for each bot. Dist between the two front encoders, or the two back encoders. In meters. -const float lightDist = 0.07; -//multiply any ticks by this ratio to get distance in meters -const float TICK_TO_METERS = TIRE_CIRCUMFERENCE / TICKS_PER_ROTATION; - -// const uint8_t Top_Left_Encoder_Index = 0; -// const uint8_t Top_Right_Encoder_Index = 1; -// const uint8_t Bottom_Left_Encoder_Index = 2; -// const uint8_t Bottom_Right_Encoder_Index = 3; - -// boolean testEncoderPID_value = false; - -// //determines the encoder values the iteration right before -// int prevPositionL = 0; -// int prevPositionR = 0; -// int timeMs = 0; - -// //robot rotation in radians -// double prevRotation = 0; +MotionController::MotionController() + : DistVelocityController(0.5, 0.01, 0.15, -1, +1, 0.0), + AVelocityController(0.5, 0.1, 0.15, -1, +1, 0.0) +{} -// //calculated previous X and Y values -// double prevX = 0; -// double prevY = 0; - -// bool runningPID = false; -// bool runningTurn = false; -// double average[50]; - -// //when moving to a different target, this is the encoder position we started from -// int startEncoderAPos = -1; -// int startEncoderBPos = -1; - -// //the encoder distance to about halfway through the tile -// int encoderAHalfwayDist = 0; -// int encoderBHalfwayDist = 0; - -// //when we receive a command from the website to center, set this from false to true, -// //then when the code sets it back to false, that's when we know we're done centering -// bool isCentering = false; - -// //holds the current status representing the progress in centering. The different values -// //are defined below -// char centeringStatus = 'S'; +void MotionController::set_goal(Coordinate2D _goal_destination, double _goal_angle) { + goal_angle = _goal_angle; + goal_position = _goal_destination; +} -// //measures if the forward encoders are aligning on the edge or the back encoders -// bool forwardAligning = true; +std::tuple MotionController::update_speeds(Coordinate2D position, double angle, double dt) { + double dist_err = position.distance_to(goal_position); -// //set this true when our robot is on an edge and is moving to the center from its given measured distance -// bool movingCenter = false; + // So that the robot will not back up from a point in front of it infinitely + bool is_behind = position.is_behind(angle, goal_position); + if (!is_behind) { + dist_err = -dist_err; + } + + if (abs(dist_err) < 1) { + if (phase == TRAVELLING) { + DistVelocityController.Reset(); + AVelocityController.Reset(); + } -// //set this true when our robot is turning to align itself on the next axis -// bool turningToNextAxis = false; + phase = ALIGNING; -// //initially 0, once 2 means both axises aligned so we done -// uint8_t axisesAligned = 0; + double angular_vel = AVelocityController.Compute(goal_angle, angle, dt); -// float angle = 0; -// unsigned long timeSinceTurn = 0; + return std::make_tuple(-angular_vel, angular_vel); + } else { + if (phase == ALIGNING) { + DistVelocityController.Reset(); + AVelocityController.Reset(); + } -// //the value of the encoder we're measuring in terms of its light value -// bool firstEncoderVal = false; -// bool secondEncoderVal = false; + phase = TRAVELLING; -// //represents which index is being referenced for the current encoders -// uint8_t firstEncoderIndex = 0; -// uint8_t secondEncoderIndex = 0; + double temp_goal_angle = position.angle_to(goal_position); -// //Here are the possible values: -// //0 = no encoder leading. -// //1 = left encoder leading. -// //2 = right encoder leading -// uint8_t leadingEncoder = 0; + double vel = DistVelocityController.Compute(0, dist_err, dt); + double angular_vel = AVelocityController.Compute(temp_goal_angle, angle, dt); -// //previous encoder distance, specifically the one that is lagging behind -// float backPrevDistance = 0; + // https://aleksandarhaber.com/tutorial-on-simple-position-controller-for-differential-drive-robot-with-simulation-and-animation-in-python/ + double left_speed = (vel / WHEEL_RADIUS_CM) - ((TRACK_WIDTH_CM * angular_vel) / (2 * WHEEL_RADIUS_CM)); + double right_speed = (vel / WHEEL_RADIUS_CM) + ((TRACK_WIDTH_CM * angular_vel) / (2 * WHEEL_RADIUS_CM)); -// //checks if the given encoders have changed tiles yet. -// bool leftEncoderChange = false; -// bool rightEncoderChange = false; + return std::make_tuple(left_speed, right_speed); + }; +} -// //determines basically what tile each encoder is one. false is one tile, true is the opposite tile. -// //it could be false = white and true = black, or false = black and white = true, doesn't really matter -// bool onFirstTile[4] = {false, false, false, false}; +void MotionController::print_status() { + serial_printf(DebugLevel::NONE, "MotionController status: %d -- goal_position: (%f, %f), goal_angle: %f\n", phase, goal_position.x, goal_position.y, goal_angle); +} -// bool waitingForLight = false; +void MotionController::reset() { + DistVelocityController.Reset(); + AVelocityController.Reset(); +} -Robot::Robot() { +Robot::Robot() + : left(false, MOTOR_A_PIN1, MOTOR_A_PIN2, ENCODER_A_PIN1, ENCODER_A_PIN2), + right(true, MOTOR_B_PIN1, MOTOR_B_PIN2, ENCODER_B_PIN1, ENCODER_B_PIN2), + + front_left_light(PHOTODIODE_A_PIN), + front_right_light(PHOTODIODE_B_PIN), + back_left_light(PHOTODIODE_C_PIN), + back_right_light(PHOTODIODE_D_PIN) +{} + +void Robot::print_status() { + serial_clear(); + activateIR(); + serial_printf( + DebugLevel::INFO, + "position: (%fcm, %fcm) rotation: %frad \n" + "Centering status: %d\n\n" + + "left power: %f right power: %f \n" + "left wheel: %fcm right wheel: %fcm\n" + "left enc raw: %d right enc raw %d\n\n" + + "front lights -- left: %hd discrete %d right: %hd discrete %d\n" + "back lights -- left: %hd discrete %d right: %hd discrete %d\n\n", + + position.x, position.y, rotation, + centeringStatus, + + left.power(), right.power(), + left.dist(), right.dist(), + left.raw_dist(), right.raw_dist(), + - } + front_left_light.raw_value(), front_left_light.value(), front_right_light.raw_value(), front_right_light.value(), + back_left_light.raw_value(), back_left_light.value(), back_right_light.raw_value(), back_right_light.value() + ); -int Robot::batteryLevel() { - return analogRead(BATTERY_VOLTAGE_PIN) - BATTERY_VOLTAGE_OFFSET; - } + motion_controller.print_status(); -void Robot::tick() { - center_tick(); - pid_tick(); - turn_tick(); } -void Robot::pid_tick() { - double lDist = (double)(readLeftEncoder()-prevPositionL)/TICKS_PER_ROTATION*2*PI; - double rDist = (double)(readRightEncoder()-prevPositionR)/TICKS_PER_ROTATION*2*PI; - - prevPositionL = readLeftEncoder(); - prevPositionR = readRightEncoder(); - - double angleDist = (rDist - lDist)*TIRE_RADIUS/trackWidth; - - double currentRot = prevRotation + angleDist; - - double currentX; - double deltaX; - double currentY; - double deltaY; - if(angleDist != 0){ - double temp = (trackWidth*(rDist+lDist))/(2*(rDist-lDist)); - deltaX = temp * (sin(currentRot) - sin(prevRotation)); - deltaY = temp * (cos(prevRotation) - cos(currentRot)); - currentX = prevX + deltaX; - currentY = prevY + deltaY; - - } else { - double totalDist = TIRE_RADIUS*(lDist + rDist)/2; - deltaX = totalDist * cos(currentRot); - deltaY = totalDist * sin(currentRot); - currentX = prevX + deltaX; - currentY = prevY + deltaY; - } - prevX = currentX; - prevY = currentY; - prevRotation = currentRot; - - double loopDelaySeconds = ((double) timeMs) / 1000; - profileX.currentPosition = currentX / TICK_TO_METERS; - profileX.currentVelocity = deltaX==0?0:deltaX / TICK_TO_METERS /loopDelaySeconds; - xSetpoint = xProfile.calculate(loopDelaySeconds, - TrapezoidProfile::State(profileX.currentPosition, profileX.currentVelocity), - TrapezoidProfile::State(getLeftMotorControl().value, 0.0)); - - double velocity = XVelocityController.Compute(xSetpoint.velocity, profileX.currentVelocity, loopDelaySeconds); - double aVel = headingController.Compute(0, currentRot*RAD_TO_DEG, loopDelaySeconds); - - profileY.currentPosition = currentY / TICK_TO_METERS; - profileY.currentVelocity = deltaY==0?0:deltaY / TICK_TO_METERS /loopDelaySeconds; - ySetpoint = yProfile.calculate(loopDelayMs/1000, - TrapezoidProfile::State(profileY.currentPosition, profileY.currentVelocity), - TrapezoidProfile::State(getRightMotorControl().value, 0.0)); - double yVel = YVelocityController.Compute(ySetpoint.velocity, profileY.currentVelocity, loopDelaySeconds); - - aVel += yVel; - - double lMotorPower = fmap((velocity-8*aVel*trackWidth/2)/TIRE_RADIUS, -25, 25, -1, 1); - double rMotorPower = fmap((velocity+8*aVel*trackWidth/2)/TIRE_RADIUS, -25, 25, -1, 1); - - if (fabs(lMotorPower) < MIN_MOTOR_POWER) lMotorPower = 0; - if (fabs(rMotorPower) < MIN_MOTOR_POWER) rMotorPower = 0; - - - serial_printf( - DebugLevel::DEBUG, - "vel %f yvel %f avel %f lpower %f rpower %f xpos %f ypos %f\n", - velocity, - yVel, - aVel, - lMotorPower, - rMotorPower, - currentX, - currentY - ); - - setLeftPower(lMotorPower); - setRightPower(rMotorPower); - - double sum = 0; - for(int x = 49; x >= 0; x--) { - average[x+1] = average[x]; - sum += fabs(average[x+1]); - } - average[0] = lMotorPower; - sum += fabs(average[0]); - timeMs += loopDelayMs; - if (sum/50 < 0.01){ - serialLogln(sum/50,3); - serialLogln(runningPID,3); - runningPID = false; - setLeftPower(0); - setRightPower(0); - - sendActionSuccess("move done"); - resetPID(); - - } else { - runningPID = true; - } +int Robot::batteryLevel() { + return analogRead(BATTERY_VOLTAGE_PIN) - BATTERY_VOLTAGE_OFFSET; } -void Robot::turn_tick() { - double lDist = left.dist(); - double rDist = right.dist(); +void Robot::tick(unsigned long frame, uint32_t delay) { + // Pass through tick, update all sensors / motors + left.tick(); + right.tick(); - prevPositionL = readLeftEncoder(); - prevPositionR = readRightEncoder(); + front_left_light.tick(); + front_right_light.tick(); + back_left_light.tick(); + back_right_light.tick(); - double angleDist = (rDist - lDist)*TIRE_RADIUS/trackWidth; + // Calculate new position and rotation + double distance_sum = right.tick_dist() + left.tick_dist(); + double distance_offset = right.tick_dist() - left.tick_dist(); - double currentRot = prevRotation + angleDist; + double d_angle = (distance_offset)/TRACK_WIDTH_CM; - double currentX; - double deltaX; - double currentY; - double deltaY; - if(angleDist != 0){ - double temp = (trackWidth*(rDist+lDist))/(2*(rDist-lDist)); - deltaX = temp * (sin(currentRot) - sin(prevRotation)); - deltaY = temp * (cos(prevRotation) - cos(currentRot)); - currentX = prevX + deltaX; - currentY = prevY + deltaY; - + // != on a double is fine here, because the robot may not move at all. + if(d_angle != 0){ + double temp = (TRACK_WIDTH_CM * distance_sum)/(2*(distance_offset)); + Coordinate2D delta(sin(rotation + d_angle) - sin(rotation), cos(rotation) - cos(rotation + d_angle)); + position = position.transform(delta.scale(temp)); } else { - double totalDist = TIRE_RADIUS*(lDist + rDist)/2; - deltaX = totalDist * cos(currentRot); - deltaY = totalDist * sin(currentRot); - currentX = prevX + deltaX; - currentY = prevY + deltaY; + double totalDist = TIRE_RADIUS*(distance_sum)/2; + Coordinate2D delta(cos(rotation + d_angle), sin(rotation + d_angle)); + position = position.transform(delta.scale(totalDist)); } - prevX = currentX; - prevY = currentY; - - prevRotation = currentRot; - double loopDelaySeconds = ((double) timeMs) / 1000; - profileA.currentPosition = currentRot*10 / TICK_TO_METERS; - profileA.currentVelocity = angleDist==0?0:angleDist*10 / TICK_TO_METERS /loopDelaySeconds; - aSetpoint = aProfile.calculate(loopDelaySeconds, - TrapezoidProfile::State(profileA.currentPosition, profileA.currentVelocity), - TrapezoidProfile::State(getHeadingTarget()*10/TICK_TO_METERS, 0.0)); + rotation = rotation + d_angle; - double velocity = AVelocityController.Compute(aSetpoint.velocity, profileA.currentVelocity, loopDelaySeconds); + center_tick(delay); + pid_tick(delay); - double lMotorPower = fmap((-8*velocity*trackWidth/2)/TIRE_RADIUS, -11, 11, -1, 1); - double rMotorPower = fmap((8*velocity*trackWidth/2)/TIRE_RADIUS, -11, 11, -1, 1); - - if (fabs(lMotorPower) < MIN_MOTOR_POWER) lMotorPower = 0; - if (fabs(rMotorPower) < MIN_MOTOR_POWER) rMotorPower = 0; - - setLeftPower(lMotorPower); - setRightPower(rMotorPower); - - serialLog("vels ", 3); - serialLog(xSetpoint.velocity, 3); - serialLog("vel ", 3); - serialLog(velocity, 3); - serialLog(" lpower ", 3); - serialLog(lMotorPower, 3); - serialLog(" rpower ", 3); - serialLog(rMotorPower, 3); - serialLog(" angle ", 3); - serialLogln(currentRot*10, 3); - - - double sum = 0; - for(int x = 49; x >= 0; x--) { - average[x+1] = average[x]; - sum += fabs(average[x+1]); - } - average[0] = lMotorPower; - sum += fabs(average[0]); - timeMs += loopDelayMs; - if (sum/50 < 0.01){ - serialLogln(sum/50,3); - serialLogln(runningPID,3); - runningPID = false; - setLeftPower(0); - setRightPower(0); - - sendActionSuccess("turn done"); - resetPID(); - - } else { - runningTurn = true; + + if (frame % 64 == 0) { + print_status(); } } -void Robot::center() { - centeringStatus = STARTED; -} +void Robot::pid_tick(uint32_t delay) { + std::tuple motor_speeds = motion_controller.update_speeds(position, rotation, (double)delay/1000); -void Robot::drive(float tiles, std::string id) { - if (!getStoppedStatus()) { - const float TILE_SIZE_INCHES = 24; - float distanceInches = tiles * TILE_SIZE_INCHES; - float ticksPerInch = TICKS_PER_ROTATION / (WHEEL_DIAMETER_INCHES * M_PI); - int tickDistance = (int)(distanceInches * ticksPerInch); - driveTicks(tickDistance, id); - } + drive(motor_speeds, "NULL"); } -// Drives the wheels according to the powers set. Negative is backwards, Positive forwards -void Robot::drive(float leftPower, float rightPower, std::string id) { - if (!getStoppedStatus()) { - if (leftPower < MIN_MOTOR_POWER && leftPower > -MIN_MOTOR_POWER) { - leftPower = 0; - } if (rightPower < MIN_MOTOR_POWER && rightPower > -MIN_MOTOR_POWER) { - rightPower = 0; - } - - setLeftPower(leftPower); - setRightPower(rightPower); - - //we only send null as id during our test drive. The only other time this drive method is called will be - //when the server sends it, meaning it will have an id to send back. - if (id != "NULL") { sendActionSuccess(id); } +void Robot::center_tick(uint32_t delay) { + if (centeringStatus == NOT_CENTERING) { + return; } - } -void Robot::driveTicks(int tickDistance, std::string id) { - if (stopped) { - resetSpeed(); - setXControl({POSITION, (float)tickDistance}); - setYControl({POSITION, 0}); - updateCritRange(); - runningPID = true; + if (centeringStatus == STARTED) { + // Set the goal position to a unit vector ahead of the robot + motion_controller.set_goal(position.transform(Coordinate2D(rotation)), 0); - if (id != "NULL") { - sendPacketOnPidComplete(id); + // The two front sensors crossed at the same time, skip aligning step + if (front_left_light.held_value() && front_right_light.held_value()) { + centeringStatus = ALIGNED_EDGE_1; } - } - } - -//turns the given amount in radians, CCW -void Robot::turn(float angleRadians, std::string id) { - serialLogln("Turning", 3); - serialLogln(angleRadians, 3); - - setXControl({POSITION, 0}); - setYControl({POSITION, 0}); - updateCritRange(); - setHeadingTarget(angleRadians*0.95); - runningTurn = true; - - if (id != "NULL") - { - sendPacketOnPidComplete(id); - } -} - -void Robot::stop() { - stopped = true; - - left.power(0); - right.power(0); - - serialLogln("Bot Stopped!", 2); -} - - - -/** - * get PID ready for the next iteration - */ -void resetPID(){ - prevPositionL = readLeftEncoder(); - prevPositionR = readRightEncoder(); - prevX = 0; - prevY = 0; - prevRotation = 0; - timeMs = 0; - for (int x = 0; x < 50; x++) average[x] = 100; -} - - -//crit range is basically getting distance we go until we are halfway to target. By the end of this range, -//we're at our max speed and are sure we aren't at a low speed just cause we're speeding up -void updateCritRange() -{ - //want to record the values before we move now - startEncoderAPos = profileX.currentPosition; - startEncoderBPos = profileY.currentPosition; - - profileX.criticalRange = fabs(profileX.targetPosition - startEncoderAPos) / 2; - profileY.criticalRange = fabs(profileY.targetPosition - startEncoderBPos) / 2; - - //update it so that time since start is now equal to this. Only really care about this value after turns though - timeSinceTurn = millis(); -} - - - - -// Sets up all the aspects needed for the bot to work -void setupBot() { - serialLogln("Setting Up Bot...", 2); - - pinMode(ONBOARD_LED_PIN, OUTPUT); - digitalWrite(ONBOARD_LED_PIN, HIGH); - setupMotors(); - setupIR(); - setupEncodersNew(); - serialLogln("Bot Set Up!", 2); - - XVelocityController.Reset(); - YVelocityController.Reset(); - AVelocityController.Reset(); - headingController.Reset(); - resetPID(); - - - // if (DO_PID_TEST) { - // testEncoderPID(); - // timerInterval(8000, &testEncoderPID); - // } - - // if (DO_TURN_TEST) { - // angle = 30; - // testTurn(); - // timerInterval(5000, testTurn); - // } - - // if (DO_CENTERING_TEST) { - // testCentering(); - // timerInterval(5000, &testCentering); - // } -} - -//this determines what our next action will be after an edge alignment, move to center, or axis turn. -void nextAction() -{ - //if we were previously turning to the next axis, and finished: - if(turningToNextAxis) - { - turningToNextAxis = false; - axisesAligned++; - //done centering yippee! - if(axisesAligned == 2) - { - axisesAligned = 0; - isCentering = false; - centeringStatus = CenteringStatus::NOT_CENTERING; + if (front_left_light.held_value() ^ front_right_light.held_value()) { + centeringStatus = ALIGNING_EDGE_1; } - //otherwise restart the whole process for this next axis - else - { - centeringStatus = CenteringStatus::STARTED; - } - } - //if previously moving to center for an axis, and finished: - else if(movingCenter) - { - //now, turn to next direction - movingCenter = false; - turningToNextAxis = true; - centeringStatus = CenteringStatus::MOVING; - //this way, if no axises aligned yet, angle = -90, and if one axis aligned, - //angle = 90, undoing the previous rotation. - angle = 90 * (axisesAligned * 2 - 1); - - // testTurn(); } - //if just aligned on a forward edge with the encoders in the front: - else if(forwardAligning) - { - //if going forward, store the current encoder value so we can see the full encoder length of the tiles - encoderAHalfwayDist = profileX.currentPosition; - encoderBHalfwayDist = profileY.currentPosition; - //swap to going back - forwardAligning = !forwardAligning; - //set that new drive - createDriveUntilNewTile(); - centeringStatus = 'E'; - - serialLog((char*)"Current encoder A: ", 2); - serialLogln(profileX.currentPosition, 2); - serialLog((char*)"Current encoder B: ", 2); - serialLogln(profileY.currentPosition, 2); - serialLog((char*)"Target encoder A: ", 2); - // serialLogln(leftMotorControl.mode == POSITION ? leftMotorControl.value : 0, 2); - serialLog((char*)"Target encoder B: ", 2); - // serialLogln(rightMotorControl.mode == POSITION ? rightMotorControl.value : 0, 2); + + if (centeringStatus == ALIGNING_EDGE_1) { + if (front_left_light.held_value() && front_right_light.held_value()) { + rotation = M_PI / 2; + position.y = -3; + centeringStatus = ALIGNED_EDGE_1; } - //if just aligned on a backward edge with the encoders in the back: - else - { - //swap to going forward now - forwardAligning = !forwardAligning; - - //since we always go forward first and then backwards, the current value of encoderHalfwayDist > currentEncoder always - //what we're doing is currently, "encoderAHalfwayDist" just stores the value of the other edge in encoder ticks, now we're - //finding the difference between them. And of course divide by 2 as want half that distance - encoderAHalfwayDist = (encoderAHalfwayDist - profileX.currentPosition) / 2; - encoderBHalfwayDist = (encoderBHalfwayDist - profileY.currentPosition) / 2; - - //decide that we take average of encoder A and B's distances, since ideally we want both to travel the same amount - int totalHalfwayDistance = (encoderAHalfwayDist + encoderBHalfwayDist) / 2; - // driveTicks(totalHalfwayDistance, "NULL"); - centeringStatus = CenteringStatus::MOVING; - //now we moving to da center - movingCenter = true; - } -} -//this updates our centering depending on the current status of it -void Robot::center_tick() -{ - //what we do depend on the current status - switch(centeringStatus) - { - case CenteringStatus::STARTED: - //create the first drive - createDriveUntilNewTile(); - //now change it so we're driving forward - centeringStatus = CenteringStatus::EDGE; - break; - case CenteringStatus::EDGE: - { - //continue driving forward - DriveStatus drive_status = driveUntilNewTile(); - //reminder status 3 = no leading encoders and driving finished - if(driveStatus == DriveStatus::REACHED) - { - //meaning we can now go in opposite direction. - nextAction(); - } - //reminder status 2 = one leading encoder finished first, but driving is finished - else if(driveStatus == == DriveStatus::REACHED_REVERSING) - { - //mean we now begin correcting - centeringStatus = CenteringStatus::MOVING; // ???? - } - break; + // If the left one crossed latest + if (front_left_light.last_changed_time() > front_right_light.last_changed_time()) { + // Turn left + motion_controller.set_goal(position, rotation + 1); + } else { + // Turn right + motion_controller.set_goal(position, rotation - 1); } - case CenteringStatus::MOVING: - //check if we're the moving we're doing is finished. If so, determine what we do next. - - // ??? - // if(checkMoveFinished()) - // { - // nextAction(); - // } - break; } -} -//checks if we're done moving to our target when either moving half a tile's length or turning -// bool checkMoveFinished() -// { -// //first, checks like "fabs(profileX.currentVelocity) < 2" see if we're slowing down or not. - -// //then, something like "fabs(currentEncoderA - encoderATarget) < criticalRangeA" is making sure -// //the reason our speed is slow is specifically because we're slowing down and not because we're -// //beginning to speed up. -// //do this by seeing if the distance remaining is less than the midpoint distance from start to end, as by then we're at our max speed. - -// bool encoderAChecks = fabs(profileX.currentPosition - profileX.targetPosition) < profileX.criticalRange && fabs(profileX.currentVelocity) < 3; -// bool encoderBChecks = fabs(profileY.currentPosition - profileY.targetPosition) < profileY.criticalRange && fabs(profileY.currentVelocity) < 3; - -// //check if we've been stalling too long, for 8 seconds. If we're over time, that's bad, and means we should declare the movement finished. -// bool timerCheck = millis() - timeSinceTurn > 8000; - -// return ((encoderAChecks && encoderBChecks) || timerCheck); -// } - -// //like the one above but just seeing if we can keep moving or not -// bool checkIfCanUpdateMovement() -// { -// return fabs(profileX.currentPosition - profileX.targetPosition) < profileX.criticalRange && fabs(profileY.currentPosition - profileY.targetPosition) < profileY.criticalRange; -// } - -boolean isRobotPidAtTarget() { - if (!DO_PID) - return true; - - boolean leftAtTarget, rightAtTarget; - - if (getLeftMotorControl().mode == POSITION) - { - leftAtTarget = approxEquals(getLeftMotorControl().value, profileX.currentPosition, PID_POSITION_TOLERANCE) - && approxEquals(profileX.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE); - - serialLog("Left Position: ", 3); - serialLog(profileX.currentPosition, 3); - serialLog(", Target: ", 3); - serialLog(getLeftMotorControl().value, 3); - serialLog(", Velocity: ", 3); - serialLog(profileX.currentVelocity, 3); - serialLog(", At Target: ", 3); - serialLogln(leftAtTarget, 3); + if (centeringStatus == ALIGNED_EDGE_1) { + motion_controller.set_goal(position.transform(Coordinate2D(rotation)), 0); } - else - { - leftAtTarget = approxEquals(getLeftMotorControl().value, profileX.currentVelocity, PID_VELOCITY_TOLERANCE); - } - if (getRightMotorControl().mode == POSITION) - { - rightAtTarget = approxEquals(getRightMotorControl().value, profileY.currentPosition, PID_POSITION_TOLERANCE) - && approxEquals(profileY.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE); - - serialLog("Right Position: ", 3); - serialLog(profileY.currentPosition, 3); - serialLog(", Target: ", 3); - serialLog(getRightMotorControl().value, 3); - serialLog(", Velocity: ", 3); - serialLog(profileY.currentVelocity, 3); - serialLog(", At Target: ", 3); - serialLogln(rightAtTarget, 3); - } - else - { - rightAtTarget = approxEquals(getRightMotorControl().value, profileY.currentVelocity, PID_VELOCITY_TOLERANCE); - } - - return leftAtTarget && rightAtTarget; } -void sendPacketOnPidComplete(std::string id) { - if (!DO_PID) - sendActionFail(id); - - if (isRobotPidAtTarget()) { - sendActionSuccess(id); - } else { - // Run on next loop - timerDelay(1, [id](){ sendPacketOnPidComplete(id); }); +void Robot::center() { + if (centeringStatus == NOT_CENTERING) { + centeringStatus = STARTED; } } -// //updates us to the next distance we're traveling -// void updateToNextDistance() -// { -// //this way if we're reversing, we're actually subtracting. if going forward was 0, then 0 * 2 - 1 = -1. -// //if going forward was 1, 1 * 2 - 1 = 1. -// float encTargetA = (float)profileX.currentPosition + 2500 * (forwardAligning * 2 - 1); -// float encTargetB = (float)profileY.currentPosition + 2500 * (forwardAligning * 2 - 1); -// setXControl({POSITION, encTargetA}); -// setYControl({POSITION, encTargetB}); -// #if LOGGING_LEVEL >= 3 -// serialLogln("changing direction!", 3); -// serialLogln(encTargetA, 3); -// serialLogln(encTargetB, 3); -// #endif - -// //update crit range yessir -// updateCritRange(); -// } - -//creates a new drive until the next tile -// void createDriveUntilNewTile() -// { -// //set the next distance to travel -// resetSpeed(); -// updateToNextDistance(); - -// //assign values here, will detect when they change -// if(forwardAligning) -// { -// firstEncoderIndex = Top_Left_Encoder_Index; -// secondEncoderIndex = Top_Right_Encoder_Index; -// } -// else -// { -// //from the robots perspective as it's going backwards, the encoder on the left is bottom right, -// //while the encoder on the right is bottom left, so we just swap em -// firstEncoderIndex = Bottom_Right_Encoder_Index; -// secondEncoderIndex = Bottom_Left_Encoder_Index; -// } -// //now set the actual values with the indices -// firstEncoderVal = onFirstTile[firstEncoderIndex]; -// secondEncoderVal = onFirstTile[secondEncoderIndex]; -// } - -//drives until the first two encoders are considered to hit a new value. -//Returns a status bit, with the corresponding values: - // 1 - drive is going - // 2 - just at this moment, we have reached our destination and are going to begin reversing now. - // 3 - just at this moment, we've reached our destination, but DON'T need to reverse. -enum DriveStatus Robot::driveUntilNewTile() -{ - //if we do finish moving, update to a new distance. I think we have to move at intervals for it to work - if(checkIfCanUpdateMovement()) - { - updateToNextDistance(); - } - - //if we already changed it, don't change it back again - leftEncoderChange = leftEncoderChange || (onFirstTile[firstEncoderIndex] != firstEncoderVal); - rightEncoderChange = rightEncoderChange || (onFirstTile[secondEncoderIndex] != secondEncoderVal); - - if(!leftEncoderChange && !rightEncoderChange) { - return CenteringStatus::STARTED; - } +void Robot::drive(Coordinate2D goal_pos, double goal_angle) { + motion_controller.set_goal(goal_pos, goal_angle); +} - //when both cross, we done. - if(leftEncoderChange && rightEncoderChange) - { - //if there had been a leading encoder, do the following: - uint8_t status = 0; - if(leadingEncoder != 0) - { - setXControl({POSITION, (float)profileX.currentPosition}); - setYControl({POSITION, (float)profileY.currentPosition}); - - //first get the encoder that we're comparing to get the distance. If leading encoder is 1 and we were moving forward, or if - //leading encoder is 2 but we were moving backward, then the back encoder is b, otherwise it's A - double encoderChosen = (leadingEncoder == 1 && forwardAligning || leadingEncoder == 2 && !forwardAligning) ? profileY.currentPosition : profileX.currentPosition; - //now, the distance we traveled is the difference between the encoders - double backEncoderDist = fabs(encoderChosen - backPrevDistance); - // serialLog("Begin encoder is: ", 3); - // serialLogln(backPrevDistance, 3); - // serialLog("End encoder is: ", 3); - // serialLogln((leadingEncoder == 1) ? profileX.currentPosition : profileY.currentPosition, 3); - //now convert difference in ticks to meter value - backEncoderDist *= TICK_TO_METERS; - // serialLog(" Encoder in front is gonna be: ", 3); - // serialLogln(leadingEncoder, 2); - // serialLog("Total distance encoder was behind is: ", 2); - // serialLogln(backEncoderDist, 2); - //reminder: angle = arctan(x/y), where x = backEncoderDist (like distance to our edge), and y = distance between two light sensors (put in manually) - - //idk why, but when dividing by 2 that gets us the true angle. The BackEncoderDist and lightDist seems to be correct vales, but the value we - //end up getting from it is double what it should be. Maybe there's an issue with how I did it. - float radAngle = atan(backEncoderDist / lightDist) / 2; - - //as a reminder, corresponding degrees = (pi/180) * x radians - float degreesAngle = 180 / M_PI * radAngle; - - serialLog("Angle is going to be: ", 2); - serialLog(degreesAngle, 2); - serialLogln(" degrees.", 2); - - //we know positive angle = turn left, negative angle means turn right. - //encoder 1 forward means turn left, encoder 2 forward means turn right. - //so 2 = -1, 1 = 1. If you plug those numbers in, that's what you get. - - int8_t degreesDirection = 3 - 2 * leadingEncoder; - serialLog("Sign is going to be: ", 2); - serialLogln(degreesDirection, 2); - - //now update the angle, and turn - angle = degreesAngle * degreesDirection; - // testTurn(); - status = 2; - } - else - { - status = 3; +void Robot::drive(float tiles, std::string id) { + const float TILE_SIZE_CM = 24 * 2.54; + motion_controller.set_goal(Coordinate2D(rotation).scale(TILE_SIZE_CM), rotation); +} - //with the other one we set the crit range after calling the turn function. - //Here we don't, so we gotta do that - updateCritRange(); - } +// Drives the wheels according to the powers set. Negative is backwards, Positive forwards +void Robot::drive(std::tuple& powers, std::string id) { + left.power(std::get<0>(powers)); + right.power(std::get<1>(powers)); - //reset all of our values - leadingEncoder = 0; - backPrevDistance = 0; - leftEncoderChange = false; - rightEncoderChange = false; + //we only send null as id during our test drive. The only other time this drive method is called will be + //when the server sends it, meaning it will have an id to send back. + if (id != "NULL") { sendActionSuccess(id); } +} - //if the encoder returned 0, no need to reverse so skip to status 3. - return status; - } - //otherwise, want to see which one crossed. Can do this by seeing if we've updated backPrevDistance yet or not. - else if(backPrevDistance == 0) - { - //if left encoder changed, that's the leading encoder, otherwise 2nd is the leading encoder obviously. - leadingEncoder = leftEncoderChange ? 1 : 2; - //this makes sense as if the left encoder first crossed but we're going backwards, that's encoder A that's behind. Meanwhile if the right - //encoder crossed first and we're going forwards, its encoder A that's behind too. In all other cases, its encoder B - backPrevDistance = (leftEncoderChange && !forwardAligning || rightEncoderChange && forwardAligning) ? profileX.currentPosition : profileY.currentPosition; - } - - return 1; +//turns the given amount in radians, CCW +void Robot::turn(float angleRadians, std::string id) { } -// // Tests the motors. This turns the motors off. -// void driveTestOff() { -// stop(); -// timerDelay(2000, &startDriveTest); -// } - -// // Test motor and encoder synchronization -// void startMotorAndEncoderTest() { -// (new MotorEncoderTest())->startMotorAndEncoderTest(); -// } - -// // Tests the motors. This turns the motors on. -// void startDriveTest() { -// drive(0.5f, 0.5f, "NULL"); -// //timerDelay(2000, &driveTestOff); -// } - -// void testCentering() -// { -// serialLogln("Running centering routine...", 2); -// startCentering(); -// } - -// void testEncoderPID() -// { -// serialLogln("Changing encoder PID setpoint!", 2); -// if (!testEncoderPID_value) -// { -// testEncoderPID_value = true; -// setXControl({POSITION, (float)TICKS_PER_ROTATION * 6}); -// setYControl({POSITION, 0.0f}); -// runningPID = true; -// } -// else -// { -// testEncoderPID_value = false; -// setXControl({POSITION, 0.0f}); -// setYControl({POSITION, 0.0f}); -// runningPID = true; -// } - -// updateCritRange(); -// } - -// void testTurn() -// { -// resetSpeed(); +void Robot::stop() { + // Set the goal to where we are right now, so the robot doesn't move + motion_controller.set_goal(position, rotation); -// serialLog("Changing destination angle to ", 2); -// serialLog(angle, 2); -// //simple maths -// turn(M_PI / 180 * angle, "NULL"); -// serialLog(" (", 2); -// serialLog(getLeftMotorControl().value, 2); -// serialLog(", ", 2); -// serialLog(getRightMotorControl().value, 2); -// serialLogln(")", 2); - -// //compute the new crit range now that target and start encoder have changed -// updateCritRange(); -// } -#endif \ No newline at end of file + serialLogln("Bot Stopped!", 2); +} \ No newline at end of file diff --git a/src/robot/pidController.cpp b/src/robot/pidController.cpp index 293a06a..0d355e7 100644 --- a/src/robot/pidController.cpp +++ b/src/robot/pidController.cpp @@ -7,6 +7,14 @@ #include #include +PIDController::PIDController(double kp, double ki, double kd, double min, double max, double _errorTolerance) + : kp(kp), ki(ki), kd(kd), + minOutput(min), maxOutput(max), + prev_error(0), + errorTolerance(_errorTolerance), + integral(0) +{} + double PIDController::Compute(double setpoint, double actual_value, double dt) { // Calculate error double error = this->getError(setpoint, actual_value); diff --git a/src/robot/splines.cpp b/src/robot/splines.cpp index c1fea2f..7aa7576 100644 --- a/src/robot/splines.cpp +++ b/src/robot/splines.cpp @@ -1,252 +1,252 @@ -#ifndef CHESSBOT_SPLINES_CPP -#define CHESSBOT_SPLINES_CPP - -#include "robot/splines.h" -#include "utils/logging.h" -#include "robot/control/robot.h" -#include "robot/trapezoidalProfile.h" -#include "utils/timer.h" -#include "wifi/connection.h" -#include "utils/config.h" -#include "utils/functions.h" -#include -#include -#include -#include - - - -void velocityUpdateTimerFunction(std::string id) -{ - // serialLogln("Update Timer was called", 3); - if (timeSlicesToExecute.size() == 0) { - if (id != "NULL") { sendActionSuccess(id); } - return; - } - - float desiredVelocityLeft, desiredVelocityRight; - std::tie(desiredVelocityLeft, desiredVelocityRight) = timeSlicesToExecute.front(); - setXControl({VELOCITY, desiredVelocityLeft}); - setYControl({VELOCITY, desiredVelocityRight}); - timeSlicesToExecute.pop(); - - // 1ms delay ensures the function will run in the next loop - timerDelay(1, [id](){ velocityUpdateTimerFunction(id); }); -} - - -void danceMonkeyCubic(std::string id, Point start, Point control1, Point control2, Point end, float totalTimeMs){ - float trackWidth = TRACK_WIDTH_INCHES; - - int steps = (int)(totalTimeMs / loopDelayMilliseconds); // 20ms steps - float dt = totalTimeMs / 1000 / steps; - - for (int i = 0; i < steps; i++) { - float t = (float)i / steps; - float tNext = (float)(i + 1) / steps; - - // Cubic Bezier Point at t - Point p = { - (float)(pow(1 - t, 3) * start.x + - 3 * pow(1 - t, 2) * t * control1.x + - 3 * (1 - t) * pow(t, 2) * control2.x + - pow(t, 3) * end.x), - (float)(pow(1 - t, 3) * start.y + - 3 * pow(1 - t, 2) * t * control1.y + - 3 * (1 - t) * pow(t, 2) * control2.y + - pow(t, 3) * end.y) - }; - - // Cubic Bezier Point at tNext - Point pNext = { - (float)(pow(1 - tNext, 3) * start.x + - 3 * pow(1 - tNext, 2) * tNext * control1.x + - 3 * (1 - tNext) * pow(tNext, 2) * control2.x + - pow(tNext, 3) * end.x), - (float)(pow(1 - tNext, 3) * start.y + - 3 * pow(1 - tNext, 2) * tNext * control1.y + - 3 * (1 - tNext) * pow(tNext, 2) * control2.y + - pow(tNext, 3) * end.y) - }; - - // Estimate linear velocity - float dx = pNext.x - p.x; - float dy = pNext.y - p.y; - float linearVelocity = sqrt(dx * dx + dy * dy) / dt; - - // Estimate angular velocity - float theta1 = atan2(dy, dx); - float theta0; - - if (i > 0) { - float tPrev = (float)(i - 1) / steps; - Point pPrev = { - (float)(pow(1 - tPrev, 3) * start.x + - 3 * pow(1 - tPrev, 2) * tPrev * control1.x + - 3 * (1 - tPrev) * pow(tPrev, 2) * control2.x + - pow(tPrev, 3) * end.x), - (float)(pow(1 - tPrev, 3) * start.y + - 3 * pow(1 - tPrev, 2) * tPrev * control1.y + - 3 * (1 - tPrev) * pow(tPrev, 2) * control2.y + - pow(tPrev, 3) * end.y) - }; - - theta0 = atan2(p.y - pPrev.y, p.x - pPrev.x); - } else { - theta0 = theta1; - } - - float angularVelocity = (theta1 - theta0) / dt; - - // Normalize angle diff - while (angularVelocity > M_PI) angularVelocity -= 2 * M_PI; - while (angularVelocity < -M_PI) angularVelocity += 2 * M_PI; - - float trackWidthTicks = trackWidth * TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); - - // Compute wheel velocities using differential drive model - float vLeft = linearVelocity - (angularVelocity * trackWidthTicks / 2); - float vRight = linearVelocity + (angularVelocity * trackWidthTicks / 2); - - timeSlicesToExecute.push({vLeft, vRight}); - } - velocityUpdateTimerFunction(id); -} - -void danceMonkeyQuadratic(std::string id, Point start, Point control, Point end, float totalTimeMs) { - serialLogln("Quadratic Dancer was called", 3); - float trackWidth = TRACK_WIDTH_INCHES; - int steps = (int)(totalTimeMs / loopDelayMilliseconds); // 20ms steps - float dt = totalTimeMs / 1000 / steps; - - for (int i = 0; i < steps; i++) { - float t = (float)i / steps; - float tNext = (float)(i + 1) / steps; - - // Bezier point at t - Point p = { - (float)((1 - t) * (1 - t) * start.x + 2 * (1 - t) * t * control.x + t * t * end.x), - (float)((1 - t) * (1 - t) * start.y + 2 * (1 - t) * t * control.y + t * t * end.y) - }; - - // Bezier point at t + dt - Point pNext = { - (float)((1 - tNext) * (1 - tNext) * start.x + 2 * (1 - tNext) * tNext * control.x + tNext * tNext * end.x), - (float)((1 - tNext) * (1 - tNext) * start.y + 2 * (1 - tNext) * tNext * control.y + tNext * tNext * end.y) - }; - - // Velocity approximation - float dx = pNext.x - p.x; - float dy = pNext.y - p.y; - // dx *= 2*12*TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); - // dy *= 2*12*TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); - float linearVelocity = sqrt(dx * dx + dy * dy) / dt; - - // Angular velocity approximation - float theta1 = atan2(dy, dx); - float theta0 = (i > 0) ? atan2(p.y - ((1 - (float)(i - 1) / steps) * (1 - (float)(i - 1) / steps) * start.y + - 2 * (1 - (float)(i - 1) / steps) * ((float)(i - 1) / steps) * control.y + - ((float)(i - 1) / steps) * ((float)(i - 1) / steps) * end.y), - p.x - ((1 - (float)(i - 1) / steps) * (1 - (float)(i - 1) / steps) * start.x + - 2 * (1 - (float)(i - 1) / steps) * ((float)(i - 1) / steps) * control.x + - ((float)(i - 1) / steps) * ((float)(i - 1) / steps) * end.x)) : theta1; - float angularVelocity = (theta1 - theta0) / dt; - - // Normalize angle diff - while (angularVelocity > M_PI) angularVelocity -= 2 * M_PI; - while (angularVelocity < -M_PI) angularVelocity += 2 * M_PI; - - float trackWidthTicks = trackWidth * TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); - - // Differential drive kinematics - float vLeft = linearVelocity - (angularVelocity * trackWidthTicks / 2); - float vRight = linearVelocity + (angularVelocity * trackWidthTicks / 2); - - - timeSlicesToExecute.push({vLeft, vRight}); - // serialLog(vLeft, 3); - // serialLog(", ", 3); - // serialLogln(vRight, 3); - } - velocityUpdateTimerFunction(id); -} - - - -int customPrevPositionA = 0, customPrevPositionB = 0; - -void startCustomMotionProfileTimer(int leftPositionTarget, int rightPositionTarget, double profileDuration, std::string id) -{ - double maxAcceleration = 6000; - - double maxPositionTarget = std::max(std::abs(leftPositionTarget), std::abs(rightPositionTarget)); - double leftAcceleration = maxAcceleration * std::abs(leftPositionTarget) / maxPositionTarget; - double rightAcceleration = maxAcceleration * std::abs(rightPositionTarget) / maxPositionTarget; - - double leftSqrtValue = profileDuration*profileDuration - 4*std::abs(leftPositionTarget)/leftAcceleration; - double rightSqrtValue = profileDuration*profileDuration - 4*std::abs(rightPositionTarget)/rightAcceleration; - - if (leftSqrtValue < 0 || rightSqrtValue < 0) - { - sendActionFail(id); - return; - } - - double maxVelocityLeft = (profileDuration - sqrt(leftSqrtValue))*leftAcceleration/2; - double maxVelocityRight = (profileDuration - sqrt(rightSqrtValue))*rightAcceleration/2; - - customPrevPositionA = readLeftEncoder(); - customPrevPositionB = readRightEncoder(); - - MotionProfile customProfileA = {maxVelocityLeft, leftAcceleration, 0, 0, (double)leftPositionTarget, 0, fabs(leftPositionTarget - customPrevPositionA) / 2}; - MotionProfile customProfileB = {maxVelocityRight, rightAcceleration, 0, 0, (double)rightPositionTarget, 0, fabs(rightPositionTarget - customPrevPositionB) / 2}; - serialLogln("Custom motion profile timer...", 3); - serialLog("Left max vel: ", 3); - serialLog(maxVelocityLeft, 3); - serialLog(" Max accel: ", 3); - serialLog(leftAcceleration, 3); - serialLog(" Target: ", 3); - serialLogln(leftPositionTarget, 3); - serialLog("Right max vel: ", 3); - serialLog(maxVelocityRight, 3); - serialLog(" Max accel: ", 3); - serialLog(rightAcceleration, 3); - serialLog(" Target: ", 3); - serialLogln(rightPositionTarget, 3); - customMotionProfileTimerFunction(customProfileA, customProfileB, loopDelayMilliseconds / 1000.0, id); -} - -void customMotionProfileTimerFunction(MotionProfile &customProfileA, MotionProfile &customProfileB, double dt, std::string id) -{ - if (approxEquals(customProfileA.targetPosition, customProfileA.currentPosition, PID_POSITION_TOLERANCE) - && approxEquals(customProfileA.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE) - && approxEquals(customProfileB.targetPosition, customProfileB.currentPosition, PID_POSITION_TOLERANCE) - && approxEquals(customProfileB.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE)) - { - if (id != "NULL") { sendActionSuccess(id); } - return; - } - - int currentPositionEncoderA = readLeftEncoder(); - int currentPositionEncoderB = readRightEncoder(); - double currentVelocityA = (currentPositionEncoderA - customPrevPositionA) / dt; - double currentVelocityB = (currentPositionEncoderB - customPrevPositionB) / dt; - - customPrevPositionA = currentPositionEncoderA; - customPrevPositionB = currentPositionEncoderB; - - customProfileA.currentPosition = currentPositionEncoderA; - customProfileA.currentVelocity = currentVelocityA; - customProfileB.currentPosition = currentPositionEncoderB; - customProfileB.currentVelocity = currentVelocityB; - - float desiredVelocityLeft = updateTrapezoidalProfile(customProfileA, dt); - float desiredVelocityRight = updateTrapezoidalProfile(customProfileB, dt); - - setXControl({VELOCITY, desiredVelocityLeft}); - setYControl({VELOCITY, desiredVelocityRight}); - - timerDelay(1, [&customProfileA, &customProfileB, dt, id](){ customMotionProfileTimerFunction(customProfileA, customProfileB, dt, id); }); -} - -#endif \ No newline at end of file +// #ifndef CHESSBOT_SPLINES_CPP +// #define CHESSBOT_SPLINES_CPP + +// #include "robot/splines.h" +// #include "utils/logging.h" +// #include "robot/control/robot.h" +// #include "robot/trapezoidalProfile.h" +// #include "utils/timer.h" +// #include "wifi/connection.h" +// #include "utils/config.h" +// #include "utils/functions.h" +// #include +// #include +// #include +// #include + + + +// void velocityUpdateTimerFunction(std::string id) +// { +// // serialLogln("Update Timer was called", 3); +// if (timeSlicesToExecute.size() == 0) { +// if (id != "NULL") { sendActionSuccess(id); } +// return; +// } + +// float desiredVelocityLeft, desiredVelocityRight; +// std::tie(desiredVelocityLeft, desiredVelocityRight) = timeSlicesToExecute.front(); +// setXControl({VELOCITY, desiredVelocityLeft}); +// setYControl({VELOCITY, desiredVelocityRight}); +// timeSlicesToExecute.pop(); + +// // 1ms delay ensures the function will run in the next loop +// timerDelay(1, [id](){ velocityUpdateTimerFunction(id); }); +// } + + +// void danceMonkeyCubic(std::string id, Point start, Point control1, Point control2, Point end, float totalTimeMs){ +// float trackWidth = TRACK_WIDTH_INCHES; + +// int steps = (int)(totalTimeMs / loopDelayMilliseconds); // 20ms steps +// float dt = totalTimeMs / 1000 / steps; + +// for (int i = 0; i < steps; i++) { +// float t = (float)i / steps; +// float tNext = (float)(i + 1) / steps; + +// // Cubic Bezier Point at t +// Point p = { +// (float)(pow(1 - t, 3) * start.x + +// 3 * pow(1 - t, 2) * t * control1.x + +// 3 * (1 - t) * pow(t, 2) * control2.x + +// pow(t, 3) * end.x), +// (float)(pow(1 - t, 3) * start.y + +// 3 * pow(1 - t, 2) * t * control1.y + +// 3 * (1 - t) * pow(t, 2) * control2.y + +// pow(t, 3) * end.y) +// }; + +// // Cubic Bezier Point at tNext +// Point pNext = { +// (float)(pow(1 - tNext, 3) * start.x + +// 3 * pow(1 - tNext, 2) * tNext * control1.x + +// 3 * (1 - tNext) * pow(tNext, 2) * control2.x + +// pow(tNext, 3) * end.x), +// (float)(pow(1 - tNext, 3) * start.y + +// 3 * pow(1 - tNext, 2) * tNext * control1.y + +// 3 * (1 - tNext) * pow(tNext, 2) * control2.y + +// pow(tNext, 3) * end.y) +// }; + +// // Estimate linear velocity +// float dx = pNext.x - p.x; +// float dy = pNext.y - p.y; +// float linearVelocity = sqrt(dx * dx + dy * dy) / dt; + +// // Estimate angular velocity +// float theta1 = atan2(dy, dx); +// float theta0; + +// if (i > 0) { +// float tPrev = (float)(i - 1) / steps; +// Point pPrev = { +// (float)(pow(1 - tPrev, 3) * start.x + +// 3 * pow(1 - tPrev, 2) * tPrev * control1.x + +// 3 * (1 - tPrev) * pow(tPrev, 2) * control2.x + +// pow(tPrev, 3) * end.x), +// (float)(pow(1 - tPrev, 3) * start.y + +// 3 * pow(1 - tPrev, 2) * tPrev * control1.y + +// 3 * (1 - tPrev) * pow(tPrev, 2) * control2.y + +// pow(tPrev, 3) * end.y) +// }; + +// theta0 = atan2(p.y - pPrev.y, p.x - pPrev.x); +// } else { +// theta0 = theta1; +// } + +// float angularVelocity = (theta1 - theta0) / dt; + +// // Normalize angle diff +// while (angularVelocity > M_PI) angularVelocity -= 2 * M_PI; +// while (angularVelocity < -M_PI) angularVelocity += 2 * M_PI; + +// float trackWidthTicks = trackWidth * TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); + +// // Compute wheel velocities using differential drive model +// float vLeft = linearVelocity - (angularVelocity * trackWidthTicks / 2); +// float vRight = linearVelocity + (angularVelocity * trackWidthTicks / 2); + +// timeSlicesToExecute.push({vLeft, vRight}); +// } +// velocityUpdateTimerFunction(id); +// } + +// void danceMonkeyQuadratic(std::string id, Point start, Point control, Point end, float totalTimeMs) { +// serialLogln("Quadratic Dancer was called", 3); +// float trackWidth = TRACK_WIDTH_INCHES; +// int steps = (int)(totalTimeMs / loopDelayMilliseconds); // 20ms steps +// float dt = totalTimeMs / 1000 / steps; + +// for (int i = 0; i < steps; i++) { +// float t = (float)i / steps; +// float tNext = (float)(i + 1) / steps; + +// // Bezier point at t +// Point p = { +// (float)((1 - t) * (1 - t) * start.x + 2 * (1 - t) * t * control.x + t * t * end.x), +// (float)((1 - t) * (1 - t) * start.y + 2 * (1 - t) * t * control.y + t * t * end.y) +// }; + +// // Bezier point at t + dt +// Point pNext = { +// (float)((1 - tNext) * (1 - tNext) * start.x + 2 * (1 - tNext) * tNext * control.x + tNext * tNext * end.x), +// (float)((1 - tNext) * (1 - tNext) * start.y + 2 * (1 - tNext) * tNext * control.y + tNext * tNext * end.y) +// }; + +// // Velocity approximation +// float dx = pNext.x - p.x; +// float dy = pNext.y - p.y; +// // dx *= 2*12*TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); +// // dy *= 2*12*TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); +// float linearVelocity = sqrt(dx * dx + dy * dy) / dt; + +// // Angular velocity approximation +// float theta1 = atan2(dy, dx); +// float theta0 = (i > 0) ? atan2(p.y - ((1 - (float)(i - 1) / steps) * (1 - (float)(i - 1) / steps) * start.y + +// 2 * (1 - (float)(i - 1) / steps) * ((float)(i - 1) / steps) * control.y + +// ((float)(i - 1) / steps) * ((float)(i - 1) / steps) * end.y), +// p.x - ((1 - (float)(i - 1) / steps) * (1 - (float)(i - 1) / steps) * start.x + +// 2 * (1 - (float)(i - 1) / steps) * ((float)(i - 1) / steps) * control.x + +// ((float)(i - 1) / steps) * ((float)(i - 1) / steps) * end.x)) : theta1; +// float angularVelocity = (theta1 - theta0) / dt; + +// // Normalize angle diff +// while (angularVelocity > M_PI) angularVelocity -= 2 * M_PI; +// while (angularVelocity < -M_PI) angularVelocity += 2 * M_PI; + +// float trackWidthTicks = trackWidth * TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); + +// // Differential drive kinematics +// float vLeft = linearVelocity - (angularVelocity * trackWidthTicks / 2); +// float vRight = linearVelocity + (angularVelocity * trackWidthTicks / 2); + + +// timeSlicesToExecute.push({vLeft, vRight}); +// // serialLog(vLeft, 3); +// // serialLog(", ", 3); +// // serialLogln(vRight, 3); +// } +// velocityUpdateTimerFunction(id); +// } + + + +// int customPrevPositionA = 0, customPrevPositionB = 0; + +// void startCustomMotionProfileTimer(int leftPositionTarget, int rightPositionTarget, double profileDuration, std::string id) +// { +// double maxAcceleration = 6000; + +// double maxPositionTarget = std::max(std::abs(leftPositionTarget), std::abs(rightPositionTarget)); +// double leftAcceleration = maxAcceleration * std::abs(leftPositionTarget) / maxPositionTarget; +// double rightAcceleration = maxAcceleration * std::abs(rightPositionTarget) / maxPositionTarget; + +// double leftSqrtValue = profileDuration*profileDuration - 4*std::abs(leftPositionTarget)/leftAcceleration; +// double rightSqrtValue = profileDuration*profileDuration - 4*std::abs(rightPositionTarget)/rightAcceleration; + +// if (leftSqrtValue < 0 || rightSqrtValue < 0) +// { +// sendActionFail(id); +// return; +// } + +// double maxVelocityLeft = (profileDuration - sqrt(leftSqrtValue))*leftAcceleration/2; +// double maxVelocityRight = (profileDuration - sqrt(rightSqrtValue))*rightAcceleration/2; + +// customPrevPositionA = readLeftEncoder(); +// customPrevPositionB = readRightEncoder(); + +// MotionProfile customProfileA = {maxVelocityLeft, leftAcceleration, 0, 0, (double)leftPositionTarget, 0, fabs(leftPositionTarget - customPrevPositionA) / 2}; +// MotionProfile customProfileB = {maxVelocityRight, rightAcceleration, 0, 0, (double)rightPositionTarget, 0, fabs(rightPositionTarget - customPrevPositionB) / 2}; +// serialLogln("Custom motion profile timer...", 3); +// serialLog("Left max vel: ", 3); +// serialLog(maxVelocityLeft, 3); +// serialLog(" Max accel: ", 3); +// serialLog(leftAcceleration, 3); +// serialLog(" Target: ", 3); +// serialLogln(leftPositionTarget, 3); +// serialLog("Right max vel: ", 3); +// serialLog(maxVelocityRight, 3); +// serialLog(" Max accel: ", 3); +// serialLog(rightAcceleration, 3); +// serialLog(" Target: ", 3); +// serialLogln(rightPositionTarget, 3); +// customMotionProfileTimerFunction(customProfileA, customProfileB, loopDelayMilliseconds / 1000.0, id); +// } + +// void customMotionProfileTimerFunction(MotionProfile &customProfileA, MotionProfile &customProfileB, double dt, std::string id) +// { +// if (approxEquals(customProfileA.targetPosition, customProfileA.currentPosition, PID_POSITION_TOLERANCE) +// && approxEquals(customProfileA.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE) +// && approxEquals(customProfileB.targetPosition, customProfileB.currentPosition, PID_POSITION_TOLERANCE) +// && approxEquals(customProfileB.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE)) +// { +// if (id != "NULL") { sendActionSuccess(id); } +// return; +// } + +// int currentPositionEncoderA = readLeftEncoder(); +// int currentPositionEncoderB = readRightEncoder(); +// double currentVelocityA = (currentPositionEncoderA - customPrevPositionA) / dt; +// double currentVelocityB = (currentPositionEncoderB - customPrevPositionB) / dt; + +// customPrevPositionA = currentPositionEncoderA; +// customPrevPositionB = currentPositionEncoderB; + +// customProfileA.currentPosition = currentPositionEncoderA; +// customProfileA.currentVelocity = currentVelocityA; +// customProfileB.currentPosition = currentPositionEncoderB; +// customProfileB.currentVelocity = currentVelocityB; + +// float desiredVelocityLeft = updateTrapezoidalProfile(customProfileA, dt); +// float desiredVelocityRight = updateTrapezoidalProfile(customProfileB, dt); + +// setXControl({VELOCITY, desiredVelocityLeft}); +// setYControl({VELOCITY, desiredVelocityRight}); + +// timerDelay(1, [&customProfileA, &customProfileB, dt, id](){ customMotionProfileTimerFunction(customProfileA, customProfileB, dt, id); }); +// } + +// #endif \ No newline at end of file diff --git a/src/robot/trapezoidalProfile.cpp b/src/robot/trapezoidalProfile.cpp index 8429398..43359f4 100644 --- a/src/robot/trapezoidalProfile.cpp +++ b/src/robot/trapezoidalProfile.cpp @@ -1,109 +1,107 @@ -#ifndef CHESSBOT_TRAPEZOIDAL_PROFILE_CPP -#define CHESSBOT_TRAPEZOIDAL_PROFILE_CPP - #include "robot/trapezoidalProfile.h" +#include "utils/config.h" #include "utils/logging.h" -#include #include -#include -#include -#include "../env.h" -using namespace std; +TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State ¤t, const State &goal) +{ + int m_direction = shouldFlipAcceleration(current, goal) ? -1 : 1; + State m_current = direct(current, m_direction); + State goalDir = direct(goal, m_direction); -double updateTrapezoidalProfile(MotionProfile &profile, double dt) { - // distanceToGo = positive, you're still behind the target. || distanceToGo = negative, you're ahead. - double distanceToGo = profile.targetPosition - profile.currentPosition; + if (m_current.velocity > m_constraints.maxVelocity) + { + m_current.velocity = m_constraints.maxVelocity; + } + else if (m_current.velocity < -m_constraints.maxVelocity) + { + m_current.velocity = -m_constraints.maxVelocity; + } - double changeInVelocity = 0; - double stoppingDistance; + double cutoffBegin = m_current.velocity / m_constraints.maxAcceleration; + double cutoffDistBegin = cutoffBegin * cutoffBegin * m_constraints.maxAcceleration / 2.0; - //store all the absolute value versions so that we don't waste more computation calculating them when we already have before - double absVelocity = fabs(profile.currentVelocity); - double absDistanceToGo = fabs(distanceToGo); - double absCurrentPos = fabs(profile.currentPosition); - double absTargetVelocity = fabs(profile.targetVelocity); - double absTargetPos = fabs(profile.targetPosition); - - // Formula is v^2 / 2a - stoppingDistance = (profile.currentVelocity * profile.currentVelocity) / (2.0 * profile.maxAcceleration); - - // Acceleration phase. If we aren't already at max and we still have distance left to go, add a bit more velocity on. - if (absVelocity < profile.maxVelocity && absDistanceToGo > 0) - changeInVelocity = profile.maxAcceleration * dt * (distanceToGo > 0 ? 1 : -1); + double cutoffEnd = max((goalDir.velocity - MIN_MOTOR_VELOCITY_TPS), 0.0) / m_constraints.maxAcceleration; + double cutoffDistEnd = cutoffEnd * cutoffEnd * m_constraints.maxAcceleration / 2.0; - // Deceleration if we’re getting close to target. See first if we stop right now, will we overshoot our target? If so, begin decelerating - if (absDistanceToGo <= stoppingDistance){ - float fraction; - //if they're the same sign (or one is 0) - if(profile.targetPosition * profile.currentPosition >= 0) - { - //no matter if theyr'e either both positive or both negative, it'll be between 0 and 1. You can verify this to make sure. - if(absTargetPos > absCurrentPos) - { - - fraction = profile.currentPosition / profile.targetPosition; - } - else - { - fraction = profile.targetPosition / profile.currentPosition; - } - } - //either the target or start position is negative, the other is positive - else - { - //going to have it as target / range. So liike if going from 50 to -150, that'd be 150/200. It's not really right, but it's kinda - //finnicky how we should be handling it. Should check with people smarter than me to make sure - float range = absTargetPos + absCurrentPos; - fraction = profile.targetPosition / range; - } - //making it dependent on leftover distance/dt instead of maxAcceleration*dt - changeInVelocity = -(fabs(fraction)) * profile.maxAcceleration * dt * (profile.currentVelocity > 0 ? 1 : -1); + double fullTrapezoidDist = cutoffDistBegin + (goalDir.position - m_current.position) + cutoffDistEnd; + double accelerationTime = m_constraints.maxVelocity / m_constraints.maxAcceleration; - //want to make sure that we're not going to be decelerating so hard that we just reverse ourselves and don't reach our target. So if our - //change in velocity causes use to reverse direction, just set it so we will change our velocity to 0. - if(fabs(changeInVelocity) > absTargetVelocity) - { - changeInVelocity = profile.targetVelocity * -1; - } + double fullSpeedDist = fullTrapezoidDist - accelerationTime * accelerationTime * m_constraints.maxAcceleration; + + if (fullSpeedDist < 0) + { + accelerationTime = std::sqrt(fullTrapezoidDist / m_constraints.maxAcceleration); + fullSpeedDist = 0; } - profile.targetVelocity += changeInVelocity; + State result(m_current.position, m_current.velocity); - //clip off velocity if it's too high - if (absTargetVelocity > profile.maxVelocity) - profile.targetVelocity = profile.maxVelocity * (profile.targetVelocity > 0 ? 1 : -1); + double dist = fabs(m_current.position - goalDir.position); - //if we're getting close to our target, may as well just stop it. Note that the reason we have the min function - //is because sometimes critRange will be an even smaller number when we're moving very smaller distances (like when - //we turn for edge alignment) - if(absDistanceToGo < min(profile.criticalRange, 75.0)) + double accelDist = (pow(m_constraints.maxVelocity,2) - pow(m_current.velocity,2)) / (2*m_constraints.maxAcceleration); //dist to/from max vel + //Unused double fastDist = dist - 2*accelDist; + + if(m_current.position < accelDist){ + result.velocity += t * m_constraints.maxAcceleration; + + } + + else if(dist > accelDist+100){ + result.velocity = m_constraints.maxVelocity; + serialLogln(result.velocity,3); + } + else if (dist > 10){ + result.velocity = m_current.velocity - min(sqrt(m_constraints.maxAcceleration*fabs(accelDist-dist))*.250,m_current.velocity*0.99); + serialLog("slowing ", 3); + serialLogln(result.velocity,3); + } + else { - profile.targetVelocity = 0; + result = goalDir; } - //use macros so that if we're not even logging, we won't even upload the code -#if LOGGING_LEVEL >= 3 - serialLog("Change in velocity was: ", 3); - serialLog(float(changeInVelocity), 3); - serialLog(", ", 3); + /* + double m_endAccel = accelerationTime - cutoffBegin; + double m_endFullSpeed = m_endAccel + fullSpeedDist / m_constraints.maxVelocity; + double m_endDecel = m_endFullSpeed + accelerationTime - cutoffEnd; + State result(m_current.position, m_current.velocity); - serialLog("Motion profile is outputting: ", 3); - serialLog(float(profile.targetVelocity), 3); - serialLog(", ", 3); - - serialLog("Current Position: ", 3); - serialLog(float(profile.currentPosition), 3); - serialLog(", ", 3); - - serialLog("Target Position: ", 3); - serialLogln(float(profile.targetPosition), 3); - - // serialLog("Stopping position: ", 3); - // serialLogln(float(stoppingDistance), 3); -#endif + if (t < m_endAccel) + { + result.velocity += t * m_constraints.maxAcceleration; + if (abs(result.velocity) < MIN_MOTOR_VELOCITY_TPS) { + result.velocity = MIN_MOTOR_VELOCITY_TPS; + } + result.position += (m_current.velocity + t * m_constraints.maxAcceleration / 2.0) * t; + serialLog("accelerating ", 3); + serialLogln(result.velocity,3); + } + else if (t < m_endFullSpeed) + { + result.velocity = m_constraints.maxVelocity; + result.position += + (m_current.velocity + m_endAccel * m_constraints.maxAcceleration / 2.0) * m_endAccel + + m_constraints.maxVelocity * (t - m_endAccel); + serialLog("holding ", 3); + serialLogln(result.velocity,3); + } + else if (t <= m_endDecel) + { + double timeLeft = m_endDecel - t; + result.velocity = goalDir.velocity + timeLeft * m_constraints.maxAcceleration; + result.position = goalDir.position - (goalDir.velocity * timeLeft) - (timeLeft * timeLeft * m_constraints.maxAcceleration / 2.0); + serialLog("slowing ", 3); + serialLogln(result.velocity,3); + } + else + { + result = goalDir; + } + */ + if (abs(result.position - goalDir.position) <= 10) { + result.velocity = 0; + } - return profile.targetVelocity; + return direct(result, m_direction); } - -#endif \ No newline at end of file diff --git a/src/robot/trapezoidalProfileNew.cpp b/src/robot/trapezoidalProfileNew.cpp deleted file mode 100644 index 748764e..0000000 --- a/src/robot/trapezoidalProfileNew.cpp +++ /dev/null @@ -1,107 +0,0 @@ -#include "robot/trapezoidalProfileNew.h" -#include "utils/config.h" -#include "utils/logging.h" -#include - -TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State ¤t, const State &goal) -{ - int m_direction = shouldFlipAcceleration(current, goal) ? -1 : 1; - State m_current = direct(current, m_direction); - State goalDir = direct(goal, m_direction); - - if (m_current.velocity > m_constraints.maxVelocity) - { - m_current.velocity = m_constraints.maxVelocity; - } - else if (m_current.velocity < -m_constraints.maxVelocity) - { - m_current.velocity = -m_constraints.maxVelocity; - } - - double cutoffBegin = m_current.velocity / m_constraints.maxAcceleration; - double cutoffDistBegin = cutoffBegin * cutoffBegin * m_constraints.maxAcceleration / 2.0; - - double cutoffEnd = max((goalDir.velocity - MIN_MOTOR_VELOCITY_TPS), 0.0) / m_constraints.maxAcceleration; - double cutoffDistEnd = cutoffEnd * cutoffEnd * m_constraints.maxAcceleration / 2.0; - - double fullTrapezoidDist = cutoffDistBegin + (goalDir.position - m_current.position) + cutoffDistEnd; - double accelerationTime = m_constraints.maxVelocity / m_constraints.maxAcceleration; - - double fullSpeedDist = fullTrapezoidDist - accelerationTime * accelerationTime * m_constraints.maxAcceleration; - - if (fullSpeedDist < 0) - { - accelerationTime = std::sqrt(fullTrapezoidDist / m_constraints.maxAcceleration); - fullSpeedDist = 0; - } - - State result(m_current.position, m_current.velocity); - - double dist = fabs(m_current.position - goalDir.position); - - double accelDist = (pow(m_constraints.maxVelocity,2) - pow(m_current.velocity,2)) / (2*m_constraints.maxAcceleration); //dist to/from max vel - //Unused double fastDist = dist - 2*accelDist; - - if(m_current.position < accelDist){ - result.velocity += t * m_constraints.maxAcceleration; - - } - - else if(dist > accelDist+100){ - result.velocity = m_constraints.maxVelocity; - serialLogln(result.velocity,3); - } - else if (dist > 10){ - result.velocity = m_current.velocity - min(sqrt(m_constraints.maxAcceleration*fabs(accelDist-dist))*.250,m_current.velocity*0.99); - serialLog("slowing ", 3); - serialLogln(result.velocity,3); - } - else - { - result = goalDir; - } - - /* - double m_endAccel = accelerationTime - cutoffBegin; - double m_endFullSpeed = m_endAccel + fullSpeedDist / m_constraints.maxVelocity; - double m_endDecel = m_endFullSpeed + accelerationTime - cutoffEnd; - State result(m_current.position, m_current.velocity); - - if (t < m_endAccel) - { - result.velocity += t * m_constraints.maxAcceleration; - if (abs(result.velocity) < MIN_MOTOR_VELOCITY_TPS) { - result.velocity = MIN_MOTOR_VELOCITY_TPS; - } - result.position += (m_current.velocity + t * m_constraints.maxAcceleration / 2.0) * t; - serialLog("accelerating ", 3); - serialLogln(result.velocity,3); - } - else if (t < m_endFullSpeed) - { - result.velocity = m_constraints.maxVelocity; - result.position += - (m_current.velocity + m_endAccel * m_constraints.maxAcceleration / 2.0) * m_endAccel + - m_constraints.maxVelocity * (t - m_endAccel); - serialLog("holding ", 3); - serialLogln(result.velocity,3); - } - else if (t <= m_endDecel) - { - double timeLeft = m_endDecel - t; - result.velocity = goalDir.velocity + timeLeft * m_constraints.maxAcceleration; - result.position = goalDir.position - (goalDir.velocity * timeLeft) - (timeLeft * timeLeft * m_constraints.maxAcceleration / 2.0); - serialLog("slowing ", 3); - serialLogln(result.velocity,3); - } - else - { - result = goalDir; - } - */ - if (abs(result.position - goalDir.position) <= 10) { - result.velocity = 0; - } - - return direct(result, m_direction); -} diff --git a/src/utils/config.cpp b/src/utils/config.cpp index c841204..6a60347 100644 --- a/src/utils/config.cpp +++ b/src/utils/config.cpp @@ -39,6 +39,7 @@ int TICKS_PER_ROTATION = 12000; float TRACK_WIDTH_INCHES = 8.29; float TRACK_WIDTH_CM = TRACK_WIDTH_INCHES * 2.54; float WHEEL_DIAMETER_INCHES = 4.75; +float WHEEL_RADIUS_CM = (WHEEL_DIAMETER_INCHES / 2) * 2.54; float THEORETICAL_MAX_VELOCITY_TPS = 52000; float THEORETICAL_MAX_ACCELERATION_TPSPS = 252000; float VELOCITY_LIMIT_TPS = 30000; diff --git a/src/utils/geometry.cpp b/src/utils/geometry.cpp new file mode 100644 index 0000000..b6ddb04 --- /dev/null +++ b/src/utils/geometry.cpp @@ -0,0 +1,67 @@ +#include +#include "utils/geometry.h" + +Coordinate2D::Coordinate2D() { + x = 0.0; + y = 0.0; +} + +Coordinate2D::Coordinate2D(double _x, double _y) { + x = _x; + y = _y; +} + +Coordinate2D::Coordinate2D(double angle) { + x = cos(angle); + y = sin(angle); +} + +// Coordinate2D operator+(const Coordinate2D& a, const Coordinate2D& b) { return a.transform(b); } +Coordinate2D Coordinate2D::transform(const Coordinate2D offset) const { + return Coordinate2D(x + offset.x, y + offset.y); +} + +Coordinate2D Coordinate2D::transform(double theta, double distance) const { + return Coordinate2D(x + distance * cos(theta), y + distance * sin(theta)); +} + +Coordinate2D Coordinate2D::rotate(double theta) const { + double newX = x * cos(theta) - y * sin(theta); + double newY = x * sin(theta) + y * cos(theta); + return Coordinate2D(newX, newY); +} + +// Coordinate2D operator*(const Coordinate2D& a, double factor) { return a.scale(factor); } +Coordinate2D Coordinate2D::scale(double factor) const { + return Coordinate2D(x * factor, y * factor); +} + +double Coordinate2D::distance_to(const Coordinate2D destination) const { + double dx = destination.x - x; + double dy = destination.y - y; + return pow( + pow(dy, 2) + pow(dx, 2), + .5 + ); +} + +double Coordinate2D::angle_to(const Coordinate2D destination) const { + double dx = destination.x - x; + double dy = destination.y - y; + return atan2(dy, dx); +} + +// Same as destination - self +Coordinate2D Coordinate2D::vector_to(const Coordinate2D destination) const { + Coordinate2D c(destination.x - x, destination.y - y); + + return c; +} + +double Coordinate2D::dot_product(const Coordinate2D other) const { + return (x * other.x) + (y * other.y); +} + +bool Coordinate2D::is_behind(double radians, Coordinate2D other) const { + return vector_to(other).dot_product(Coordinate2D(radians)) < 0; +} \ No newline at end of file diff --git a/src/utils/logging.cpp b/src/utils/logging.cpp index c8d9370..f622e18 100644 --- a/src/utils/logging.cpp +++ b/src/utils/logging.cpp @@ -16,27 +16,24 @@ // Prints a value or message through Serial. (The console) // ln means it sends a new newline character -enum DebugLevel { - NONE, - INFO, - DEBUG, - TRACE, - RIDICULOUS, // Use if insane -}; - void serial_printf(enum DebugLevel level, const char* fmt, ...) { - char buf[256]; + char buf[1024]; - if level > LOGGING_LEVEL { + if (level > LOGGING_LEVEL) { return; } va_list args; + va_start(args, fmt); + vsnprintf(buf, sizeof(buf), fmt, args); + va_end(args); - vsnprintf(buf, sizeof(buf) fmt, args) + Serial.print(buf); +} - Serial.print(buf) +void serial_clear() { + serial_printf(DebugLevel::NONE, "\033[3J\033[H\033[2J"); } void serialLog(const char *message, int serialLoggingLevel) diff --git a/src/wifi/packet.cpp b/src/wifi/packet.cpp index 277c2a8..d17a83b 100644 --- a/src/wifi/packet.cpp +++ b/src/wifi/packet.cpp @@ -50,7 +50,7 @@ void handlePacket(Robot& r, JsonDocument packet) { setConfig(packet["config"].as()); } else if (packet["type"] == DRIVE_TANK) { // This is received when the bot is being manually controlled via the debug page - r.drive(packet["left"], packet["right"], packet["packetId"]); + // r.drive(packet["left"], packet["right"], packet["packetId"]); } else if (packet["type"] == DRIVE_TICKS){ r.driveTicks(packet["tickDistance"], packet["packetId"]); } else if (packet["type"] == ESTOP) { @@ -74,7 +74,7 @@ void handlePacket(Robot& r, JsonDocument packet) { } else if (packet["type"] == TURN_BY_ANGLE) { r.turn(packet["deltaHeadingRadians"], packet["packetId"]); } else if (packet["type"] == DRIVE_TILES) { - r.drive(packet["tiles"], packet["packetId"]); + // r.drive(packet["tiles"], packet["packetId"]); } else if (packet["type"] == PING_SEND) { sendPingResponse(); } From 889b5afde86e81f5a5a61a5a527be3b06ba018b7 Mon Sep 17 00:00:00 2001 From: Siddharth Narayan Date: Mon, 6 Apr 2026 17:06:41 -0500 Subject: [PATCH 04/12] Significantly clean up code - Replace all instances of serialLog and serialLogLn with serial_printf - Remove #ifndef #define pattern, replace with #pragma once - Alphabitize #include statements and separate library headers, paired headers, and other headers - Add new tests - Added FPS counter to check speed - Deleted old code, including splines, trapezoidalProfile --- env.h.schema | 2 +- include/robot/control/lights.h | 10 +- include/robot/control/magnet.h | 9 +- include/robot/control/motor.h | 28 +-- include/robot/control/robot.h | 19 +- include/robot/driveTest.h | 35 ---- include/robot/pidController.h | 7 +- include/robot/profiledPIDController.h | 41 ----- include/robot/pwm.h | 8 - include/robot/splines.h | 23 --- include/robot/trapezoidalProfile.h | 64 ------- include/tests.h | 7 + include/utils/config.h | 14 +- include/utils/functions.h | 12 +- include/utils/logging.h | 20 +- include/utils/status.h | 7 +- include/utils/timer.h | 8 +- include/wifi/connection.h | 9 +- include/wifi/packet.h | 8 +- include/wifi/wireless.h | 7 +- src/calibrate.cpp.bak | 93 ---------- src/main.cpp | 57 ++---- src/robot/control/lights.cpp | 20 +- src/robot/control/magnet.cpp | 11 +- src/robot/control/motor.cpp | 38 ++-- src/robot/control/robot.cpp | 52 +++--- src/robot/driveTest.cpp | 194 -------------------- src/robot/pidController.cpp | 21 +-- src/robot/pwm.cpp | 37 ---- src/robot/splines.cpp | 252 -------------------------- src/robot/trapezoidalProfile.cpp | 107 ----------- src/tests.cpp | 84 +++++++++ src/tests/tests.cpp | 20 -- src/utils/config.cpp | 19 +- src/utils/functions.cpp | 33 +--- src/utils/geometry.cpp | 1 + src/utils/logging.cpp | 75 +------- src/utils/status.cpp | 16 +- src/utils/timer.cpp | 15 +- src/wifi/connection.cpp | 61 +++---- src/wifi/packet.cpp | 31 +--- src/wifi/wireless.cpp | 36 ++-- 42 files changed, 282 insertions(+), 1329 deletions(-) delete mode 100644 include/robot/driveTest.h delete mode 100644 include/robot/profiledPIDController.h delete mode 100644 include/robot/pwm.h delete mode 100644 include/robot/splines.h delete mode 100644 include/robot/trapezoidalProfile.h create mode 100644 include/tests.h delete mode 100644 src/calibrate.cpp.bak delete mode 100644 src/robot/driveTest.cpp delete mode 100644 src/robot/pwm.cpp delete mode 100644 src/robot/splines.cpp delete mode 100644 src/robot/trapezoidalProfile.cpp create mode 100644 src/tests.cpp delete mode 100644 src/tests/tests.cpp diff --git a/env.h.schema b/env.h.schema index 62117bb..7e286e0 100644 --- a/env.h.schema +++ b/env.h.schema @@ -16,7 +16,7 @@ #define PING_TIMEOUT 1000 #define PING_MAX_MISSES 2 -// The amount of serialLogging to do +// The amount of debugging to do // 0: None // 1: Error Logging (Logs only when an error occurs) // 2: General Logging (Logs when important things happen) diff --git a/include/robot/control/lights.h b/include/robot/control/lights.h index 7cec383..e78ec83 100644 --- a/include/robot/control/lights.h +++ b/include/robot/control/lights.h @@ -1,8 +1,6 @@ -#ifndef CHESSBOT_LIGHT_SENSOR_H -#define CHESSBOT_LIGHT_SENSOR_H +#pragma once -// Built-In Libraries -#include "Arduino.h" +#include class Light { public: @@ -28,6 +26,4 @@ class Light { void setupIR(); void activateIR(); -void deactivateIR(); - -#endif \ No newline at end of file +void deactivateIR(); \ No newline at end of file diff --git a/include/robot/control/magnet.h b/include/robot/control/magnet.h index 72f5be5..cacc310 100644 --- a/include/robot/control/magnet.h +++ b/include/robot/control/magnet.h @@ -1,7 +1,6 @@ -#ifndef MAGNET_H -#define MAGNET_H +#pragma once -#include "Arduino.h" +#include #include "DFRobot_BMM350.h" struct MagnetReading { @@ -32,6 +31,4 @@ class Magnet { float previousReading = -1.0; bool activeFlag = false; -}; - -#endif // MAGNET_H \ No newline at end of file +}; \ No newline at end of file diff --git a/include/robot/control/motor.h b/include/robot/control/motor.h index d09fb67..3707084 100644 --- a/include/robot/control/motor.h +++ b/include/robot/control/motor.h @@ -1,13 +1,13 @@ -#ifndef CHESSBOT_MOTOR_H -#define CHESSBOT_MOTOR_H +#pragma once +#include #include #include "utils/config.h" -#include "Encoder.h" -const float TIRE_RADIUS = 5.9; -const float TIRE_CIRCUMFERENCE = M_PI * 2 * TIRE_RADIUS; + +const double TIRE_RADIUS = 5.9; +const double TIRE_CIRCUMFERENCE = M_PI * 2 * TIRE_RADIUS; class Motor { public: @@ -16,9 +16,9 @@ class Motor { void tick(); // Sets the motor power - // power is a float between [-1, 1] - float power(); - void power(float power); + // power is a double between [-1, 1] + double power(); + void power(double power); void encoder_reset(); double dist(); // Total distance in cm @@ -30,19 +30,11 @@ class Motor { bool inverted; - float _power; + double _power; int32_t raw_enc_value; int32_t prev_raw_enc_value; Encoder encoder; - - - }; -// Encoder EncoderA(ENCODER_A_PIN1, ENCODER_A_PIN2); -// void setupMotors(); -// void setLeftPower(float power); -// void setRightPower(float power); - -#endif \ No newline at end of file +int power_to_duty(double power); \ No newline at end of file diff --git a/include/robot/control/robot.h b/include/robot/control/robot.h index d153913..c03d2e0 100644 --- a/include/robot/control/robot.h +++ b/include/robot/control/robot.h @@ -1,13 +1,12 @@ -#ifndef CHESSBOT_CONTROL_H -#define CHESSBOT_CONTROL_H +#pragma once + +#include -#include "Arduino.h" -#include "utils/config.h" -#include "utils/geometry.h" -#include "robot/trapezoidalProfile.h" #include "robot/control/lights.h" #include "robot/control/motor.h" #include "robot/pidController.h" +#include "utils/config.h" +#include "utils/geometry.h" enum OperatingMode { @@ -74,7 +73,7 @@ class Robot { static int batteryLevel(); // Runs all the necessary processing for each tick of the global event loop - void tick(unsigned long frame, uint32_t delay); + void tick(uint32_t frame, uint32_t delay); void center(); void drive(float tiles, std::string id); @@ -109,7 +108,5 @@ class Robot { void center_tick(uint32_t delay); void pid_tick(uint32_t delay); - void print_status(); -}; - -#endif \ No newline at end of file + void print_status(uint32_t delay); +}; \ No newline at end of file diff --git a/include/robot/driveTest.h b/include/robot/driveTest.h deleted file mode 100644 index 5a0d43f..0000000 --- a/include/robot/driveTest.h +++ /dev/null @@ -1,35 +0,0 @@ -#ifndef CHESSBOT_DRIVETEST_H -#define CHESSBOT_DRIVETEST_H - -class MotorEncoderTest -{ -public: - inline void startMotorAndEncoderTest() { init(); } - -private: - int startEncoderA; - int _startEncoderB; - int startEncoderB; - int prevEncA; - int prevEncB; - unsigned long prevTime; - float maxEncoderVelocity = 0; - float prevEncVelA; - float prevEncVelB; - float maxEncoderAccel = 0; - unsigned long encoderCheckTimerId; - bool testSuccessful; - const int ENCODER_TOLERANCE = 100; - - void init(); - void testLeftMotor(); - void testWait(); - void testRightMotor(); - void testDriveForward(); - void checkMotorDeadzone(bool leftMotor); - void testMotorDeadzones(); - void checkEncoderVelocity(); - void testDriveDone(); -}; - -#endif \ No newline at end of file diff --git a/include/robot/pidController.h b/include/robot/pidController.h index 92ce073..46209d1 100644 --- a/include/robot/pidController.h +++ b/include/robot/pidController.h @@ -1,5 +1,4 @@ -#ifndef PID_CONTROLLER_H -#define PID_CONTROLLER_H +#pragma once class PIDController { @@ -44,6 +43,4 @@ class ContinuousPIDController : public PIDController } private: double minInput, maxInput; // Input range for continuous wrapping -}; - -#endif // PID_CONTROLLER_H +}; \ No newline at end of file diff --git a/include/robot/profiledPIDController.h b/include/robot/profiledPIDController.h deleted file mode 100644 index e11cd0b..0000000 --- a/include/robot/profiledPIDController.h +++ /dev/null @@ -1,41 +0,0 @@ -#ifndef PROFILED_PID_CONTROLLER_H -#define PROFILED_PID_CONTROLLER_H - -#include "robot/pidController.h" -#include "robot/trapezoidalProfile.h" - -class ProfiledPIDController { -public: - ProfiledPIDController(double kp, double ki, double kd, - double minOutput, double maxOutput, - double errorTolerance, - const TrapezoidProfile::Constraints& constraints) - : pid(kp, ki, kd, minOutput, maxOutput, errorTolerance), profile(constraints), lastTime(0.0) {} - - // Call this every control loop - double Compute(double goalPosition, double actualPosition, double actualVelocity, double dt) { - TrapezoidProfile::State current(actualPosition, actualVelocity); - TrapezoidProfile::State goal(goalPosition, 0.0); // Assume goal velocity is zero - - // Generate profile for current time - TrapezoidProfile::State profiledSetpoint = profile.calculate(lastTime, current, goal); - - // PID tracks profiled position - double output = pid.Compute(profiledSetpoint.position, actualPosition, dt); - - lastTime += dt; - return output; - } - - void Reset() { - pid.Reset(); - lastTime = 0.0; - } - -private: - PIDController pid; - TrapezoidProfile profile; - double lastTime; -}; - -#endif // PROFILED_PID_CONTROLLER_H \ No newline at end of file diff --git a/include/robot/pwm.h b/include/robot/pwm.h deleted file mode 100644 index 7dea316..0000000 --- a/include/robot/pwm.h +++ /dev/null @@ -1,8 +0,0 @@ -#ifndef CHESSBOT_PWM_H -#define CHESSBOT_PWM_H - -void setupPWM(int pin); -void writePWM(int channel, int dutyCycle); -int mapPowerToDuty(float power); - -#endif \ No newline at end of file diff --git a/include/robot/splines.h b/include/robot/splines.h deleted file mode 100644 index 8cc6cd7..0000000 --- a/include/robot/splines.h +++ /dev/null @@ -1,23 +0,0 @@ -// #ifndef CHESSBOT_SPLINES_H -// #define CHESSBOT_SPLINES_H - -// #include -// #include -// #include -// #include "wifi/packet.h" -// #include "trapezoidalProfile.h" - -// struct Point { -// float x; -// float y; -// }; - -// static std::queue> timeSlicesToExecute; - -// void velocityUpdateTimerFunction(std::string id); -// void danceMonkeyQuadratic(std::string id, Point start, Point control, Point end, float totalTime); -// void danceMonkeyCubic(std::string id, Point start, Point control1, Point control2, Point end, float totalTime); -// void startCustomMotionProfileTimer(int leftPositionTarget, int rightPositionTarget, double profileDuration, std::string id); -// void customMotionProfileTimerFunction(MotionProfile &customProfileA, MotionProfile &customProfileB, double dt, std::string id); - -// #endif \ No newline at end of file diff --git a/include/robot/trapezoidalProfile.h b/include/robot/trapezoidalProfile.h deleted file mode 100644 index 41da6ff..0000000 --- a/include/robot/trapezoidalProfile.h +++ /dev/null @@ -1,64 +0,0 @@ -#ifndef TRAPEZOIDAL_PROFILE_NEW_H -#define TRAPEZOIDAL_PROFILE_NEW_H - -#include -#include - -class TrapezoidProfile -{ -public: - struct Constraints - { - double maxVelocity; - double maxAcceleration; - - Constraints(double maxVelocity, double maxAcceleration) - { - if (maxVelocity < 0.0 || maxAcceleration < 0.0) - { - throw std::runtime_error("Constraints must be non-negative"); - } - this->maxVelocity = maxVelocity; - this->maxAcceleration = maxAcceleration; - // Remove MathSharedStore.reportUsage for now (Java-specific) - } - }; - - struct State - { - double position = 0.0; - double velocity = 0.0; - - State() = default; - State(double position, double velocity) - : position(position), velocity(velocity) {} - - bool operator==(const State& rhs) const - { - // Don't use equals for floats? - return position == rhs.position && velocity == rhs.velocity; - } - }; - - TrapezoidProfile(const Constraints& constraints) - : m_constraints(constraints) {} - - State calculate(double t, const State& current, const State& goal); - - // bool isFinished(double t) const { return t >= totalTime(); } - -private: - static bool shouldFlipAcceleration(const State& initial, const State& goal) - { - return initial.position > goal.position; - } - - State direct(const State& in, int m_direction) const - { - return State(in.position * m_direction, in.velocity * m_direction); - } - - Constraints m_constraints; -}; - -#endif \ No newline at end of file diff --git a/include/tests.h b/include/tests.h new file mode 100644 index 0000000..5dde1be --- /dev/null +++ b/include/tests.h @@ -0,0 +1,7 @@ +#include "robot/control/robot.h" + +// Moves to 0 -> 2PI -> 0 -> 4PI -> 0 on a clock to test angular PID +void circle_test(Robot& r); + +// Moves to the points on a 1x1 meter square +void square_test(Robot& r); \ No newline at end of file diff --git a/include/utils/config.h b/include/utils/config.h index 86f932e..1b4b40a 100644 --- a/include/utils/config.h +++ b/include/utils/config.h @@ -1,14 +1,10 @@ -#ifndef CHESSBOT_CONFIG_H -#define CHESSBOT_CONFIG_H +#pragma once -// Built-In Libraries -#include "Arduino.h" - -// external Libraries +#include #include extern int loopDelayMilliseconds; -extern unsigned long frame; +extern uint32_t frame; // These variables are declared here, and defined in config.cpp // config.cpp is the only file that should be modifying these values. Everything else is read-only @@ -51,6 +47,4 @@ extern int MAGNET_CCW_IS_POSITIVE; // Set to 1 if counterclockwise rotation is p extern float PID_POSITION_TOLERANCE; extern float PID_VELOCITY_TOLERANCE; -void setConfig(JsonObject config); - -#endif \ No newline at end of file +void setConfig(JsonObject config); \ No newline at end of file diff --git a/include/utils/functions.h b/include/utils/functions.h index af12db3..f153ea8 100644 --- a/include/utils/functions.h +++ b/include/utils/functions.h @@ -1,13 +1,9 @@ -#ifndef CHESSBOT_FUNCTIONS_H -#define CHESSBOT_FUNCTIONS_H +#pragma once -// Built-In Libraries -#include "Arduino.h" +#include -float fmap(float x, float in_min, float in_max, float out_min, float out_max); +double fmap(double x, double in_min, double in_max, double out_min, double out_max); bool approxEquals(int x, int y, int epsilon); bool approxEquals(double x, double y, double epsilon); int radiansToTicks(double angle); -std::string unint8ArrayToHexString(uint8_t* oldArray, int len); - -#endif \ No newline at end of file +std::string unint8ArrayToHexString(uint8_t* oldArray, int len); \ No newline at end of file diff --git a/include/utils/logging.h b/include/utils/logging.h index 2de56ae..efd9a95 100644 --- a/include/utils/logging.h +++ b/include/utils/logging.h @@ -1,7 +1,5 @@ -#ifndef CHESSBOT_LOGGING_H -#define CHESSBOT_LOGGING_H +#pragma once -// Built-In Libraries #include enum DebugLevel { @@ -12,19 +10,5 @@ enum DebugLevel { RIDICULOUS, // Use if insane }; -void serialLog(const char *message, int serialLoggingLevel); -void serialLog(int value, int serialLoggingLevel); -void serialLog(double value, int serialLoggingLevel); -void serialLog(std::string value, int serialLoggingLevel); - -void serialLogln(const char *message, int serialLoggingLevel); -void serialLogln(int value, int serialLoggingLevel); -void serialLogln(double value, int serialLoggingLevel); -void serialLogln(float value, int serialLoggingLevel); -void serialLogln(std::string value, int serialLoggingLevel); - -void serialLogError(char message[], int error); - void serial_printf(enum DebugLevel level, const char* fmt, ...); -void serial_clear(); -#endif \ No newline at end of file +void serial_clear(); \ No newline at end of file diff --git a/include/utils/status.h b/include/utils/status.h index 8b74e45..33dc159 100644 --- a/include/utils/status.h +++ b/include/utils/status.h @@ -1,5 +1,4 @@ -#ifndef CHESSBOT_STATUS_H -#define CHESSBOT_STATUS_H +#pragma once bool getServerConnectionStatus(); void setServerConnectionStatus(bool value); @@ -8,6 +7,4 @@ bool getWiFiConnectionStatus(); void setWiFiConnectionStatus(bool value); bool getStoppedStatus(); -void setStoppedStatus(bool value); - -#endif \ No newline at end of file +void setStoppedStatus(bool value); \ No newline at end of file diff --git a/include/utils/timer.h b/include/utils/timer.h index 93071b2..0d38ceb 100644 --- a/include/utils/timer.h +++ b/include/utils/timer.h @@ -1,7 +1,5 @@ -#ifndef CHESSBOT_TIMER_H -#define CHESSBOT_TIMER_H +#pragma once -// Built-In Libraries #include //we're gonna need this if we need to use delays which require functions #include @@ -30,6 +28,4 @@ void timerReset(unsigned long id); void timerCancel(unsigned long id); void timerCancelAll(); -void timerStep(); - -#endif \ No newline at end of file +void timerStep(); \ No newline at end of file diff --git a/include/wifi/connection.h b/include/wifi/connection.h index 98ff8ff..aba79bd 100644 --- a/include/wifi/connection.h +++ b/include/wifi/connection.h @@ -1,7 +1,6 @@ -#ifndef CHESSBOT_CONNECTION_H -#define CHESSBOT_CONNECTION_H +#pragma once -#include "Arduino.h" +#include #include void connectServer(); @@ -14,6 +13,4 @@ JsonDocument acceptData(); void sendPacket(JsonDocument& packet); void sendActionSuccess(std::string messageId); void sendActionFail(std::string messageId); -void sendPingResponse(); - -#endif \ No newline at end of file +void sendPingResponse(); \ No newline at end of file diff --git a/include/wifi/packet.h b/include/wifi/packet.h index 7389a51..6d414e4 100644 --- a/include/wifi/packet.h +++ b/include/wifi/packet.h @@ -1,7 +1,6 @@ -#ifndef CHESSBOT_PACKET_H -#define CHESSBOT_PACKET_H +#pragma once -#include "Arduino.h" +#include #include @@ -11,5 +10,4 @@ std::string unint8ArrayToHexString(uint8_t* oldArray, int len); void constructHelloPacket(JsonDocument& packet); void constructSuccessPacket(JsonDocument& packet, std::string messageId); void constructFailPacket(JsonDocument& packet, std::string messageId); -void constructPingPacket(JsonDocument& packet); -#endif \ No newline at end of file +void constructPingPacket(JsonDocument& packet); \ No newline at end of file diff --git a/include/wifi/wireless.h b/include/wifi/wireless.h index 3f87e5b..0bbc5bb 100644 --- a/include/wifi/wireless.h +++ b/include/wifi/wireless.h @@ -1,5 +1,4 @@ -#ifndef CHESSBOT_WIRELESS_H -#define CHESSBOT_WIRELESS_H +#pragma once const char* getWifiStatus(int status); bool checkWiFiConnection(); @@ -7,6 +6,4 @@ void confirmWiFi(); void connectWiFI(); void reconnectWiFI(); void disconnectWiFI(); -void createWiFi(); - -#endif \ No newline at end of file +void createWiFi(); \ No newline at end of file diff --git a/src/calibrate.cpp.bak b/src/calibrate.cpp.bak deleted file mode 100644 index c42fae7..0000000 --- a/src/calibrate.cpp.bak +++ /dev/null @@ -1,93 +0,0 @@ -/*! - * @file getGeomagneticData.ino - * @brief Get the calibration data - * @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north - * @n Experimental phenomenon: serial print the geomagnetic data of x-axis, y-axis and z-axis and the compass degree - * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - * @license The MIT License (MIT) - * @author [GDuang](yonglei.ren@dfrobot.com) - * @version V1.0.0 - * @date 2024-05-06 - * @url https://github.com/DFRobot/DFRobot_BMM350/ - */ - -// ======================================================= -// 请先阅读项目 https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration -// Please read https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration -// 包含使用说明、校准步骤。 -// It contains usage instructions, calibration steps. -// ======================================================= -#include "DFRobot_BMM350.h" - -DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); -void setup() { - Serial.begin(115200); - while (!Serial) - ; - Wire.begin(8, 9); - while (bmm350.begin()) { - Serial.println("bmm350 init failed, Please try again!"); - delay(1000); - } - Serial.println("bmm350 init success!"); - - /** - * Set sensor operation mode - * opMode: - * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - * eBmm350NormalMode // normal mode Get geomagnetic data normally. - * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. - * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. - */ - bmm350.setOperationMode(eBmm350NormalMode); - /** - * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - * presetMode: - * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. - * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. - * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. - * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. - * rate: - * BMM350_DATA_RATE_1_5625HZ - * BMM350_DATA_RATE_3_125HZ - * BMM350_DATA_RATE_6_25HZ - * BMM350_DATA_RATE_12_5HZ (default rate) - * BMM350_DATA_RATE_25HZ - * BMM350_DATA_RATE_50HZ - * BMM350_DATA_RATE_100HZ - * BMM350_DATA_RATE_200HZ - * BMM350_DATA_RATE_400HZ - */ - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); - - /** - * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. - * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. - */ - bmm350.setMeasurementXYZ(); -} - -void loop() { - sBmm350MagData_t magData = bmm350.getGeomagneticData(); - Serial.print("Raw:"); - Serial.print(0); - Serial.print(','); - Serial.print(0); - Serial.print(','); - Serial.print(0); - Serial.print(','); - Serial.print(0); - Serial.print(','); - Serial.print(0); - Serial.print(','); - Serial.print(0); - Serial.print(','); - Serial.print(magData.x*10); - Serial.print(','); - Serial.print(magData.y*10); - Serial.print(','); - Serial.print(magData.z*10); - Serial.println(); - delay(100); -} diff --git a/src/main.cpp b/src/main.cpp index b66b085..ba0ed19 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -1,21 +1,20 @@ -#include "Arduino.h" +#include -// Custom Libraries +#include "../env.h" +#include "robot/control/magnet.h" +#include "robot/control/robot.h" +#include "robot/pidController.h" +#include "tests.h" #include "utils/config.h" #include "utils/logging.h" -#include "utils/timer.h" #include "utils/status.h" -#include "wifi/wireless.h" +#include "utils/timer.h" #include "wifi/connection.h" -#include "robot/control/robot.h" -#include "../env.h" -#include "robot/pidController.h" -#include "robot/control/magnet.h" +#include "wifi/wireless.h" -void loop_test(); +uint32_t frame = 0; -unsigned long frame = 0; -unsigned long previousTime = 0; // For loop timing +uint32_t previous_time = 0; Robot robot = Robot(); @@ -25,13 +24,12 @@ void setup() { if (LOGGING_LEVEL > 0) Serial.begin(115200); delay(STARTUP_DELAY); - serialLogln("Finished Delay!", 2); + serial_printf(DebugLevel::DEBUG, "Finished Delay!\n"); // Create a WiFi network for the laptop to connect to if (!RUN_OFFLINE) connectWiFI(); - previousTime = millis() - loopDelayMilliseconds; - + previous_time = micros(); // robot.center(); } @@ -51,34 +49,11 @@ void loop() { if (getServerConnectionStatus()) acceptData(); } - // Run control loop - // TODO change time parameter to be actual delta time, not just delay between loops - unsigned long deltaTime = millis() - previousTime; - previousTime = millis(); + uint32_t delta = micros() - previous_time; + previous_time = micros(); - loop_test(); - robot.tick(frame, (uint32_t)deltaTime); + square_test(robot); + robot.tick(frame, delta); frame++; -} - -void loop_test() { - unsigned long time_seconds = millis() / 1000; - - Coordinate2D goal; - double rotation = 0; - - if (time_seconds > 10) { - goal = Coordinate2D(100, 100); - } - - if (time_seconds > 20) { - goal = Coordinate2D(0, 0); - } - - if (time_seconds > 30) { - goal = Coordinate2D(500, 200); - } - - robot.drive(goal, rotation); } \ No newline at end of file diff --git a/src/robot/control/lights.cpp b/src/robot/control/lights.cpp index 2399fc8..ad6f5d5 100644 --- a/src/robot/control/lights.cpp +++ b/src/robot/control/lights.cpp @@ -1,16 +1,10 @@ -#ifndef CHESSBOT_LIGHT_SENSOR_CPP -#define CHESSBOT_LIGHT_SENSOR_CPP +#include -// Associated Header File #include "robot/control/lights.h" -#include "../../../env.h" - -// Built-In Libraries -#include "Arduino.h" -// Custom Libraries -#include "utils/logging.h" +#include "../../../env.h" #include "utils/config.h" +#include "utils/logging.h" static short LIGHT_RAW_VALUE_CUTOFF = 7600; bool is_light_value_on(short value) { @@ -62,9 +56,9 @@ bool IR_activated = false; // Sets the IR (Infrared) Blaster to be able to output void setupIR() { - serialLogln("Setting Up Light Sensors...", 2); + serial_printf(DebugLevel::DEBUG, "Setting Up Light Sensors...\n"); pinMode(RELAY_IR_LED_PIN, OUTPUT); - serialLogln("Light Sensors Setup!", 2); + serial_printf(DebugLevel::DEBUG, "Light Sensors Setup!\n"); } // Turns on the IR Blaster @@ -86,6 +80,4 @@ void deactivateIR() { // digitalWrite(RELAY_IR_LED_PIN, LOW); // IR_activated = false; -} - -#endif \ No newline at end of file +} \ No newline at end of file diff --git a/src/robot/control/magnet.cpp b/src/robot/control/magnet.cpp index 5936ab1..b271498 100644 --- a/src/robot/control/magnet.cpp +++ b/src/robot/control/magnet.cpp @@ -1,6 +1,7 @@ -#include "DFRobot_BMM350.h" +#include #include "robot/control/magnet.h" + #include "utils/logging.h" #define SDA_PIN 8 @@ -15,15 +16,13 @@ Magnet::Magnet() while (maxTries-- > 0 && (errorCode=bmm350.begin())) { delay(500); - serialLog("Retrying BMM350 connection... (error code ", 1); - serialLog(errorCode, 1); - serialLogln(")", 1); + serial_printf(DebugLevel::INFO, "Retrying BMM350 connection... (error code %d)\n", errorCode); } if (errorCode > 0) { - serialLogln("BMM350 not detected at default I2C address. Check wiring.", 1); + serial_printf(DebugLevel::INFO, "BMM350 not detected at default I2C address. Check wiring.\n"); return; } else { - serialLogln("BMM350 detected.", 1); + serial_printf(DebugLevel::INFO, "BMM350 detected.\n"); } bmm350.setOperationMode(eBmm350NormalMode); bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY, BMM350_DATA_RATE_25HZ); diff --git a/src/robot/control/motor.cpp b/src/robot/control/motor.cpp index 13c1d64..6c01692 100644 --- a/src/robot/control/motor.cpp +++ b/src/robot/control/motor.cpp @@ -1,15 +1,9 @@ -#ifndef CHESSBOT_MOTOR_CPP -#define CHESSBOT_MOTOR_CPP +#include -// Associated Header File #include "robot/control/motor.h" -// Built-In Libraries -#include "Arduino.h" - -// Custom Libraries -#include "robot/pwm.h" #include "utils/config.h" +#include "utils/functions.h" #include "utils/logging.h" Motor::Motor(bool _inverted, int motor_pin_a, int motor_pin_b, uint8_t enc_pin_a, uint8_t enc_pin_b) @@ -18,8 +12,8 @@ Motor::Motor(bool _inverted, int motor_pin_a, int motor_pin_b, uint8_t enc_pin_a pin_a = motor_pin_a; pin_b = motor_pin_b; - setupPWM(pin_a); - setupPWM(pin_b); + pinMode(pin_a, OUTPUT); + pinMode(pin_b, OUTPUT); } void Motor::tick() { @@ -29,7 +23,7 @@ void Motor::tick() { } // Returns the current power of the motor -float Motor::power() { +double Motor::power() { if (inverted) { return -_power; } @@ -40,7 +34,7 @@ float Motor::power() { // This will set how fast and what direction left motor will spin // Value between [-1, 1] // Negative is backwards, Positive is forwards -void Motor::power(float __power) { +void Motor::power(double __power) { if (inverted) { __power = -__power; } @@ -53,15 +47,14 @@ void Motor::power(float __power) { if (_power > 0) { - writePWM(pin_b, 0); - writePWM(pin_a, mapPowerToDuty(_power)); + analogWrite(pin_b, 0); + analogWrite(pin_a, power_to_duty(_power)); } else { - writePWM(pin_a, 0); - writePWM(pin_b, mapPowerToDuty(-_power)); + analogWrite(pin_a, 0); + analogWrite(pin_b, power_to_duty(-_power)); } - serialLog("Motor Power: ", 4); - serialLogln(_power, 4); + serial_printf(DebugLevel::RIDICULOUS, "Motor Power: %f\n", _power); } void Motor::encoder_reset() { @@ -85,4 +78,11 @@ double Motor::tick_dist() { return ((double)dist / TICKS_PER_ROTATION) * TIRE_CIRCUMFERENCE; } -#endif \ No newline at end of file +// Takes in a power between [0, 1] +// We use this to change a double power between 0-1 to an int duty cycle between 0-4096 +int power_to_duty(double power) { + int value = fmap(power, 0.0, 1.0, 0.0, 4096); + serial_printf(DebugLevel::RIDICULOUS, "Mapped Duty: %d\n", value); + + return value; +} \ No newline at end of file diff --git a/src/robot/control/robot.cpp b/src/robot/control/robot.cpp index 726686f..5f4ccda 100644 --- a/src/robot/control/robot.cpp +++ b/src/robot/control/robot.cpp @@ -1,30 +1,26 @@ -// Associated Header File -#include "robot/control/robot.h" - -// Built-In Libraries -#include "Arduino.h" +#include #include #include +#include -// Custom Libraries -#include "utils/logging.h" -#include "utils/timer.h" +#include "robot/control/robot.h" + +#include "../../../env.h" +#include "robot/control/lights.h" +#include "robot/control/motor.h" +#include "robot/pidController.h" #include "utils/config.h" -#include "utils/logging.h" +#include "utils/functions.h" #include "utils/geometry.h" +#include "utils/logging.h" +#include "utils/logging.h" #include "utils/status.h" -#include "robot/control/motor.h" -#include "robot/control/lights.h" +#include "utils/timer.h" #include "wifi/connection.h" -#include "robot/pidController.h" -#include "robot/driveTest.h" -#include "../../../env.h" -#include -#include "utils/functions.h" MotionController::MotionController() - : DistVelocityController(0.5, 0.01, 0.15, -1, +1, 0.0), - AVelocityController(0.5, 0.1, 0.15, -1, +1, 0.0) + : DistVelocityController(0.1, 0.2, 0.05, -1, +1, 0.0), + AVelocityController(.1, 0.2, 0.05, -1, +1, 0.0) {} void MotionController::set_goal(Coordinate2D _goal_destination, double _goal_angle) { @@ -41,7 +37,7 @@ std::tuple MotionController::update_speeds(Coordinate2D position dist_err = -dist_err; } - if (abs(dist_err) < 1) { + if (abs(dist_err) < 3) { if (phase == TRAVELLING) { DistVelocityController.Reset(); AVelocityController.Reset(); @@ -92,12 +88,16 @@ Robot::Robot() back_right_light(PHOTODIODE_D_PIN) {} -void Robot::print_status() { +void Robot::print_status(uint32_t delay) { serial_clear(); activateIR(); + + uint32_t fps = delay == 0 ? 0 : 1000000 / delay; serial_printf( DebugLevel::INFO, - "position: (%fcm, %fcm) rotation: %frad \n" + "FPS: %lu (%luus)\n" + + "Position: (%fcm, %fcm) rotation: %frad \n" "Centering status: %d\n\n" "left power: %f right power: %f \n" @@ -107,6 +107,8 @@ void Robot::print_status() { "front lights -- left: %hd discrete %d right: %hd discrete %d\n" "back lights -- left: %hd discrete %d right: %hd discrete %d\n\n", + fps, delay, + position.x, position.y, rotation, centeringStatus, @@ -127,7 +129,7 @@ int Robot::batteryLevel() { return analogRead(BATTERY_VOLTAGE_PIN) - BATTERY_VOLTAGE_OFFSET; } -void Robot::tick(unsigned long frame, uint32_t delay) { +void Robot::tick(uint32_t frame, uint32_t delay) { // Pass through tick, update all sensors / motors left.tick(); right.tick(); @@ -161,12 +163,12 @@ void Robot::tick(unsigned long frame, uint32_t delay) { if (frame % 64 == 0) { - print_status(); + print_status(delay); } } void Robot::pid_tick(uint32_t delay) { - std::tuple motor_speeds = motion_controller.update_speeds(position, rotation, (double)delay/1000); + std::tuple motor_speeds = motion_controller.update_speeds(position, rotation, (double)delay / 1000000); drive(motor_speeds, "NULL"); } @@ -245,5 +247,5 @@ void Robot::stop() { // Set the goal to where we are right now, so the robot doesn't move motion_controller.set_goal(position, rotation); - serialLogln("Bot Stopped!", 2); + serial_printf(DebugLevel::DEBUG, "Bot Stopped!\n"); } \ No newline at end of file diff --git a/src/robot/driveTest.cpp b/src/robot/driveTest.cpp deleted file mode 100644 index fb9da45..0000000 --- a/src/robot/driveTest.cpp +++ /dev/null @@ -1,194 +0,0 @@ -// #ifndef CHESSBOT_DRIVETEST_CPP -// #define CHESSBOT_DRIVETEST_CPP - -// #include "robot/driveTest.h" -// #include "Arduino.h" -// #include "robot/control/motor.h" -// #include "utils/timer.h" -// #include "utils/logging.h" - -// void MotorEncoderTest::init() -// { -// serialLogln("Starting Motor & Encoder Test", 2); - -// this->testSuccessful = true; - -// this->startEncoderA = readLeftEncoder(); -// this->_startEncoderB = readRightEncoder(); - -// setLeftPower(1); -// setRightPower(0); -// auto fp = std::bind(&MotorEncoderTest::testLeftMotor, this); -// timerDelay(1000, fp); -// } - -// void MotorEncoderTest::testLeftMotor() -// { -// int encoderAValue = readLeftEncoder(); -// if (encoderAValue > (this->startEncoderA + this->ENCODER_TOLERANCE)) -// { -// serialLogln("Encoder A (lbl RightEncoder) is aligned with left motor (lbl M1). (Positive motor = positive encoder = CW from Motor POV)", 2); -// } -// else if (encoderAValue < (this->startEncoderA - this->ENCODER_TOLERANCE)) -// { -// serialLogln("[WARN] Encoder A (lbl RightEncoder) is inverted with left motor (lbl M1)!", 2); -// this->testSuccessful = false; -// } -// else -// { -// serialLogln("[ERR] Encoder A (lbl RightEncoder) is not associated with left motor (lbl M1)!", 2); -// this->testSuccessful = false; -// } -// setLeftPower(0); -// setRightPower(0); -// auto fp = std::bind(&MotorEncoderTest::testWait, this); -// timerDelay(2000, fp); -// } - -// void MotorEncoderTest::testWait() -// { -// this->startEncoderB = readRightEncoder(); - -// setLeftPower(0); -// setRightPower(1); -// auto fp = std::bind(&MotorEncoderTest::testRightMotor, this); -// timerDelay(1000, fp); -// } - -// void MotorEncoderTest::testRightMotor() -// { -// int encoderBValue = readRightEncoder(); -// if (encoderBValue > (this->startEncoderB + this->ENCODER_TOLERANCE)) -// { -// serialLogln("Encoder B (lbl LeftEncoder) is aligned with right motor (lbl M2). (Positive motor = positive encoder = CCW from Motor POV)", 2); -// } -// else if (encoderBValue < (this->startEncoderB - this->ENCODER_TOLERANCE)) -// { -// serialLogln("[WARN] Encoder B (lbl LeftEncoder) is inverted with right motor (lbl M2)!", 2); -// this->testSuccessful = false; -// } -// else -// { -// serialLogln("[ERR] Encoder B (lbl LeftEncoder) is not associated with right motor (lbl M2)!", 2); -// this->testSuccessful = false; -// } -// setRightPower(0); -// if (this->testSuccessful) -// { -// serialLogln("Test successful!", 2); -// serialLogln("To go forward, both left and right should be set positive.", 2); -// auto fp = std::bind(&MotorEncoderTest::testMotorDeadzones, this); -// timerDelay(2000, fp); -// } -// else -// { -// int encoderAValue = readLeftEncoder(); -// if ((this->startEncoderA - this->ENCODER_TOLERANCE) <= encoderAValue && encoderAValue <= (this->startEncoderA + this->ENCODER_TOLERANCE)) { -// serialLogln("[WARN] Encoder A (lbl RightEncoder) did not significantly change over the course of the test!", 2); -// } -// if ((this->_startEncoderB - this->ENCODER_TOLERANCE) <= encoderBValue && encoderBValue <= (this->_startEncoderB + this->ENCODER_TOLERANCE)) -// { -// serialLogln("[WARN] Encoder B (lbl LeftEncoder) did not significantly change over the course of the test!", 2); -// } -// serialLogln("Test failed for one or more reasons, listed above.", 2); -// if (((this->startEncoderA - this->ENCODER_TOLERANCE) > encoderAValue || encoderAValue > (this->startEncoderA + this->ENCODER_TOLERANCE)) -// && ((this->_startEncoderB - this->ENCODER_TOLERANCE) > encoderBValue || encoderBValue > (this->_startEncoderB + this->ENCODER_TOLERANCE))) { -// serialLogln("Encoder A and B changed but did not have the correct associations. Maybe swap the motors or the encoders?", 2); -// } -// } -// } - -// void MotorEncoderTest::checkMotorDeadzone(bool leftMotor) -// { -// serialLogln(leftMotor ? "Checking LEFT motor deadzone..." : "Checking RIGHT motor deadzone...", 2); -// const float powerStep = 0.01f; -// const float maxPower = 1.0f; -// const int encoderThreshold = 200; // Minimum encoder ticks to consider as movement -// int initialEncoder = leftMotor ? readLeftEncoder() : readRightEncoder(); - -// for (float power = 0.0f; power <= maxPower; power += powerStep) -// { -// if (leftMotor) -// { -// setLeftPower(power); -// setRightPower(0); -// } -// else -// { -// setLeftPower(0); -// setRightPower(power); -// } -// delay(200); // Wait for motor to respond - -// int currentEncoder = leftMotor ? readLeftEncoder() : readRightEncoder(); -// if (abs(currentEncoder - initialEncoder) >= encoderThreshold) -// { -// serialLog("Deadzone crossed at power: ", 2); -// serialLogln(power, 2); -// break; -// } -// } -// setLeftPower(0); -// setRightPower(0); -// } - -// void MotorEncoderTest::testMotorDeadzones() -// { -// delay(500); -// checkMotorDeadzone(true); // Check left motor -// delay(500); -// checkMotorDeadzone(false); // Check right motor -// serialLogln("Deadzone test complete!", 2); -// auto fp = std::bind(&MotorEncoderTest::testDriveForward, this); -// timerDelay(1000, fp); -// } - -// void MotorEncoderTest::checkEncoderVelocity() -// { -// int encA = readLeftEncoder(); -// int encB = readRightEncoder(); -// float timeDiff = (millis() - prevTime) / 1000.0; // in seconds -// float encAVel = (encA - prevEncA) / timeDiff; -// float encBVel = (encB - prevEncB) / timeDiff; -// float encAAccel = (encAVel - prevEncVelA) / timeDiff; // Am I miscalculating acceleration? Should be change in velocity over change in time, but I'm not dividing by time here -// float encBAccel = (encBVel - prevEncVelB) / timeDiff; -// if (abs(encAVel) > maxEncoderVelocity) maxEncoderVelocity = abs(encAVel); -// if (abs(encBVel) > maxEncoderVelocity) maxEncoderVelocity = abs(encBVel); -// if (abs(encAAccel) > maxEncoderAccel) maxEncoderAccel = abs(encAAccel); -// if (abs(encBAccel) > maxEncoderAccel) maxEncoderAccel = abs(encBAccel); -// prevEncA = encA; -// prevEncB = encB; -// prevEncVelA = encAVel; -// prevEncVelB = encBVel; -// prevTime = millis(); -// } - -// void MotorEncoderTest::testDriveForward() -// { -// prevEncA = readLeftEncoder(); -// prevEncB = readRightEncoder(); -// prevEncVelA = 0; -// prevEncVelB = 0; -// prevTime = millis(); -// serialLogln("Setting motors to go 'forward' for 5 seconds...", 2); -// setLeftPower(1); -// setRightPower(1); -// auto fp2 = std::bind(&MotorEncoderTest::checkEncoderVelocity, this); -// encoderCheckTimerId = timerInterval(20, fp2); -// auto fp = std::bind(&MotorEncoderTest::testDriveDone, this); -// timerDelay(5000, fp); -// } - -// void MotorEncoderTest::testDriveDone() -// { -// serialLogln("Driving done!", 2); -// serialLog("Max encoder velocity is ", 2); -// serialLogln(maxEncoderVelocity, 2); -// serialLog("Max encoder acceleration is ", 2); -// serialLogln(maxEncoderAccel, 2); -// timerCancel(encoderCheckTimerId); -// setLeftPower(0); -// setRightPower(0); -// } - -// #endif \ No newline at end of file diff --git a/src/robot/pidController.cpp b/src/robot/pidController.cpp index 0d355e7..dd3e474 100644 --- a/src/robot/pidController.cpp +++ b/src/robot/pidController.cpp @@ -1,12 +1,12 @@ -#ifndef PID_CONTROLLER_CPP -#define PID_CONTROLLER_CPP - -#include "robot/pidController.h" -#include "utils/logging.h" #include #include #include +#include "robot/pidController.h" + +#include "utils/logging.h" + + PIDController::PIDController(double kp, double ki, double kd, double min, double max, double _errorTolerance) : kp(kp), ki(ki), kd(kd), minOutput(min), maxOutput(max), @@ -48,18 +48,9 @@ double PIDController::Compute(double setpoint, double actual_value, double dt) { // Clamp output output = std::max(minOutput, std::min(maxOutput, output)); - // serialLog("PID is outputting: ", 3); - // serialLog(float(output), 3); - // serialLogln(",", 3); - // if (abs(output) < 0.2) { - // output = 0; - // } - return (output); } void PIDController::Reset(){ integral = 0; -} - -#endif \ No newline at end of file +} \ No newline at end of file diff --git a/src/robot/pwm.cpp b/src/robot/pwm.cpp deleted file mode 100644 index 768e789..0000000 --- a/src/robot/pwm.cpp +++ /dev/null @@ -1,37 +0,0 @@ -#ifndef CHESSBOT_PWM_CPP -#define CHESSBOT_PWM_CPP - -// Associated Header File -#include "robot/pwm.h" - -// Built-In Libraries -#include "Arduino.h" - -// Custom Libraries -#include "utils/logging.h" -#include "utils/config.h" -#include "utils/functions.h" - -// Sets a pin to be able to output -void setupPWM(int pin) { - pinMode(pin, OUTPUT); -} - -// Writes PWM to a pin. The duty cycle is a number -// between 0 and 255 that determines how often the signal is HIGH. -// You can refer to this link for more information on PWM -// https://learn.sparkfun.com/tutorials/pulse-width-modulation/all -void writePWM(int pin, int dutyCycle) { - analogWrite(pin, dutyCycle); -} - -// Takes in a power between [0, 1] -// We use this to change a float power between 0-1 to an int duty cycle between 0-4096 -int mapPowerToDuty(float power) { - int value = fmap(power, 0.0, 1.0, 0.0, 4096); - serialLog("Mapped Duty: ", 4); - serialLogln(value, 4); - return value; -} - -#endif \ No newline at end of file diff --git a/src/robot/splines.cpp b/src/robot/splines.cpp deleted file mode 100644 index 7aa7576..0000000 --- a/src/robot/splines.cpp +++ /dev/null @@ -1,252 +0,0 @@ -// #ifndef CHESSBOT_SPLINES_CPP -// #define CHESSBOT_SPLINES_CPP - -// #include "robot/splines.h" -// #include "utils/logging.h" -// #include "robot/control/robot.h" -// #include "robot/trapezoidalProfile.h" -// #include "utils/timer.h" -// #include "wifi/connection.h" -// #include "utils/config.h" -// #include "utils/functions.h" -// #include -// #include -// #include -// #include - - - -// void velocityUpdateTimerFunction(std::string id) -// { -// // serialLogln("Update Timer was called", 3); -// if (timeSlicesToExecute.size() == 0) { -// if (id != "NULL") { sendActionSuccess(id); } -// return; -// } - -// float desiredVelocityLeft, desiredVelocityRight; -// std::tie(desiredVelocityLeft, desiredVelocityRight) = timeSlicesToExecute.front(); -// setXControl({VELOCITY, desiredVelocityLeft}); -// setYControl({VELOCITY, desiredVelocityRight}); -// timeSlicesToExecute.pop(); - -// // 1ms delay ensures the function will run in the next loop -// timerDelay(1, [id](){ velocityUpdateTimerFunction(id); }); -// } - - -// void danceMonkeyCubic(std::string id, Point start, Point control1, Point control2, Point end, float totalTimeMs){ -// float trackWidth = TRACK_WIDTH_INCHES; - -// int steps = (int)(totalTimeMs / loopDelayMilliseconds); // 20ms steps -// float dt = totalTimeMs / 1000 / steps; - -// for (int i = 0; i < steps; i++) { -// float t = (float)i / steps; -// float tNext = (float)(i + 1) / steps; - -// // Cubic Bezier Point at t -// Point p = { -// (float)(pow(1 - t, 3) * start.x + -// 3 * pow(1 - t, 2) * t * control1.x + -// 3 * (1 - t) * pow(t, 2) * control2.x + -// pow(t, 3) * end.x), -// (float)(pow(1 - t, 3) * start.y + -// 3 * pow(1 - t, 2) * t * control1.y + -// 3 * (1 - t) * pow(t, 2) * control2.y + -// pow(t, 3) * end.y) -// }; - -// // Cubic Bezier Point at tNext -// Point pNext = { -// (float)(pow(1 - tNext, 3) * start.x + -// 3 * pow(1 - tNext, 2) * tNext * control1.x + -// 3 * (1 - tNext) * pow(tNext, 2) * control2.x + -// pow(tNext, 3) * end.x), -// (float)(pow(1 - tNext, 3) * start.y + -// 3 * pow(1 - tNext, 2) * tNext * control1.y + -// 3 * (1 - tNext) * pow(tNext, 2) * control2.y + -// pow(tNext, 3) * end.y) -// }; - -// // Estimate linear velocity -// float dx = pNext.x - p.x; -// float dy = pNext.y - p.y; -// float linearVelocity = sqrt(dx * dx + dy * dy) / dt; - -// // Estimate angular velocity -// float theta1 = atan2(dy, dx); -// float theta0; - -// if (i > 0) { -// float tPrev = (float)(i - 1) / steps; -// Point pPrev = { -// (float)(pow(1 - tPrev, 3) * start.x + -// 3 * pow(1 - tPrev, 2) * tPrev * control1.x + -// 3 * (1 - tPrev) * pow(tPrev, 2) * control2.x + -// pow(tPrev, 3) * end.x), -// (float)(pow(1 - tPrev, 3) * start.y + -// 3 * pow(1 - tPrev, 2) * tPrev * control1.y + -// 3 * (1 - tPrev) * pow(tPrev, 2) * control2.y + -// pow(tPrev, 3) * end.y) -// }; - -// theta0 = atan2(p.y - pPrev.y, p.x - pPrev.x); -// } else { -// theta0 = theta1; -// } - -// float angularVelocity = (theta1 - theta0) / dt; - -// // Normalize angle diff -// while (angularVelocity > M_PI) angularVelocity -= 2 * M_PI; -// while (angularVelocity < -M_PI) angularVelocity += 2 * M_PI; - -// float trackWidthTicks = trackWidth * TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); - -// // Compute wheel velocities using differential drive model -// float vLeft = linearVelocity - (angularVelocity * trackWidthTicks / 2); -// float vRight = linearVelocity + (angularVelocity * trackWidthTicks / 2); - -// timeSlicesToExecute.push({vLeft, vRight}); -// } -// velocityUpdateTimerFunction(id); -// } - -// void danceMonkeyQuadratic(std::string id, Point start, Point control, Point end, float totalTimeMs) { -// serialLogln("Quadratic Dancer was called", 3); -// float trackWidth = TRACK_WIDTH_INCHES; -// int steps = (int)(totalTimeMs / loopDelayMilliseconds); // 20ms steps -// float dt = totalTimeMs / 1000 / steps; - -// for (int i = 0; i < steps; i++) { -// float t = (float)i / steps; -// float tNext = (float)(i + 1) / steps; - -// // Bezier point at t -// Point p = { -// (float)((1 - t) * (1 - t) * start.x + 2 * (1 - t) * t * control.x + t * t * end.x), -// (float)((1 - t) * (1 - t) * start.y + 2 * (1 - t) * t * control.y + t * t * end.y) -// }; - -// // Bezier point at t + dt -// Point pNext = { -// (float)((1 - tNext) * (1 - tNext) * start.x + 2 * (1 - tNext) * tNext * control.x + tNext * tNext * end.x), -// (float)((1 - tNext) * (1 - tNext) * start.y + 2 * (1 - tNext) * tNext * control.y + tNext * tNext * end.y) -// }; - -// // Velocity approximation -// float dx = pNext.x - p.x; -// float dy = pNext.y - p.y; -// // dx *= 2*12*TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); -// // dy *= 2*12*TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); -// float linearVelocity = sqrt(dx * dx + dy * dy) / dt; - -// // Angular velocity approximation -// float theta1 = atan2(dy, dx); -// float theta0 = (i > 0) ? atan2(p.y - ((1 - (float)(i - 1) / steps) * (1 - (float)(i - 1) / steps) * start.y + -// 2 * (1 - (float)(i - 1) / steps) * ((float)(i - 1) / steps) * control.y + -// ((float)(i - 1) / steps) * ((float)(i - 1) / steps) * end.y), -// p.x - ((1 - (float)(i - 1) / steps) * (1 - (float)(i - 1) / steps) * start.x + -// 2 * (1 - (float)(i - 1) / steps) * ((float)(i - 1) / steps) * control.x + -// ((float)(i - 1) / steps) * ((float)(i - 1) / steps) * end.x)) : theta1; -// float angularVelocity = (theta1 - theta0) / dt; - -// // Normalize angle diff -// while (angularVelocity > M_PI) angularVelocity -= 2 * M_PI; -// while (angularVelocity < -M_PI) angularVelocity += 2 * M_PI; - -// float trackWidthTicks = trackWidth * TICKS_PER_ROTATION/(WHEEL_DIAMETER_INCHES*M_PI); - -// // Differential drive kinematics -// float vLeft = linearVelocity - (angularVelocity * trackWidthTicks / 2); -// float vRight = linearVelocity + (angularVelocity * trackWidthTicks / 2); - - -// timeSlicesToExecute.push({vLeft, vRight}); -// // serialLog(vLeft, 3); -// // serialLog(", ", 3); -// // serialLogln(vRight, 3); -// } -// velocityUpdateTimerFunction(id); -// } - - - -// int customPrevPositionA = 0, customPrevPositionB = 0; - -// void startCustomMotionProfileTimer(int leftPositionTarget, int rightPositionTarget, double profileDuration, std::string id) -// { -// double maxAcceleration = 6000; - -// double maxPositionTarget = std::max(std::abs(leftPositionTarget), std::abs(rightPositionTarget)); -// double leftAcceleration = maxAcceleration * std::abs(leftPositionTarget) / maxPositionTarget; -// double rightAcceleration = maxAcceleration * std::abs(rightPositionTarget) / maxPositionTarget; - -// double leftSqrtValue = profileDuration*profileDuration - 4*std::abs(leftPositionTarget)/leftAcceleration; -// double rightSqrtValue = profileDuration*profileDuration - 4*std::abs(rightPositionTarget)/rightAcceleration; - -// if (leftSqrtValue < 0 || rightSqrtValue < 0) -// { -// sendActionFail(id); -// return; -// } - -// double maxVelocityLeft = (profileDuration - sqrt(leftSqrtValue))*leftAcceleration/2; -// double maxVelocityRight = (profileDuration - sqrt(rightSqrtValue))*rightAcceleration/2; - -// customPrevPositionA = readLeftEncoder(); -// customPrevPositionB = readRightEncoder(); - -// MotionProfile customProfileA = {maxVelocityLeft, leftAcceleration, 0, 0, (double)leftPositionTarget, 0, fabs(leftPositionTarget - customPrevPositionA) / 2}; -// MotionProfile customProfileB = {maxVelocityRight, rightAcceleration, 0, 0, (double)rightPositionTarget, 0, fabs(rightPositionTarget - customPrevPositionB) / 2}; -// serialLogln("Custom motion profile timer...", 3); -// serialLog("Left max vel: ", 3); -// serialLog(maxVelocityLeft, 3); -// serialLog(" Max accel: ", 3); -// serialLog(leftAcceleration, 3); -// serialLog(" Target: ", 3); -// serialLogln(leftPositionTarget, 3); -// serialLog("Right max vel: ", 3); -// serialLog(maxVelocityRight, 3); -// serialLog(" Max accel: ", 3); -// serialLog(rightAcceleration, 3); -// serialLog(" Target: ", 3); -// serialLogln(rightPositionTarget, 3); -// customMotionProfileTimerFunction(customProfileA, customProfileB, loopDelayMilliseconds / 1000.0, id); -// } - -// void customMotionProfileTimerFunction(MotionProfile &customProfileA, MotionProfile &customProfileB, double dt, std::string id) -// { -// if (approxEquals(customProfileA.targetPosition, customProfileA.currentPosition, PID_POSITION_TOLERANCE) -// && approxEquals(customProfileA.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE) -// && approxEquals(customProfileB.targetPosition, customProfileB.currentPosition, PID_POSITION_TOLERANCE) -// && approxEquals(customProfileB.currentVelocity, 0.0, PID_VELOCITY_TOLERANCE)) -// { -// if (id != "NULL") { sendActionSuccess(id); } -// return; -// } - -// int currentPositionEncoderA = readLeftEncoder(); -// int currentPositionEncoderB = readRightEncoder(); -// double currentVelocityA = (currentPositionEncoderA - customPrevPositionA) / dt; -// double currentVelocityB = (currentPositionEncoderB - customPrevPositionB) / dt; - -// customPrevPositionA = currentPositionEncoderA; -// customPrevPositionB = currentPositionEncoderB; - -// customProfileA.currentPosition = currentPositionEncoderA; -// customProfileA.currentVelocity = currentVelocityA; -// customProfileB.currentPosition = currentPositionEncoderB; -// customProfileB.currentVelocity = currentVelocityB; - -// float desiredVelocityLeft = updateTrapezoidalProfile(customProfileA, dt); -// float desiredVelocityRight = updateTrapezoidalProfile(customProfileB, dt); - -// setXControl({VELOCITY, desiredVelocityLeft}); -// setYControl({VELOCITY, desiredVelocityRight}); - -// timerDelay(1, [&customProfileA, &customProfileB, dt, id](){ customMotionProfileTimerFunction(customProfileA, customProfileB, dt, id); }); -// } - -// #endif \ No newline at end of file diff --git a/src/robot/trapezoidalProfile.cpp b/src/robot/trapezoidalProfile.cpp deleted file mode 100644 index 43359f4..0000000 --- a/src/robot/trapezoidalProfile.cpp +++ /dev/null @@ -1,107 +0,0 @@ -#include "robot/trapezoidalProfile.h" -#include "utils/config.h" -#include "utils/logging.h" -#include - -TrapezoidProfile::State TrapezoidProfile::calculate(double t, const State ¤t, const State &goal) -{ - int m_direction = shouldFlipAcceleration(current, goal) ? -1 : 1; - State m_current = direct(current, m_direction); - State goalDir = direct(goal, m_direction); - - if (m_current.velocity > m_constraints.maxVelocity) - { - m_current.velocity = m_constraints.maxVelocity; - } - else if (m_current.velocity < -m_constraints.maxVelocity) - { - m_current.velocity = -m_constraints.maxVelocity; - } - - double cutoffBegin = m_current.velocity / m_constraints.maxAcceleration; - double cutoffDistBegin = cutoffBegin * cutoffBegin * m_constraints.maxAcceleration / 2.0; - - double cutoffEnd = max((goalDir.velocity - MIN_MOTOR_VELOCITY_TPS), 0.0) / m_constraints.maxAcceleration; - double cutoffDistEnd = cutoffEnd * cutoffEnd * m_constraints.maxAcceleration / 2.0; - - double fullTrapezoidDist = cutoffDistBegin + (goalDir.position - m_current.position) + cutoffDistEnd; - double accelerationTime = m_constraints.maxVelocity / m_constraints.maxAcceleration; - - double fullSpeedDist = fullTrapezoidDist - accelerationTime * accelerationTime * m_constraints.maxAcceleration; - - if (fullSpeedDist < 0) - { - accelerationTime = std::sqrt(fullTrapezoidDist / m_constraints.maxAcceleration); - fullSpeedDist = 0; - } - - State result(m_current.position, m_current.velocity); - - double dist = fabs(m_current.position - goalDir.position); - - double accelDist = (pow(m_constraints.maxVelocity,2) - pow(m_current.velocity,2)) / (2*m_constraints.maxAcceleration); //dist to/from max vel - //Unused double fastDist = dist - 2*accelDist; - - if(m_current.position < accelDist){ - result.velocity += t * m_constraints.maxAcceleration; - - } - - else if(dist > accelDist+100){ - result.velocity = m_constraints.maxVelocity; - serialLogln(result.velocity,3); - } - else if (dist > 10){ - result.velocity = m_current.velocity - min(sqrt(m_constraints.maxAcceleration*fabs(accelDist-dist))*.250,m_current.velocity*0.99); - serialLog("slowing ", 3); - serialLogln(result.velocity,3); - } - else - { - result = goalDir; - } - - /* - double m_endAccel = accelerationTime - cutoffBegin; - double m_endFullSpeed = m_endAccel + fullSpeedDist / m_constraints.maxVelocity; - double m_endDecel = m_endFullSpeed + accelerationTime - cutoffEnd; - State result(m_current.position, m_current.velocity); - - if (t < m_endAccel) - { - result.velocity += t * m_constraints.maxAcceleration; - if (abs(result.velocity) < MIN_MOTOR_VELOCITY_TPS) { - result.velocity = MIN_MOTOR_VELOCITY_TPS; - } - result.position += (m_current.velocity + t * m_constraints.maxAcceleration / 2.0) * t; - serialLog("accelerating ", 3); - serialLogln(result.velocity,3); - } - else if (t < m_endFullSpeed) - { - result.velocity = m_constraints.maxVelocity; - result.position += - (m_current.velocity + m_endAccel * m_constraints.maxAcceleration / 2.0) * m_endAccel + - m_constraints.maxVelocity * (t - m_endAccel); - serialLog("holding ", 3); - serialLogln(result.velocity,3); - } - else if (t <= m_endDecel) - { - double timeLeft = m_endDecel - t; - result.velocity = goalDir.velocity + timeLeft * m_constraints.maxAcceleration; - result.position = goalDir.position - (goalDir.velocity * timeLeft) - (timeLeft * timeLeft * m_constraints.maxAcceleration / 2.0); - serialLog("slowing ", 3); - serialLogln(result.velocity,3); - } - else - { - result = goalDir; - } - */ - if (abs(result.position - goalDir.position) <= 10) { - result.velocity = 0; - } - - return direct(result, m_direction); -} diff --git a/src/tests.cpp b/src/tests.cpp new file mode 100644 index 0000000..720d133 --- /dev/null +++ b/src/tests.cpp @@ -0,0 +1,84 @@ +#include + +#include "tests.h" + +#include "robot/control/robot.h" +#include "utils/geometry.h" + +// Test the distance PID controller +void line_test(Robot& r) { + unsigned long time_seconds = millis() / 1000; + + Coordinate2D goal; + double rotation = 0; + + if (time_seconds > 5) { + goal = Coordinate2D(100, 0); + } + + if (time_seconds > 10) { + goal = Coordinate2D(100, 100); + } + + if (time_seconds > 15) { + goal = Coordinate2D(0, 100); + } + + if (time_seconds > 20) { + goal = Coordinate2D(0, 0); + } + + r.drive(goal, rotation); +} + +// Test the angular PID controller +void circle_test(Robot& r) { + unsigned long time_seconds = millis() / 1000; + + Coordinate2D goal(00, 0.0); + double rotation = 0; + + if (time_seconds > 5) { + rotation = 2 * M_PI; + } + + if (time_seconds > 10) { + rotation = 0; + } + + if (time_seconds > 15) { + rotation = 4 * M_PI; + } + + if (time_seconds > 20) { + rotation = 0; + } + + r.drive(goal, rotation); +} + +// Test all of MotionController +void square_test(Robot& r) { + unsigned long time_seconds = millis() / 1000; + + Coordinate2D goal; + double rotation = 0; + + if (time_seconds > 5) { + goal = Coordinate2D(100, 0); + } + + if (time_seconds > 10) { + goal = Coordinate2D(100, 100); + } + + if (time_seconds > 15) { + goal = Coordinate2D(0, 100); + } + + if (time_seconds > 20) { + goal = Coordinate2D(0, 0); + } + + r.drive(goal, rotation); +} \ No newline at end of file diff --git a/src/tests/tests.cpp b/src/tests/tests.cpp deleted file mode 100644 index 48ef3e5..0000000 --- a/src/tests/tests.cpp +++ /dev/null @@ -1,20 +0,0 @@ -// #include "config.h" - -// void do_tests() { -// if (DO_DRIVE_TEST) { -// startDriveTest(); -// } - -// delay(2000); - - -// if (DO_DRIVE_TICKS_TEST){ -// driveTicks(20000, "NULL"); -// } - -// delay(5000); - -// if (DO_HARDWARE_TEST) { -// startMotorAndEncoderTest(); -// } -// } diff --git a/src/utils/config.cpp b/src/utils/config.cpp index 6a60347..c42080e 100644 --- a/src/utils/config.cpp +++ b/src/utils/config.cpp @@ -1,17 +1,12 @@ -#ifndef CHESSBOT_CONFIG_CPP -#define CHESSBOT_CONFIG_CPP +#include +#include -// Associated Header File #include "utils/config.h" -// Built-In Libraries -#include "Arduino.h" - -// Custom Libraries #include "utils/logging.h" // External Libraries -#include + int loopDelayMilliseconds = 20; @@ -54,7 +49,7 @@ float PID_POSITION_TOLERANCE = 100; float PID_VELOCITY_TOLERANCE = 6000; void setConfig(JsonObject config) { - serialLogln("Setting Config...", 2); + serial_printf(DebugLevel::DEBUG, "Setting Config...\n"); // The is() method checks the type of the variable. If the type isn't none, then // we know this variable exists in the config and has a value @@ -84,7 +79,5 @@ void setConfig(JsonObject config) { if (config["MAGNET_CCW_IS_POSITIVE"].is()) MAGNET_CCW_IS_POSITIVE = config["MAGNET_CCW_IS_POSITIVE"]; - serialLogln("Config Set!", 2); -} - -#endif \ No newline at end of file + serial_printf(DebugLevel::DEBUG, "Config Set!\n"); +} \ No newline at end of file diff --git a/src/utils/functions.cpp b/src/utils/functions.cpp index 5fe57df..6f9e65c 100644 --- a/src/utils/functions.cpp +++ b/src/utils/functions.cpp @@ -1,19 +1,13 @@ -#ifndef CHESSBOT_FUNCTIONS_CPP -#define CHESSBOT_FUNCTIONS_CPP +#include -// Associated Header File #include "utils/functions.h" -// Built-In Libraries -#include "Arduino.h" - -// Custom Libraries -#include "utils/logging.h" #include "utils/config.h" +#include "utils/logging.h" // This custom map function takes a number, and scales it from one range to another. // We use this to change a number between 0-1 to a number between 0-255 -float fmap(float x, float in_min, float in_max, float out_min, float out_max) { +double fmap(double x, double in_min, double in_max, double out_min, double out_max) { return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min; } @@ -25,21 +19,6 @@ bool approxEquals(double x, double y, double epsilon) { return std::abs(x-y) <= epsilon; } -int radiansToTicks(double angle) { - double offsetInches = TRACK_WIDTH_INCHES * angle / 2; - int offsetTicks = (int)(offsetInches / (WHEEL_DIAMETER_INCHES * M_PI) * TICKS_PER_ROTATION); - - // Add debug logging - serialLog("Turn angle (rad): ", 3); - serialLog(angle, 3); - serialLog(", Offset inches: ", 3); - serialLog(offsetInches, 3); - serialLog(", Offset ticks: ", 3); - serialLogln(offsetTicks, 3); - - return offsetTicks; -} - // When we get the mac address from the esp, it gives it as an array of unsigned // 8 bit integers. The server is expecting it as a hex string separated by colons std::string unint8ArrayToHexString(uint8_t* oldArray, int len) { @@ -56,8 +35,6 @@ std::string unint8ArrayToHexString(uint8_t* oldArray, int len) { result.push_back(hex[oldArray[i] / 16]); result.push_back(hex[oldArray[i] % 16]); } - serialLogln(result, 4); - return result; -} -#endif \ No newline at end of file + return result; +} \ No newline at end of file diff --git a/src/utils/geometry.cpp b/src/utils/geometry.cpp index b6ddb04..9e7efb5 100644 --- a/src/utils/geometry.cpp +++ b/src/utils/geometry.cpp @@ -1,4 +1,5 @@ #include + #include "utils/geometry.h" Coordinate2D::Coordinate2D() { diff --git a/src/utils/logging.cpp b/src/utils/logging.cpp index f622e18..9430864 100644 --- a/src/utils/logging.cpp +++ b/src/utils/logging.cpp @@ -1,17 +1,9 @@ -#ifndef CHESSBOT_LOGGING_CPP -#define CHESSBOT_LOGGING_CPP -#include - -// Associated Header File -#include "utils/logging.h" - -// Built-In Libraries #include -// Custom Libraries -#include "utils/status.h" #include "../env.h" +#include "utils/logging.h" +#include "utils/status.h" // Prints a value or message through Serial. (The console) // ln means it sends a new newline character @@ -34,65 +26,4 @@ void serial_printf(enum DebugLevel level, const char* fmt, ...) { void serial_clear() { serial_printf(DebugLevel::NONE, "\033[3J\033[H\033[2J"); -} - -void serialLog(const char *message, int serialLoggingLevel) -{ - if (serialLoggingLevel <= LOGGING_LEVEL) - Serial.print(message); -} - -void serialLog(int value, int serialLoggingLevel) -{ - if (serialLoggingLevel <= LOGGING_LEVEL) - Serial.print(value); -} - -void serialLog(double value, int serialLoggingLevel) -{ - if (serialLoggingLevel <= LOGGING_LEVEL) - Serial.print(value); -} - -void serialLog(std::string value, int serialLoggingLevel) -{ - serialLog(value.c_str(), serialLoggingLevel); -} - -void serialLogln(const char *message, int serialLoggingLevel) -{ - if (serialLoggingLevel <= LOGGING_LEVEL) - Serial.println(message); -} - -void serialLogln(int value, int serialLoggingLevel) -{ - if (serialLoggingLevel <= LOGGING_LEVEL) - Serial.println(value); -} - -void serialLogln(double value, int serialLoggingLevel) -{ - if (serialLoggingLevel <= LOGGING_LEVEL) - Serial.println(value); -} - -void serialLogln(float value, int serialLoggingLevel) -{ - if (serialLoggingLevel <= LOGGING_LEVEL) - Serial.println(value); -} - -void serialLogln(std::string value, int serialLoggingLevel) -{ - serialLogln(value.c_str(), serialLoggingLevel); -} - -// This is used for specifically serialLogging errors -void serialLogError(char message[], int error) -{ - if (LOGGING_LEVEL > 0) - Serial.printf(message, error); -} - -#endif \ No newline at end of file +} \ No newline at end of file diff --git a/src/utils/status.cpp b/src/utils/status.cpp index 841ba9d..e60632a 100644 --- a/src/utils/status.cpp +++ b/src/utils/status.cpp @@ -1,7 +1,3 @@ -#ifndef CHESSBOT_STATUS_CPP -#define CHESSBOT_STATUS_CPP - -// Associated Header File #include "utils/status.h" bool wifiConnected = false; @@ -20,14 +16,4 @@ bool getServerConnectionStatus() { } void setServerConnectionStatus(bool value) { serverConnected = value; -} - -bool getStoppedStatus() { - return botStopped; -} - -void setStoppedStatus(bool value) { - botStopped = value; -} - -#endif \ No newline at end of file +} \ No newline at end of file diff --git a/src/utils/timer.cpp b/src/utils/timer.cpp index 348aa46..3f3af37 100644 --- a/src/utils/timer.cpp +++ b/src/utils/timer.cpp @@ -1,15 +1,8 @@ -#ifndef CHESSBOT_TIMER_CPP -#define CHESSBOT_TIMER_CPP - -// Associated Header File -#include "utils/timer.h" - -// Built-In Libraries -#include "Arduino.h" +#include #include -// Custom Libraries #include "utils/logging.h" +#include "utils/timer.h" // How to pass function from within a class (Uses a lambda that captures the class' pointer) // [this](){ func(); } @@ -91,6 +84,4 @@ void timerStep() { index++; } } -} - -#endif \ No newline at end of file +} \ No newline at end of file diff --git a/src/wifi/connection.cpp b/src/wifi/connection.cpp index f681a0b..8c7606c 100644 --- a/src/wifi/connection.cpp +++ b/src/wifi/connection.cpp @@ -1,24 +1,15 @@ -#ifndef CHESSBOT_CONNECTION_CPP -#define CHESSBOT_CONNECTION_CPP +#include +#include +#include -// Associated Header File #include "wifi/connection.h" -// Built-In Libraries -#include "Arduino.h" -#include "WiFi.h" - -// External Libraries -#include - -// Custom Libraries -#include "wifi/packet.h" +#include "../../env.h" +#include "robot/control/robot.h" #include "utils/logging.h" -#include "utils/timer.h" #include "utils/status.h" -#include "robot/control/robot.h" - -#include "../../env.h" +#include "utils/timer.h" +#include "wifi/packet.h" bool serverConnecting = false; bool pinging = false; @@ -29,19 +20,19 @@ WiFiClient client; // Called to connect to the server whose info is stored in env.h void connectServer() { - serialLogln("Connecting to Server...", 2); + serial_printf(DebugLevel::DEBUG, "Connecting to Server...\n"); if (client.connect(SERVER_IP, SERVER_PORT)) { // If successful, sets the connection status and stops trying to connect to the server setServerConnectionStatus(true); serverConnecting = false; - serialLogln("Connected to Server!", 2); + serial_printf(DebugLevel::DEBUG, "Connected to Server!\n"); // A handshake is an initial exchange of information, and a confirmation of a connection if (DO_HANDSHAKE) { initiateHandshake(); } } else { serverConnecting = true; // If unsuccessful, tries again in 5 seconds - serialLogln("Connection To Server Failed! Retrying...", 2); + serial_printf(DebugLevel::DEBUG, "Connection To Server Failed! Retrying...\n"); timerDelay(HANDSHAKE_INTERVAL, &connectServer); } @@ -51,14 +42,14 @@ void connectServer() { void disconnectServer() { setServerConnectionStatus(false); client.stop(); - serialLogln("Disconnected From Server!", 2); + serial_printf(DebugLevel::DEBUG, "Disconnected From Server!\n"); } // If not connected to the server (whether by disconnect or by lost connection), reconnects void reconnectServer() { if (!serverConnecting) { setServerConnectionStatus(false); - serialLogln("Disconnected From Server! Reconnecting...", 2); + serial_printf(DebugLevel::DEBUG, "Disconnected From Server! Reconnecting...\n"); connectServer(); } } @@ -72,7 +63,7 @@ bool checkServerConnection() { void initiateHandshake() { JsonDocument packet; constructHelloPacket(packet); - serialLogln((char*)"Sending Handshake...", 2); + serial_printf(DebugLevel::DEBUG, "Sending Handshake...\n"); sendPacket(packet); } @@ -102,10 +93,6 @@ JsonDocument acceptData() { // This turns the character buffer into a fully formed JSON object deserializeJson(packet, rawPacket); - serialLog("Received Packet: ", 2); - // This takes that JSON object and prints it to Serial (the console) for debugging purposes - if (LOGGING_LEVEL >= 3) serializeJson(packet, Serial); - serialLog("\n", 2); } return packet; @@ -117,33 +104,29 @@ void sendPacket(JsonDocument& packet) { serializeJson(packet, client); // Sends a delimiter character to mark the end of the packet client.write(';'); - serialLogln("Sent Packet: ", 2); - // This takes that JSON object and prints it to Serial (the console) for debugging purposes - if (LOGGING_LEVEL >= 3) serializeJson(packet, Serial); - serialLog("\n", 2); } void sendActionSuccess(std::string messageId) { JsonDocument packet; constructSuccessPacket(packet, messageId); - serialLogln((char*)"Sending Action Success...", 2); + serial_printf(DebugLevel::DEBUG, "Sending Action Success...\n"); sendPacket(packet); } void sendActionFail(std::string messageId) { JsonDocument packet; constructFailPacket(packet, messageId); - serialLogln((char*)"Sending Action Success...", 2); + serial_printf(DebugLevel::DEBUG, "Sending Action Success...\n"); sendPacket(packet); } void pingTimeout() { if (DO_PINGING) { missedPings++; - serialLog(missedPings, 2); - serialLogln((char*)" missed ping!", 2); + serial_printf(DebugLevel::DEBUG, "%u missed pings!\n", missedPings); + if (missedPings >= PING_MAX_MISSES) { - serialLogln((char*)"SERVER TIMED OUT!", 2); + serial_printf(DebugLevel::DEBUG, "SERVER TIMED OUT!\n"); // TODO: stop(); pinging = false; } else { @@ -156,17 +139,15 @@ void sendPingResponse() { if (DO_PINGING) { JsonDocument packet; constructPingPacket(packet); - serialLogln((char*)"Sending Ping Response...", 2); + serial_printf(DebugLevel::DEBUG, "Sending Ping Response...\n"); sendPacket(packet); if (pinging) { timerReset(pingTimeoutTimer); } else { pingTimeoutTimer = timerDelay(PING_TIMEOUT, &pingTimeout); - serialLogln((char*)"Started Ping Timeout Timer", 2); + serial_printf(DebugLevel::DEBUG, "Started Ping Timeout Timer\n"); pinging = true; } missedPings = 0; } -} - -#endif \ No newline at end of file +} \ No newline at end of file diff --git a/src/wifi/packet.cpp b/src/wifi/packet.cpp index d17a83b..b4e842d 100644 --- a/src/wifi/packet.cpp +++ b/src/wifi/packet.cpp @@ -1,23 +1,14 @@ -#ifndef CHESSBOT_PACKET_CPP -#define CHESSBOT_PACKET_CPP +#include +#include +#include -// Associated Header File #include "wifi/packet.h" -// Built-In Libraries -#include "Arduino.h" -#include "esp_mac.h" - -// External Libraries -#include - -// Custom Libraries +#include "robot/control/robot.h" +#include "utils/config.h" +#include "utils/functions.h" #include "utils/logging.h" #include "utils/status.h" -#include "utils/functions.h" -#include "utils/config.h" -#include "robot/control/robot.h" -#include "robot/splines.h" #include "wifi/connection.h" // These are the various different supported message types that can be sent over TCP @@ -43,7 +34,7 @@ const char* BS_MOVE = "BS_MOVE"; // Takes a packet a does specific things based on the type void handlePacket(Robot& r, JsonDocument packet) { // Sadly a switch case can't be used due to the packet type being a string. - // We do this to allow the packets to be more readable when serialLogged + // We do this to allow the packets to be more readable when serial_printf(DebugLevel::ged if (packet["type"] == SERVER_HELLO) { // When we initiate a handshake, the server sends a handshake back. This server handshake // contains any variable that should be changed in this bot's config @@ -62,13 +53,13 @@ void handlePacket(Robot& r, JsonDocument packet) { // Point controlPositionB = {(float)packet["controlPositionB"]["x"]*TILES_TO_TICKS, (float)packet["controlPositionB"]["y"]*TILES_TO_TICKS}; // danceMonkeyCubic(packet["packetId"], startPosition, controlPositionA, controlPositionB, endPosition, packet["timeDeltaMs"]); } else if (packet["type"] == QUADRATIC) { - // serialLog("I have arrived!! at Quadratic", 3); + // serial_printf(DebugLevel::("I have arrived!! at Quadratic", 3); // Point startPosition = {(float)packet["startPosition"]["x"]*TILES_TO_TICKS, (float)packet["startPosition"]["y"]*TILES_TO_TICKS}; // Point endPosition = {(float)packet["endPosition"]["x"]*TILES_TO_TICKS, (float)packet["endPosition"]["y"]*TILES_TO_TICKS}; // Point controlPosition = {(float)packet["controlPosition"]["x"]*TILES_TO_TICKS, (float)packet["controlPosition"]["y"]*TILES_TO_TICKS}; // danceMonkeyQuadratic(packet["packetId"], startPosition, controlPosition, endPosition, packet["timeDeltaMs"]); } else if (packet["type"] == SPIN_RADIANS) { - // serialLog("Going to spin!", 3); + // serial_printf(DebugLevel::("Going to spin!", 3); // int offsetTicks = radiansToTicks((float)packet["radians"]); // startCustomMotionProfileTimer(-offsetTicks, offsetTicks, (double)packet["timeDeltaMs"]/1000, packet["packetId"]); } else if (packet["type"] == TURN_BY_ANGLE) { @@ -114,6 +105,4 @@ void constructFailPacket(JsonDocument& packet, std::string messageId) { void constructPingPacket(JsonDocument& packet) { packet["type"] = PING_RESPONSE; packet["batteryLevel"] = Robot::batteryLevel(); -} - -#endif \ No newline at end of file +} \ No newline at end of file diff --git a/src/wifi/wireless.cpp b/src/wifi/wireless.cpp index d1eff42..cbf86b4 100644 --- a/src/wifi/wireless.cpp +++ b/src/wifi/wireless.cpp @@ -1,19 +1,13 @@ -#ifndef CHESSBOT_WIRELESS_CPP -#define CHESSBOT_WIRELESS_CPP +#include +#include -// Associated Header File #include "wifi/wireless.h" -// Built-In Libraries -#include "Arduino.h" -#include "WiFi.h" - -// Custom Libraries +#include "../../env.h" #include "utils/logging.h" -#include "utils/timer.h" #include "utils/status.h" +#include "utils/timer.h" #include "wifi/connection.h" -#include "../../env.h" bool wifiConnecting = false; @@ -43,22 +37,20 @@ bool checkWiFiConnection() { return WiFi.status() == WL_CONNECTED; } -// If not connected to WiFi by now, serialLog 'why' +// If not connected to WiFi by now, serial_printf(DebugLevel:: 'why' // Tries to connect until success. After connected to WiFi, starts trying to connect to the server void confirmWiFi() { if (checkWiFiConnection()) { setWiFiConnectionStatus(true); wifiConnecting = false; - serialLogln("Connected to WiFi Network!", 2); + serial_printf(DebugLevel::DEBUG, "Connected to WiFi Network!\n"); // Connect to the server connectServer(); } else { setWiFiConnectionStatus(false); wifiConnecting = true; - serialLog("Failed To Connect To WiFi: ", 2); - serialLog(getWifiStatus(WiFi.status()), 2); - serialLogln(". Retrying... ", 2); + serial_printf(DebugLevel::DEBUG, "Failed To Connect To WiFi: %s. Retrying...\n", getWifiStatus(WiFi.status())); // Check connection again after half a second timerDelay(500, &confirmWiFi); @@ -68,7 +60,7 @@ void confirmWiFi() { // Connects to a WiFi network with the SSID and Password set in env.h void connectWiFI() { wifiConnecting = true; - serialLogln("Connecting to WiFi Network...", 2); + serial_printf(DebugLevel::DEBUG, "Connecting to WiFi Network...\n"); WiFi.mode(WIFI_STA); WiFi.begin(WIFI_SSID, WIFI_PASSWORD); // We delay the connection test to give the ESP time to fully connect to the network @@ -79,24 +71,22 @@ void connectWiFI() { void disconnectWiFI() { setWiFiConnectionStatus(false); WiFi.disconnect(); - serialLogln("Disconnected From WiFI!", 2); + serial_printf(DebugLevel::DEBUG, "Disconnected From WiFI!\n"); } // If not connected to WiFi (whether by disconnect or by lost connection), reconnects void reconnectWiFI() { if (!wifiConnecting) { setWiFiConnectionStatus(false); - serialLogln("Disconnected From WiFI! Reconnecting...", 2); + serial_printf(DebugLevel::DEBUG, "Disconnected From WiFI! Reconnecting...\n"); connectWiFI(); } } // Creates a WiFi network with the SSID and Password set in env.h void createWiFi() { - serialLogln("Creating Access Point", 2); + serial_printf(DebugLevel::DEBUG, "Creating Access Point\n"); WiFi.softAP(WIFI_SSID, WIFI_PASSWORD); - serialLogln("Access Point Created", 2); + serial_printf(DebugLevel::DEBUG, "Access Point Created\n"); connectServer(); -} - -#endif \ No newline at end of file +} \ No newline at end of file From d028907d08cefcc97dfba9f88c7de5a0f1194e05 Mon Sep 17 00:00:00 2001 From: Siddharth Narayan Date: Sat, 11 Apr 2026 01:24:38 -0500 Subject: [PATCH 05/12] Remove Magnet library --- lib/DFRobot_BMM350/LICENSE | 7 - lib/DFRobot_BMM350/README.md | 216 -- lib/DFRobot_BMM350/README_CN.md | 214 -- .../CalibratedMagnedticData.ino | 129 -- .../examples/calibration/README.md | 175 -- .../examples/calibration/README_CN.md | 242 --- .../getCalibrateData/getCalibrateData.ino | 92 - .../examples/getAllState/getAllState.ino | 95 - .../getGeomagneticData/getGeomagneticData.ino | 84 - .../magDrdyInterrupt/magDrdyInterrupt.ino | 186 -- .../thresholdInterrupt/thresholdInterrupt.ino | 194 -- lib/DFRobot_BMM350/keywords.txt | 76 - lib/DFRobot_BMM350/library.properties | 9 - .../python/raspberrypi/DFRobot_bmm350.py | 1595 --------------- .../python/raspberrypi/README.md | 201 -- .../python/raspberrypi/README_CN.md | 218 -- .../examples/data_ready_interrupt.py | 111 - .../examples/demo_data_ready_interrupt.py | 112 -- .../examples/demo_get_all_state.py | 107 - .../examples/demo_get_geomagnetic_data.py | 90 - .../examples/demo_threshold_interrupt.py | 115 -- .../raspberrypi/examples/get_all_state.py | 108 - .../get_calibrated_geomagnetic_data.py | 107 - .../examples/get_geomagnetic_data.py | 89 - .../examples/threshold_interrupt.py | 115 -- .../resources/images/BMM350.png | Bin 200001 -> 0 bytes .../resources/images/BMM350Size.png | Bin 64972 -> 0 bytes .../resources/images/cal_pic1.jpg | Bin 33222 -> 0 bytes .../resources/images/cal_pic2.jpg | Bin 11813 -> 0 bytes .../resources/images/cal_pic3.jpg | Bin 154473 -> 0 bytes .../resources/images/cal_pic4.jpg | Bin 10879 -> 0 bytes lib/DFRobot_BMM350/src/DFRobot_BMM350.cpp | 483 ----- lib/DFRobot_BMM350/src/DFRobot_BMM350.h | 250 --- lib/DFRobot_BMM350/src/bmm350.c | 1781 ----------------- lib/DFRobot_BMM350/src/bmm350.h | 595 ------ lib/DFRobot_BMM350/src/bmm350_defs.h | 1215 ----------- lib/DFRobot_BMM350/src/bmm350_oor.c | 329 --- lib/DFRobot_BMM350/src/bmm350_oor.h | 136 -- 38 files changed, 9476 deletions(-) delete mode 100644 lib/DFRobot_BMM350/LICENSE delete mode 100644 lib/DFRobot_BMM350/README.md delete mode 100644 lib/DFRobot_BMM350/README_CN.md delete mode 100644 lib/DFRobot_BMM350/examples/calibration/CalibratedMagnedticData/CalibratedMagnedticData.ino delete mode 100644 lib/DFRobot_BMM350/examples/calibration/README.md delete mode 100644 lib/DFRobot_BMM350/examples/calibration/README_CN.md delete mode 100644 lib/DFRobot_BMM350/examples/calibration/getCalibrateData/getCalibrateData.ino delete mode 100644 lib/DFRobot_BMM350/examples/getAllState/getAllState.ino delete mode 100644 lib/DFRobot_BMM350/examples/getGeomagneticData/getGeomagneticData.ino delete mode 100644 lib/DFRobot_BMM350/examples/magDrdyInterrupt/magDrdyInterrupt.ino delete mode 100644 lib/DFRobot_BMM350/examples/thresholdInterrupt/thresholdInterrupt.ino delete mode 100644 lib/DFRobot_BMM350/keywords.txt delete mode 100644 lib/DFRobot_BMM350/library.properties delete mode 100644 lib/DFRobot_BMM350/python/raspberrypi/DFRobot_bmm350.py delete mode 100644 lib/DFRobot_BMM350/python/raspberrypi/README.md delete mode 100644 lib/DFRobot_BMM350/python/raspberrypi/README_CN.md delete mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/data_ready_interrupt.py delete mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/demo_data_ready_interrupt.py delete mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_all_state.py delete mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_geomagnetic_data.py delete mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/demo_threshold_interrupt.py delete mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/get_all_state.py delete mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/get_calibrated_geomagnetic_data.py delete mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/get_geomagnetic_data.py delete mode 100644 lib/DFRobot_BMM350/python/raspberrypi/examples/threshold_interrupt.py delete mode 100644 lib/DFRobot_BMM350/resources/images/BMM350.png delete mode 100644 lib/DFRobot_BMM350/resources/images/BMM350Size.png delete mode 100644 lib/DFRobot_BMM350/resources/images/cal_pic1.jpg delete mode 100644 lib/DFRobot_BMM350/resources/images/cal_pic2.jpg delete mode 100644 lib/DFRobot_BMM350/resources/images/cal_pic3.jpg delete mode 100644 lib/DFRobot_BMM350/resources/images/cal_pic4.jpg delete mode 100644 lib/DFRobot_BMM350/src/DFRobot_BMM350.cpp delete mode 100644 lib/DFRobot_BMM350/src/DFRobot_BMM350.h delete mode 100644 lib/DFRobot_BMM350/src/bmm350.c delete mode 100644 lib/DFRobot_BMM350/src/bmm350.h delete mode 100644 lib/DFRobot_BMM350/src/bmm350_defs.h delete mode 100644 lib/DFRobot_BMM350/src/bmm350_oor.c delete mode 100644 lib/DFRobot_BMM350/src/bmm350_oor.h diff --git a/lib/DFRobot_BMM350/LICENSE b/lib/DFRobot_BMM350/LICENSE deleted file mode 100644 index 79f3100..0000000 --- a/lib/DFRobot_BMM350/LICENSE +++ /dev/null @@ -1,7 +0,0 @@ -Copyright 2010 DFRobot Co.Ltd - -Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. \ No newline at end of file diff --git a/lib/DFRobot_BMM350/README.md b/lib/DFRobot_BMM350/README.md deleted file mode 100644 index 3ff4694..0000000 --- a/lib/DFRobot_BMM350/README.md +++ /dev/null @@ -1,216 +0,0 @@ -# DFRobot_BMM350 - -* [中文](./README_CN.md) - -The BMM350 is a low-power and low noise 3-axis digital geomagnetic sensor that perfectly matches the requirements of compass applications. Based on Bosch’s proprietary FlipCore technology, the BMM350 provides absolute spatial orientation and motion vectors with high accuracy and dynamics. Featuring small size and lightweight, it is also especially suited for supporting drones in accurate heading. The BMM350 can also be used together with an inertial measurement unit consisting of a 3-axis accelerometer and a 3-axis gyroscope. - -![产品效果图](./resources/images/BMM350.png)![产品效果图](./resources/images/BMM350Size.png) - -## Product Link([https://www.dfrobot.com](https://www.dfrobot.com)) - -```yaml -SKU: SEN0619 -``` - -## Table of Contents - -* [Summary](#summary) -* [Installation](#installation) -* [Methods](#methods) -* [Compatibility](#compatibility) -* [History](#history) -* [Credits](#credits) - -## Summary - -Get geomagnetic data along the XYZ axis. - -1. This module can obtain high threshold and low threshold geomagnetic data.
-2. Geomagnetism on three(xyz) axes can be measured.
-3. This module can choose I2C or I3C communication mode.
- -## Installation - -To use this library download the zip file, uncompress it to a folder named DFRobot_BMM350. -Download the zip file first to use this library and uncompress it to a folder named DFRobot_BMM350. - -## Methods - -```C++ - /** - * @fn softReset - * @brief Soft reset, restore to suspended mode after soft reset. - */ - void softReset(void); - - /** - * @fn setOperationMode - * @brief Set sensor operation mode - * @param powermode - * @n eBmm350SuspendMode suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - * @n eBmm350NormalMode normal mode: Get geomagnetic data normally. - * @n eBmm350ForcedMode forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. - * @n eBmm350ForcedModeFast To reach ODR = 200Hz is only possible by using FM_ FAST. - */ - void setOperationMode(enum eBmm350PowerModes_t powermode); - - - /** - * @fn getOperationMode - * @brief Get sensor operation mode - * @return result Return sensor operation mode as a character string - */ - String getOperationMode(void); - - /** - * @fn setPresetMode - * @brief Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default collection rate is 12.5Hz) - * @param presetMode - * @n BMM350_PRESETMODE_LOWPOWER Low power mode, get a fraction of data and take the mean value. - * @n BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and take the mean value. - * @n BMM350_PRESETMODE_ENHANCED Enhanced mode, get a plenty of data and take the mean value. - * @n BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and take the mean value. - */ - void setPresetMode(uint8_t presetMode, uint8_t rate = BMM350_DATA_RATE_12_5HZ); - - /** - * @fn setRate - * @brief Set the rate of obtaining geomagnetic data, the higher, the faster (without delay function) - * @param rate - * @n BMM350_DATA_RATE_1_5625HZ - * @n BMM350_DATA_RATE_3_125HZ - * @n BMM350_DATA_RATE_6_25HZ - * @n BMM350_DATA_RATE_12_5HZ (default rate) - * @n BMM350_DATA_RATE_25HZ - * @n BMM350_DATA_RATE_50HZ - * @n BMM350_DATA_RATE_100HZ - * @n BMM350_DATA_RATE_200HZ - * @n BMM350_DATA_RATE_400HZ - */ - void setRate(uint8_t rate); - - /** - * @fn getRate - * @brief Get the config data rate, unit: HZ - * @return rate - */ - float getRate(void); - - /** - * @fn selfTest - * @brief The sensor self test, the returned value indicate the self test result. - * @param testMode: - * @n eBmm350SelfTestNormal Normal self test, test whether x-axis, y-axis and z-axis are connected or short-circuited - * @return result The returned character string is the self test result - */ - String selfTest(eBmm350SelfTest_t testMode = eBmm350SelfTestNormal); - - /** - * @fn setMeasurementXYZ - * @brief Enable the measurement at x-axis, y-axis and z-axis, default to be enabled. After disabling, the geomagnetic data at x, y, and z axis are wrong. - * @param en_x - * @n BMM350_X_EN Enable the measurement at x-axis - * @n BMM350_X_DIS Disable the measurement at x-axis - * @param en_y - * @n BMM350_Y_EN Enable the measurement at y-axis - * @n BMM350_Y_DIS Disable the measurement at y-axis - * @param en_z - * @n BMM350_Z_EN Enable the measurement at z-axis - * @n BMM350_Z_DIS Disable the measurement at z-axis - */ - void setMeasurementXYZ(enum eBmm350XAxisEnDis_t enX = BMM350_X_EN, enum eBmm350YAxisEnDis_t enY = BMM350_Y_EN, enum eBmm350ZAxisEnDis_t enZ = BMM350_Z_EN); - - /** - * @fn getMeasurementStateXYZ - * @brief Get the enabling status at x-axis, y-axis and z-axis - * @return result Return enabling status as a character string - */ - String getMeasurementStateXYZ(void); - - /** - * @fn getGeomagneticData - * @brief Get the geomagnetic data of 3 axis (x, y, z) - * @return Geomagnetic data structure, unit: (uT) - */ - sBmm350MagData_t getGeomagneticData(void); - - /** - * @fn getCompassDegree - * @brief Get compass degree - * @return Compass degree (0° - 360°) - * @n 0° = North, 90° = East, 180° = South, 270° = West. - */ - float getCompassDegree(void); - - /** - * @fn setDataReadyPin - * @brief Enable or disable data ready interrupt pin - * @n After enabling, the DRDY pin jump when there's data coming. - * @n After disabling, the DRDY pin will not jump when there's data coming. - * @n High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. - * @n Low polarity: active on low, default is high level, which turns to low level when the interrupt is triggered. - * @param modes - * @n BMM350_ENABLE_INTERRUPT Enable DRDY - * @n BMM350_DISABLE_INTERRUPT Disable DRDY - * @param polarity - * @n BMM350_ACTIVE_HIGH High polarity - * @n BMM350_ACTIVE_LOW Low polarity - */ - void setDataReadyPin(enum eBmm350InterruptEnableDisable_t modes, enum eBmm350IntrPolarity_t polarity=BMM350_ACTIVE_HIGH); - - /** - * @fn getDataReadyState - * @brief Get the data ready status, determine whether the data is ready - * @return status - * @n true Data ready - * @n false Data is not ready - */ - bool getDataReadyState(void); - - /** - * @fn setThresholdInterrupt(uint8_t modes, int8_t threshold, uint8_t polarity) - * @brief Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold - * @n High polarity: active on high level, the default is low level, which turns to high level when the interrupt is triggered. - * @n Low polarity: active on low level, the default is high level, which turns to low level when the interrupt is triggered. - * @param modes - * @n LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode - * @n HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode - * @param threshold - * @n Threshold, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt - * @param polarity - * @n POLARITY_HIGH High polarity - * @n POLARITY_LOW Low polarity - */ - void setThresholdInterrupt(uint8_t modes, int8_t threshold, enum eBmm350IntrPolarity_t polarity); - - /** - * @fn getThresholdData - * @brief Get the data with threshold interrupt occurred - * @return Returns the structure for storing geomagnetic data, the structure stores the data of 3 axis and interrupt status, - * @n The interrupt is not triggered when the data at x-axis, y-axis and z-axis are NO_DATA - * @n mag_x、mag_y、mag_z store geomagnetic data - * @n interrupt_x、interrupt_y、interrupt_z store the xyz axis interrupt state - */ - sBmm350ThresholdData_t getThresholdData(void); -``` - -## Compatibility - -| MCU | Work Well | Work Wrong | Untested | Remarks | -| ------------------ |:---------:|:----------:|:--------:| ------- | -| Arduino uno | √ | | | | -| FireBeetle esp32 | √ | | | | -| FireBeetle esp8266 | √ | | | | -| FireBeetle m0 | √ | | | | -| Leonardo | √ | | | | -| Microbit | √ | | | | -| Arduino MEGA2560 | √ | | | | - -## History - -- 2024/05/08 - Version 1.0.0 released. - -## Credits - -Written by [GDuang](yonglei.ren@dfrobot.com), 2024. (Welcome to our [website](https://www.dfrobot.com/)) diff --git a/lib/DFRobot_BMM350/README_CN.md b/lib/DFRobot_BMM350/README_CN.md deleted file mode 100644 index 0da933b..0000000 --- a/lib/DFRobot_BMM350/README_CN.md +++ /dev/null @@ -1,214 +0,0 @@ -DFRobot_BMP350 -=========================== - -* [English Version](./README.md) - -BMM350 是一款低功耗、低噪声的 3 轴数字地磁传感器,完全符合罗盘应用的要求。 基于博世专有的 FlipCore 技术,BMM350 提供了高精度和动态的绝对空间方向和运动矢量。 体积小、重量轻,特别适用于支持无人机精准航向。 BMM350 还可与由 3 轴加速度计和 3 轴陀螺仪组成的惯性测量单元一起使用。 - -![产品效果图](./resources/images/BMM350.png)![产品效果图](./resources/images/BMM350Size.png) - -## 产品链接([https://www.dfrobot.com.cn](https://www.dfrobot.com.cn)) - -```yaml -SKU: SEN0619 -``` - -## 目录 - -* [概述](#概述) -* [库安装](#库安装) -* [方法](#方法) -* [兼容性](#兼容性) -* [历史](#历史) -* [创作者](#创作者) - -## 概述 - -您可以沿 XYZ 轴获取地磁数据 - -1. 本模块可以获得高阈值和低阈值地磁数据。
-2. 可以测量三个(xyz)轴上的地磁。
-3. 本模块可选择I2C或I3C通讯方式。
- -## 库安装 - -使用此库前,请首先下载库文件,将其粘贴到\Arduino\libraries目录中,然后打开examples文件夹并在该文件夹中运行演示。 - -## 方法 - -```C++ - /** - * @fn softReset - * @brief 软件复位,软件复位后先恢复为挂起模式 - */ - void softReset(void); - - /** - * @fn setOperationMode - * @brief 设置传感器的执行模式 - * @param opMode mode - * @n eBmm350SuspendMode 挂起模式:挂起模式是芯片上电后BMM350的默认电源模式,在挂起模式下电流消耗最小,因此该模式适用于不需要数据转换的时期(所有寄存器的读写都是可能的) - * @n eBmm350NormalMode 常规模式: 获取地磁数据 - * @n eBmm350ForcedMode 强制模式: 单次测量,测量完成后传感器恢复到暂停模式 - * @n eBmm350ForcedModeFast 只有使用FM_FAST时,ODR才能达到200Hz - */ - void setOperationMode(uint8_t opMode); - - /** - * @fn getOperationMode - * @brief 获取传感器的执行模式 - * @return result 返回字符串为传感器的执行模式 - */ - String getOperationMode(void); - - /** - * @fn setPresetMode - * @brief 设置预置模式,使用户更简单的配置传感器来获取地磁数据(默认的采集速率为12.5Hz) - * @param presetMode - * @n BMM350_PRESETMODE_LOWPOWER 低功率模式,获取少量的数据 取均值 - * @n BMM350_PRESETMODE_REGULAR 普通模式,获取中量数据 取均值 - * @n BMM350_PRESETMODE_ENHANCED 增强模式,获取大量数据 取均值 - * @n BMM350_PRESETMODE_HIGHACCURACY 高精度模式,获取超大量数据 取均值 - */ - void setPresetMode(uint8_t presetMode, uint8_t rate = BMM350_DATA_RATE_12_5HZ); - - /** - * @fn setRate - * @brief 设置获取地磁数据的速率,速率越大获取越快(不加延时函数) - * @param rate - * @n BMM350_DATA_RATE_1_5625HZ - * @n BMM350_DATA_RATE_3_125HZ - * @n BMM350_DATA_RATE_6_25HZ - * @n BMM350_DATA_RATE_12_5HZ (默认速率) - * @n BMM350_DATA_RATE_25HZ - * @n BMM350_DATA_RATE_50HZ - * @n BMM350_DATA_RATE_100HZ - * @n BMM350_DATA_RATE_200HZ - * @n BMM350_DATA_RATE_400HZ - */ - void setRate(uint8_t rate); - - /** - * @fn getRate - * @brief 获取配置的数据速率 单位:HZ - * @return rate - */ - uint8_t getRate(void); - - /** - * @fn selfTest - * @brief 传感器自测,返回值表明自检结果 - * @param testMode: - * @n eBmm350SelfTestNormal 常规自检,检查x轴、y轴、z轴是否接通或短路 - * @return result 返回的字符串为自测的结果 - */ - String selfTest(eBmm350SelfTest_t testMode = eBmm350SelfTestNormal); - - /** - * @fn setMeasurementXYZ - * @brief 使能x y z 轴的测量,默认设置为使能,禁止后xyz轴的地磁数据不准确 - * @param en_x - * @n BMM350_X_EN 使能 x 轴的测量 - * @n BMM350_X_DIS 禁止 x 轴的测量 - * @param en_y - * @n BMM350_Y_EN 使能 y 轴的测量 - * @n BMM350_Y_DIS 禁止 y 轴的测量 - * @param en_z - * @n BMM350_Z_EN 使能 z 轴的测量 - * @n BMM350_Z_DIS 禁止 z 轴的测量 - */ - void setMeasurementXYZ(enum eBmm350XAxisEnDis_t enX = BMM350_X_EN, enum eBmm350YAxisEnDis_t enY = BMM350_Y_EN, enum eBmm350ZAxisEnDis_t enZ = BMM350_Z_EN); - - /** - * @fn getMeasurementStateXYZ - * @brief 获取 x y z 轴的使能状态 - * @return result 返回字符串为使能的状态 - */ - String getMeasurementStateXYZ(void); - - /** - * @fn getGeomagneticData - * @brief 获取x y z 三轴的地磁数据 - * @return 地磁的数据的结构体,单位:微特斯拉(uT) - */ - sBmm350MagData_t getGeomagneticData(void); - - /** - * @fn getCompassDegree - * @brief 获取罗盘方向 - * @return 罗盘方向 (0° - 360°) - * @n 0° = North, 90° = East, 180° = South, 270° = West. - */ - float getCompassDegree(void); - - /** - * @fn setDataReadyPin - * @brief 使能或者禁止数据准备中断引脚 - * @n 使能后有数据来临DRDY引脚跳变 - * @n 禁止后有数据来临DRDY不进行跳变 - * @n 高极性:高电平为活动电平,默认为低电平,触发中断时电平变为高 - * @n 低极性:低电平为活动电平,默认为高电平,触发中断时电平变为低 - * @param modes - * @n BMM350_ENABLE_INTERRUPT 使能DRDY - * @n BMM350_DISABLE_INTERRUPT 禁止DRDY - * @param polarity - * @n BMM350_ACTIVE_HIGH 高极性 - * @n BMM350_ACTIVE_LOW 低极性 - */ - void setDataReadyPin(uint8_t modes, uint8_t polarity=POLARITY_HIGH); - - /** - * @fn getDataReadyState - * @brief 获取数据准备的状态,用来判断数据是否准备好 - * @return status - * @n true 数据准备好了 - * @n false 数据没有准备好 - */ - bool getDataReadyState(void); - - /** - * @fn setThresholdInterrupt(uint8_t modes, int8_t threshold, uint8_t polarity) - * @brief 设置阈值中断,当某个通道的地磁值高/低于阈值时触发中断 - * @n 高极性:高电平为活动电平,默认为低电平,触发中断时电平变为高 - * @n 低极性:低电平为活动电平,默认为高电平,触发中断时电平变为低 - * @param modes - * @n LOW_THRESHOLD_INTERRUPT 低阈值中断模式 - * @n HIGH_THRESHOLD_INTERRUPT 高阈值中断模式 - * @param threshold - * @n 阈值,默认扩大16倍,例如:低阈值模式下传入阈值1,实际低于16的地磁数据都会触发中断 - * @param polarity - * @n POLARITY_HIGH 高极性 - * @n POLARITY_LOW 低极性 - */ - void setThresholdInterrupt(uint8_t modes, int8_t threshold, enum eBmm350IntrPolarity_t polarity); - - /** - * @fn getThresholdData - * @brief 获取发生阈值中断的数据 - * @return 返回存放地磁数据的结构体,结构体存放三轴当数据和中断状态, - * @n xyz轴的数据为 NO_DATA 时,未触发中断 - * @n mag_x、mag_y、mag_z 存放地磁数据 - * @n interrupt_x、interrupt_y、interrupt_z 存放轴中断状态 - */ - sBmm350ThresholdData_t getThresholdData(void); -``` - -## 兼容性 - -| MCU | Work Well | Work Wrong | Untested | Remarks | -| ------------------ |:---------:|:----------:|:--------:| ------- | -| Arduino uno | √ | | | | -| FireBeetle esp32 | √ | | | | -| FireBeetle esp8266 | √ | | | | -| FireBeetle m0 | √ | | | | -| Leonardo | √ | | | | -| Microbit | √ | | | | -| Arduino MEGA2560 | √ | | | | - -## History - -- 2024/05/08 - Version 1.0.0 released. - -## Credits - -Written by [GDuang](yonglei.ren@dfrobot.com), 2024. (Welcome to our [website](https://www.dfrobot.com/)) diff --git a/lib/DFRobot_BMM350/examples/calibration/CalibratedMagnedticData/CalibratedMagnedticData.ino b/lib/DFRobot_BMM350/examples/calibration/CalibratedMagnedticData/CalibratedMagnedticData.ino deleted file mode 100644 index bbde827..0000000 --- a/lib/DFRobot_BMM350/examples/calibration/CalibratedMagnedticData/CalibratedMagnedticData.ino +++ /dev/null @@ -1,129 +0,0 @@ -/*! - * @file CalibratedMagnedticData.ino - * @brief Get the Calibrated geomagnetic data at 3 axis (x, y, z), get the compass degree - * @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north - * @n Experimental phenomenon: serial print the geomagnetic data of x-axis, y-axis and z-axis and the compass degree - * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - * @license The MIT License (MIT) - * @author [GDuang](yonglei.ren@dfrobot.com) - * @version V1.0.0 - * @date 2024-05-06 - * @url https://github.com/DFRobot/DFRobot_BMM350/ - */ - -// ======================================================= -// 请先阅读项目 https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration -// Please read https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration -// 包含使用说明、校准步骤。 -// It contains usage instructions, calibration steps. -// ======================================================= - -#include "DFRobot_BMM350.h" - -DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); -//hard iron calibration parameters -const float hard_iron[3] = { -13.45, -28.95, 12.69 }; -//soft iron calibration parameters -const float soft_iron[3][3] = { - { 0.992, -0.006, -0.007 }, - { -0.006, 0.990, -0.004 }, - { -0.007, -0.004, 1.019 } -}; - -void setup() { - Serial.begin(115200); - while (!Serial) - ; - while (bmm350.begin()) { - Serial.println("bmm350 init failed, Please try again!"); - delay(1000); - } - Serial.println("bmm350 init success!"); - - /** - * Set sensor operation mode - * opMode: - * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - * eBmm350NormalMode // normal mode Get geomagnetic data normally. - * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. - * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. - */ - bmm350.setOperationMode(eBmm350NormalMode); - - /** - * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - * presetMode: - * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. - * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. - * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. - * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. - * rate: - * BMM350_DATA_RATE_1_5625HZ - * BMM350_DATA_RATE_3_125HZ - * BMM350_DATA_RATE_6_25HZ - * BMM350_DATA_RATE_12_5HZ (default rate) - * BMM350_DATA_RATE_25HZ - * BMM350_DATA_RATE_50HZ - * BMM350_DATA_RATE_100HZ - * BMM350_DATA_RATE_200HZ - * BMM350_DATA_RATE_400HZ - */ - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); - - /** - * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. - * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. - */ - bmm350.setMeasurementXYZ(); -} - -void loop() { - sBmm350MagData_t magData = bmm350.getGeomagneticData(); - - float mag_data[3]; - - // hard iron calibration - mag_data[0] = magData.float_x + hard_iron[0]; - mag_data[1] = magData.float_y + hard_iron[1]; - mag_data[2] = magData.float_z + hard_iron[2]; - - //soft iron calibration - for (int i = 0; i < 3; i++) { - mag_data[i] = (soft_iron[i][0] * mag_data[0]) + (soft_iron[i][1] * mag_data[1]) + (soft_iron[i][2] * mag_data[2]); - } - - magData.x = mag_data[0]; - magData.y = mag_data[1]; - magData.z = mag_data[2]; - magData.float_x = mag_data[0]; - magData.float_y = mag_data[1]; - magData.float_z = mag_data[2]; - - Serial.print("mag x = ");Serial.print(magData.x);Serial.println(" uT"); - Serial.print("mag y = ");Serial.print(magData.y);Serial.println(" uT"); - Serial.print("mag z = ");Serial.print(magData.z);Serial.println(" uT"); - - // float type data - //Serial.print("mag x = "); Serial.print(magData.float_x); Serial.println(" uT"); - //Serial.print("mag y = "); Serial.print(magData.float_y); Serial.println(" uT"); - //Serial.print("mag z = "); Serial.print(magData.float_z); Serial.println(" uT"); - - float compassDegree = getCompassDegree(magData); - Serial.print("the angle between the pointing direction and north (counterclockwise) is:"); - Serial.println(compassDegree); - Serial.println("--------------------------------"); - delay(3000); -} -float getCompassDegree(sBmm350MagData_t magData) -{ - float compass = 0.0; - compass = atan2(magData.x, magData.y); - if (compass < 0) { - compass += 2 * PI; - } - if (compass > 2 * PI) { - compass -= 2 * PI; - } - return compass * 180 / M_PI; -} diff --git a/lib/DFRobot_BMM350/examples/calibration/README.md b/lib/DFRobot_BMM350/examples/calibration/README.md deleted file mode 100644 index fc0f586..0000000 --- a/lib/DFRobot_BMM350/examples/calibration/README.md +++ /dev/null @@ -1,175 +0,0 @@ -# Guide to Calibrating BMM350 Magnetic Field Data Using MotionCal - -* [中文版本](./README_CN.md) - -Magnetometers in real-world applications are susceptible to interference from metal objects, electrical currents, and fluctuations in the Earth's magnetic field. Uncalibrated data can lead to deviations in direction recognition, affecting the accuracy of the heading angle (yaw) or the functionality of the electronic compass. - ---- - -## Required Tools - -* [MotionCal](https://www.pjrc.com/store/prop_shield.html#motioncal) tool (supports Windows/macOS/Linux) -* Arduino IDE -* A development board supported by the DFRobot_BMM350 sensor, with the serial port correctly connected to the PC - ---- - -## Step 1: Upload the Calibration Firmware - -Use a development board supported by the DFRobot_BMM350 sensor and connect the serial port to the PC correctly. - ---- - -## Step 2: Run the MotionCal Tool - -1. Open the [MotionCal](https://www.pjrc.com/store/prop_shield.html#motioncal) download page, select your platform, and download and install the tool. - -![MotionCal download pic](/resources/images/cal_pic1.jpg) - -2. Launch `MotionCal`. -3. Select the correct serial port in the menu (consistent with your device). - -![MotionCal port choose](/resources/images/cal_pic2.jpg) - -4. MotionCal automatically starts receiving and visualizing the data from the magnetometer, accelerometer, and gyroscope. - -> Ensure that no other serial port software is open simultaneously! - ---- - -## Step 3: Rotate the Sensor for Omnidirectional Sampling - -> Slowly rotate the sensor along the **X/Y/Z axes** to ensure that the data graph covers a complete sphere. - -![MotionCal cal](/resources/images/cal_pic3.jpg) - -## Step 4: Apply Compensation in the Code - -![calibration parameters](/resources/images/cal_pic4.jpg) - -The calibration parameters required are located in the top-left corner of the MotionCal software. -Fill in the calibration coefficients in the corresponding positions of the reference code `CalibrateMagnedticData.ino`. - -```cpp -//hard iron calibration parameters -const float hard_iron[3] = { -13.45, -28.95, 12.69 }; -//soft iron calibration parameters -const float soft_iron[3][3] = { - { 0.992, -0.006, -0.007 }, - { -0.006, 0.990, -0.004 }, - { -0.007, -0.004, 1.019 } -}; -``` - -The complete reference code is as follows: - -```cpp -#include "DFRobot_BMM350.h" - -DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); -//hard iron calibration parameters -const float hard_iron[3] = { -13.45, -28.95, 12.69 }; -//soft iron calibration parameters -const float soft_iron[3][3] = { - { 0.992, -0.006, -0.007 }, - { -0.006, 0.990, -0.004 }, - { -0.007, -0.004, 1.019 } -}; - -void setup() { - Serial.begin(115200); - while (!Serial) - ; - while (bmm350.begin()) { - Serial.println("bmm350 init failed, Please try again!"); - delay(1000); - } - Serial.println("bmm350 init success!"); - - /** - * Set sensor operation mode - * opMode: - * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - * eBmm350NormalMode // normal mode Get geomagnetic data normally. - * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. - * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. - */ - bmm350.setOperationMode(eBmm350NormalMode); - - /** - * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - * presetMode: - * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. - * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. - * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. - * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. - */ - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); - - /** - * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. - * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. - */ - bmm350.setMeasurementXYZ(); -} - -void loop() { - sBmm350MagData_t magData = bmm350.getGeomagneticData(); - - float mag_data[3]; - - // hard iron calibration - mag_data[0] = magData.float_x + hard_iron[0]; - mag_data[1] = magData.float_y + hard_iron[1]; - mag_data[2] = magData.float_z + hard_iron[2]; - - //soft iron calibration - for (int i = 0; i < 3; i++) { - mag_data[i] = (soft_iron[i][0] * mag_data[0]) + (soft_iron[i][1] * mag_data[1]) + (soft_iron[i][2] * mag_data[2]); - } - - magData.x = mag_data[0]; - magData.y = mag_data[1]; - magData.z = mag_data[2]; - magData.float_x = mag_data[0]; - magData.float_y = mag_data[1]; - magData.float_z = mag_data[2]; - - Serial.print("mag x = ");Serial.print(magData.x);Serial.println(" uT"); - Serial.print("mag y = ");Serial.print(magData.y);Serial.println(" uT"); - Serial.print("mag z = ");Serial.print(magData.z);Serial.println(" uT"); - - // float type data - //Serial.print("mag x = "); Serial.print(magData.float_x); Serial.println(" uT"); - //Serial.print("mag y = "); Serial.print(magData.float_y); Serial.println(" uT"); - //Serial.print("mag z = "); Serial.print(magData.float_z); Serial.println(" uT"); - - float compassDegree = getCompassDegree(magData); - Serial.print("the angle between the pointing direction and north (counterclockwise) is:"); - Serial.println(compassDegree); - Serial.println("--------------------------------"); - delay(3000); -} -float getCompassDegree(sBmm350MagData_t magData) -{ - float compass = 0.0; - compass = atan2(magData.x, magData.y); - if (compass < 0) { - compass += 2 * PI; - } - if (compass > 2 * PI) { - compass -= 2 * PI; - } - return compass * 180 / M_PI; -} -``` - ---- - ---- - -## 📎 Appendix - -* MotionCal download link: [https://www.pjrc.com/store/prop_shield.html#motioncal](https://www.pjrc.com/store/prop_shield.html#motioncal) -* DFRobot BMM350 Sensor: [https://wiki.dfrobot.com.cn/_SKU_SEN0619_Gravity_BMM350_TripleAxis_Magnetometer_Sensor](https://wiki.dfrobot.com.cn/_SKU_SEN0619_Gravity_BMM350_TripleAxis_Magnetometer_Sensor) \ No newline at end of file diff --git a/lib/DFRobot_BMM350/examples/calibration/README_CN.md b/lib/DFRobot_BMM350/examples/calibration/README_CN.md deleted file mode 100644 index d7ada6f..0000000 --- a/lib/DFRobot_BMM350/examples/calibration/README_CN.md +++ /dev/null @@ -1,242 +0,0 @@ -# 使用 MotionCal 校准磁场数据指南 - -* [English Version](./README.md) - -磁力计在现实应用中易受金属物体、电流干扰和地磁场波动的影响。未经校准的数据可能会导致方向识别偏移,影响航向角(yaw)或电子罗盘功能的准确性。 - ---- - -## 所需工具 - -* [MotionCal](https://www.pjrc.com/store/prop_shield.html#motioncal) 工具(支持 Windows/macOS/Linux) -* Arduino IDE -* DFRobot_BMM350传感器器所支持的开发板,并将串口正确连接到PC - ---- - -## 步骤一:上传校准固件 - -DFRobot_BMM350传感器器所支持的开发板,并将串口正确连接到PC - -```cpp -#include "DFRobot_BMM350.h" - -DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); -void setup() { - Serial.begin(115200); - while (!Serial) - ; - while (bmm350.begin()) { - Serial.println("bmm350 init failed, Please try again!"); - delay(1000); - } - Serial.println("bmm350 init success!"); - - /** - * Set sensor operation mode - * opMode: - * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - * eBmm350NormalMode // normal mode Get geomagnetic data normally. - * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. - * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. - */ - bmm350.setOperationMode(eBmm350NormalMode); - - /** - * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - * presetMode: - * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. - * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. - * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. - * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. - */ - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); - - /** - * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. - * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. - */ - bmm350.setMeasurementXYZ(); -} - -void loop() { - sBmm350MagData_t magData = bmm350.getGeomagneticData(); - Serial.print("Raw:"); - Serial.print(0); - Serial.print(','); - Serial.print(0); - Serial.print(','); - Serial.print(0); - Serial.print(','); - Serial.print(0); - Serial.print(','); - Serial.print(0); - Serial.print(','); - Serial.print(0); - Serial.print(','); - Serial.print(magData.x*10); - Serial.print(','); - Serial.print(magData.y*10); - Serial.print(','); - Serial.print(magData.z*10); - Serial.println(); - delay(100); -} -``` - ---- - -## 步骤二:运行 MotionCal 工具 - -1. 打开 [MotionCal](https://www.pjrc.com/store/prop_shield.html#motioncal) 下载页面,选择你的平台并下载安装。 - -![MotionCal download pic](/resources/images/cal_pic1.jpg) - -2. 启动 `MotionCal`。 -3. 在菜单中选择正确的串口(与你的设备一致)。 - -![MotionCal port choose](/resources/images/cal_pic2.jpg) - -4. MotionCal 自动开始自动接收并可视化磁力计、加速度计和陀螺仪数据。 - -> 确保没有其它串口软件同时打开!! - ---- - -## 步骤三:旋转传感器进行全向采样 - -> 将传感器沿 **X/Y/Z 各轴方向**缓慢旋转,使数据图形覆盖完整的球体。 - -![MotionCal cal](/resources/images/cal_pic3.jpg) - -## 步骤四:在代码中应用补偿 - -![calibration parameters](/resources/images/cal_pic4.jpg) - -MotionCal软件左上角即为所需的校正参数 -分别将校正系数填入参考代码`CalibrateMagnedticData.ino`,对应位置 - -```cpp -//hard iron calibration parameters -const float hard_iron[3] = { -13.45, -28.95, 12.69 }; -//soft iron calibration parameters -const float soft_iron[3][3] = { - { 0.992, -0.006, -0.007 }, - { -0.006, 0.990, -0.004 }, - { -0.007, -0.004, 1.019 } -}; -``` - -完整参考代码如下: - -```cpp -#include "DFRobot_BMM350.h" - -DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); -//hard iron calibration parameters -const float hard_iron[3] = { -13.45, -28.95, 12.69 }; -//soft iron calibration parameters -const float soft_iron[3][3] = { - { 0.992, -0.006, -0.007 }, - { -0.006, 0.990, -0.004 }, - { -0.007, -0.004, 1.019 } -}; - -void setup() { - Serial.begin(115200); - while (!Serial) - ; - while (bmm350.begin()) { - Serial.println("bmm350 init failed, Please try again!"); - delay(1000); - } - Serial.println("bmm350 init success!"); - - /** - * Set sensor operation mode - * opMode: - * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - * eBmm350NormalMode // normal mode Get geomagnetic data normally. - * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. - * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. - */ - bmm350.setOperationMode(eBmm350NormalMode); - - /** - * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - * presetMode: - * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. - * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. - * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. - * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. - */ - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); - - /** - * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. - * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. - */ - bmm350.setMeasurementXYZ(); -} - -void loop() { - sBmm350MagData_t magData = bmm350.getGeomagneticData(); - - float mag_data[3]; - - // hard iron calibration - mag_data[0] = magData.float_x + hard_iron[0]; - mag_data[1] = magData.float_y + hard_iron[1]; - mag_data[2] = magData.float_z + hard_iron[2]; - - //soft iron calibration - for (int i = 0; i < 3; i++) { - mag_data[i] = (soft_iron[i][0] * mag_data[0]) + (soft_iron[i][1] * mag_data[1]) + (soft_iron[i][2] * mag_data[2]); - } - - magData.x = mag_data[0]; - magData.y = mag_data[1]; - magData.z = mag_data[2]; - magData.float_x = mag_data[0]; - magData.float_y = mag_data[1]; - magData.float_z = mag_data[2]; - - Serial.print("mag x = ");Serial.print(magData.x);Serial.println(" uT"); - Serial.print("mag y = ");Serial.print(magData.y);Serial.println(" uT"); - Serial.print("mag z = ");Serial.print(magData.z);Serial.println(" uT"); - - // float type data - //Serial.print("mag x = "); Serial.print(magData.float_x); Serial.println(" uT"); - //Serial.print("mag y = "); Serial.print(magData.float_y); Serial.println(" uT"); - //Serial.print("mag z = "); Serial.print(magData.float_z); Serial.println(" uT"); - - float compassDegree = getCompassDegree(magData); - Serial.print("the angle between the pointing direction and north (counterclockwise) is:"); - Serial.println(compassDegree); - Serial.println("--------------------------------"); - delay(3000); -} -float getCompassDegree(sBmm350MagData_t magData) -{ - float compass = 0.0; - compass = atan2(magData.x, magData.y); - if (compass < 0) { - compass += 2 * PI; - } - if (compass > 2 * PI) { - compass -= 2 * PI; - } - return compass * 180 / M_PI; -} -``` - ---- - ---- - -## 📎 附录 - -* MotionCal 下载地址:[https://www.pjrc.com/store/prop\_shield.html#motioncal](https://www.pjrc.com/store/prop_shield.html#motioncal) -* DFRobot BMM350 Sensor:[https://wiki.dfrobot.com.cn/_SKU_SEN0619_Gravity_BMM350_TripleAxis_Magnetometer_Sensor](https://wiki.dfrobot.com.cn/_SKU_SEN0619_Gravity_BMM350_TripleAxis_Magnetometer_Sensor) diff --git a/lib/DFRobot_BMM350/examples/calibration/getCalibrateData/getCalibrateData.ino b/lib/DFRobot_BMM350/examples/calibration/getCalibrateData/getCalibrateData.ino deleted file mode 100644 index 36ef582..0000000 --- a/lib/DFRobot_BMM350/examples/calibration/getCalibrateData/getCalibrateData.ino +++ /dev/null @@ -1,92 +0,0 @@ -/*! - * @file getGeomagneticData.ino - * @brief Get the calibration data - * @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north - * @n Experimental phenomenon: serial print the geomagnetic data of x-axis, y-axis and z-axis and the compass degree - * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - * @license The MIT License (MIT) - * @author [GDuang](yonglei.ren@dfrobot.com) - * @version V1.0.0 - * @date 2024-05-06 - * @url https://github.com/DFRobot/DFRobot_BMM350/ - */ - -// ======================================================= -// 请先阅读项目 https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration -// Please read https://github.com/DFRobot/DFRobot_BMM350/tree/master/examples/calibration -// 包含使用说明、校准步骤。 -// It contains usage instructions, calibration steps. -// ======================================================= -#include "DFRobot_BMM350.h" - -DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); -void setup() { - Serial.begin(115200); - while (!Serial) - ; - while (bmm350.begin()) { - Serial.println("bmm350 init failed, Please try again!"); - delay(1000); - } - Serial.println("bmm350 init success!"); - - /** - * Set sensor operation mode - * opMode: - * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - * eBmm350NormalMode // normal mode Get geomagnetic data normally. - * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. - * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. - */ - bmm350.setOperationMode(eBmm350NormalMode); - /** - * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - * presetMode: - * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. - * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. - * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. - * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. - * rate: - * BMM350_DATA_RATE_1_5625HZ - * BMM350_DATA_RATE_3_125HZ - * BMM350_DATA_RATE_6_25HZ - * BMM350_DATA_RATE_12_5HZ (default rate) - * BMM350_DATA_RATE_25HZ - * BMM350_DATA_RATE_50HZ - * BMM350_DATA_RATE_100HZ - * BMM350_DATA_RATE_200HZ - * BMM350_DATA_RATE_400HZ - */ - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); - - /** - * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. - * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. - */ - bmm350.setMeasurementXYZ(); -} - -void loop() { - sBmm350MagData_t magData = bmm350.getGeomagneticData(); - Serial.print("Raw:"); - Serial.print(0); - Serial.print(','); - Serial.print(0); - Serial.print(','); - Serial.print(0); - Serial.print(','); - Serial.print(0); - Serial.print(','); - Serial.print(0); - Serial.print(','); - Serial.print(0); - Serial.print(','); - Serial.print(magData.x*10); - Serial.print(','); - Serial.print(magData.y*10); - Serial.print(','); - Serial.print(magData.z*10); - Serial.println(); - delay(100); -} diff --git a/lib/DFRobot_BMM350/examples/getAllState/getAllState.ino b/lib/DFRobot_BMM350/examples/getAllState/getAllState.ino deleted file mode 100644 index aad0cfa..0000000 --- a/lib/DFRobot_BMM350/examples/getAllState/getAllState.ino +++ /dev/null @@ -1,95 +0,0 @@ - /*! - * @file getAllState.ino - * @brief Get all the config status, self test status; the sensor turns to sleep mode from normal mode after reset - * @n Experimental phenomenon: serial print the sensor config information and the self-test information - * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - * @license The MIT License (MIT) - * @author [GDuang](yonglei.ren@dfrobot.com) - * @version V1.0.0 - * @date 2024-05-06 - * @url https://github.com/DFRobot/DFRobot_BMM350 - */ -#include "DFRobot_BMM350.h" - -DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); - -void setup() -{ - Serial.begin(115200); - while(!Serial); - while(bmm350.begin()){ - Serial.println("bmm350 init failed, Please try again!"); - delay(1000); - } Serial.println("bmm350 init success!"); - - /** - * Sensor self test, the returned character string indicates the test result. - */ - Serial.println(bmm350.selfTest()); - - /** - * Set sensor operation mode - * opMode: - * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - * eBmm350NormalMode // normal mode Get geomagnetic data normally. - * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. - * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. - */ - bmm350.setOperationMode(eBmm350NormalMode); - /** - * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - * presetMode: - * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. - * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. - * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. - * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. - * rate: - * BMM350_DATA_RATE_1_5625HZ - * BMM350_DATA_RATE_3_125HZ - * BMM350_DATA_RATE_6_25HZ - * BMM350_DATA_RATE_12_5HZ (default rate) - * BMM350_DATA_RATE_25HZ - * BMM350_DATA_RATE_50HZ - * BMM350_DATA_RATE_100HZ - * BMM350_DATA_RATE_200HZ - * BMM350_DATA_RATE_400HZ - */ - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); - - /** - * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. - * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. - */ - bmm350.setMeasurementXYZ(); - - /** - * Get the config data rate unit: HZ - */ - float rate = bmm350.getRate(); - Serial.print("rate is "); Serial.print(rate); Serial.println(" HZ"); - - /** - * Get the measurement status at x-axis, y-axis and z-axis, return the measurement status as character string - */ - Serial.println(bmm350.getMeasurementStateXYZ()); - - /** - * Get the sensor operation mode, return the sensor operation status as character string - */ - Serial.println(bmm350.getOperationMode()); - - /** - * After the software is reset, it enters the suspended mode. - */ - bmm350.softReset(); -} - -void loop() -{ - /** - * Get the sensor operation mode, return the sensor operation status as character string - */ - Serial.println(bmm350.getOperationMode()); - delay(3000); -} diff --git a/lib/DFRobot_BMM350/examples/getGeomagneticData/getGeomagneticData.ino b/lib/DFRobot_BMM350/examples/getGeomagneticData/getGeomagneticData.ino deleted file mode 100644 index 5cb3298..0000000 --- a/lib/DFRobot_BMM350/examples/getGeomagneticData/getGeomagneticData.ino +++ /dev/null @@ -1,84 +0,0 @@ - /*! - * @file getGeomagneticData.ino - * @brief Get the geomagnetic data at 3 axis (x, y, z), get the compass degree - * @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north - * @n Experimental phenomenon: serial print the geomagnetic data of x-axis, y-axis and z-axis and the compass degree - * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - * @license The MIT License (MIT) - * @author [GDuang](yonglei.ren@dfrobot.com) - * @version V1.0.0 - * @date 2024-05-06 - * @url https://github.com/DFRobot/DFRobot_BMM350 - */ - -#include "DFRobot_BMM350.h" - - -DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); - -void setup() -{ - Serial.begin(115200); - while(!Serial); - while(bmm350.begin()){ - Serial.println("bmm350 init failed, Please try again!"); - delay(1000); - } Serial.println("bmm350 init success!"); - - /** - * Set sensor operation mode - * opMode: - * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - * eBmm350NormalMode // normal mode Get geomagnetic data normally. - * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. - * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. - */ - bmm350.setOperationMode(eBmm350NormalMode); - - /** - * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - * presetMode: - * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. - * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. - * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. - * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. - * rate: - * BMM350_DATA_RATE_1_5625HZ - * BMM350_DATA_RATE_3_125HZ - * BMM350_DATA_RATE_6_25HZ - * BMM350_DATA_RATE_12_5HZ (default rate) - * BMM350_DATA_RATE_25HZ - * BMM350_DATA_RATE_50HZ - * BMM350_DATA_RATE_100HZ - * BMM350_DATA_RATE_200HZ - * BMM350_DATA_RATE_400HZ - */ - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); - - - /** - * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. - * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. - */ - bmm350.setMeasurementXYZ(); -} - -void loop() -{ - sBmm350MagData_t magData = bmm350.getGeomagneticData(); - Serial.print("mag x = "); Serial.print(magData.x); Serial.println(" uT"); - Serial.print("mag y = "); Serial.print(magData.y); Serial.println(" uT"); - Serial.print("mag z = "); Serial.print(magData.z); Serial.println(" uT"); - - // float type data - //Serial.print("mag x = "); Serial.print(magData.float_x); Serial.println(" uT"); - //Serial.print("mag y = "); Serial.print(magData.float_y); Serial.println(" uT"); - //Serial.print("mag z = "); Serial.print(magData.float_z); Serial.println(" uT"); - - float compassDegree = bmm350.getCompassDegree(); - Serial.print("the angle between the pointing direction and north (counterclockwise) is:"); - Serial.println(compassDegree); - Serial.println("--------------------------------"); - delay(3000); -} diff --git a/lib/DFRobot_BMM350/examples/magDrdyInterrupt/magDrdyInterrupt.ino b/lib/DFRobot_BMM350/examples/magDrdyInterrupt/magDrdyInterrupt.ino deleted file mode 100644 index 56d4331..0000000 --- a/lib/DFRobot_BMM350/examples/magDrdyInterrupt/magDrdyInterrupt.ino +++ /dev/null @@ -1,186 +0,0 @@ - /*! - * @file magDrdyInterrupt.ino - * @brief Data ready interrupt, DRDY interrupt will be triggered when the geomagnetic data is ready (the software and hardware can determine whether the interrupt occur) - * @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis, unit (uT) - * @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by DRDY pin interrupt, then the geomagnetic data can be obtained. - * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - * @license The MIT License (MIT) - * @author [GDuang](yonglei.ren@dfrobot.com) - * @version V1.0.0 - * @date 2024-05-06 - * @url https://github.com/DFRobot/DFRobot_BMM350 - */ -#include "DFRobot_BMM350.h" - -DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); - -volatile uint8_t interruptFlag = 0; -void myInterrupt(void) -{ - interruptFlag = 1; // Interrupt flag - #if defined(ESP32) || defined(ESP8266) || defined(ARDUINO_SAM_ZERO) - detachInterrupt(13); // Detach interrupt - #else - detachInterrupt(0); // Detach interrupt - #endif -} - -void setup() -{ - Serial.begin(115200); - while(!Serial); - while(bmm350.begin()){ - Serial.println("bmm350 init failed, Please try again!"); - delay(1000); - } Serial.println("bmm350 init success!"); - - /** - * Set sensor operation mode - * opMode: - * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - * eBmm350NormalMode // normal mode Get geomagnetic data normally. - * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. - * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. - */ - bmm350.setOperationMode(eBmm350NormalMode); - - /** - * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - * presetMode: - * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. - * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. - * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. - * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. - * rate: - * BMM350_DATA_RATE_1_5625HZ - * BMM350_DATA_RATE_3_125HZ - * BMM350_DATA_RATE_6_25HZ - * BMM350_DATA_RATE_12_5HZ (default rate) - * BMM350_DATA_RATE_25HZ - * BMM350_DATA_RATE_50HZ - * BMM350_DATA_RATE_100HZ - * BMM350_DATA_RATE_200HZ - * BMM350_DATA_RATE_400HZ - */ - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); - - - /** - * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. - * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. - */ - bmm350.setMeasurementXYZ(); - - /** - * Enable or disable data ready interrupt pin, - * After enabling, the DRDY pin level will change when there's data coming. - * After disabling, the DRDY pin level will not change when there's data coming. - * High polarity: active on high level, the default is low level, which turns to high level when the interrupt is triggered. - * Low polarity: active on low level, the default is high level, which turns to low level when the interrupt is triggered. - * modes: - * BMM350_ENABLE_INTERRUPT // Enable DRDY - * BMM350_DISABLE_INTERRUPT // Disable DRDY - * polatily: - * BMM350_ACTIVE_HIGH // High polarity - * BMM350_ACTIVE_LOW // Low polarity - */ - bmm350.setDataReadyPin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW); - - -#if defined(ESP32) || defined(ESP8266) - /** - Select according to the set DADY pin polarity - INPUT_PULLUP // Low polarity, set pin 13 to pull-up input - INPUT_PULLDOWN // High polarity, set pin 13 to pull-down input - interput io - All pins can be used. Pin 13 is recommended - */ - pinMode(/*Pin */13 ,INPUT_PULLUP); - attachInterrupt(/*interput io*/13, myInterrupt, ONLOW); -#elif defined(ARDUINO_SAM_ZERO) - pinMode(/*Pin */13 ,INPUT_PULLUP); - attachInterrupt(/*interput io*/13, myInterrupt, LOW); -#else - /** The Correspondence Table of AVR Series Arduino Interrupt Pins And Terminal Numbers - * --------------------------------------------------------------------------------------- - * | | Pin | 2 | 3 | | - * | Uno, Nano, Mini, other 328-based |--------------------------------------------| - * | | Interrupt No | 0 | 1 | | - * |-------------------------------------------------------------------------------------| - * | | Pin | 2 | 3 | 21 | 20 | 19 | 18 | - * | Mega2560 |--------------------------------------------| - * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | 5 | - * |-------------------------------------------------------------------------------------| - * | | Pin | 3 | 2 | 0 | 1 | 7 | | - * | Leonardo, other 32u4-based |--------------------------------------------| - * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | | - * |-------------------------------------------------------------------------------------- - */ - - /** The Correspondence Table of micro:bit Interrupt Pins And Terminal Numbers - * --------------------------------------------------------------------------------------------------------------------------------------------- - * | micro:bit | DigitalPin |P0-P20 can be used as an external interrupt | - * | (When using as an external interrupt, |---------------------------------------------------------------------------------------------| - * |no need to set it to input mode with pinMode)|Interrupt No|Interrupt number is a pin digital value, such as P0 interrupt number 0, P1 is 1 | - * |-------------------------------------------------------------------------------------------------------------------------------------------| - */ - /** - Select according to the set DADY pin polarity - INPUT_PULLUP // Low polarity, set pin 2 to pull-up input - */ - pinMode(/*Pin */2 ,INPUT_PULLUP); - - /** - Set the pin to interrupt mode - // Open the external interrupt 0, connect INT1/2 to the digital pin of the main control: - function - callback function - state - LOW // When the pin is at low level, the interrupt occur, enter interrupt function - */ - attachInterrupt(/*Interrupt No*/0, /*function*/myInterrupt ,/*state*/LOW ); -#endif -} - -void loop() -{ - /** - * Get data ready status, determine whether the data is ready (get the data ready status through software) - * status: - * true Data ready - * false Data is not ready yet - */ - /* - if(bmm350.getDataReadyState()){ - sBmm350MagData_t magData = bmm350.getGeomagneticData(); - Serial.print("mag x = "); Serial.print(magData.x); Serial.println(" uT"); - Serial.print("mag y = "); Serial.print(magData.y); Serial.println(" uT"); - Serial.print("mag z = "); Serial.print(magData.z); Serial.println(" uT"); - Serial.println(); - } - */ - - /** - When the interrupt occur in DRDY IO, get the geomagnetic data (get the data ready status through hardware) - Enable interrupt again - */ - if(interruptFlag == 1){ - Serial.println("Interrupt triggering!"); - sBmm350MagData_t magData = bmm350.getGeomagneticData(); - Serial.print("mag x = "); Serial.print(magData.x); Serial.println(" uT"); - Serial.print("mag y = "); Serial.print(magData.y); Serial.println(" uT"); - Serial.print("mag z = "); Serial.print(magData.z); Serial.println(" uT"); - Serial.println(); - interruptFlag = 0; - #if defined(ESP32) || defined(ESP8266) - attachInterrupt(13, myInterrupt, ONLOW); - #elif defined(ARDUINO_SAM_ZERO) - attachInterrupt(13, myInterrupt, LOW); - #else - attachInterrupt(0, myInterrupt, LOW); - #endif - } - - delay(1000); -} diff --git a/lib/DFRobot_BMM350/examples/thresholdInterrupt/thresholdInterrupt.ino b/lib/DFRobot_BMM350/examples/thresholdInterrupt/thresholdInterrupt.ino deleted file mode 100644 index a75813f..0000000 --- a/lib/DFRobot_BMM350/examples/thresholdInterrupt/thresholdInterrupt.ino +++ /dev/null @@ -1,194 +0,0 @@ - /*! - * @file thresholdInterrupt.ino - * @brief Set the interrupt to be triggered when beyond/below threshold, when the interrupt at a axis occur, the relevant data will be printed in the serial port. - * @n Experimental phenomenon: when the geomagnetic data at 3 axis (x, y, z) beyond/below threshold, serial print the geomagnetic data, unit (uT) - * @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by INT pin interrupt, then the geomagnetic data can be obtained - * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - * @license The MIT License (MIT) - * @author [GDuang](yonglei.ren@dfrobot.com) - * @version V1.0.0 - * @date 2024-05-06 - * @url https://github.com/DFRobot/DFRobot_BMM350 - */ -#include "DFRobot_BMM350.h" - -DFRobot_BMM350_I2C bmm350(&Wire, I2C_ADDRESS); - -volatile uint8_t interruptFlag = 0; -void myInterrupt(void) -{ - interruptFlag = 1; // Interrupt flag - #if defined(ESP32) || defined(ESP8266) || defined(ARDUINO_SAM_ZERO) - detachInterrupt(13); // Detach interrupt - #else - detachInterrupt(0); // Detach interrupt - #endif -} - -void setup() -{ - Serial.begin(115200); - while(!Serial); - delay(1000); - while(bmm350.begin()){ - Serial.println("bmm350 init failed, Please try again!"); - delay(1000); - } Serial.println("bmm350 init success!"); - - /** - * Set sensor operation mode - * opMode: - * eBmm350SuspendMode // suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - * eBmm350NormalMode // normal mode Get geomagnetic data normally. - * eBmm350ForcedMode // forced mode Single measurement, the sensor restores to suspend mode when the measurement is done. - * eBmm350ForcedModeFast // To reach ODR = 200Hz is only possible by using FM_ FAST. - */ - bmm350.setOperationMode(eBmm350NormalMode); - /** - * Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - * presetMode: - * BMM350_PRESETMODE_LOWPOWER // Low power mode, get a fraction of data and take the mean value. - * BMM350_PRESETMODE_REGULAR // Regular mode, get a number of data and take the mean value. - * BMM350_PRESETMODE_ENHANCED // Enhanced mode, get a plenty of data and take the mean value. - * BMM350_PRESETMODE_HIGHACCURACY // High accuracy mode, get a huge number of take and draw the mean value. - * rate: - * BMM350_DATA_RATE_1_5625HZ - * BMM350_DATA_RATE_3_125HZ - * BMM350_DATA_RATE_6_25HZ - * BMM350_DATA_RATE_12_5HZ (default rate) - * BMM350_DATA_RATE_25HZ - * BMM350_DATA_RATE_50HZ - * BMM350_DATA_RATE_100HZ - * BMM350_DATA_RATE_200HZ - * BMM350_DATA_RATE_400HZ - */ - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ); - - - /** - * Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required, the geomagnetic data at x, y and z will be inaccurate when disabled. - * Refer to setMeasurementXYZ() function in the .h file if you want to configure more parameters. - */ - bmm350.setMeasurementXYZ(); - - /*! - * Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold - * High polarity: active on high level, the default is low level, which turns to high level when the interrupt is triggered. - * Low polarity: active on low level, the default is high level, which turns to low level when the interrupt is triggered. - * modes: - * LOW_THRESHOLD_INTERRUPT // Low threshold interrupt mode, interrupt is triggered when below the threshold - * HIGH_THRESHOLD_INTERRUPT // High threshold interrupt mode, interrupt is triggered when beyond the threshold - * threshold //Threshold range, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt - * polarity: - * BMM350_ACTIVE_HIGH // High polarity - * BMM350_ACTIVE_LOW // Low polarity - * Refer to setThresholdInterrput() function in the .h file if you want to use more parameters. - */ - bmm350.setThresholdInterrupt(LOW_THRESHOLD_INTERRUPT, 0, BMM350_ACTIVE_LOW); - -#if defined(ESP32) || defined(ESP8266) - /** - Select according to the set DADY pin polarity - INPUT_PULLUP // Low polarity, set pin 13 to pull-up input - INPUT_PULLDOWN // High polarity, set pin 13 to pull-down input - interput io - All pins can be used. Pin 13 is recommended - */ - pinMode(/*Pin */13 ,INPUT_PULLUP); - attachInterrupt(/*interput io*/13, myInterrupt, ONLOW); -#elif defined(ARDUINO_SAM_ZERO) - pinMode(/*Pin */13 ,INPUT_PULLUP); - attachInterrupt(/*interput io*/13, myInterrupt, LOW); -#else - /** The Correspondence Table of AVR Series Arduino Interrupt Pins And Terminal Numbers - * --------------------------------------------------------------------------------------- - * | | Pin | 2 | 3 | | - * | Uno, Nano, Mini, other 328-based |--------------------------------------------| - * | | Interrupt No | 0 | 1 | | - * |-------------------------------------------------------------------------------------| - * | | Pin | 2 | 3 | 21 | 20 | 19 | 18 | - * | Mega2560 |--------------------------------------------| - * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | 5 | - * |-------------------------------------------------------------------------------------| - * | | Pin | 3 | 2 | 0 | 1 | 7 | | - * | Leonardo, other 32u4-based |--------------------------------------------| - * | | Interrupt No | 0 | 1 | 2 | 3 | 4 | | - * |-------------------------------------------------------------------------------------- - */ - - /** The Correspondence Table of micro:bit Interrupt Pins And Terminal Numbers - * --------------------------------------------------------------------------------------------------------------------------------------------- - * | micro:bit | DigitalPin |P0-P20 can be used as an external interrupt | - * | (When using as an external interrupt, |---------------------------------------------------------------------------------------------| - * |no need to set it to input mode with pinMode)|Interrupt No|Interrupt number is a pin digital value, such as P0 interrupt number 0, P1 is 1 | - * |-------------------------------------------------------------------------------------------------------------------------------------------| - */ - /** - Select according to the set DADY pin polarity - INPUT_PULLUP // Low polarity, set pin 2 to pull-up input - */ - pinMode(/*Pin */2 ,INPUT_PULLUP); - - /** - Set the pin to interrupt mode - // Open the external interrupt 0, connect INT to the digital pin of the main control: - function - callback function - state - LOW // When the pin is at low level, the interrupt occur, enter interrupt function - */ - attachInterrupt(/*Interrupt No*/0, /*function*/myInterrupt ,/*state*/LOW ); -#endif - -} - -void loop() -{ - /** - * Get the data that threshold interrupt occured and interrupt status (get the data ready status through software) - * Returns the structure for storing geomagnetic data, the structure stores the data of 3 axis and interrupt status, - * No interrupt triggered when the data at x-axis, y-axis and z-axis is NO_DATA - * Refer to .h file if you want to check interrupt status. - */ - /* - sBmm350ThresholdData_t thresholdData = bmm350.getThresholdData(); - if(thresholdData.mag_x != NO_DATA){ - Serial.print("mag x = "); Serial.print(thresholdData.mag_x); Serial.println(" uT"); - } - if(thresholdData.mag_y != NO_DATA){ - Serial.print("mag y = "); Serial.print(thresholdData.mag_y); Serial.println(" uT"); - } - if(thresholdData.mag_z != NO_DATA){ - Serial.print("mag z = "); Serial.print(thresholdData.mag_z); Serial.println(" uT"); - } - Serial.println(); - */ - - /** - When the interrupt occur in INT IO, get the threshold interrupt data (get the threshold interrupt status through hardware) - */ - if(interruptFlag == 1){ - sBmm350ThresholdData_t thresholdData = bmm350.getThresholdData(); - if(thresholdData.mag_x != NO_DATA){ - Serial.print("mag x = "); Serial.print(thresholdData.mag_x); Serial.println(" uT"); - } - if(thresholdData.mag_y != NO_DATA){ - Serial.print("mag y = "); Serial.print(thresholdData.mag_y); Serial.println(" uT"); - } - if(thresholdData.mag_z != NO_DATA){ - Serial.print("mag z = "); Serial.print(thresholdData.mag_z); Serial.println(" uT"); - } - Serial.println(); - interruptFlag = 0; - #if defined(ESP32) || defined(ESP8266) - attachInterrupt(13, myInterrupt, ONLOW); - #elif defined(ARDUINO_SAM_ZERO) - attachInterrupt(13, myInterrupt, LOW); - #else - attachInterrupt(0, myInterrupt, LOW); - #endif - - } - delay(1000); -} diff --git a/lib/DFRobot_BMM350/keywords.txt b/lib/DFRobot_BMM350/keywords.txt deleted file mode 100644 index 0432f89..0000000 --- a/lib/DFRobot_BMM350/keywords.txt +++ /dev/null @@ -1,76 +0,0 @@ -####################################### -# Syntax Coloring DFRobot_bmm350 -####################################### - -####################################### -# Datatypes (KEYWORD1) -####################################### - -begin KEYWORD2 -softReset KEYWORD2 -selfTest KEYWORD2 -setOperationMode KEYWORD2 -getOperationMode KEYWORD2 -setRate KEYWORD2 -getRate KEYWORD2 -setPresetMode KEYWORD2 -getGeomagneticData KEYWORD2 -getCompassDegree KEYWORD2 -setDataReadyPin KEYWORD2 -getDataReadyState KEYWORD2 -setMeasurementXYZ KEYWORD2 -getMeasurementStateXYZ KEYWORD2 -setThresholdInterrupt KEYWORD2 -getThresholdData KEYWORD2 - -####################################### -# Constants (LITERAL1) -####################################### - -DFRobot_bmm350 KEYWORD1 -DFRobot_bmm350_I2C KEYWORD1 -DFRobot_bmm350_I3C KEYWORD1 - -####################################### -# Methods and Functions (KEYWORD2) -####################################### - -BMM350_OK LITERAL1 - -BMM350_SELF_TEST_ADVANCED LITERAL1 -BMM350_SELF_TEST_NORMAL LITERAL1 - -eBmm350SuspendMode LITERAL1 -eBmm350NormalMode LITERAL1 -eBmm350ForcedMode LITERAL1 -eBmm350ForcedModeFast LITERAL1 - -BMM350_PRESETMODE_LOWPOWER LITERAL1 -BMM350_PRESETMODE_REGULAR LITERAL1 -BMM350_PRESETMODE_HIGHACCURACY LITERAL1 -BMM350_PRESETMODE_ENHANCED LITERAL1 - -BMM350_ODR_1_5625HZ LITERAL1 -BMM350_ODR_3_125HZ LITERAL1 -BMM350_ODR_6_25HZ LITERAL1 -BMM350_ODR_12_5HZ LITERAL1 -BMM350_ODR_25HZ LITERAL1 -BMM350_ODR_50HZ LITERAL1 -BMM350_ODR_100HZ LITERAL1 -BMM350_ODR_200HZ LITERAL1 -BMM350_ODR_400HZ LITERAL1 - -POLARITY_HIGH LITERAL1 -POLARITY_LOW LITERAL1 - -INTERRUPT_X_ENABLE LITERAL1 -INTERRUPT_Y_ENABLE LITERAL1 -INTERRUPT_Z_ENABLE LITERAL1 -INTERRUPT_X_DISABLE LITERAL1 -INTERRUPT_Y_DISABLE LITERAL1 -INTERRUPT_Z_DISABLE LITERAL1 - -ENABLE_INTERRUPT_PIN LITERAL1 -DISABLE_INTERRUPT_PIN LITERAL1 -LOW_THRESHOLD_INTERRUPT LITERAL1 -HIGH_THRESHOLD_INTERRUPT LITERAL1 diff --git a/lib/DFRobot_BMM350/library.properties b/lib/DFRobot_BMM350/library.properties deleted file mode 100644 index 23b406c..0000000 --- a/lib/DFRobot_BMM350/library.properties +++ /dev/null @@ -1,9 +0,0 @@ -name=DFRobot_BMM350 -version=1.0.0 -author=DFRobot -maintainer=[GDuang](yonglei.ren@dfrobot.com) -sentence=DFRobot Standard 3-axis geomagnetic sensor library(SKU:SEN0419). -paragraph=The BMM350 is a low-power and low noise 3-axis digital geomagnetic sensor that perfectly matches the requirements of compass applications. -category=Sensors -url=https://github.com/DFRobot/DFRobot_BMM350 -architectures=* diff --git a/lib/DFRobot_BMM350/python/raspberrypi/DFRobot_bmm350.py b/lib/DFRobot_BMM350/python/raspberrypi/DFRobot_bmm350.py deleted file mode 100644 index b0d8596..0000000 --- a/lib/DFRobot_BMM350/python/raspberrypi/DFRobot_bmm350.py +++ /dev/null @@ -1,1595 +0,0 @@ -# -*- coding: utf-8 -* -''' - @file DFRobot_bmm350.py - @note DFRobot_bmm350 Class infrastructure, implementation of underlying methods - @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - @license The MIT License (MIT) - @author [GDuang](yonglei.ren@dfrobot.com) - @version V1.0.0 - @date 2024-05-06 - @url https://github.com/DFRobot/DFRobot_BMM350 -''' -import serial -import time -import os -import math - - -# Chip id of BMM350 -BMM350_CHIP_ID = 0x33 - -# Variant ID of BMM350 -BMM350_MIN_VAR = 0x10 - -# Sensor interface success code -BMM350_INTF_RET_SUCCESS = 0 - -# API success code -BMM350_OK = 0 - -# API error codes -BMM350_E_NULL_PTR = -1 -BMM350_E_COM_FAIL = -2 -BMM350_E_DEV_NOT_FOUND = -3 -BMM350_E_INVALID_CONFIG = -4 -BMM350_E_BAD_PAD_DRIVE = -5 -BMM350_E_RESET_UNFINISHED = -6 -BMM350_E_INVALID_INPUT = -7 -BMM350_E_SELF_TEST_INVALID_AXIS = -8 -BMM350_E_OTP_BOOT = -9 -BMM350_E_OTP_PAGE_RD = -10 -BMM350_E_OTP_PAGE_PRG = -11 -BMM350_E_OTP_SIGN = -12 -BMM350_E_OTP_INV_CMD = -13 -BMM350_E_OTP_UNDEFINED = -14 -BMM350_E_ALL_AXIS_DISABLED = -15 -BMM350_E_PMU_CMD_VALUE = -16 - -BMM350_NO_ERROR = 0 - -# Sensor delay time settings in microseconds -BMM350_SOFT_RESET_DELAY = 24000/1000000 -BMM350_MAGNETIC_RESET_DELAY = 40000/1000000 -BMM350_START_UP_TIME_FROM_POR = 3000/1000000 -BMM350_GOTO_SUSPEND_DELAY = 6000/1000000 -BMM350_SUSPEND_TO_NORMAL_DELAY = 38000/1000000 -BMM350_SUS_TO_FORCEDMODE_NO_AVG_DELAY = 15000/1000000 -BMM350_SUS_TO_FORCEDMODE_AVG_2_DELAY = 17000/1000000 -BMM350_SUS_TO_FORCEDMODE_AVG_4_DELAY = 20000/1000000 -BMM350_SUS_TO_FORCEDMODE_AVG_8_DELAY = 28000/1000000 -BMM350_SUS_TO_FORCEDMODE_FAST_NO_AVG_DELAY = 4000/1000000 -BMM350_SUS_TO_FORCEDMODE_FAST_AVG_2_DELAY = 5000/1000000 -BMM350_SUS_TO_FORCEDMODE_FAST_AVG_4_DELAY = 9000/1000000 -BMM350_SUS_TO_FORCEDMODE_FAST_AVG_8_DELAY = 16000/1000000 -BMM350_UPD_OAE_DELAY = 1000/1000000 -BMM350_BR_DELAY = 14000/1000000 -BMM350_FGR_DELAY = 18000/1000000 - -# Length macros -BMM350_OTP_DATA_LENGTH = 32 -BMM350_READ_BUFFER_LENGTH = 127 -BMM350_MAG_TEMP_DATA_LEN = 12 - -# Averaging macros -BMM350_AVG_NO_AVG = 0x0 -BMM350_AVG_2 = 0x1 -BMM350_AVG_4 = 0x2 -BMM350_AVG_8 = 0x3 - -# ODR -BMM350_ODR_400HZ = 0x2 -BMM350_ODR_200HZ = 0x3 -BMM350_ODR_100HZ = 0x4 -BMM350_ODR_50HZ = 0x5 -BMM350_ODR_25HZ = 0x6 -BMM350_ODR_12_5HZ = 0x7 # default rate -BMM350_ODR_6_25HZ = 0x8 -BMM350_ODR_3_125HZ = 0x9 -BMM350_ODR_1_5625HZ = 0xA - -# Power modes -BMM350_PMU_CMD_SUS = 0x00 -BMM350_PMU_CMD_NM = 0x01 -BMM350_PMU_CMD_UPD_OAE = 0x02 -BMM350_PMU_CMD_FM = 0x03 -BMM350_PMU_CMD_FM_FAST = 0x04 -BMM350_PMU_CMD_FGR = 0x05 -BMM350_PMU_CMD_FGR_FAST = 0x06 -BMM350_PMU_CMD_BR = 0x07 -BMM350_PMU_CMD_BR_FAST = 0x08 -BMM350_PMU_CMD_NM_TC = 0x09 - -BMM350_PMU_STATUS_0 = 0x0 - -BMM350_DISABLE = 0x0 -BMM350_ENABLE = 0x1 -BMM350_MAP_TO_PIN = BMM350_ENABLE - -BMM350_CMD_NOP = 0x0 -BMM350_CMD_SOFTRESET = 0xB6 - -BMM350_TARGET_PAGE_PAGE0 = 0x0 -BMM350_TARGET_PAGE_PAGE1 = 0x1 - -BMM350_INT_MODE_LATCHED = 0x1 -BMM350_INT_MODE_PULSED = 0x0 - -BMM350_INT_POL_ACTIVE_HIGH = 0x1 -BMM350_INT_POL_ACTIVE_LOW = 0x0 - -BMM350_INT_OD_PUSHPULL = 0x1 -BMM350_INT_OD_OPENDRAIN = 0x0 - -BMM350_INT_OUTPUT_EN_OFF = 0x0 -BMM350_INT_OUTPUT_EN_ON = 0x1 - -BMM350_INT_DRDY_EN = 0x1 -BMM350_INT_DRDY_DIS = 0x0 - -BMM350_MR_MR1K8 = 0x0 -BMM350_MR_MR2K1 = 0x1 -BMM350_MR_MR1K5 = 0x2 -BMM350_MR_MR0K6 = 0x3 - -BMM350_SEL_DTB1X_PAD_PAD_INT = 0x0 -BMM350_SEL_DTB1X_PAD_PAD_BYP = 0x1 - -BMM350_TMR_TST_HIZ_VTMR_VTMR_ON = 0x0 -BMM350_TMR_TST_HIZ_VTMR_VTMR_HIZ = 0x1 - -BMM350_LSB_MASK = 0x00FF -BMM350_MSB_MASK = 0xFF00 - -# Pad drive strength -BMM350_PAD_DRIVE_WEAKEST = 0 -BMM350_PAD_DRIVE_STRONGEST = 7 - -# I2C Register Addresses - -# Register to set I2C address to LOW -BMM350_I2C_ADSEL_SET_LOW = 0x14 - -# Register to set I2C address to HIGH -BMM350_I2C_ADSEL_SET_HIGH = 0x15 - -BMM350_DUMMY_BYTES = 2 - -# Register Addresses - -BMM350_REG_CHIP_ID = 0x00 -BMM350_REG_REV_ID = 0x01 -BMM350_REG_ERR_REG = 0x02 -BMM350_REG_PAD_CTRL = 0x03 -BMM350_REG_PMU_CMD_AGGR_SET = 0x04 -BMM350_REG_PMU_CMD_AXIS_EN = 0x05 -BMM350_REG_PMU_CMD = 0x06 -BMM350_REG_PMU_CMD_STATUS_0 = 0x07 -BMM350_REG_PMU_CMD_STATUS_1 = 0x08 -BMM350_REG_I3C_ERR = 0x09 -BMM350_REG_I2C_WDT_SET = 0x0A -BMM350_REG_TRSDCR_REV_ID = 0x0D -BMM350_REG_TC_SYNC_TU = 0x21 -BMM350_REG_TC_SYNC_ODR = 0x22 -BMM350_REG_TC_SYNC_TPH_1 = 0x23 -BMM350_REG_TC_SYNC_TPH_2 = 0x24 -BMM350_REG_TC_SYNC_DT = 0x25 -BMM350_REG_TC_SYNC_ST_0 = 0x26 -BMM350_REG_TC_SYNC_ST_1 = 0x27 -BMM350_REG_TC_SYNC_ST_2 = 0x28 -BMM350_REG_TC_SYNC_STATUS = 0x29 -BMM350_REG_INT_CTRL = 0x2E -BMM350_REG_INT_CTRL_IBI = 0x2F -BMM350_REG_INT_STATUS = 0x30 -BMM350_REG_MAG_X_XLSB = 0x31 -BMM350_REG_MAG_X_LSB = 0x32 -BMM350_REG_MAG_X_MSB = 0x33 -BMM350_REG_MAG_Y_XLSB = 0x34 -BMM350_REG_MAG_Y_LSB = 0x35 -BMM350_REG_MAG_Y_MSB = 0x36 -BMM350_REG_MAG_Z_XLSB = 0x37 -BMM350_REG_MAG_Z_LSB = 0x38 -BMM350_REG_MAG_Z_MSB = 0x39 -BMM350_REG_TEMP_XLSB = 0x3A -BMM350_REG_TEMP_LSB = 0x3B -BMM350_REG_TEMP_MSB = 0x3C -BMM350_REG_SENSORTIME_XLSB = 0x3D -BMM350_REG_SENSORTIME_LSB = 0x3E -BMM350_REG_SENSORTIME_MSB = 0x3F -BMM350_REG_OTP_CMD_REG = 0x50 -BMM350_REG_OTP_DATA_MSB_REG = 0x52 -BMM350_REG_OTP_DATA_LSB_REG = 0x53 -BMM350_REG_OTP_STATUS_REG = 0x55 -BMM350_REG_TMR_SELFTEST_USER = 0x60 -BMM350_REG_CTRL_USER = 0x61 -BMM350_REG_CMD = 0x7E - -# Macros for OVWR -BMM350_REG_OVWR_VALUE_ANA_0 = 0x3A -BMM350_REG_OVWR_EN_ANA_0 = 0x3B - -# Macros for bit masking - -BMM350_CHIP_ID_OTP_MSK = 0xf -BMM350_CHIP_ID_OTP_POS = 0x0 -BMM350_CHIP_ID_FIXED_MSK = 0xf0 -BMM350_CHIP_ID_FIXED_POS = 0x4 -BMM350_REV_ID_MAJOR_MSK = 0xf0 -BMM350_REV_ID_MAJOR_POS = 0x4 -BMM350_REV_ID_MINOR_MSK = 0xf -BMM350_REV_ID_MINOR_POS = 0x0 -BMM350_PMU_CMD_ERROR_MSK = 0x1 -BMM350_PMU_CMD_ERROR_POS = 0x0 -BMM350_BOOT_UP_ERROR_MSK = 0x2 -BMM350_BOOT_UP_ERROR_POS = 0x1 -BMM350_DRV_MSK = 0x7 -BMM350_DRV_POS = 0x0 -BMM350_AVG_MSK = 0x30 -BMM350_AVG_POS = 0x4 -BMM350_ODR_MSK = 0xf -BMM350_ODR_POS = 0x0 -BMM350_PMU_CMD_MSK = 0xf -BMM350_PMU_CMD_POS = 0x0 -BMM350_EN_X_MSK = 0x01 -BMM350_EN_X_POS = 0x0 -BMM350_EN_Y_MSK = 0x02 -BMM350_EN_Y_POS = 0x1 -BMM350_EN_Z_MSK = 0x04 -BMM350_EN_Z_POS = 0x2 -BMM350_EN_XYZ_MSK = 0x7 -BMM350_EN_XYZ_POS = 0x0 -BMM350_PMU_CMD_BUSY_MSK = 0x1 -BMM350_PMU_CMD_BUSY_POS = 0x0 -BMM350_ODR_OVWR_MSK = 0x2 -BMM350_ODR_OVWR_POS = 0x1 -BMM350_AVG_OVWR_MSK = 0x4 -BMM350_AVG_OVWR_POS = 0x2 -BMM350_PWR_MODE_IS_NORMAL_MSK = 0x8 -BMM350_PWR_MODE_IS_NORMAL_POS = 0x3 -BMM350_CMD_IS_ILLEGAL_MSK = 0x10 -BMM350_CMD_IS_ILLEGAL_POS = 0x4 -BMM350_PMU_CMD_VALUE_MSK = 0xE0 -BMM350_PMU_CMD_VALUE_POS = 0x5 -BMM350_PMU_ODR_S_MSK = 0xf -BMM350_PMU_ODR_S_POS = 0x0 -BMM350_PMU_AVG_S_MSK = 0x30 -BMM350_PMU_AVG_S_POS = 0x4 -BMM350_I3C_ERROR_0_MSK = 0x1 -BMM350_I3C_ERROR_0_POS = 0x0 -BMM350_I3C_ERROR_3_MSK = 0x8 -BMM350_I3C_ERROR_3_POS = 0x3 -BMM350_I2C_WDT_EN_MSK = 0x1 -BMM350_I2C_WDT_EN_POS = 0x0 -BMM350_I2C_WDT_SEL_MSK = 0x2 - -BMM350_I2C_WDT_SEL_POS = 0x1 -BMM350_TRSDCR_REV_ID_OTP_MSK = 0x3 -BMM350_TRSDCR_REV_ID_OTP_POS = 0x0 -BMM350_TRSDCR_REV_ID_FIXED_MSK = 0xfc -BMM350_TRSDCR_REV_ID_FIXED_POS = 0x2 -BMM350_PAGING_EN_MSK = 0x80 -BMM350_PAGING_EN_POS = 0x7 -BMM350_DRDY_DATA_REG_MSK = 0x4 -BMM350_DRDY_DATA_REG_POS = 0x2 -BMM350_INT_MODE_MSK = 0x1 -BMM350_INT_MODE_POS = 0x0 -BMM350_INT_POL_MSK = 0x2 -BMM350_INT_POL_POS = 0x1 -BMM350_INT_OD_MSK = 0x4 -BMM350_INT_OD_POS = 0x2 -BMM350_INT_OUTPUT_EN_MSK = 0x8 -BMM350_INT_OUTPUT_EN_POS = 0x3 -BMM350_DRDY_DATA_REG_EN_MSK = 0x80 -BMM350_DRDY_DATA_REG_EN_POS = 0x7 -BMM350_DRDY_INT_MAP_TO_IBI_MSK = 0x1 -BMM350_DRDY_INT_MAP_TO_IBI_POS = 0x0 -BMM350_CLEAR_DRDY_INT_STATUS_UPON_IBI_MSK = 0x10 -BMM350_CLEAR_DRDY_INT_STATUS_UPON_IBI_POS = 0x4 -BMM350_TC_SYNC_TU_MSK = 0xff -BMM350_TC_SYNC_ODR_MSK = 0xff -BMM350_TC_SYNC_TPH_1_MSK = 0xff -BMM350_TC_SYNC_TPH_2_MSK = 0xff -BMM350_TC_SYNC_DT_MSK = 0xff -BMM350_TC_SYNC_ST_0_MSK = 0xff -BMM350_TC_SYNC_ST_1_MSK = 0xff -BMM350_TC_SYNC_ST_2_MSK = 0xff -BMM350_CFG_FORCE_SOSC_EN_MSK = 0x4 -BMM350_CFG_FORCE_SOSC_EN_POS = 0x2 -BMM350_ST_IGEN_EN_MSK = 0x1 -BMM350_ST_IGEN_EN_POS = 0x0 -BMM350_ST_N_MSK = 0x2 -BMM350_ST_N_POS = 0x1 -BMM350_ST_P_MSK = 0x4 -BMM350_ST_P_POS = 0x2 -BMM350_IST_EN_X_MSK = 0x8 -BMM350_IST_EN_X_POS = 0x3 -BMM350_IST_EN_Y_MSK = 0x10 -BMM350_IST_EN_Y_POS = 0x4 -BMM350_CFG_SENS_TIM_AON_MSK = 0x1 -BMM350_CFG_SENS_TIM_AON_POS = 0x0 -BMM350_DATA_X_7_0_MSK = 0xff -BMM350_DATA_X_7_0_POS = 0x0 -BMM350_DATA_X_15_8_MSK = 0xff -BMM350_DATA_X_15_8_POS = 0x0 -BMM350_DATA_X_23_16_MSK = 0xff -BMM350_DATA_X_23_16_POS = 0x0 -BMM350_DATA_Y_7_0_MSK = 0xff -BMM350_DATA_Y_7_0_POS = 0x0 -BMM350_DATA_Y_15_8_MSK = 0xff -BMM350_DATA_Y_15_8_POS = 0x0 -BMM350_DATA_Y_23_16_MSK = 0xff -BMM350_DATA_Y_23_16_POS = 0x0 -BMM350_DATA_Z_7_0_MSK = 0xff -BMM350_DATA_Z_7_0_POS = 0x0 -BMM350_DATA_Z_15_8_MSK = 0xff -BMM350_DATA_Z_15_8_POS = 0x0 -BMM350_DATA_Z_23_16_MSK = 0xff -BMM350_DATA_Z_23_16_POS = 0x0 -BMM350_DATA_T_7_0_MSK = 0xff -BMM350_DATA_T_7_0_POS = 0x0 -BMM350_DATA_T_15_8_MSK = 0xff -BMM350_DATA_T_15_8_POS = 0x0 -BMM350_DATA_T_23_16_MSK = 0xff -BMM350_DATA_T_23_16_POS = 0x0 -BMM350_DATA_ST_7_0_MSK = 0xff -BMM350_DATA_ST_7_0_POS = 0x0 -BMM350_DATA_ST_15_8_MSK = 0xff -BMM350_DATA_ST_15_8_POS = 0x0 -BMM350_DATA_ST_23_16_MSK = 0xff -BMM350_DATA_ST_23_16_POS = 0x0 -BMM350_SIGN_INVERT_T_MSK = 0x10 -BMM350_SIGN_INVERT_T_POS = 0x4 -BMM350_SIGN_INVERT_X_MSK = 0x20 -BMM350_SIGN_INVERT_X_POS = 0x5 -BMM350_SIGN_INVERT_Y_MSK = 0x40 -BMM350_SIGN_INVERT_Y_POS = 0x6 -BMM350_SIGN_INVERT_Z_MSK = 0x80 -BMM350_SIGN_INVERT_Z_POS = 0x7 -BMM350_DIS_BR_NM_MSK = 0x1 -BMM350_DIS_BR_NM_POS = 0x0 -BMM350_DIS_FGR_NM_MSK = 0x2 -BMM350_DIS_FGR_NM_POS = 0x1 -BMM350_DIS_CRST_AT_ALL_MSK = 0x4 -BMM350_DIS_CRST_AT_ALL_POS = 0x2 -BMM350_DIS_BR_FM_MSK = 0x8 -BMM350_DIS_BR_FM_POS = 0x3 -BMM350_FRC_EN_BUFF_MSK = 0x1 -BMM350_FRC_EN_BUFF_POS = 0x0 -BMM350_FRC_INA_EN1_MSK = 0x2 -BMM350_FRC_INA_EN1_POS = 0x1 -BMM350_FRC_INA_EN2_MSK = 0x4 -BMM350_FRC_INA_EN2_POS = 0x2 -BMM350_FRC_ADC_EN_MSK = 0x8 -BMM350_FRC_ADC_EN_POS = 0x3 -BMM350_FRC_INA_RST_MSK = 0x10 -BMM350_FRC_INA_RST_POS = 0x4 -BMM350_FRC_ADC_RST_MSK = 0x20 -BMM350_FRC_ADC_RST_POS = 0x5 -BMM350_FRC_INA_XSEL_MSK = 0x1 -BMM350_FRC_INA_XSEL_POS = 0x0 -BMM350_FRC_INA_YSEL_MSK = 0x2 -BMM350_FRC_INA_YSEL_POS = 0x1 -BMM350_FRC_INA_ZSEL_MSK = 0x4 -BMM350_FRC_INA_ZSEL_POS = 0x2 -BMM350_FRC_ADC_TEMP_EN_MSK = 0x8 -BMM350_FRC_ADC_TEMP_EN_POS = 0x3 -BMM350_FRC_TSENS_EN_MSK = 0x10 -BMM350_FRC_TSENS_EN_POS = 0x4 -BMM350_DSENS_FM_MSK = 0x20 -BMM350_DSENS_FM_POS = 0x5 -BMM350_DSENS_SEL_MSK = 0x40 -BMM350_DSENS_SEL_POS = 0x6 -BMM350_DSENS_SHORT_MSK = 0x80 -BMM350_DSENS_SHORT_POS = 0x7 -BMM350_ERR_MISS_BR_DONE_MSK = 0x1 -BMM350_ERR_MISS_BR_DONE_POS = 0x0 -BMM350_ERR_MISS_FGR_DONE_MSK = 0x2 -BMM350_ERR_MISS_FGR_DONE_POS = 0x1 -BMM350_TST_CHAIN_LN_MODE_MSK = 0x1 -BMM350_TST_CHAIN_LN_MODE_POS = 0x0 -BMM350_TST_CHAIN_LP_MODE_MSK = 0x2 -BMM350_TST_CHAIN_LP_MODE_POS = 0x1 -BMM350_EN_OVWR_TMR_IF_MSK = 0x1 -BMM350_EN_OVWR_TMR_IF_POS = 0x0 -BMM350_TMR_CKTRIGB_MSK = 0x2 -BMM350_TMR_CKTRIGB_POS = 0x1 -BMM350_TMR_DO_BR_MSK = 0x4 -BMM350_TMR_DO_BR_POS = 0x2 -BMM350_TMR_DO_FGR_MSK = 0x18 -BMM350_TMR_DO_FGR_POS = 0x3 -BMM350_TMR_EN_OSC_MSK = 0x80 -BMM350_TMR_EN_OSC_POS = 0x7 -BMM350_VCM_TRIM_X_MSK = 0x1f -BMM350_VCM_TRIM_X_POS = 0x0 -BMM350_VCM_TRIM_Y_MSK = 0x1f -BMM350_VCM_TRIM_Y_POS = 0x0 -BMM350_VCM_TRIM_Z_MSK = 0x1f -BMM350_VCM_TRIM_Z_POS = 0x0 -BMM350_VCM_TRIM_DSENS_MSK = 0x1f -BMM350_VCM_TRIM_DSENS_POS = 0x0 -BMM350_TWLB_MSK = 0x30 -BMM350_TWLB_POS = 0x4 -BMM350_PRG_PLS_TIM_MSK = 0x30 -BMM350_PRG_PLS_TIM_POS = 0x4 -BMM350_OTP_OVWR_EN_MSK = 0x1 -BMM350_OTP_OVWR_EN_POS = 0x0 -BMM350_OTP_MEM_CLK_MSK = 0x2 -BMM350_OTP_MEM_CLK_POS = 0x1 -BMM350_OTP_MEM_CS_MSK = 0x4 -BMM350_OTP_MEM_CS_POS = 0x2 -BMM350_OTP_MEM_PGM_MSK = 0x8 -BMM350_OTP_MEM_PGM_POS = 0x3 -BMM350_OTP_MEM_RE_MSK = 0x10 -BMM350_OTP_MEM_RE_POS = 0x4 -BMM350_SAMPLE_RDATA_PLS_MSK = 0x80 -BMM350_SAMPLE_RDATA_PLS_POS = 0x7 -BMM350_CFG_FW_MSK = 0x1 -BMM350_CFG_FW_POS = 0x0 -BMM350_EN_BR_X_MSK = 0x2 -BMM350_EN_BR_X_POS = 0x1 -BMM350_EN_BR_Y_MSK = 0x4 -BMM350_EN_BR_Y_POS = 0x2 -BMM350_EN_BR_Z_MSK = 0x8 -BMM350_EN_BR_Z_POS = 0x3 -BMM350_CFG_PAUSE_TIME_MSK = 0x30 -BMM350_CFG_PAUSE_TIME_POS = 0x4 -BMM350_CFG_FGR_PLS_DUR_MSK = 0xf -BMM350_CFG_FGR_PLS_DUR_POS = 0x0 -BMM350_CFG_BR_Z_ORDER_MSK = 0x10 -BMM350_CFG_BR_Z_ORDER_POS = 0x4 -BMM350_CFG_BR_XY_CHOP_MSK = 0x20 -BMM350_CFG_BR_XY_CHOP_POS = 0x5 -BMM350_CFG_BR_PLS_DUR_MSK = 0xc0 -BMM350_CFG_BR_PLS_DUR_POS = 0x6 -BMM350_ENABLE_BR_FGR_TEST_MSK = 0x1 -BMM350_ENABLE_BR_FGR_TEST_POS = 0x0 -BMM350_SEL_AXIS_MSK = 0xe -BMM350_SEL_AXIS_POS = 0x1 -BMM350_TMR_CFG_TEST_CLK_EN_MSK = 0x10 -BMM350_TMR_CFG_TEST_CLK_EN_POS = 0x4 -BMM350_TEST_VAL_BITS_7DOWNTO0_MSK = 0xff -BMM350_TEST_VAL_BITS_7DOWNTO0_POS = 0x0 -BMM350_TEST_VAL_BITS_8_MSK = 0x1 -BMM350_TEST_VAL_BITS_8_POS = 0x0 -BMM350_TEST_P_SAMPLE_MSK = 0x2 -BMM350_TEST_P_SAMPLE_POS = 0x1 -BMM350_TEST_N_SAMPLE_MSK = 0x4 -BMM350_TEST_N_SAMPLE_POS = 0x2 -BMM350_TEST_APPLY_TO_REM_MSK = 0x10 -BMM350_TEST_APPLY_TO_REM_POS = 0x4 -BMM350_UFO_TRM_OSC_RANGE_MSK = 0xf -BMM350_UFO_TRM_OSC_RANGE_POS = 0x0 -BMM350_ISO_CHIP_ID_MSK = 0x78 -BMM350_ISO_CHIP_ID_POS = 0x3 -BMM350_ISO_I2C_DEV_ID_MSK = 0x80 -BMM350_ISO_I2C_DEV_ID_POS = 0x7 -BMM350_I3C_FREQ_BITS_1DOWNTO0_MSK = 0xc -BMM350_I3C_FREQ_BITS_1DOWNTO0_POS = 0x2 -BMM350_I3C_IBI_MDB_SEL_MSK = 0x10 -BMM350_I3C_IBI_MDB_SEL_POS = 0x4 -BMM350_TC_ASYNC_EN_MSK = 0x20 -BMM350_TC_ASYNC_EN_POS = 0x5 -BMM350_TC_SYNC_EN_MSK = 0x40 -BMM350_TC_SYNC_EN_POS = 0x6 -BMM350_I3C_SCL_GATING_EN_MSK = 0x80 -BMM350_I3C_SCL_GATING_EN_POS = 0x7 -BMM350_I3C_INACCURACY_BITS_6DOWNTO0_MSK = 0x7f -BMM350_I3C_INACCURACY_BITS_6DOWNTO0_POS = 0x0 -BMM350_EST_EN_X_MSK = 0x1 -BMM350_EST_EN_X_POS = 0x0 -BMM350_EST_EN_Y_MSK = 0x2 -BMM350_EST_EN_Y_POS = 0x1 -BMM350_CRST_DIS_MSK = 0x4 -BMM350_CRST_DIS_POS = 0x2 -BMM350_BR_TFALL_MSK = 0x7 -BMM350_BR_TFALL_POS = 0x0 -BMM350_BR_TRISE_MSK = 0x70 -BMM350_BR_TRISE_POS = 0x4 -BMM350_TMR_SOFT_START_DIS_MSK = 0x80 -BMM350_TMR_SOFT_START_DIS_POS = 0x7 -BMM350_FOSC_LOW_RANGE_MSK = 0x80 -BMM350_FOSC_LOW_RANGE_POS = 0x7 -BMM350_VCRST_TRIM_FG_MSK = 0x3f -BMM350_VCRST_TRIM_FG_POS = 0x0 -BMM350_VCRST_TRIM_BR_MSK = 0x3f -BMM350_VCRST_TRIM_BR_POS = 0x0 -BMM350_BG_TRIM_VRP_MSK = 0xc0 -BMM350_BG_TRIM_VRP_POS = 0x6 -BMM350_BG_TRIM_TC_MSK = 0xf -BMM350_BG_TRIM_TC_POS = 0x0 -BMM350_BG_TRIM_VRA_MSK = 0xf0 -BMM350_BG_TRIM_VRA_POS = 0x4 -BMM350_BG_TRIM_VRD_MSK = 0xf -BMM350_BG_TRIM_VRD_POS = 0x0 -BMM350_OVWR_REF_IB_EN_MSK = 0x10 -BMM350_OVWR_REF_IB_EN_POS = 0x4 -BMM350_OVWR_VDDA_EN_MSK = 0x20 -BMM350_OVWR_VDDA_EN_POS = 0x5 -BMM350_OVWR_VDDP_EN_MSK = 0x40 -BMM350_OVWR_VDDP_EN_POS = 0x6 -BMM350_OVWR_VDDS_EN_MSK = 0x80 -BMM350_OVWR_VDDS_EN_POS = 0x7 -BMM350_REF_IB_EN_MSK = 0x10 -BMM350_REF_IB_EN_POS = 0x4 -BMM350_VDDA_EN_MSK = 0x20 -BMM350_VDDA_EN_POS = 0x5 -BMM350_VDDP_EN_MSK = 0x40 -BMM350_VDDP_EN_POS = 0x6 -BMM350_VDDS_EN_MSK = 0x80 -BMM350_VDDS_EN_POS = 0x7 -BMM350_OVWR_OTP_PROG_VDD_SW_EN_MSK = 0x8 -BMM350_OVWR_OTP_PROG_VDD_SW_EN_POS = 0x3 -BMM350_OVWR_EN_MFE_BG_FILT_BYPASS_MSK = 0x10 -BMM350_OVWR_EN_MFE_BG_FILT_BYPASS_POS = 0x4 -BMM350_OTP_PROG_VDD_SW_EN_MSK = 0x8 -BMM350_OTP_PROG_VDD_SW_EN_POS = 0x3 -BMM350_CP_COMP_CRST_EN_TM_MSK = 0x10 -BMM350_CP_COMP_CRST_EN_TM_POS = 0x4 -BMM350_CP_COMP_VDD_EN_TM_MSK = 0x20 -BMM350_CP_COMP_VDD_EN_TM_POS = 0x5 -BMM350_CP_INTREFS_EN_TM_MSK = 0x40 -BMM350_CP_INTREFS_EN_TM_POS = 0x6 -BMM350_ADC_LOCAL_CHOP_EN_MSK = 0x20 -BMM350_ADC_LOCAL_CHOP_EN_POS = 0x5 -BMM350_INA_MODE_MSK = 0x40 -BMM350_INA_MODE_POS = 0x6 -BMM350_VDDD_EXT_EN_MSK = 0x20 -BMM350_VDDD_EXT_EN_POS = 0x5 -BMM350_VDDP_EXT_EN_MSK = 0x80 -BMM350_VDDP_EXT_EN_POS = 0x7 -BMM350_ADC_DSENS_EN_MSK = 0x10 -BMM350_ADC_DSENS_EN_POS = 0x4 -BMM350_DSENS_EN_MSK = 0x20 -BMM350_DSENS_EN_POS = 0x5 -BMM350_OTP_TM_CLVWR_EN_MSK = 0x40 -BMM350_OTP_TM_CLVWR_EN_POS = 0x6 -BMM350_OTP_VDDP_DIS_MSK = 0x80 -BMM350_OTP_VDDP_DIS_POS = 0x7 -BMM350_FORCE_HIGH_VREF_IREF_OK_MSK = 0x10 -BMM350_FORCE_HIGH_VREF_IREF_OK_POS = 0x4 -BMM350_FORCE_HIGH_FOSC_OK_MSK = 0x20 -BMM350_FORCE_HIGH_FOSC_OK_POS = 0x5 -BMM350_FORCE_HIGH_MFE_BG_RDY_MSK = 0x40 -BMM350_FORCE_HIGH_MFE_BG_RDY_POS = 0x6 -BMM350_FORCE_HIGH_MFE_VTMR_RDY_MSK = 0x80 -BMM350_FORCE_HIGH_MFE_VTMR_RDY_POS = 0x7 -BMM350_ERR_END_OF_RECHARGE_MSK = 0x1 -BMM350_ERR_END_OF_RECHARGE_POS = 0x0 -BMM350_ERR_END_OF_DISCHARGE_MSK = 0x2 -BMM350_ERR_END_OF_DISCHARGE_POS = 0x1 -BMM350_CP_TMX_DIGTP_SEL_MSK = 0x7 -BMM350_CP_TMX_DIGTP_SEL_POS = 0x0 -BMM350_CP_CPOSC_EN_TM_MSK = 0x80 -BMM350_CP_CPOSC_EN_TM_POS = 0x7 -BMM350_TST_ATM1_CFG_MSK = 0x3f -BMM350_TST_ATM1_CFG_POS = 0x0 -BMM350_TST_TB1_EN_MSK = 0x80 -BMM350_TST_TB1_EN_POS = 0x7 -BMM350_TST_ATM2_CFG_MSK = 0x1f -BMM350_TST_ATM2_CFG_POS = 0x0 -BMM350_TST_TB2_EN_MSK = 0x80 -BMM350_TST_TB2_EN_POS = 0x7 -BMM350_REG_DTB1X_SEL_MSK = 0x7f -BMM350_REG_DTB1X_SEL_POS = 0x0 -BMM350_SEL_DTB1X_PAD_MSK = 0x80 -BMM350_SEL_DTB1X_PAD_POS = 0x7 -BMM350_REG_DTB2X_SEL_MSK = 0x7f -BMM350_REG_DTB2X_SEL_POS = 0x0 -BMM350_TMR_TST_CFG_MSK = 0x7f -BMM350_TMR_TST_CFG_POS = 0x0 -BMM350_TMR_TST_HIZ_VTMR_MSK = 0x80 -BMM350_TMR_TST_HIZ_VTMR_POS = 0x7 - -# OTP MACROS -BMM350_OTP_CMD_DIR_READ = 0x20 -BMM350_OTP_CMD_DIR_PRGM_1B = 0x40 -BMM350_OTP_CMD_DIR_PRGM = 0x60 -BMM350_OTP_CMD_PWR_OFF_OTP = 0x80 -BMM350_OTP_CMD_EXT_READ = 0xA0 -BMM350_OTP_CMD_EXT_PRGM = 0xE0 -BMM350_OTP_CMD_MSK = 0xE0 -BMM350_OTP_WORD_ADDR_MSK = 0x1F - -BMM350_OTP_STATUS_ERROR_MSK = 0xE0 -BMM350_OTP_STATUS_NO_ERROR = 0x00 -BMM350_OTP_STATUS_BOOT_ERR = 0x20 -BMM350_OTP_STATUS_PAGE_RD_ERR = 0x40 -BMM350_OTP_STATUS_PAGE_PRG_ERR = 0x60 -BMM350_OTP_STATUS_SIGN_ERR = 0x80 -BMM350_OTP_STATUS_INV_CMD_ERR = 0xA0 -BMM350_OTP_STATUS_CMD_DONE = 0x01 - -# OTP indices -BMM350_TEMP_OFF_SENS = 0x0D - -BMM350_MAG_OFFSET_X = 0x0E -BMM350_MAG_OFFSET_Y = 0x0F -BMM350_MAG_OFFSET_Z = 0x10 - -BMM350_MAG_SENS_X = 0x10 -BMM350_MAG_SENS_Y = 0x11 -BMM350_MAG_SENS_Z = 0x11 - -BMM350_MAG_TCO_X = 0x12 -BMM350_MAG_TCO_Y = 0x13 -BMM350_MAG_TCO_Z = 0x14 - -BMM350_MAG_TCS_X = 0x12 -BMM350_MAG_TCS_Y = 0x13 -BMM350_MAG_TCS_Z = 0x14 - -BMM350_MAG_DUT_T_0 = 0x18 - -BMM350_CROSS_X_Y = 0x15 -BMM350_CROSS_Y_X = 0x15 -BMM350_CROSS_Z_X = 0x16 -BMM350_CROSS_Z_Y = 0x16 - -BMM350_SENS_CORR_Y = 0.01 -BMM350_TCS_CORR_Z = 0.000 - -# Signed bit macros -BMM350_SIGNED_8_BIT = 8 -BMM350_SIGNED_12_BIT = 12 -BMM350_SIGNED_16_BIT = 16 -BMM350_SIGNED_21_BIT = 21 -BMM350_SIGNED_24_BIT = 24 - -# Self-test macros -BMM350_SELF_TEST_DISABLE = 0x00 -BMM350_SELF_TEST_POS_X = 0x0D -BMM350_SELF_TEST_NEG_X = 0x0B -BMM350_SELF_TEST_POS_Y = 0x15 -BMM350_SELF_TEST_NEG_Y = 0x13 - -BMM350_X_FM_XP_UST_MAX_LIMIT = 150 -BMM350_X_FM_XP_UST_MIN_LIMIT = 50 - -BMM350_X_FM_XN_UST_MAX_LIMIT = -50 -BMM350_X_FM_XN_UST_MIN_LIMIT = -150 - -BMM350_Y_FM_YP_UST_MAX_LIMIT = 150 -BMM350_Y_FM_YP_UST_MIN_LIMIT = 50 - -BMM350_Y_FM_YN_UST_MAX_LIMIT = -50 -BMM350_Y_FM_YN_UST_MIN_LIMIT = -150 - -# PMU command status 0 macros -BMM350_PMU_CMD_STATUS_0_SUS = 0x00 -BMM350_PMU_CMD_STATUS_0_NM = 0x01 -BMM350_PMU_CMD_STATUS_0_UPD_OAE = 0x02 -BMM350_PMU_CMD_STATUS_0_FM = 0x03 -BMM350_PMU_CMD_STATUS_0_FM_FAST = 0x04 -BMM350_PMU_CMD_STATUS_0_FGR = 0x05 -BMM350_PMU_CMD_STATUS_0_FGR_FAST = 0x06 -BMM350_PMU_CMD_STATUS_0_BR = 0x07 -BMM350_PMU_CMD_STATUS_0_BR_FAST = 0x07 - - -# PRESET MODE DEFINITIONS -BMM350_PRESETMODE_LOWPOWER = 0x01 -BMM350_PRESETMODE_REGULAR = 0x02 -BMM350_PRESETMODE_HIGHACCURACY = 0x03 -BMM350_PRESETMODE_ENHANCED = 0x04 - -LOW_THRESHOLD_INTERRUPT = 0 -HIGH_THRESHOLD_INTERRUPT = 1 -INTERRUPT_X_ENABLE = 0 -INTERRUPT_Y_ENABLE = 0 -INTERRUPT_Z_ENABLE = 0 -INTERRUPT_X_DISABLE = 1 -INTERRUPT_Y_DISABLE = 1 -INTERRUPT_Z_DISABLE = 1 -ENABLE_INTERRUPT_PIN = 1 -DISABLE_INTERRUPT_PIN = 0 -NO_DATA = -32768 - -# ------------------------------------------- -BMM350_CHIP_ID_ERROR = -1 - - -# ------------------------------------------- - -BMM350_DISABLE_INTERRUPT = BMM350_DISABLE -BMM350_ENABLE_INTERRUPT = BMM350_ENABLE - -BMM350_SUSPEND_MODE = BMM350_PMU_CMD_SUS -BMM350_NORMAL_MODE = BMM350_PMU_CMD_NM -BMM350_FORCED_MODE = BMM350_PMU_CMD_FM -BMM350_FORCED_MODE_FAST = BMM350_PMU_CMD_FM_FAST - -BMM350_DATA_RATE_400HZ = BMM350_ODR_400HZ -BMM350_DATA_RATE_200HZ = BMM350_ODR_200HZ -BMM350_DATA_RATE_100HZ = BMM350_ODR_100HZ -BMM350_DATA_RATE_50HZ = BMM350_ODR_50HZ -BMM350_DATA_RATE_25HZ = BMM350_ODR_25HZ -BMM350_DATA_RATE_12_5HZ = BMM350_ODR_12_5HZ -BMM350_DATA_RATE_6_25HZ = BMM350_ODR_6_25HZ -BMM350_DATA_RATE_3_125HZ = BMM350_ODR_3_125HZ -BMM350_DATA_RATE_1_5625HZ = BMM350_ODR_1_5625HZ - -BMM350_FLUXGUIDE_9MS = BMM350_PMU_CMD_FGR -BMM350_FLUXGUIDE_FAST = BMM350_PMU_CMD_FGR_FAST -BMM350_BITRESET_9MS = BMM350_PMU_CMD_BR -BMM350_BITRESET_FAST = BMM350_PMU_CMD_BR_FAST -BMM350_NOMAGRESET = 127 - -BMM350_INTR_DISABLE = BMM350_DISABLE -BMM350_INTR_ENABLE = BMM350_ENABLE - -BMM350_UNMAP_FROM_PIN = BMM350_DISABLE -BMM350_MAP_TO_PIN = BMM350_ENABLE - -BMM350_PULSED = BMM350_INT_MODE_PULSED -BMM350_LATCHED = BMM350_INT_MODE_LATCHED - -BMM350_ACTIVE_LOW = BMM350_INT_POL_ACTIVE_LOW -BMM350_ACTIVE_HIGH = BMM350_INT_POL_ACTIVE_HIGH - -BMM350_INTR_OPEN_DRAIN = BMM350_INT_OD_OPENDRAIN -BMM350_INTR_PUSH_PULL = BMM350_INT_OD_PUSHPULL - -BMM350_IBI_DISABLE = BMM350_DISABLE -BMM350_IBI_ENABLE = BMM350_ENABLE - -BMM350_NOCLEAR_ON_IBI = BMM350_DISABLE -BMM350_CLEAR_ON_IBI = BMM350_ENABLE - -BMM350_I2C_WDT_DIS = BMM350_DISABLE -BMM350_I2C_WDT_EN = BMM350_ENABLE - -BMM350_I2C_WDT_SEL_SHORT = BMM350_DISABLE -BMM350_I2C_WDT_SEL_LONG = BMM350_ENABLE - -BMM350_NO_AVERAGING = BMM350_AVG_NO_AVG -BMM350_AVERAGING_2 = BMM350_AVG_2 -BMM350_AVERAGING_4 = BMM350_AVG_4 -BMM350_AVERAGING_8 = BMM350_AVG_8 - -BMM350_ST_IGEN_DIS = BMM350_DISABLE -BMM350_ST_IGEN_EN = BMM350_ENABLE - -BMM350_ST_N_DIS = BMM350_DISABLE -BMM350_ST_N_EN = BMM350_ENABLE - -BMM350_ST_P_DIS = BMM350_DISABLE -BMM350_ST_P_EN = BMM350_ENABLE - -BMM350_IST_X_DIS = BMM350_DISABLE -BMM350_IST_X_EN = BMM350_ENABLE - -BMM350_IST_Y_DIS = BMM350_DISABLE -BMM350_IST_Y_EN = BMM350_ENABLE - -BMM350_CFG_SENS_TIM_AON_DIS = BMM350_DISABLE -BMM350_CFG_SENS_TIM_AON_EN = BMM350_ENABLE - -BMM350_X_DIS = BMM350_DISABLE -BMM350_X_EN = BMM350_ENABLE - -BMM350_Y_DIS = BMM350_DISABLE -BMM350_Y_EN = BMM350_ENABLE - -BMM350_Z_DIS = BMM350_DISABLE -BMM350_Z_EN = BMM350_ENABLE - -PI = 3.141592653 -M_PI = 3.14159265358979323846 - - -# -------------------------------------------- -'''! - @brief bmm350 magnetometer dut offset coefficient structure -''' -class bmm350_dut_offset_coef: - def __init__(self, t_offs: float, offset_x: float, offset_y: float, offset_z: float): - self.t_offs = t_offs - self.offset_x = offset_x - self.offset_y = offset_y - self.offset_z = offset_z - -'''! - @brief bmm350 magnetometer dut sensitivity coefficient structure -''' -class bmm350_dut_sensit_coef: - def __init__(self, t_sens: float, sens_x: float, sens_y: float, sens_z: float): - self.t_sens = t_sens - self.sens_x = sens_x - self.sens_y = sens_y - self.sens_z = sens_z - -'''! - @brief bmm350 magnetometer dut tco structure -''' -class bmm350_dut_tco: - def __init__(self, tco_x: float, tco_y: float, tco_z: float): - self.tco_x = tco_x - self.tco_y = tco_y - self.tco_z = tco_z -'''! - @brief bmm350 magnetometer dut tcs structure -''' -class bmm350_dut_tcs: - def __init__(self, tcs_x: float, tcs_y: float, tcs_z: float): - self.tcs_x = tcs_x - self.tcs_y = tcs_y - self.tcs_z = tcs_z - -'''! - @brief bmm350 magnetometer cross axis compensation structure -''' -class bmm350_cross_axis: - def __init__(self, cross_x_y: float, cross_y_x: float, cross_z_x: float, cross_z_y: float): - self.cross_x_y = cross_x_y - self.cross_y_x = cross_y_x - self.cross_z_x = cross_z_x - self.cross_z_y = cross_z_y - -'''! - @brief bmm350 magnetometer compensate structure -''' -class bmm350_mag_compensate: - def __init__(self, dut_offset_coef: bmm350_dut_offset_coef, dut_sensit_coef: bmm350_dut_sensit_coef, dut_tco: bmm350_dut_tco, dut_tcs: bmm350_dut_tcs, dut_t0: float, cross_axis: bmm350_cross_axis): - self.dut_offset_coef = dut_offset_coef - self.dut_sensit_coef = dut_sensit_coef - self.dut_tco = dut_tco - self.dut_tcs = dut_tcs - self.dut_t0 = dut_t0 - self.cross_axis = cross_axis - -'''! - @brief bmm350 device structure -''' -class bmm350_dev: - def __init__(self, mag_comp: bmm350_mag_compensate): - self.chipID = 0 - self.otp_data = [0] * 32 - self.var_id = 0 - self.mag_comp = mag_comp - self.power_mode = 0 - self.axis_en = 0 - -# Create instances of the required classes with example values -dut_offset_coef = bmm350_dut_offset_coef(t_offs=0, offset_x=0, offset_y=0, offset_z=0) -dut_sensit_coef = bmm350_dut_sensit_coef(t_sens=0, sens_x=0, sens_y=0, sens_z=0) -dut_tco = bmm350_dut_tco(tco_x=0, tco_y=0, tco_z=0) -dut_tcs = bmm350_dut_tcs(tcs_x=0, tcs_y=0, tcs_z=0) -cross_axis = bmm350_cross_axis(cross_x_y=0, cross_y_x=0, cross_z_x=0, cross_z_y=0) -mag_comp = bmm350_mag_compensate( - dut_offset_coef=dut_offset_coef, - dut_sensit_coef=dut_sensit_coef, - dut_tco=dut_tco, - dut_tcs=dut_tcs, - dut_t0=0, - cross_axis=cross_axis -) -# The bmm350_mag_compensate object now contains all the data defined above. -bmm350_sensor = bmm350_dev(mag_comp) - - -# Uncompensated geomagnetic and temperature data -class BMM350RawMagData: - def __init__(self): - self.raw_x_data = 0 - self.raw_y_data = 0 - self.raw_z_data = 0 - self.raw_t_data = 0 -_raw_mag_data = BMM350RawMagData() - -class BMM350MagData: - def __init__(self): - self.x = 0 - self.y = 0 - self.z = 0 - self.temperature = 0 -_mag_data = BMM350MagData() - -class bmm350_pmu_cmd_status_0: - def __init__(self, pmu_cmd_busy, odr_ovwr, avr_ovwr, pwr_mode_is_normal, cmd_is_illegal, pmu_cmd_value): - self.pmu_cmd_busy = pmu_cmd_busy - self.odr_ovwr = odr_ovwr - self.avr_ovwr = avr_ovwr - self.pwr_mode_is_normal = pwr_mode_is_normal - self.cmd_is_illegal = cmd_is_illegal - self.pmu_cmd_value = pmu_cmd_value -pmu_cmd_stat_0 = bmm350_pmu_cmd_status_0(pmu_cmd_busy=0, odr_ovwr=0, avr_ovwr=0, pwr_mode_is_normal=0, cmd_is_illegal=0, pmu_cmd_value=0) - -# -------------------------------------------- -class DFRobot_bmm350(object): - I2C_MODE = 1 - I3C_MODE = 2 - __thresholdMode = 2 - threshold = 0 - - - def __init__(self, bus): - if bus != 0: - self.__i2c_i3c = self.I2C_MODE - else: - self.__i2c_i3c = self.I3C_MODE - - def BMM350_SET_BITS(self, reg_data, bitname_msk, bitname_pos, data): - return (reg_data & ~bitname_msk) | ((data << bitname_pos) & bitname_msk) - - def BMM350_GET_BITS(self, reg_data, mask, pos): - return (reg_data & mask) >> pos - - def BMM350_GET_BITS_POS_0(self, reg_data, mask): - return reg_data & mask - - def BMM350_SET_BITS_POS_0(self, reg_data, mask, data): - return ((reg_data & ~(mask)) | (data & mask)) - - - - # brief This internal API converts the raw data from the IC data registers to signed integer - def fix_sign(self, inval, number_of_bits): - power = 0 - if number_of_bits == BMM350_SIGNED_8_BIT: - power = 128; # 2^7 - elif number_of_bits == BMM350_SIGNED_12_BIT: - power = 2048 # 2^11 - elif number_of_bits == BMM350_SIGNED_16_BIT: - power = 32768 # 2^15 - elif number_of_bits == BMM350_SIGNED_21_BIT: - power = 1048576 # 2^20 - elif number_of_bits == BMM350_SIGNED_24_BIT: - power = 8388608 # 2^23 - else: - power = 0 - if inval >= power: - inval = inval - (power * 2) - return inval - - # brief This internal API is used to update magnetometer offset and sensitivity data. - def update_mag_off_sens(self): - off_x_lsb_msb = bmm350_sensor.otp_data[BMM350_MAG_OFFSET_X] & 0x0FFF - off_y_lsb_msb = ((bmm350_sensor.otp_data[BMM350_MAG_OFFSET_X] & 0xF000) >> 4) + (bmm350_sensor.otp_data[BMM350_MAG_OFFSET_Y] & BMM350_LSB_MASK) - off_z_lsb_msb = (bmm350_sensor.otp_data[BMM350_MAG_OFFSET_Y] & 0x0F00) + (bmm350_sensor.otp_data[BMM350_MAG_OFFSET_Z] & BMM350_LSB_MASK) - t_off = bmm350_sensor.otp_data[BMM350_TEMP_OFF_SENS] & BMM350_LSB_MASK - - bmm350_sensor.mag_comp.dut_offset_coef.offset_x = self.fix_sign(off_x_lsb_msb, BMM350_SIGNED_12_BIT) - bmm350_sensor.mag_comp.dut_offset_coef.offset_y = self.fix_sign(off_y_lsb_msb, BMM350_SIGNED_12_BIT) - bmm350_sensor.mag_comp.dut_offset_coef.offset_z = self.fix_sign(off_z_lsb_msb, BMM350_SIGNED_12_BIT) - bmm350_sensor.mag_comp.dut_offset_coef.t_offs = self.fix_sign(t_off, BMM350_SIGNED_8_BIT) / 5.0 - - sens_x = (bmm350_sensor.otp_data[BMM350_MAG_SENS_X] & BMM350_MSB_MASK) >> 8 - sens_y = (bmm350_sensor.otp_data[BMM350_MAG_SENS_Y] & BMM350_LSB_MASK) - sens_z = (bmm350_sensor.otp_data[BMM350_MAG_SENS_Z] & BMM350_MSB_MASK) >> 8 - t_sens = (bmm350_sensor.otp_data[BMM350_TEMP_OFF_SENS] & BMM350_MSB_MASK) >> 8 - - bmm350_sensor.mag_comp.dut_sensit_coef.sens_x = self.fix_sign(sens_x, BMM350_SIGNED_8_BIT) / 256.0 - bmm350_sensor.mag_comp.dut_sensit_coef.sens_y = (self.fix_sign(sens_y, BMM350_SIGNED_8_BIT) / 256.0) + BMM350_SENS_CORR_Y - bmm350_sensor.mag_comp.dut_sensit_coef.sens_z = self.fix_sign(sens_z, BMM350_SIGNED_8_BIT) / 256.0 - bmm350_sensor.mag_comp.dut_sensit_coef.t_sens = self.fix_sign(t_sens, BMM350_SIGNED_8_BIT) / 512.0 - - tco_x = (bmm350_sensor.otp_data[BMM350_MAG_TCO_X] & BMM350_LSB_MASK) - tco_y = (bmm350_sensor.otp_data[BMM350_MAG_TCO_Y] & BMM350_LSB_MASK) - tco_z = (bmm350_sensor.otp_data[BMM350_MAG_TCO_Z] & BMM350_LSB_MASK) - - bmm350_sensor.mag_comp.dut_tco.tco_x = self.fix_sign(tco_x, BMM350_SIGNED_8_BIT) / 32.0 - bmm350_sensor.mag_comp.dut_tco.tco_y = self.fix_sign(tco_y, BMM350_SIGNED_8_BIT) / 32.0 - bmm350_sensor.mag_comp.dut_tco.tco_z = self.fix_sign(tco_z, BMM350_SIGNED_8_BIT) / 32.0 - - tcs_x = (bmm350_sensor.otp_data[BMM350_MAG_TCS_X] & BMM350_MSB_MASK) >> 8 - tcs_y = (bmm350_sensor.otp_data[BMM350_MAG_TCS_Y] & BMM350_MSB_MASK) >> 8 - tcs_z = (bmm350_sensor.otp_data[BMM350_MAG_TCS_Z] & BMM350_MSB_MASK) >> 8 - - bmm350_sensor.mag_comp.dut_tcs.tcs_x = self.fix_sign(tcs_x, BMM350_SIGNED_8_BIT) / 16384.0 - bmm350_sensor.mag_comp.dut_tcs.tcs_y = self.fix_sign(tcs_y, BMM350_SIGNED_8_BIT) / 16384.0 - bmm350_sensor.mag_comp.dut_tcs.tcs_z = (self.fix_sign(tcs_z, BMM350_SIGNED_8_BIT) / 16384.0) - BMM350_TCS_CORR_Z - - bmm350_sensor.mag_comp.dut_t0 = (self.fix_sign(bmm350_sensor.otp_data[BMM350_MAG_DUT_T_0], BMM350_SIGNED_16_BIT) / 512.0) + 23.0 - - cross_x_y = (bmm350_sensor.otp_data[BMM350_CROSS_X_Y] & BMM350_LSB_MASK) - cross_y_x = (bmm350_sensor.otp_data[BMM350_CROSS_Y_X] & BMM350_MSB_MASK) >> 8 - cross_z_x = (bmm350_sensor.otp_data[BMM350_CROSS_Z_X] & BMM350_LSB_MASK) - cross_z_y = (bmm350_sensor.otp_data[BMM350_CROSS_Z_Y] & BMM350_MSB_MASK) >> 8 - - bmm350_sensor.mag_comp.cross_axis.cross_x_y = self.fix_sign(cross_x_y, BMM350_SIGNED_8_BIT) / 800.0 - bmm350_sensor.mag_comp.cross_axis.cross_y_x = self.fix_sign(cross_y_x, BMM350_SIGNED_8_BIT) / 800.0 - bmm350_sensor.mag_comp.cross_axis.cross_z_x = self.fix_sign(cross_z_x, BMM350_SIGNED_8_BIT) / 800.0 - bmm350_sensor.mag_comp.cross_axis.cross_z_y = self.fix_sign(cross_z_y, BMM350_SIGNED_8_BIT) / 800.0 - - - def bmm350_set_powermode(self, powermode): - last_pwr_mode = self.read_reg(BMM350_REG_PMU_CMD, 1) - if (last_pwr_mode[0] == BMM350_PMU_CMD_NM) or (last_pwr_mode[0] == BMM350_PMU_CMD_UPD_OAE): - self.write_reg(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_SUS) - time.sleep(BMM350_GOTO_SUSPEND_DELAY) - # Array to store suspend to forced mode delay - sus_to_forced_mode =[BMM350_SUS_TO_FORCEDMODE_NO_AVG_DELAY, BMM350_SUS_TO_FORCEDMODE_AVG_2_DELAY, - BMM350_SUS_TO_FORCEDMODE_AVG_4_DELAY, BMM350_SUS_TO_FORCEDMODE_AVG_8_DELAY] - # Array to store suspend to forced mode fast delay - sus_to_forced_mode_fast = [BMM350_SUS_TO_FORCEDMODE_FAST_NO_AVG_DELAY, BMM350_SUS_TO_FORCEDMODE_FAST_AVG_2_DELAY, - BMM350_SUS_TO_FORCEDMODE_FAST_AVG_4_DELAY, BMM350_SUS_TO_FORCEDMODE_FAST_AVG_8_DELAY] - # Set PMU command configuration to desired power mode - self.write_reg(BMM350_REG_PMU_CMD, powermode) - # Get average configuration - get_avg = self.read_reg(BMM350_REG_PMU_CMD_AGGR_SET, 1) - # Mask the average value - avg = ((get_avg[0] & BMM350_AVG_MSK) >> BMM350_AVG_POS) - delay_us = 0 - # Check if desired power mode is normal mode - if powermode == BMM350_NORMAL_MODE: - delay_us = BMM350_SUSPEND_TO_NORMAL_DELAY - # Check if desired power mode is forced mode - if powermode == BMM350_FORCED_MODE: - delay_us = sus_to_forced_mode[avg]; # Store delay based on averaging mode - # Check if desired power mode is forced mode fast - if powermode == BMM350_FORCED_MODE_FAST: - delay_us = sus_to_forced_mode_fast[avg] # Store delay based on averaging mode - # Perform delay based on power mode - time.sleep(delay_us) - bmm350_sensor.power_mode = powermode - - - def bmm350_magnetic_reset_and_wait(self): - # 1. Read PMU CMD status - reg_data = self.read_reg(BMM350_REG_PMU_CMD_STATUS_0, 1) - pmu_cmd_stat_0.pmu_cmd_busy = self.BMM350_GET_BITS_POS_0(reg_data[0], BMM350_PMU_CMD_BUSY_MSK) - pmu_cmd_stat_0.odr_ovwr = self.BMM350_GET_BITS(reg_data[0], BMM350_ODR_OVWR_MSK, BMM350_ODR_OVWR_POS) - pmu_cmd_stat_0.avr_ovwr = self.BMM350_GET_BITS(reg_data[0], BMM350_AVG_OVWR_MSK, BMM350_AVG_OVWR_POS) - pmu_cmd_stat_0.pwr_mode_is_normal = self.BMM350_GET_BITS(reg_data[0], BMM350_PWR_MODE_IS_NORMAL_MSK, BMM350_PWR_MODE_IS_NORMAL_POS) - pmu_cmd_stat_0.cmd_is_illegal = self.BMM350_GET_BITS(reg_data[0], BMM350_CMD_IS_ILLEGAL_MSK, BMM350_CMD_IS_ILLEGAL_POS) - pmu_cmd_stat_0.pmu_cmd_value = self.BMM350_GET_BITS(reg_data[0], BMM350_PMU_CMD_VALUE_MSK, BMM350_PMU_CMD_VALUE_POS) - # 2. Check whether the power mode is normal before magnetic reset - restore_normal = BMM350_DISABLE - if pmu_cmd_stat_0.pwr_mode_is_normal == BMM350_ENABLE: - restore_normal = BMM350_ENABLE - # Reset can only be triggered in suspend - self.bmm350_set_powermode(BMM350_SUSPEND_MODE) - # Set BR to PMU_CMD register - self.write_reg(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_BR) - time.sleep(BMM350_BR_DELAY) - # Set FGR to PMU_CMD register - self.write_reg(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_FGR) - time.sleep(BMM350_FGR_DELAY) - if restore_normal == BMM350_ENABLE: - self.bmm350_set_powermode(BMM350_NORMAL_MODE) - - - def sensor_init(self): - '''! - @brief Init bmm350 check whether the chip id is right - @return - @retval 0 is init success - @retval -1 is init failed - ''' - rslt = BMM350_OK - # Specifies that all axes are enabled - bmm350_sensor.axis_en = BMM350_EN_XYZ_MSK - time.sleep(BMM350_START_UP_TIME_FROM_POR) - # 1. Software reset - self.write_reg(BMM350_REG_CMD, BMM350_CMD_SOFTRESET) - time.sleep(BMM350_SOFT_RESET_DELAY) - # 2. Read chip ID - reg_date = self.read_reg(BMM350_REG_CHIP_ID, 1) - bmm350_sensor.chipID = reg_date[0] - if reg_date[0] == BMM350_CHIP_ID: - # 3. Download OTP compensation data - for indx in range(BMM350_OTP_DATA_LENGTH): - # 3.1 Set the OTP address register -- > Each address corresponds to a different OTP value (total OTP data is 32 bytes) - otp_cmd = BMM350_OTP_CMD_DIR_READ | (indx & BMM350_OTP_WORD_ADDR_MSK) - self.write_reg(BMM350_REG_OTP_CMD_REG, otp_cmd) - while (True): - time.sleep(0.0003) - # 3.2 The OTP status was read - otp_status = self.read_reg(BMM350_REG_OTP_STATUS_REG, 1) - otp_err = otp_status[0] & BMM350_OTP_STATUS_ERROR_MSK - if otp_err != BMM350_OTP_STATUS_NO_ERROR: - break - if (otp_status[0] & BMM350_OTP_STATUS_CMD_DONE): - break - # 3.3 Gets 16 bytes of OTP data from the OTP address specified above - OTP_MSB_data = self.read_reg(BMM350_REG_OTP_DATA_MSB_REG, 1) - OTP_LSB_data = self.read_reg(BMM350_REG_OTP_DATA_LSB_REG, 1) - OTP_data = ((OTP_MSB_data[0] << 8) | OTP_LSB_data[0]) & 0xFFFF - bmm350_sensor.otp_data[indx] = OTP_data - bmm350_sensor.var_id = (bmm350_sensor.otp_data[30] & 0x7f00) >> 9 - # 3.4 Update the magnetometer offset and sensitivity data - self.update_mag_off_sens() - # 4. Disable OTP - self.write_reg(BMM350_REG_OTP_CMD_REG, BMM350_OTP_CMD_PWR_OFF_OTP) - - # 5. Magnetic reset - self.bmm350_magnetic_reset_and_wait() - else: - # The chip id verification failed and initialization failed. Procedure - rslt = BMM350_CHIP_ID_ERROR - return rslt - - - def get_chip_id(self): - chip_id = self.read_reg(BMM350_REG_CHIP_ID, 1) - return chip_id[0] - - - def soft_reset(self): - '''! - @brief Soft reset, restore to suspended mode after soft reset. (You need to manually enter the normal mode) - ''' - self.write_reg(BMM350_REG_CMD, BMM350_CMD_SOFTRESET) # Software reset - time.sleep(BMM350_SOFT_RESET_DELAY) - self.write_reg(BMM350_REG_OTP_CMD_REG, BMM350_OTP_CMD_PWR_OFF_OTP) # Disable OTP - self.bmm350_magnetic_reset_and_wait() # magnetic reset - self.bmm350_set_powermode(BMM350_SUSPEND_MODE) - - - def set_operation_mode(self, modes): - '''! - @brief Set sensor operation mode - @param modes - @n BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - @n BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. - @n BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. - @n BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. - ''' - self.bmm350_set_powermode(modes) - - - def get_operation_mode(self): - '''! - @brief Get sensor operation mode - @return Return the character string of the operation mode - ''' - result = "" - if bmm350_sensor.power_mode == BMM350_SUSPEND_MODE: - result = "bmm350 is suspend mode!" - elif bmm350_sensor.power_mode == BMM350_NORMAL_MODE: - result = "bmm350 is normal mode!" - elif bmm350_sensor.power_mode == BMM350_FORCED_MODE: - result = "bmm350 is forced mode!" - elif bmm350_sensor.power_mode == BMM350_FORCED_MODE_FAST: - result = "bmm350 is forced_fast mode!" - else: - result = "error mode!" - return result - - - - - - def get_rate(self): - '''! - @brief Get the config data rate, unit: HZ - @return rate - ''' - avg_odr_reg = self.read_reg(BMM350_REG_PMU_CMD_AGGR_SET, 1) - odr_reg = self.BMM350_GET_BITS(avg_odr_reg[0], BMM350_ODR_MSK, BMM350_ODR_POS) - if odr_reg == BMM350_ODR_1_5625HZ: - result = 1.5625 - elif odr_reg == BMM350_ODR_3_125HZ: - result = 3.125 - elif odr_reg == BMM350_ODR_6_25HZ: - result = 6.25 - elif odr_reg == BMM350_ODR_12_5HZ: - result = 12.5 - elif odr_reg == BMM350_ODR_25HZ: - result = 25 - elif odr_reg == BMM350_ODR_50HZ: - result = 50 - elif odr_reg == BMM350_ODR_100HZ: - result = 100 - elif odr_reg == BMM350_ODR_200HZ: - result = 200 - elif odr_reg == BMM350_ODR_400HZ: - result = 400 - return result - - - def set_preset_mode(self, avg, rate = BMM350_DATA_RATE_12_5HZ): - '''! - @brief Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - @param modes - @n BMM350_PRESETMODE_LOWPOWER Low power mode, get a fraction of data and take the mean value. - @n BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and take the mean value. - @n BMM350_PRESETMODE_ENHANCED Enhanced mode, get a plenty of data and take the mean value. - @n BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and take the mean value. - @param rate - @n BMM350_DATA_RATE_1_5625HZ - @n BMM350_DATA_RATE_3_125HZ - @n BMM350_DATA_RATE_6_25HZ - @n BMM350_DATA_RATE_12_5HZ (default rate) - @n BMM350_DATA_RATE_25HZ - @n BMM350_DATA_RATE_50HZ - @n BMM350_DATA_RATE_100HZ - @n BMM350_DATA_RATE_200HZ - @n BMM350_DATA_RATE_400HZ - - ''' - reg_data = (rate & BMM350_ODR_MSK) - reg_data = self.BMM350_SET_BITS(reg_data, BMM350_AVG_MSK, BMM350_AVG_POS, avg) - self.write_reg(BMM350_REG_PMU_CMD_AGGR_SET, reg_data) - self.write_reg(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_UPD_OAE) - - def set_rate(self, rates): - '''! - @brief Set the rate of obtaining geomagnetic data, the higher, the faster (without delay function) - @param rate - @n BMM350_DATA_RATE_1_5625HZ - @n BMM350_DATA_RATE_3_125HZ - @n BMM350_DATA_RATE_6_25HZ - @n BMM350_DATA_RATE_12_5HZ (default rate) - @n BMM350_DATA_RATE_25HZ - @n BMM350_DATA_RATE_50HZ - @n BMM350_DATA_RATE_100HZ - @n BMM350_DATA_RATE_200HZ - @n BMM350_DATA_RATE_400HZ - ''' - # self.bmm350_set_powermode(BMM350_NORMAL_MODE) - avg_odr_reg = self.read_reg(BMM350_REG_PMU_CMD_AGGR_SET, 1) - avg_reg = self.BMM350_GET_BITS(avg_odr_reg[0], BMM350_AVG_MSK, BMM350_AVG_POS) - reg_data = (rates & BMM350_ODR_MSK) - reg_data = self.BMM350_SET_BITS(reg_data, BMM350_AVG_MSK, BMM350_AVG_POS, avg_reg) - self.write_reg(BMM350_REG_PMU_CMD_AGGR_SET, reg_data) - self.write_reg(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_UPD_OAE) - time.sleep(BMM350_UPD_OAE_DELAY) - - def self_test(self): - '''! - @brief Sensor self test, the returned character string indicate the self test result. - @return The character string of the test result - ''' - axis_en = self.read_reg(BMM350_REG_PMU_CMD_AXIS_EN, 1) - en_x = self.BMM350_GET_BITS(axis_en[0], BMM350_EN_X_MSK, BMM350_EN_X_POS) - en_y = self.BMM350_GET_BITS(axis_en[0], BMM350_EN_Y_MSK, BMM350_EN_Y_POS) - en_z = self.BMM350_GET_BITS(axis_en[0], BMM350_EN_Z_MSK, BMM350_EN_Z_POS) - str1 = "" - if en_x & 0x01: - str1 += "x " - if en_y & 0x01: - str1 += "y " - if en_z & 0x01: - str1 += "z " - if axis_en == 0: - str1 = "xyz aix self test fail" - else: - str1 += "aix test success" - return str1 - - - def set_measurement_XYZ(self, en_x = BMM350_X_EN, en_y = BMM350_Y_EN, en_z = BMM350_Z_EN): - '''! - @brief Enable the measurement at x-axis, y-axis and z-axis, default to be enabled. After disabling, the geomagnetic data at x, y, and z axis are wrong. - @param en_x - @n BMM350_X_EN Enable the measurement at x-axis - @n BMM350_X_DIS Disable the measurement at x-axis - @param en_y - @n BMM350_Y_EN Enable the measurement at y-axis - @n BMM350_Y_DIS Disable the measurement at y-axis - @param en_z - @n BMM350_Z_EN Enable the measurement at z-axis - @n BMM350_Z_DIS Disable the measurement at z-axis - ''' - if en_x == BMM350_X_DIS and en_y == BMM350_Y_DIS and en_z == BMM350_Z_DIS: - bmm350_sensor.axis_en = BMM350_DISABLE - else: - axis_en = self.read_reg(BMM350_REG_PMU_CMD_AXIS_EN, 1) - data = self.BMM350_SET_BITS(axis_en[0], BMM350_EN_X_MSK, BMM350_EN_X_POS, en_x) - data = self.BMM350_SET_BITS(data, BMM350_EN_Y_MSK, BMM350_EN_Y_POS, en_y) - data = self.BMM350_SET_BITS(data, BMM350_EN_Z_MSK, BMM350_EN_Z_POS, en_z) - bmm350_sensor.axis_en = data - - - def get_measurement_state_XYZ(self): - '''! - @brief Get the enabling status at x-axis, y-axis and z-axis - @return Return enabling status at x-axis, y-axis and z-axis as a character string - ''' - axis_en = bmm350_sensor.axis_en - en_x = self.BMM350_GET_BITS(axis_en, BMM350_EN_X_MSK, BMM350_EN_X_POS) - en_y = self.BMM350_GET_BITS(axis_en, BMM350_EN_Y_MSK, BMM350_EN_Y_POS) - en_z = self.BMM350_GET_BITS(axis_en, BMM350_EN_Z_MSK, BMM350_EN_Z_POS) - result = "" - result += "The x axis is enable! " if en_x == 1 else "The x axis is disable! " - result += "The y axis is enable! " if en_y == 1 else "The y axis is disable! " - result += "The z axis is enable! " if en_z == 1 else "The z axis is disable! " - return result - - - def get_geomagnetic_data(self): - '''! - @brief Get the geomagnetic data of 3 axis (x, y, z) - @return The list of the geomagnetic data at 3 axis (x, y, z) unit: uT - @ [0] The geomagnetic data at x-axis - @ [1] The geomagnetic data at y-axis - @ [2] The geomagnetic data at z-axis - ''' - # 1. Get raw data without compensation - mag_data = self.read_reg(BMM350_REG_MAG_X_XLSB, BMM350_MAG_TEMP_DATA_LEN) - raw_mag_x = mag_data[0] + (mag_data[1] << 8) + (mag_data[2] << 16) - raw_mag_y = mag_data[3] + (mag_data[4] << 8) + (mag_data[5] << 16) - raw_mag_z = mag_data[6] + (mag_data[7] << 8) + (mag_data[8] << 16) - raw_temp = mag_data[9] + (mag_data[10] << 8) + (mag_data[11] << 16) - if (bmm350_sensor.axis_en & BMM350_EN_X_MSK) == BMM350_DISABLE: - _raw_mag_data.raw_x_data = BMM350_DISABLE - else: - _raw_mag_data.raw_x_data = self.fix_sign(raw_mag_x, BMM350_SIGNED_24_BIT) - if (bmm350_sensor.axis_en & BMM350_EN_Y_MSK) == BMM350_DISABLE: - _raw_mag_data.raw_y_data = BMM350_DISABLE - else: - _raw_mag_data.raw_y_data = self.fix_sign(raw_mag_y, BMM350_SIGNED_24_BIT) - if (bmm350_sensor.axis_en & BMM350_EN_Z_MSK) == BMM350_DISABLE: - _raw_mag_data.raw_z_data = BMM350_DISABLE - else: - _raw_mag_data.raw_z_data = self.fix_sign(raw_mag_z, BMM350_SIGNED_24_BIT) - _raw_mag_data.raw_t_data = self.fix_sign(raw_temp, BMM350_SIGNED_24_BIT) - # 2. The raw data is processed - # 2.1 Parameter preparation - bxy_sens = 14.55 - bz_sens = 9.0 - temp_sens = 0.00204 - ina_xy_gain_trgt = 19.46 - ina_z_gain_trgt = 31.0 - adc_gain = 1 / 1.5 - lut_gain = 0.714607238769531 - power = (1000000.0 / 1048576.0) - lsb_to_ut_degc = [None] * 4 - lsb_to_ut_degc[0] = (power / (bxy_sens * ina_xy_gain_trgt * adc_gain * lut_gain)) - lsb_to_ut_degc[1] = (power / (bxy_sens * ina_xy_gain_trgt * adc_gain * lut_gain)) - lsb_to_ut_degc[2] = (power / (bz_sens * ina_z_gain_trgt * adc_gain * lut_gain)) - lsb_to_ut_degc[3] = 1 / (temp_sens * adc_gain * lut_gain * 1048576) - # 2.1 Start processing raw data - out_data = [None] * 4 - out_data[0] = _raw_mag_data.raw_x_data * lsb_to_ut_degc[0] - out_data[1] = _raw_mag_data.raw_y_data * lsb_to_ut_degc[1] - out_data[2] = _raw_mag_data.raw_z_data * lsb_to_ut_degc[2] - out_data[3] = _raw_mag_data.raw_t_data * lsb_to_ut_degc[3] - if out_data[3] > 0.0: - temp = out_data[3] - (1 * 25.49) - elif out_data[3] < 0.0: - temp = out_data[3] - (-1 * 25.49) - else: - temp = out_data[3] - out_data[3] = temp - # 3. Compensate for the original data - # 3.1 Compensation for temperature data - out_data[3] = (1 + bmm350_sensor.mag_comp.dut_sensit_coef.t_sens) * out_data[3] + bmm350_sensor.mag_comp.dut_offset_coef.t_offs - # 3.2 Store the magnetic compensation data in a list - dut_offset_coef = [None] * 3 - dut_offset_coef[0] = bmm350_sensor.mag_comp.dut_offset_coef.offset_x - dut_offset_coef[1] = bmm350_sensor.mag_comp.dut_offset_coef.offset_y - dut_offset_coef[2] = bmm350_sensor.mag_comp.dut_offset_coef.offset_z - - dut_sensit_coef = [None] * 3 - dut_sensit_coef[0] = bmm350_sensor.mag_comp.dut_sensit_coef.sens_x - dut_sensit_coef[1] = bmm350_sensor.mag_comp.dut_sensit_coef.sens_y - dut_sensit_coef[2] = bmm350_sensor.mag_comp.dut_sensit_coef.sens_z - - dut_tco = [None] * 3 - dut_tco[0] = bmm350_sensor.mag_comp.dut_tco.tco_x - dut_tco[1] = bmm350_sensor.mag_comp.dut_tco.tco_y - dut_tco[2] = bmm350_sensor.mag_comp.dut_tco.tco_z - - dut_tcs = [None] * 3 - dut_tcs[0] = bmm350_sensor.mag_comp.dut_tcs.tcs_x - dut_tcs[1] = bmm350_sensor.mag_comp.dut_tcs.tcs_y - dut_tcs[2] = bmm350_sensor.mag_comp.dut_tcs.tcs_z; - # 3.3 Compensation for magnetic data - for indx in range(3): - out_data[indx] *= 1 + dut_sensit_coef[indx] - out_data[indx] += dut_offset_coef[indx] - out_data[indx] += dut_tco[indx] * (out_data[3] - bmm350_sensor.mag_comp.dut_t0) - out_data[indx] /= 1 + dut_tcs[indx] * (out_data[3] - bmm350_sensor.mag_comp.dut_t0) - - cr_ax_comp_x = (out_data[0] - bmm350_sensor.mag_comp.cross_axis.cross_x_y * out_data[1]) / \ - (1 - bmm350_sensor.mag_comp.cross_axis.cross_y_x * bmm350_sensor.mag_comp.cross_axis.cross_x_y) - cr_ax_comp_y = (out_data[1] - bmm350_sensor.mag_comp.cross_axis.cross_y_x * out_data[0]) / \ - (1 - bmm350_sensor.mag_comp.cross_axis.cross_y_x * bmm350_sensor.mag_comp.cross_axis.cross_x_y) - cr_ax_comp_z = (out_data[2] + (out_data[0] * - (bmm350_sensor.mag_comp.cross_axis.cross_y_x * bmm350_sensor.mag_comp.cross_axis.cross_z_y - bmm350_sensor.mag_comp.cross_axis.cross_z_x) - out_data[1] * - (bmm350_sensor.mag_comp.cross_axis.cross_z_y - bmm350_sensor.mag_comp.cross_axis.cross_x_y * bmm350_sensor.mag_comp.cross_axis.cross_z_x)) / - (1 - bmm350_sensor.mag_comp.cross_axis.cross_y_x * bmm350_sensor.mag_comp.cross_axis.cross_x_y)) - - out_data[0] = cr_ax_comp_x - out_data[1] = cr_ax_comp_y - out_data[2] = cr_ax_comp_z - - if (bmm350_sensor.axis_en & BMM350_EN_X_MSK) == BMM350_DISABLE: - _mag_data.x = BMM350_DISABLE - else: - _mag_data.x = out_data[0] - - if (bmm350_sensor.axis_en & BMM350_EN_Y_MSK) == BMM350_DISABLE: - _mag_data.y = BMM350_DISABLE - else: - _mag_data.y = out_data[1] - - if (bmm350_sensor.axis_en & BMM350_EN_Z_MSK) == BMM350_DISABLE: - _mag_data.z = BMM350_DISABLE - else: - _mag_data.z = out_data[2] - - _mag_data.temperature = out_data[3] - - geomagnetic = [None] * 3 - geomagnetic[0] = _mag_data.x - geomagnetic[1] = _mag_data.y - geomagnetic[2] = _mag_data.z - return geomagnetic - - - def get_compass_degree(self): - '''! - @brief Get compass degree - @return Compass degree (0° - 360°) 0° = North, 90° = East, 180° = South, 270° = West. - ''' - magData = self.get_geomagnetic_data() - compass = math.atan2(magData[0], magData[1]) - if compass < 0: - compass += 2 * PI - if compass > 2 * PI: - compass -= 2 * PI - return compass * 180 / M_PI - - - def set_data_ready_pin(self, modes, polarity): - '''! - @brief Enable or disable data ready interrupt pin - @n After enabling, the DRDY pin jump when there's data coming. - @n After disabling, the DRDY pin will not jump when there's data coming. - @n High polarity active on high, the default is low level, which turns to high level when the interrupt is triggered. - @n Low polarity active on low, default is high level, which turns to low level when the interrupt is triggered. - @param modes - @n BMM350_ENABLE_INTERRUPT Enable DRDY - @n BMM350_DISABLE_INTERRUPT Disable DRDY - @param polarity - @n BMM350_ACTIVE_HIGH High polarity - @n BMM350_ACTIVE_LOW Low polarity - ''' - # 1. Gets and sets the interrupt control configuration - reg_data = self.read_reg(BMM350_REG_INT_CTRL, 1) - reg_data[0] = self.BMM350_SET_BITS_POS_0(reg_data[0], BMM350_INT_MODE_MSK, BMM350_INT_MODE_PULSED) - reg_data[0] = self.BMM350_SET_BITS(reg_data[0], BMM350_INT_POL_MSK, BMM350_INT_POL_POS, polarity) - reg_data[0] = self.BMM350_SET_BITS(reg_data[0], BMM350_INT_OD_MSK, BMM350_INT_OD_POS, BMM350_INT_OD_PUSHPULL) - reg_data[0] = self.BMM350_SET_BITS(reg_data[0], BMM350_INT_OUTPUT_EN_MSK, BMM350_INT_OUTPUT_EN_POS, BMM350_MAP_TO_PIN) - reg_data[0] = self.BMM350_SET_BITS(reg_data[0], BMM350_DRDY_DATA_REG_EN_MSK, BMM350_DRDY_DATA_REG_EN_POS, modes) - # 2. Update interrupt control configuration - self.write_reg(BMM350_REG_INT_CTRL, reg_data[0]) - - - def get_data_ready_state(self): - '''! - @brief Get data ready status, determine whether the data is ready - @return status - @n True Data ready - @n False Data is not ready - ''' - int_status_reg = self.read_reg(BMM350_REG_INT_STATUS, 1) - drdy_status = self.BMM350_GET_BITS(int_status_reg[0], BMM350_DRDY_DATA_REG_MSK, BMM350_DRDY_DATA_REG_POS) - if drdy_status & 0x01: - return True - else: - return False - - - def set_threshold_interrupt(self, modes, threshold, polarity): - '''! - @brief Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold - @n High polarity active on high level, the default is low level, which turns to high level when the interrupt is triggered. - @n Low polarity active on low level, the default is high level, which turns to low level when the interrupt is triggered. - @param modes - @n LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode - @n HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode - @param threshold - @n Threshold, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt - @param polarity - @n POLARITY_HIGH High polarity - @n POLARITY_LOW Low polarity - ''' - if modes == LOW_THRESHOLD_INTERRUPT: - self.__thresholdMode = LOW_THRESHOLD_INTERRUPT - self.set_data_ready_pin(BMM350_ENABLE_INTERRUPT, polarity) - self.threshold = threshold - else: - self.__thresholdMode = HIGH_THRESHOLD_INTERRUPT - self.set_data_ready_pin(BMM350_ENABLE_INTERRUPT, polarity) - self.threshold = threshold - - - def get_threshold_data(self): - '''! - @brief Get the data that threshold interrupt occured - @return Return the list for storing geomagnetic data, how the data at 3 axis influence interrupt status, - @n [0] The data triggering threshold at x-axis, when the data is NO_DATA, the interrupt is triggered. - @n [1] The data triggering threshold at y-axis, when the data is NO_DATA, the interrupt is triggered. - @n [2] The data triggering threshold at z-axis, when the data is NO_DATA, the interrupt is triggered. - ''' - Data = [NO_DATA] * 3 - state = self.get_data_ready_state() - if state == True: - magData = self.get_geomagnetic_data() - if self.__thresholdMode == LOW_THRESHOLD_INTERRUPT: - if magData[0] < self.threshold*16: - Data[0] = magData[0] - if magData[1] < self.threshold*16: - Data[1] = magData[1] - if magData[2] < self.threshold*16: - Data[2] = magData[2] - elif self.__thresholdMode == HIGH_THRESHOLD_INTERRUPT: - if magData[0] < self.threshold*16: - Data[0] = magData[0] - if magData[1] < self.threshold*16: - Data[1] = magData[1] - if magData[2] < self.threshold*16: - Data[2] = magData[2] - return Data - -# I2C interface -class DFRobot_bmm350_I2C(DFRobot_bmm350): - '''! - @brief An example of an i2c interface module - ''' - def __init__(self, bus, addr): - self.bus = bus - self.__addr = addr - if self.is_raspberrypi(): - import smbus - self.i2cbus = smbus.SMBus(bus) - else: - self.test_platform() - super(DFRobot_bmm350_I2C, self).__init__(self.bus) - - def is_raspberrypi(self): - import io - try: - with io.open('/sys/firmware/devicetree/base/model', 'r') as m: - if 'raspberry pi' in m.read().lower(): return True - except Exception: pass - return False - - def test_platform(self): - import re - import platform - import subprocess - where = platform.system() - if where == "Linux": - p = subprocess.Popen(['i2cdetect', '-l'], stdout=subprocess.PIPE,) - for i in range(0, 25): - line = str(p.stdout.readline()) - s = re.search("i2c-tiny-usb", line) - if s: - line = re.split(r'\W+', line) - bus = int(line[2]) - import smbus - self.i2cbus = smbus.SMBus(bus) - elif where == "Windows": - from i2c_mp_usb import I2C_MP_USB as SMBus - self.i2cbus = SMBus() - else: - print("Platform not supported") - - - - def write_reg(self, reg, data): - '''! - @brief writes data to a register - @param reg register address - @param data written data - ''' - while 1: - try: - self.i2cbus.write_byte_data(self.__addr, reg, data) - return - except: - print("please check connect w!") - time.sleep(1) - return - - def read_reg(self, reg ,len): - '''! - @brief read the data from the register - @param reg register address - @param len read data length - ''' - while True: - try: - # Read data from I2C bus - temp_buf = self.i2cbus.read_i2c_block_data(self.__addr, reg, len + BMM350_DUMMY_BYTES) - # Copy data after dummy byte indices - reg_data = temp_buf[BMM350_DUMMY_BYTES:] - return reg_data # Assuming this function is part of a larger method - except Exception as e: - time.sleep(1) - print("please check connect r!") diff --git a/lib/DFRobot_BMM350/python/raspberrypi/README.md b/lib/DFRobot_BMM350/python/raspberrypi/README.md deleted file mode 100644 index 33c89e6..0000000 --- a/lib/DFRobot_BMM350/python/raspberrypi/README.md +++ /dev/null @@ -1,201 +0,0 @@ -# DFRobot_bmm350 - -* [中文](./README_CN.md) - -This RaspberryPi BMM350 sensor board can communicate with RaspberryPi via I2C or I3C.
-The BMM350 is capable of obtaining triaxial geomagnetic data.
- -![产品效果图](../../resources/images/)![产品效果图](../../resources/images/) - -## Product Link([https://www.dfrobot.com](https://www.dfrobot.com)) - SKU: - -## Table of Contents - -* [Summary](#summary) -* [Installation](#installation) -* [Methods](#methods) -* [History](#history) -* [Credits](#credits) - -## Summary - -Get geomagnetic data along the XYZ axis. - -1. This module can obtain high threshold and low threshold geomagnetic data.
-2. Geomagnetism on three(xyz) axes can be measured.
-3. This module can choose I2C or I3C communication mode.
- - -## Installation - -This Sensor should work with DFRobot_BMM350 on RaspberryPi.
-Run the program: - -``` -$> python3 get_all_state.py -$> python3 data_ready_interrupt.py -$> python3 get_geomagnetic_data.py -$> python3 threshold_interrupt.py -``` - -## Methods - -```python - '''! - @brief Init bmm350 check whether the chip id is right - @return 0 is init success - -1 is init failed - ''' - def sensor_init(self): - - '''! - @brief Soft reset, restore to suspended mode after soft reset. (You need to manually enter the normal mode) - ''' - def soft_reset(self): - - '''! - @brief Sensor self test, the returned character string indicate the self test result. - @return The character string of the test result - ''' - def self_test(self): - - '''! - @brief Set sensor operation mode - @param modes - @n BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - @n BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. - @n BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. - @n BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. - ''' - def set_operation_mode(self, modes): - - '''! - @brief Get sensor operation mode - @return Return the character string of the operation mode - ''' - def get_operation_mode(self): - - '''! - @brief Set the rate of obtaining geomagnetic data, the higher, the faster (without delay function) - @param rate - @n BMM350_DATA_RATE_1_5625HZ - @n BMM350_DATA_RATE_3_125HZ - @n BMM350_DATA_RATE_6_25HZ - @n BMM350_DATA_RATE_12_5HZ (default rate) - @n BMM350_DATA_RATE_25HZ - @n BMM350_DATA_RATE_50HZ - @n BMM350_DATA_RATE_100HZ - @n BMM350_DATA_RATE_200HZ - @n BMM350_DATA_RATE_400HZ - ''' - def set_rate(self, rates): - - '''! - @brief Get the config data rate, unit: HZ - @return rate - ''' - def get_rate(self): - - '''! - @brief Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - @param modes - @n BMM350_PRESETMODE_LOWPOWER Low power mode, get a fraction of data and take the mean value. - @n BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and take the mean value. - @n BMM350_PRESETMODE_ENHANCED Enhanced mode, get a plenty of data and take the mean value. - @n BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and take the mean value. - - ''' - def set_preset_mode(self, modes): - - '''! - @brief Enable the measurement at x-axis, y-axis and z-axis, default to be enabled. After disabling, the geomagnetic data at x, y, and z axis are wrong. - @param en_x - @n BMM350_X_EN Enable the measurement at x-axis - @n BMM350_X_DIS Disable the measurement at x-axis - @param en_y - @n BMM350_Y_EN Enable the measurement at y-axis - @n BMM350_Y_DIS Disable the measurement at y-axis - @param en_z - @n BMM350_Z_EN Enable the measurement at z-axis - @n BMM350_Z_DIS Disable the measurement at z-axis - ''' - def set_measurement_XYZ(self, en_x = BMM350_X_EN, en_y = BMM350_Y_EN, en_z = BMM350_Z_EN): - - '''! - @brief Get the enabling status at x-axis, y-axis and z-axis - @return Return enabling status at x-axis, y-axis and z-axis as a character string - ''' - def get_measurement_state_XYZ(self): - - '''! - @brief Get the geomagnetic data of 3 axis (x, y, z) - @return The list of the geomagnetic data at 3 axis (x, y, z) unit: uT - @ [0] The geomagnetic data at x-axis - @ [1] The geomagnetic data at y-axis - @ [2] The geomagnetic data at z-axis - ''' - def get_geomagnetic_data(self): - - '''! - @brief Get compass degree - @return Compass degree (0° - 360°) 0° = North, 90° = East, 180° = South, 270° = West. - ''' - def get_compass_degree(self): - - '''! - @brief Enable or disable data ready interrupt pin - @n After enabling, the DRDY pin jump when there's data coming. - @n After disabling, the DRDY pin will not jump when there's data coming. - @n High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. - @n Low polarity: active on low, default is high level, which turns to low level when the interrupt is triggered. - @param modes - @n BMM350_ENABLE_INTERRUPT Enable DRDY - @n BMM350_DISABLE_INTERRUPT Disable DRDY - @param polarity - @n BMM350_ACTIVE_HIGH High polarity - @n BMM350_ACTIVE_LOW Low polarity - ''' - def set_data_ready_pin(self, modes, polarity): - - '''! - @brief Get data ready status, determine whether the data is ready - @return status - @n True Data ready - @n False Data is not ready - ''' - def get_data_ready_state(self): - - '''! - @brief Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold - @n High polarity: active on high level, the default is low level, which turns to high level when the interrupt is triggered. - @n Low polarity: active on low level, the default is high level, which turns to low level when the interrupt is triggered. - @param modes - @n LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode - @n HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode - @param threshold - @n Threshold, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt - @param polarity - @n POLARITY_HIGH High polarity - @n POLARITY_LOW Low polarity - ''' - def set_threshold_interrupt(self, modes, threshold, polarity): - - '''! - @brief Get the data that threshold interrupt occured - @return Return the list for storing geomagnetic data, how the data at 3 axis influence interrupt status, - @n [0] The data triggering threshold at x-axis, when the data is NO_DATA, the interrupt is triggered. - @n [1] The data triggering threshold at y-axis, when the data is NO_DATA, the interrupt is triggered. - @n [2] The data triggering threshold at z-axis, when the data is NO_DATA, the interrupt is triggered. - ''' - def get_threshold_data(self): -``` - -## History - -- 2024/05/11 - Version 1.0.0 released. - -## Credits - -Written by [GDuang](yonglei.ren@dfrobot.com), 2024. (Welcome to our website) diff --git a/lib/DFRobot_BMM350/python/raspberrypi/README_CN.md b/lib/DFRobot_BMM350/python/raspberrypi/README_CN.md deleted file mode 100644 index 71331e8..0000000 --- a/lib/DFRobot_BMM350/python/raspberrypi/README_CN.md +++ /dev/null @@ -1,218 +0,0 @@ -# DFRobot_bmm350 - -- [English Version](./README.md) - -BMM350 是一款低功耗、低噪声的 3 轴数字地磁传感器,完全符合罗盘应用的要求。 基于博世专有的 FlipCore 技术,BMM350 提供了高精度和动态的绝对空间方向和运动矢量。 体积小、重量轻,特别适用于支持无人机精准航向。 BMM350 还可与由 3 轴加速度计和 3 轴陀螺仪组成的惯性测量单元一起使用。 - -![产品效果图](../../resources/images)![产品效果图](../../resources/images) - - -## 产品链接([https://www.dfrobot.com.cn](https://www.dfrobot.com.cn)) - SKU: - -## 目录 - - * [概述](#概述) - * [库安装](#库安装) - * [方法](#方法) - * [兼容性](#兼容性) - * [历史](#历史) - * [创作者](#创作者) - -## 概述 - -您可以沿 XYZ 轴获取地磁数据 - -1. 本模块可以获得高阈值和低阈值地磁数据。
-2. 可以测量三个(xyz)轴上的地磁。
-3. 本模块可选择I2C或I3C通讯方式。
- - -## 库安装 -1. 下载库至树莓派,要使用这个库,首先要将库下载到Raspberry Pi,命令下载方法如下:
-```python -sudo git clone https://github.com/DFRobot/DFRobot_BMM350 -``` -2. 打开并运行例程,要执行一个例程demo_x.py,请在命令行中输入python demo_x.py。例如,要执行data_ready_interrupt.py例程,你需要输入:
- -```python -python3 data_ready_interrupt.py -``` - -## 方法 - -```python - '''! - @brief 初始化bmm350 判断芯片id是否正确 - @return 0 is init success - @n -1 is init failed - ''' - def sensor_init(self): - - '''! - @brief 软件复位,软件复位后先恢复为挂起模式(需手动进行普通模式) - ''' - def soft_reset(self): - - '''! - @brief 传感器自测,返回字符串表明自检结果 - @return 测试结果的字符串 - ''' - def self_test(self): - - '''! - @brief 设置传感器的执行模式 - @param modes - @n BMM350_SUSPEND_MODE 挂起模式: 挂起模式是芯片上电后BMM350的默认电源模式,在挂起模式下电流消耗最小,因此,这种模式在不需要进行数据转换时非常有用。所有寄存器的读写是可能的 - @n BMM350_NORMAL_MODE 普通模式: 正常获取地磁数据 - @n BMM350_FORCED_MODE 强制模式: 单次测量,测量完成后传感器恢复到暂停模式 - @n BMM350_FORCED_MODE_FAST 只有使用FM_ FAST才能达到ODR = 200Hz - ''' - def set_operation_mode(self, modes): - - '''! - @brief 获取传感器的执行模式 - @return 返回模式的字符串 - ''' - def get_operation_mode(self): - - '''! - @brief 设置地磁数据获取的速率,速率越大获取越快(不加延时函数) - @param rate - @n BMM350_DATA_RATE_1_5625HZ - @n BMM350_DATA_RATE_3_125HZ - @n BMM350_DATA_RATE_6_25HZ - @n BMM350_DATA_RATE_12_5HZ (default rate) - @n BMM350_DATA_RATE_25HZ - @n BMM350_DATA_RATE_50HZ - @n BMM350_DATA_RATE_100HZ - @n BMM350_DATA_RATE_200HZ - @n BMM350_DATA_RATE_400HZ - ''' - def set_rate(self, rates): - - '''! - @brief 获取配置的数据速率 单位:HZ - @return rate - ''' - def get_rate(self): - - '''! - @brief 设置预置模式,使用户更简单的配置传感器来获取地磁数据 (默认的采集速率为12.5Hz) - @param modes - @n BMM350_PRESETMODE_LOWPOWER 低功率模式,获取少量的数据 取均值 - @n BMM350_PRESETMODE_REGULAR 普通模式,获取中量数据 取均值 - @n BMM350_PRESETMODE_ENHANCED 增强模式,获取大量数据 取均值 - @n BMM350_PRESETMODE_HIGHACCURACY 高精度模式,获取超大量数据 取均值 - ''' - def set_preset_mode(self, modes): - - '''! - @brief 使能x y z 轴的测量,默认设置为使能不需要配置,禁止后xyz轴的地磁数据不准确 - @param en_x - @n BMM350_X_EN 使能 x 轴的测量 - @n BMM350_X_DIS 禁止 x 轴的测量 - @param channel_y - @n BMM350_Y_EN 使能 y 轴的测量 - @n BMM350_Y_DIS 禁止 y 轴的测量 - @param channel_z - @n BMM350_Z_EN 使能 z 轴的测量 - @n BMM350_Z_DIS 禁止 z 轴的测量 - ''' - def set_measurement_XYZ(self, en_x = BMM350_X_EN, en_y = BMM350_Y_EN, en_z = BMM350_Z_EN): - - '''! - @brief 获取 x y z 轴的使能状态 - @return 返回xyz 轴的使能状态的字符串 - ''' - def get_measurement_state_XYZ(self): - - '''! - @brief 获取x y z 三轴的地磁数据 - @return x y z 三轴的地磁数据的列表 单位:微特斯拉(uT) - @n [0] x 轴地磁的数据 - @n [1] y 轴地磁的数据 - @n [2] z 轴地磁的数据 - ''' - def get_geomagnetic_data(self): - - '''! - @brief 获取罗盘方向 - @return 罗盘方向 (0° - 360°) 0° = North, 90° = East, 180° = South, 270° = West. - ''' - def get_compass_degree(self): - - '''! - @brief 使能或者禁止数据准备中断引脚 - @n 使能后有数据来临DRDY引脚跳变 - @n 禁止后有数据来临DRDY不进行跳变 - @n 高极性:高电平为活动电平,默认为低电平,触发中断时电平变为高 - @n 低极性:低电平为活动电平,默认为高电平,触发中断时电平变为低 - @param modes - @n BMM350_ENABLE_INTERRUPT 使能DRDY - @n BMM350_DISABLE_INTERRUPT 禁止DRDY - @param polarity - @n BMM350_ACTIVE_HIGH 高极性 - @n BMM350_ACTIVE_LOW 低极性 - ''' - def set_data_ready_pin(self, modes, polarity): - - '''! - @brief 获取数据准备的状态,用来判断数据是否准备好 - @return status - @n True 表示数据已准备好 - @n False 表示数据还未准备好 - ''' - def get_data_ready_state(self): - - '''! - @brief 设置阈值中断,当某个通道的地磁值高/低于阈值时触发中断 - @n 高极性:高电平为活动电平,默认为低电平,触发中断时电平变为高 - @n 低极性:低电平为活动电平,默认为高电平,触发中断时电平变为低 - @param modes - @n LOW_THRESHOLD_INTERRUPT 低阈值中断模式 - @n HIGH_THRESHOLD_INTERRUPT 高阈值中断模式 - @param threshold 阈值,默认扩大16倍,例如:低阈值模式下传入阈值1,实际低于16的地磁数据都会触发中断 - @param polarity - @n POLARITY_HIGH 高极性 - @n POLARITY_LOW 低极性 - ''' - def set_threshold_interrupt(self, modes, threshold, polarity): - - '''! - @brief 获取发生阈值中断的数据 - @return 返回存放地磁数据的列表,列表三轴当数据和中断状态, - @n [0] x 轴触发阈值的数据 ,当数据为NO_DATA时为触发中断 - @n [1] y 轴触发阈值的数据 ,当数据为NO_DATA时为触发中断 - @n [2] z 轴触发阈值的数据 ,当数据为NO_DATA时为触发中断 - ''' - def get_threshold_data(self): -``` - -## 兼容性 - -| 主板 | 通过 | 未通过 | 未测试 | 备注 | -| ------------ | :--: | :----: | :----: | :--: | -| RaspberryPi2 | | | √ | | -| RaspberryPi3 | | | √ | | -| RaspberryPi4 | √ | | | | - -* Python 版本 - -| Python | 通过 | 未通过 | 未测试 | 备注 | -| ------- | :--: | :----: | :----: | ---- | -| Python3 | √ | | | | - -## 历史 - -- 2024/05/11 - 1.0.0 版本 - -## 创作者 - -Written by [GDuang](yonglei.ren@dfrobot.com), 2024. (Welcome to our [website](https://www.dfrobot.com/)) - - - - - - diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/data_ready_interrupt.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/data_ready_interrupt.py deleted file mode 100644 index 3bd60c3..0000000 --- a/lib/DFRobot_BMM350/python/raspberrypi/examples/data_ready_interrupt.py +++ /dev/null @@ -1,111 +0,0 @@ -# -*- coding:utf-8 -*- -''' - @file demo_data_ready_interrupt.py - @brief Data ready interrupt, DRDY interrupt will be triggered when the geomagnetic data is ready (the software and hardware can determine whether the interrupt occur) - @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis, unit (uT) - @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by DRDY pin interrupt, then the geomagnetic data can be obtained. - @n Connect the sensor DADY pin to the interrupt pin (RASPBERR_PIN_DRDY) of the main controller - @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - @license The MIT License (MIT) - @author [GDuang](yonglei.ren@dfrobot.com) - @version V1.0.0 - @date 2024-05-11 - @url https://github.com/DFRobot/DFRobot_BMM350 -''' -import sys -import os - -sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) -from DFRobot_bmm350 import * - -''' - If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port - Connect to VCC, GND, SCL, SDA pin -''' -I2C_BUS = 0x01 #default use I2C1 -bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) - -def setup(): - while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): - print("sensor init error, please check connect") - time.sleep(1) - - ''' - Set sensor operation mode - opMode: - BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. - BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. - BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. - ''' - bmm350.set_operation_mode(BMM350_NORMAL_MODE) - - ''' - Get the operation mode character string of the sensor - ''' - print('Current power mode: ', bmm350.get_operation_mode()) - - ''' - Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - presetMode: - BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. - BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. - BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. - BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. - rate: - BMM350_DATA_RATE_1_5625HZ - BMM350_DATA_RATE_3_125HZ - BMM350_DATA_RATE_6_25HZ - BMM350_DATA_RATE_12_5HZ (default rate) - BMM350_DATA_RATE_25HZ - BMM350_DATA_RATE_50HZ - BMM350_DATA_RATE_100HZ - BMM350_DATA_RATE_200HZ - BMM350_DATA_RATE_400HZ - ''' - bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) - - ''' - Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. - Refer to readme file if you want to configure more parameters. - ''' - bmm350.set_measurement_XYZ() - - ''' - Enable or disable data ready interrupt pin - After enabling, the pin DRDY signal jump when there's data coming. - After disabling, the pin DRDY signal does not jump when there's data coming. - High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. - Low polarity: active on low, the default is high level, which turns to low level when the interrupt is triggered. - modes: - BMM350_ENABLE_INTERRUPT Enable DRDY - BMM350_DISABLE_INTERRUPT Disable DRDY - polarity: - BMM350_ACTIVE_HIGH High polarity - BMM350_ACTIVE_LOW Low polarity - ''' - bmm350.set_data_ready_pin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW) - - -def loop(): - ''' - Get data ready status, determine whether the data is ready (through software) - status: - True Data ready - False Data is not ready yet - ''' - if bmm350.get_data_ready_state() == 1: - rslt = bmm350.get_geomagnetic_data() - print("mag x = %d ut"%rslt[0]) - print("mag y = %d ut"%rslt[1]) - print("mag z = %d ut"%rslt[2]) - print("") - else: - time.sleep(1) - - -if __name__ == "__main__": - setup() - while True: - loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_data_ready_interrupt.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_data_ready_interrupt.py deleted file mode 100644 index f7e1110..0000000 --- a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_data_ready_interrupt.py +++ /dev/null @@ -1,112 +0,0 @@ -# -*- coding:utf-8 -*- -''' - @file demo_data_ready_interrupt.py - @brief Data ready interrupt, DRDY interrupt will be triggered when the geomagnetic data is ready (the software and hardware can determine whether the interrupt occur) - @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis, unit (uT) - @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by DRDY pin interrupt, then the geomagnetic data can be obtained. - @n Connect the sensor DADY pin to the interrupt pin (RASPBERR_PIN_DRDY) of the main controller - @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - @license The MIT License (MIT) - @author [GDuang](yonglei.ren@dfrobot.com) - @version V1.0.0 - @date 2024-05-11 - @url https://github.com/DFRobot/DFRobot_BMM350 -''' -import sys -import os - -sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) -from DFRobot_bmm350 import * - -''' - If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port - Connect to VCC,GND,SCL,SDA pin -''' -I2C_BUS = 0x01 #default use I2C1 -bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) - -def setup(): - while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): - print("sensor init error, please check connect") - time.sleep(1) - - ''' - Set sensor operation mode - opMode: - BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. - BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. - BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. - ''' - bmm350.set_operation_mode(BMM350_NORMAL_MODE) - - ''' - Get the operation mode character string of the sensor - ''' - print('Current power mode: ', bmm350.get_operation_mode()) - - ''' - Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - presetMode: - BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. - BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. - BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. - BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. - rate: - BMM350_DATA_RATE_1_5625HZ - BMM350_DATA_RATE_3_125HZ - BMM350_DATA_RATE_6_25HZ - BMM350_DATA_RATE_12_5HZ (default rate) - BMM350_DATA_RATE_25HZ - BMM350_DATA_RATE_50HZ - BMM350_DATA_RATE_100HZ - BMM350_DATA_RATE_200HZ - BMM350_DATA_RATE_400HZ - ''' - bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) - - - ''' - Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. - Refer to readme file if you want to configure more parameters. - ''' - bmm350.set_measurement_XYZ() - - ''' - Enable or disable data ready interrupt pin - After enabling, the pin DRDY signal jump when there's data coming. - After disabling, the pin DRDY signal does not jump when there's data coming. - High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. - Low polarity: active on low, the default is high level, which turns to low level when the interrupt is triggered. - modes: - BMM350_ENABLE_INTERRUPT Enable DRDY - BMM350_DISABLE_INTERRUPT Disable DRDY - polarity: - BMM350_ACTIVE_HIGH High polarity - BMM350_ACTIVE_LOW Low polarity - ''' - bmm350.set_data_ready_pin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW) - - -def loop(): - ''' - Get data ready status, determine whether the data is ready (through software) - status: - True Data ready - False Data is not ready yet - ''' - if bmm350.get_data_ready_state() == 1: - rslt = bmm350.get_geomagnetic_data() - print("mag x = %d ut"%rslt[0]) - print("mag y = %d ut"%rslt[1]) - print("mag z = %d ut"%rslt[2]) - print("") - else: - time.sleep(1) - - -if __name__ == "__main__": - setup() - while True: - loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_all_state.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_all_state.py deleted file mode 100644 index 7faa65e..0000000 --- a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_all_state.py +++ /dev/null @@ -1,107 +0,0 @@ -# -*- coding:utf-8 -*- -''' - @file demo_get_all_state.py - @brief Get all the config and self test status, the sensor can change from normal mode to sleep mode after soft reset - @n Experimental phenomenon: the sensor config and self test information are printed in the serial port. - @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - @license The MIT License (MIT) - @author [GDuang](yonglei.ren@dfrobot.com) - @version V1.0.0 - @date 2024-05-11 - @url https://github.com/DFRobot/DFRobot_BMM350 -''' -import sys -import os - -sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) -from DFRobot_bmm350 import * - - -''' - If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port - Connect to VCC,GND,SCL,SDA pin -''' -I2C_BUS = 0x01 #default use I2C1 -bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) - -def setup(): - while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): - print("sensor init error, please check connect") - time.sleep(1) - - print('Power mode after sensor initialization: ', bmm350.get_operation_mode()) - - ''' - Sensor self test, the returned character string indicates the test result. - ''' - print(bmm350.self_test()) - - ''' - Set sensor operation mode - opMode: - BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. - BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. - BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. - ''' - bmm350.set_operation_mode(BMM350_NORMAL_MODE) - - ''' - Get the operation mode character string of the sensor - ''' - print('Current power mode: ', bmm350.get_operation_mode()) - - ''' - Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - presetMode: - BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. - BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. - BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. - BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. - rate: - BMM350_DATA_RATE_1_5625HZ - BMM350_DATA_RATE_3_125HZ - BMM350_DATA_RATE_6_25HZ - BMM350_DATA_RATE_12_5HZ (default rate) - BMM350_DATA_RATE_25HZ - BMM350_DATA_RATE_50HZ - BMM350_DATA_RATE_100HZ - BMM350_DATA_RATE_200HZ - BMM350_DATA_RATE_400HZ - ''' - bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) - ''' - Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. - Refer to readme file if you want to configure more parameters. - ''' - bmm350.set_measurement_XYZ() - - ''' - Get the config data rate unit: HZ - ''' - print("rates is %d HZ"%bmm350.get_rate() ) - - ''' - Get the character string of enabling status at x-axis, y-axis and z-axis - ''' - print(bmm350.get_measurement_state_XYZ()) - - ''' - @brief Soft reset, restore to suspended mode after soft reset. (You need to manually enter the normal mode) - ''' - bmm350.soft_reset() - print('Power mode after software reset: ', bmm350.get_operation_mode()) - -def loop(): - ''' - Get the operation mode character string of the sensor - ''' - print('Current power mode: ', bmm350.get_operation_mode()) - exit() - - -if __name__ == "__main__": - setup() - while True: - loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_geomagnetic_data.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_geomagnetic_data.py deleted file mode 100644 index f64ffcf..0000000 --- a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_get_geomagnetic_data.py +++ /dev/null @@ -1,90 +0,0 @@ -# -*- coding:utf-8 -*- -''' - @file demo_get_geomagnetic_data.py - @brief Get the geomagnetic data at 3 axis (x, y, z), get the compass degree - @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north - @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis and the angle formed when the needle rotates counterclockwise from the current position to the true north - @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - @license The MIT License (MIT) - @author [GDuang](yonglei.ren@dfrobot.com) - @version V1.0.0 - @date 2024-05-11 - @url https://github.com/DFRobot/DFRobot_BMM350 -''' -import sys -import os - -sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) -from DFRobot_bmm350 import * - -''' - If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port - Connect to VCC,GND,SCL,SDA pin -''' -I2C_BUS = 0x01 #default use I2C1 -bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) - -def setup(): - while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): - print("sensor init error, please check connect") - time.sleep(1) - - ''' - Set sensor operation mode - opMode: - BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. - BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. - BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. - ''' - bmm350.set_operation_mode(BMM350_NORMAL_MODE) - - ''' - Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - presetMode: - BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. - BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. - BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. - BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. - rate: - BMM350_DATA_RATE_1_5625HZ - BMM350_DATA_RATE_3_125HZ - BMM350_DATA_RATE_6_25HZ - BMM350_DATA_RATE_12_5HZ (default rate) - BMM350_DATA_RATE_25HZ - BMM350_DATA_RATE_50HZ - BMM350_DATA_RATE_100HZ - BMM350_DATA_RATE_200HZ - BMM350_DATA_RATE_400HZ - ''' - bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) - - - ''' - Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. - Refer to readme file if you want to configure more parameters. - ''' - bmm350.set_measurement_XYZ() - -def loop(): - geomagnetic = bmm350.get_geomagnetic_data() - print("mag x = %d ut"%geomagnetic[0]) - print("mag y = %d ut"%geomagnetic[1]) - print("mag z = %d ut"%geomagnetic[2]) - - # get float type data - # geomagnetic = bmm350.get_geomagnetic_data() - # print("---------------------------------") - # print("mag x = %.2f ut"%geomagnetic[0]) - # print("mag y = %.2f ut"%geomagnetic[1]) - # print("mag z = %.2f ut"%geomagnetic[2]) - degree = bmm350.get_compass_degree() - print("---------------------------------") - print("the angle between the pointing direction and north (counterclockwise) is: %.2f "%degree) - time.sleep(1) - -if __name__ == "__main__": - setup() - while True: - loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_threshold_interrupt.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_threshold_interrupt.py deleted file mode 100644 index 2b4434e..0000000 --- a/lib/DFRobot_BMM350/python/raspberrypi/examples/demo_threshold_interrupt.py +++ /dev/null @@ -1,115 +0,0 @@ -# -*- coding:utf-8 -*- -''' - @file demo_threshold_interrupt.py - @brief Set the interrupt to be triggered when beyond/below threshold, when the interrupt at a axis occur, the data will be printed in the serial port. - @n When the geomagnetic data at 3 axis (x, y, z) beyond/below the set threshold, the data will be printed in the serial port, unit (uT) - @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by INT pin interrupt, then the geomagnetic data can be obtained - @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - @license The MIT License (MIT) - @author [GDuang](yonglei.ren@dfrobot.com) - @version V1.0.0 - @date 2024-05-11 - @url https://github.com/DFRobot/DFRobot_BMM350 -''' -import sys -import os - -sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) -from DFRobot_bmm350 import * - -''' - If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port - Connect to VCC,GND,SCL,SDA pin -''' -I2C_BUS = 0x01 #default use I2C1 -bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) - -def setup(): - while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): - print("sensor init error ,please check connect") - time.sleep(1) - - ''' - Set sensor operation mode - opMode: - BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. - BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. - BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. - ''' - bmm350.set_operation_mode(BMM350_NORMAL_MODE) - - ''' - Get the operation mode character string of the sensor - ''' - print('Current power mode: ', bmm350.get_operation_mode()) - - ''' - Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - presetMode: - BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. - BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. - BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. - BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. - rate: - BMM350_DATA_RATE_1_5625HZ - BMM350_DATA_RATE_3_125HZ - BMM350_DATA_RATE_6_25HZ - BMM350_DATA_RATE_12_5HZ (default rate) - BMM350_DATA_RATE_25HZ - BMM350_DATA_RATE_50HZ - BMM350_DATA_RATE_100HZ - BMM350_DATA_RATE_200HZ - BMM350_DATA_RATE_400HZ - ''' - bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) - - ''' - Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. - Refer to readme file if you want to configure more parameters. - ''' - bmm350.set_measurement_XYZ() - - - ''' - Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold - High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. - Low polarity: active on low, the default is high level, which turns to low level when the interrupt is triggered. - modes: - LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode, interrupt is triggered when below the threshold - HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode, interrupt is triggered when beyond the threshold - threshold - Threshold range, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt - polarity: - BMM350_ACTIVE_HIGH High polarity - BMM350_ACTIVE_LOW Low polarity - View the use method in the readme file if you want to use more configs - ''' - bmm350.set_threshold_interrupt(LOW_THRESHOLD_INTERRUPT, 0, BMM350_ACTIVE_LOW) - - -def loop(): - ''' - Get the data that threshold interrupt occured (get the threshold interrupt status through software) - That the data at (x, y, z) axis are printed in the serial port indicates threshold interrupt occur at (x, y, z) axis - Return the list for storing geomagnetic data, how the data at 3 axis influence interrupt status - [0] The data triggering threshold at x-axis, when the data is NO_DATA, the interrupt is triggered. - [1] The data triggering threshold at y-axis, when the data is NO_DATA, the interrupt is triggered. - [2] The data triggering threshold at z-axis, when the data is NO_DATA, the interrupt is triggered. - ''' - threshold_data = bmm350.get_threshold_data() - if threshold_data[0] != NO_DATA: - print("mag x = %d ut"%threshold_data[0]) - if threshold_data[1] != NO_DATA: - print("mag y = %d ut"%threshold_data[1]) - if threshold_data[2] != NO_DATA: - print("mag z = %d ut"%threshold_data[2]) - print("") - time.sleep(1) - - -if __name__ == "__main__": - setup() - while True: - loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/get_all_state.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/get_all_state.py deleted file mode 100644 index 36023cc..0000000 --- a/lib/DFRobot_BMM350/python/raspberrypi/examples/get_all_state.py +++ /dev/null @@ -1,108 +0,0 @@ -# -*- coding:utf-8 -*- -''' - @file demo_get_all_state.py - @brief Get all the config and self test status, the sensor can change from normal mode to sleep mode after soft reset - @n Experimental phenomenon: the sensor config and self test information are printed in the serial port. - @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - @license The MIT License (MIT) - @author [GDuang](yonglei.ren@dfrobot.com) - @version V1.0.0 - @date 2024-05-11 - @url https://github.com/DFRobot/DFRobot_BMM350 -''' -import sys -import os - -sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) -from DFRobot_bmm350 import * - - -''' - If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port - Connect to VCC, GND, SCL, SDA pin -''' -I2C_BUS = 0x01 #default use I2C1 -bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) - -def setup(): - while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): - print("sensor init error, please check connect") - time.sleep(1) - - print('Power mode after sensor initialization: ', bmm350.get_operation_mode()) - - ''' - Sensor self test, the returned character string indicates the test result. - ''' - print(bmm350.self_test()) - - ''' - Set sensor operation mode - opMode: - BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. - BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. - BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. - ''' - bmm350.set_operation_mode(BMM350_NORMAL_MODE) - - ''' - Get the operation mode character string of the sensor - ''' - print('Current power mode: ', bmm350.get_operation_mode()) - - ''' - Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - presetMode: - BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. - BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. - BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. - BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. - rate: - BMM350_DATA_RATE_1_5625HZ - BMM350_DATA_RATE_3_125HZ - BMM350_DATA_RATE_6_25HZ - BMM350_DATA_RATE_12_5HZ (default rate) - BMM350_DATA_RATE_25HZ - BMM350_DATA_RATE_50HZ - BMM350_DATA_RATE_100HZ - BMM350_DATA_RATE_200HZ - BMM350_DATA_RATE_400HZ - ''' - bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) - - ''' - Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. - Refer to readme file if you want to configure more parameters. - ''' - bmm350.set_measurement_XYZ() - - ''' - Get the config data rate unit: HZ - ''' - print("rates is %d HZ"%bmm350.get_rate() ) - - ''' - Get the character string of enabling status at x-axis, y-axis and z-axis - ''' - print(bmm350.get_measurement_state_XYZ()) - - ''' - @brief Soft reset, restore to suspended mode after soft reset. (You need to manually enter the normal mode) - ''' - bmm350.soft_reset() - print('Power mode after software reset: ', bmm350.get_operation_mode()) - -def loop(): - ''' - Get the operation mode character string of the sensor - ''' - print('Current power mode: ', bmm350.get_operation_mode()) - exit() - - -if __name__ == "__main__": - setup() - while True: - loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/get_calibrated_geomagnetic_data.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/get_calibrated_geomagnetic_data.py deleted file mode 100644 index 2ef2d11..0000000 --- a/lib/DFRobot_BMM350/python/raspberrypi/examples/get_calibrated_geomagnetic_data.py +++ /dev/null @@ -1,107 +0,0 @@ -# -*- coding:utf-8 -*- -''' - @file get_calibrated_geomagnetic_data.py - @brief Get the geomagnetic data at 3 axis (x, y, z), get the compass degree - @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north - @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis and the angle formed when the needle rotates counterclockwise from the current position to the true north - @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - @license The MIT License (MIT) - @author [GDuang](yonglei.ren@dfrobot.com) - @version V1.0.0 - @date 2024-05-11 - @url https://github.com/DFRobot/DFRobot_BMM350 -''' -import sys -import os -import math -sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) -from DFRobot_bmm350 import * - -''' - If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port - Connect to VCC,GND,SCL,SDA pin -''' -I2C_BUS = 0x01 #default use I2C1 -bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) - -def setup(): - while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): - print("sensor init error, please check connect") - time.sleep(1) - - ''' - Set sensor operation mode - opMode: - BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. - BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. - BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. - ''' - bmm350.set_operation_mode(BMM350_NORMAL_MODE) - - ''' - Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - presetMode: - BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. - BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. - BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. - BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. - rate: - BMM350_DATA_RATE_1_5625HZ - BMM350_DATA_RATE_3_125HZ - BMM350_DATA_RATE_6_25HZ - BMM350_DATA_RATE_12_5HZ (default rate) - BMM350_DATA_RATE_25HZ - BMM350_DATA_RATE_50HZ - BMM350_DATA_RATE_100HZ - BMM350_DATA_RATE_200HZ - BMM350_DATA_RATE_400HZ - ''' - bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) - - - ''' - Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. - Refer to readme file if you want to configure more parameters. - ''' - bmm350.set_measurement_XYZ() - -def loop(): - geomagnetic = bmm350.get_geomagnetic_data() - #hard iron calibration parameters - hard_iron= (-13.45, -28.95, 12.69 ) - #soft iron calibration parameters - soft_iron= [ - ( 0.992, -0.006, -0.007 ), - ( -0.006, 0.990, -0.004 ), - ( -0.007, -0.004, 1.019 ) - ] - - # hard iron calibration - geomagnetic[0] =geomagnetic[0] + hard_iron[0] - geomagnetic[1] =geomagnetic[1] + hard_iron[1] - geomagnetic[2] = geomagnetic[2] + hard_iron[2] - - #soft iron calibration - for i in range(3): - geomagnetic[i] = (soft_iron[i][0] * geomagnetic[0]) + (soft_iron[i][1] * geomagnetic[1]) + (soft_iron[i][2] * geomagnetic[2]) - - compass = math.atan2(geomagnetic[0], geomagnetic[1]) - if compass < 0: - compass += 2 * PI - if compass > 2 * PI: - compass -= 2 * PI - degree=compass * 180 / M_PI - print("---------------------------------") - print("mag x = %.2f ut"%geomagnetic[0]) - print("mag y = %.2f ut"%geomagnetic[1]) - print("mag z = %.2f ut"%geomagnetic[2]) - print("---------------------------------") - print("the angle between the pointing direction and north (counterclockwise) is: %.2f "%degree) - time.sleep(1) - -if __name__ == "__main__": - setup() - while True: - loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/get_geomagnetic_data.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/get_geomagnetic_data.py deleted file mode 100644 index 1989b7f..0000000 --- a/lib/DFRobot_BMM350/python/raspberrypi/examples/get_geomagnetic_data.py +++ /dev/null @@ -1,89 +0,0 @@ -# -*- coding:utf-8 -*- -''' - @file demo_get_geomagnetic_data.py - @brief Get the geomagnetic data at 3 axis (x, y, z), get the compass degree - @n "Compass Degree", the angle formed when the needle rotates counterclockwise from the current position to the true north - @n Experimental phenomenon: serial print the geomagnetic data at x-axis, y-axis and z-axis and the angle formed when the needle rotates counterclockwise from the current position to the true north - @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - @license The MIT License (MIT) - @author [GDuang](yonglei.ren@dfrobot.com) - @version V1.0.0 - @date 2024-05-11 - @url https://github.com/DFRobot/DFRobot_BMM350 -''' -import sys -import os - -sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) -from DFRobot_bmm350 import * - -''' - If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port - Connect to VCC, GND, SCL, SDA pin -''' -I2C_BUS = 0x01 #default use I2C1 -bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) - -def setup(): - while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): - print("sensor init error, please check connect") - time.sleep(1) - - ''' - Set sensor operation mode - opMode: - BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. - BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. - BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. - ''' - bmm350.set_operation_mode(BMM350_NORMAL_MODE) - - ''' - Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - presetMode: - BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. - BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. - BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. - BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. - rate: - BMM350_DATA_RATE_1_5625HZ - BMM350_DATA_RATE_3_125HZ - BMM350_DATA_RATE_6_25HZ - BMM350_DATA_RATE_12_5HZ (default rate) - BMM350_DATA_RATE_25HZ - BMM350_DATA_RATE_50HZ - BMM350_DATA_RATE_100HZ - BMM350_DATA_RATE_200HZ - BMM350_DATA_RATE_400HZ - ''' - bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) - - ''' - Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. - Refer to readme file if you want to configure more parameters. - ''' - bmm350.set_measurement_XYZ() - -def loop(): - geomagnetic = bmm350.get_geomagnetic_data() - print("mag x = %d ut"%geomagnetic[0]) - print("mag y = %d ut"%geomagnetic[1]) - print("mag z = %d ut"%geomagnetic[2]) - - # get float type data - # geomagnetic = bmm350.get_geomagnetic_data() - # print("---------------------------------") - # print("mag x = %.2f ut"%geomagnetic[0]) - # print("mag y = %.2f ut"%geomagnetic[1]) - # print("mag z = %.2f ut"%geomagnetic[2]) - degree = bmm350.get_compass_degree() - print("---------------------------------") - print("the angle between the pointing direction and north (counterclockwise) is: %.2f "%degree) - time.sleep(1) - -if __name__ == "__main__": - setup() - while True: - loop() diff --git a/lib/DFRobot_BMM350/python/raspberrypi/examples/threshold_interrupt.py b/lib/DFRobot_BMM350/python/raspberrypi/examples/threshold_interrupt.py deleted file mode 100644 index ff0893f..0000000 --- a/lib/DFRobot_BMM350/python/raspberrypi/examples/threshold_interrupt.py +++ /dev/null @@ -1,115 +0,0 @@ -# -*- coding:utf-8 -*- -''' - @file demo_threshold_interrupt.py - @brief Set the interrupt to be triggered when beyond/below threshold, when the interrupt at a axis occur, the data will be printed in the serial port. - @n When the geomagnetic data at 3 axis (x, y, z) beyond/below the set threshold, the data will be printed in the serial port, unit (uT) - @n Experimental phenomenon: the main controller interrupt will be triggered by level change caused by INT pin interrupt, then the geomagnetic data can be obtained - @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - @license The MIT License (MIT) - @author [GDuang](yonglei.ren@dfrobot.com) - @version V1.0.0 - @date 2024-05-11 - @url https://github.com/DFRobot/DFRobot_BMM350 -''' -import sys -import os - -sys.path.append(os.path.dirname(os.path.dirname(os.path.realpath(__file__)))) -from DFRobot_bmm350 import * - -''' - If you want to use I2C to drive this module, uncomment the codes below, and connect the module with Raspberry Pi via I2C port - Connect to VCC, GND, SCL, SDA pin -''' -I2C_BUS = 0x01 #default use I2C1 -bmm350 = DFRobot_bmm350_I2C(I2C_BUS, 0x14) - -def setup(): - while BMM350_CHIP_ID_ERROR == bmm350.sensor_init(): - print("sensor init error ,please check connect") - time.sleep(1) - - ''' - Set sensor operation mode - opMode: - BMM350_SUSPEND_MODE suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - BMM350_NORMAL_MODE normal mode: Get geomagnetic data normally. - BMM350_FORCED_MODE forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. - BMM350_FORCED_MODE_FAST To reach ODR = 200Hz is only possible by using FM_ FAST. - ''' - bmm350.set_operation_mode(BMM350_NORMAL_MODE) - - ''' - Get the operation mode character string of the sensor - ''' - print('Current power mode: ', bmm350.get_operation_mode()) - - ''' - Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default rate for obtaining geomagnetic data is 12.5Hz) - presetMode: - BMM350_PRESETMODE_LOWPOWER Low power mode, get a small number of data and draw the mean value. - BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and draw the mean value. - BMM350_PRESETMODE_ENHANCED Enhanced mode, get a large number of data and draw the mean value. - BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and draw the mean value. - rate: - BMM350_DATA_RATE_1_5625HZ - BMM350_DATA_RATE_3_125HZ - BMM350_DATA_RATE_6_25HZ - BMM350_DATA_RATE_12_5HZ (default rate) - BMM350_DATA_RATE_25HZ - BMM350_DATA_RATE_50HZ - BMM350_DATA_RATE_100HZ - BMM350_DATA_RATE_200HZ - BMM350_DATA_RATE_400HZ - ''' - bmm350.set_preset_mode(BMM350_PRESETMODE_HIGHACCURACY,BMM350_DATA_RATE_25HZ) - - ''' - Enable the measurement at x-axis, y-axis and z-axis, default to be enabled, no config required. When disabled, the geomagnetic data at x, y, and z will be inaccurate. - Refer to readme file if you want to configure more parameters. - ''' - bmm350.set_measurement_XYZ() - - - ''' - Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold - High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. - Low polarity: active on low, the default is high level, which turns to low level when the interrupt is triggered. - modes: - LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode, interrupt is triggered when below the threshold - HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode, interrupt is triggered when beyond the threshold - threshold - Threshold range, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt - polarity: - BMM350_ACTIVE_HIGH High polarity - BMM350_ACTIVE_LOW Low polarity - View the use method in the readme file if you want to use more configs - ''' - bmm350.set_threshold_interrupt(LOW_THRESHOLD_INTERRUPT, 0, BMM350_ACTIVE_LOW) - - -def loop(): - ''' - Get the data that threshold interrupt occured (get the threshold interrupt status through software) - That the data at (x, y, z) axis are printed in the serial port indicates threshold interrupt occur at (x, y, z) axis - Return the list for storing geomagnetic data, how the data at 3 axis influence interrupt status - [0] The data triggering threshold at x-axis, when the data is NO_DATA, the interrupt is triggered. - [1] The data triggering threshold at y-axis, when the data is NO_DATA, the interrupt is triggered. - [2] The data triggering threshold at z-axis, when the data is NO_DATA, the interrupt is triggered. - ''' - threshold_data = bmm350.get_threshold_data() - if threshold_data[0] != NO_DATA: - print("mag x = %d ut"%threshold_data[0]) - if threshold_data[1] != NO_DATA: - print("mag y = %d ut"%threshold_data[1]) - if threshold_data[2] != NO_DATA: - print("mag z = %d ut"%threshold_data[2]) - print("") - time.sleep(1) - - -if __name__ == "__main__": - setup() - while True: - loop() diff --git a/lib/DFRobot_BMM350/resources/images/BMM350.png b/lib/DFRobot_BMM350/resources/images/BMM350.png deleted file mode 100644 index 7978f228908f2007ae9d3aab7447844da0b94b55..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 200001 zcma(2XEdDc_Xmz*h%S2Xh8R5v!w@9e5WNJ0D5HIBogG@`JVsptn=c$IBN~ovbe9duf0EI-$}-XINy&0e2&Zk@RBJ^h+2K%K)1On+-?u_H&V%}5(5-3lid(kRa z6@I=fYBu^u?xl`Way{YlA*QPB&y0%JUp`?`PT$MlRe#Tn{xT`BrQ9RKeRV@C(=E$k zc;Ke>1T?8;NUlVLdakECZceXxNjBKHnu`4T5hFRS z&ev!~-4_mCJzt^d9C`Qdom!s@g>J^O=M%Gcl>KUTm`W>EY zXAzp3q<&C4WH_*snWhE8K3?Q`Ioc-Rr-2h+gfwMzu1uaNG-piM_?QW-+sVJ ziAx}hTdv#CqukNoihqU@=Pl2XS^cwf68e*tYlG3sIc$*BiT;lvOUyj@>kC)_4~Z%kf@7&Oq)Z

0 z_}>H_AiRELdN%3rq_|>b{anG7I~h?R~R4 z*#Df`=yAIgJmI!WrmztB=Ulqk`Sx&%iMQm(}~8Q@SDG*lB&oCd*?X zIyp@5s=e!>0%f5Bx*TpZAO!5JdMRk8G16c+*rms*bM^gyvVyK+==)7|2kOpb<{4?9 zZz$|L$k|NA*j#qU%|2F0XpNWc<#d6oBE0ZA=IxCxgiKWW^1mJ7P}H{Crfa@cK$@QG zYHdUEQ>N5#R|`@m>*vRRn(@mHI-N-VJOsqDIbm4uX~BV()xI6~CVo8=M&}AHMjk>*NrWa;J~}GjB-b`d ziQn;GM1uqPw?loprW0>rif!-h(Vu9Buo=poN_!b;S>|qR*b_t2<*H2fIo{u3{pqV{ zG{jdFE1r{lkFdq*JhXVXr%`TiWXy1QDjUd~8%aGYqGzR>@|Em%BuJm8^y?Q&H6LOD41 zH`JMvCCU5%qQAq3M+`HaARuk*!B1OtaUZCYV%x0<+4)sxEl|u0OT4#K$`QE+BB!3h z2rP_VUqt!u@O}9IV;nT|Od+;%)>m*GCp$~W4S!Hi=(>}oTTtj)pbk7pRjhpXT2NC@ z@Y)g&-%%g>y2k0FZEBS(vyDfbUuj{>=ly$*BJ{CGaJ2!+|88T%!wr-*F$-c5A>l|3 zNOK!yW(|MhMB)I~Ih())%Sp$CA#m@X0#{28vw)3bc(;LlryGL%(w78AFgnD)TPMTi z$sQ-c6!XzTZU6pOLQQsdK&{i|LQ>>mLG-kXe>NSTQmO6#_n~3uUIIHeaq6b)X9$hTjr|WH=Q*7aQ1Gq1dW1`%uPg^V9TFhyq6$f?xurwtW{CJ^VW{*iZM{; zr`=AP=uhthnQ+XciNsM2rL#gextE)kdH$s(E(2~V5)$gz*fz;f=hAbAel|n+U2_W~ zBcmYG6fhL4vz~gn>Yef1#VC(e=gf*PMX7f}w;QXHJMTnMK)S#YbA5fyqp0l)hB2B| z=XjP?FeEaIO<<1ReXy+!C?-50&}qg2;S2;Jr38gwamXr1O(f}*F0Sp}MA@)QB`X;- z<$z7@=%T~zI0KS{)PAY)&sD9FL`rkzH#QVfYXm7%2#woGzl31PLeFbx2tdxB{CfF8 zvzeY*f({xL^3={IlBdYoxV0h5j`5EoTIilzM%aqCo5N3r{vo)T`G+Y8SB`{uyXYpD z9u{37$d4%&Y+1auokUPr-2PYRv$f(X{_SyTLmzD(swG0d_Qh@sRIuePtIjogeT4Nb zgHc5VfK(!e`Z@?`q>ib@BJWwfgi-xv`5=VzNZtCcE_U*?Q`TmqVupgC?6P!aBN_)G zL;t8K#^)y9!s?*@1>9H~1w?3j^kWS6TCYM>-@+1uY8Yn7050HZ20;NwkscA_QsJpU3FsB2NtaDpg68=@V=ZTx)sDB5G>vGZOzpVlgf3cD~^mO zlk39l#(6Bi9$S1?qI$SC2AtILQ0OzNSad>`4Ojp&16n?ByYp!Azm5u}2`+fZ4quuP z(wD_(=+R=jrSf~RBu(NXWJh6%rZ-6sxIl6TOgZjHMCRY$wX0wk<|8LKMT?pf;N&Ba zX_#v>r>oK7orWy4xl9-mmnVMb?LsE`;Of~O4MqN|I{m3g{T_r=tsEw;f&<^1% zS@K~qvgeKBNtz{_=(nd2+bB9(^YfsOWrSk_MRg0XS~0b5IAP#O7yzj9^ZdN*)08Yf zXUUjhDF_|ab9C%y5U7n^_lR7AL{ta;`WqS=ItfNIj(q7wENL^1*BESc)6mM+(qvaQ z{OD9qP7D)-sd$q#H7mG43=gy8UFGjW3Dx|Vu^O0rA?WJr3Y%!$+1IDGoph?alB+1> zkNpyIrC@H_90!t2>|M{VrvRGIo*^bcrdY0`bWXs*83R{9LKdANA( zKch1U-BlS2u*IyE7695JwXwqKN4X0j-(hdP;en&od_u$b%+61^gk~4h2pm_9T(Nyk zf~r8m_?4(P#Ds^G8brVOrcZD`cBF@Un``fU^oansAK~0|Go-rALhz6OrP|42`=4xo zbKQUR_xEr9P-~giRq#|H%M>H`!|+u4`N;eG5j_VArgym6u13n7BYrTNggbG<&nKe6 z+L8*f%LjK0lI}rmB=%VVNji3N5pOfj%gxQr&K~wmH>53C2*yZIZ|a-J>V~(5qq0>R zD=E@{tvc#_70c0s{YvpO9lT3tBkYK-$lc8V!?ryvHWJmaI;QM!`~St?ukttOUYo{) zQdKAvD8M~QAz(fz+{iy=hlQLRz!JNm`}w|t=#{ByCWR4ojz7>uaBV}c#hj859xuoX zM~0Z6)H49LG5B|hc?6I!XCd^IREEBWvSJUU|sFhTi+wi>VGUoGPB-Es5Xn!Peuf1zX`}2~kn>!Y80^{dOREbmvwF zP`cTQS5tp+;lzc?nNKw1wXV@TjUE6@j;J@R4vJ_Pml1QWs92u-&16N-%$659FNeX^ ztc(GRRauKSb~q5}2~5FOgowZGzF+iPGnZq$*pvk_^Pdo2rKa^YT!8UY|9_Tyyz}mP zx`VN|A6jvY#4?ru#mKY~-zR}aY4s*v3PlVFNs5RC&sTDcfA;I5{_-M0P_r8M?_T^N zKnkAqnXl#;w4$OYgNVl68KE}$z|1rQZ-V}~F%~^u^p+*aVTvZ4qN3Ew_SNn7XrcgI zvfXm)WA|Mrb?o79j?BL2 z{-Ga_*Oz>|&|LCwP@VOby8sn&K6;>8Y5G|w{JDp#o&>qlc`9fq`n1j z>0)fVGrr%_`_M^+r{-{Nex3=QL+#sXovQ|9aTn^8e}yNar#Ee#_;=;N+K0~t*)1ip z=FP~YZl(*J^F(r(St;d!)V=zyVE=5kp0coL(uf-`(1b``tdf_`L`qTPF%f`TO?L;l ze1O{noIifxU&X|4t*oL{2z2kISw1%@eAILTXaC1`>91>!(WL^FHwI#yD2ox^e)V-xEnud3Pw&3Q z^HkB@EAx$TN(2Yi>$T6ku~K}_b2jiyw_R|}ZUvFVjYD<7< zM4hY3nK8*FpY~FY!h$iS3Si8#?b!y`-%idSgD~D?c1}o1Rv`;I0GSjaVELBv@hNT^ zlVzE@PTxB4LVGkYGH51)=}*%HkOydE=jpkgi?7-Kv! zR-=PBGU!)OyBui+w103@%OU96%Z)^7V;SH#8{DZPG9G(#<(yQOqsufr!UgwK9p2@l zsMIx@nMp};l%?);@`Z*fH5uj8-i$9uhU;XonsJNMciCRdxgumMUM*A-BqBBsQjt0b z8LE5PlKU-g$n|v`YYJM7ydh(Frjf@$JfBRsfS&nPX~34YPU*HOM4gx}TX6RN7b=Df z8D$@73$dL4{`(Jm+4N@373}D8)RiPiK4dOyuHc&xmZTRxZW_loV=CAaT2$L*;h>g- zdZ^GbBj;LeSBVqNrT-BfIim z(Qvt6s)C90Rq*bvLW-^xL&=&Z`q>ymzF=3w%@{~#!6{~VWO4W#5_KB+jnSop3VP&a zkvD66%yW~5rtMo2!$I3U+eXWl>i)-6-^m9TQlGLayL>nQSfGP7xqa1bV=4I441i4& z=ZdBP%PJGm7%K64XdhRF;sCv9{ecz)Lh-t)0S>q@K9=EId@DN^V*-IvT4 z*FipiP;!kbtEQH94rcs%Cb_pxp995Tt!^}aUQ-X5q0f;uweTS(~))d#k&{6mWt+0?ntkAR;P<=0d z=C0=~`7wEmQRsrBvdbL8CfCazi%t<|>z}VZwhi-PdP-iVzNam>A_j#L^%3G=9SH^W zI4<{_)v!nBYyYIJb9n~V0+TR5Kbel`SUM9`bWz<3Y1tc-P(WzeW!VY`YInsQT`P@$ z{M3Cn+EnxU2&Z#q`~oy5;WgFt{xR!Yw1{>KI;zb=FzVN?dKgfw>40^d`*nYJc{j}q z2wz4_jx8MVZs39wUk4QqE9&HLQ@RRbiey+a@m{@VsaMRkZqBT~coLWW0?&+>@6rkG zBYmOt7xM;6oi$fANzj$F>05UKV2r?{Lak9|0u#Cx3`RXixMtO)$@6-i_FfGztXtq& z91AI$Sv$nNNb?_+{RX2y+5CKvlr5BIAuK&!16q6wyASpv7WU!nKFNZjbWO zD03ewO;dI}We6k3MaL@dhi7q0n-h!o@n|}QZ$-QeIpWV;cRq@ZOSONLEi8X*$5Z0-2bbdjiG7PC0+^FRdV6*CMO5p#n4G z@yNQ^@I%bivgJ1J#nLKK_Fd$ z;^;KDOjM-`MO3iRE&T#gR#J48=9Y(cbyvE~>GO~A)dh98Q^d<74RYN6H&*!Mxzzv9 zvEGD&3yf|ZR5h<&9KZ89akKRUY5vT<5c3Y7XsoYK=~t!6tc&FryXoQ1sOh5F2Fxl0 z0Me$Sr0b?Z52wWJsqefFf__REj^P-0O*|kGCuU_cf3Su^F+6a{D%EWgysHJC zJ0%2Syx)y6LiY1mBtmIA@(7QVTFe~|3#Xk`S7Qzj0upZ50oiT0TdTIb|9`j)y)MRo z_emn3zEn*;8~0Oh)~&IR|4DmBn%=Okpjb3x#XUN3COOcL2@@J0{TUsVXOfk?ftZ z@J4*68_(^xe%t;i-BZ|Nd%z;wq+n6jDwS&mskHiB2;!f7KkJk`G0esVh-mFgW?Onq z6~le^0O{rRq5iiqH-6z+SfMN32A3xG5=1?(k!>l(>c7@4@}bcF=1Id1ERoGaWZNoa z>dMgjXnIrB7b#sJ&RGKRhrDU73!Tdc^(6Hl#OlOSie4vz2Yo!e=KpTK=5jgwXn^f{ zw6&4815M4A=f@|1*kJW3F&*TFQzB-FmA|MD&5QNu>&R_~y6gdX2|P&LsGIuD*}wGm zbr1-)(gsglS7Ik#yUvQ|8JNrCc}k$$+>GX;Kg}h3zoJ~ky{h^kTsA;^a0A@jmAr}F zFFS!?CVyuGGeQ`q+>yQvSfm?I_{SR$AwcK?Beu=OBvxC5hF?0HGxD zTcJMkT%T{DiQ*VCxnS?(=K&KTp@z8`YeAYPxR=LOMQIGqJA)J`o^}+ndR-h5kLTK# zui$Q^cwfOjh2H|mXUf0v* zs2_{J&`I`imi(MV_t0o)(7yeeBkGbqiag+=NUiRby4~=XLN51}Mhj9MNb-aoG@?~G-JYVcKkpNinH|@$A1g54 z9~rdxT7?;d#Yq|pt+|IWk6-I5uxL{y@)(ilXQS-Rb$6mymHsC%aXUO5GkbVjdGAL4 z?4oyvYL7Wqh!~x%sUjm!DO$>(c#t$ueme16CtT=yj5qCjDpK+3%$~KghcUR;<;ZZ> zU0Wr>1Y1knJ4pmxB2zG?TXbq!XI%amS50uQ&ud>j31Sx$N1(Git@1PFDN(dqGGtKt zVeQ?Vv;T!5F!epuI1c5pdwnz-yFEH>NnYl+hg&L85s;$QiWY=RdOdH38dIgE){6-z z8MZIf($^*|#gc*5seCn!Cbc=wseWZblVBBT7ik> zpRkvCnOp{2$8ciJC_;<>AuZ)(Q%ON zeZkO>szx850kR|x9+$0taZ9<-wyGG?YQQ7uf9QOBUqVv*@MW5iWa5EGhicvE%Iu*{ zBP%@VtfSN73^5bp@cWB;_GH(r#G#P`m1ZR|^P;bu1B`9aTEONx_HeJj96M`FzR`wB zyXWyLJI63mj^n0QlBD4N*RP@aSp*Y`e~e~(&An^}@ZGfa*1jVR^%~@@xYGiydv;Oe zRRwgKU4>lJ*z13Y%%`wC0>6`^cE}phZUY!P>zaQIr0|4(>>U0DGH}t=BX?T=EuH$8 z{{KYqO)B|Kur7n1%0nkOr4jLJR#8qycgq7aAC4|M20(JFb(&xVL}Nhb8NsJ_oxL(l z10NFq0p!Jmgxfg_U6=9dB!hYib0AzRA-naYc>crN~w7w0!to1DW-hSJ_El7eH)uG)Yh;a zwd?dwo`9c^{pj1;a@@ajU}R6uZ*Ko@Dz;FAFmC?$#Cc;{l?H(R@qh!FL{k130Fjpr zH_z=b-bU?X6TC2&Rf4iRB4rqd6J)Qw$JsF9_u=j;fB9HE3u1})gTqV7k&m){l)?!8 zm#fT|#V=mX1WUiVV{m;svxw=;q;B+J0=BgxtB8jSoHH1E z8k?~UB8oZ*Y;TC`IyLrAx|4snHYY;HObWS=6D~{p%>~HrycP&taboqBawuHk=1c3y z26M6F&$16!1?F?JfW*j{>y>w-g(bMTeWwOj69l(v2|mhwyIsTkL?STZuC@w?K&8}e zemZ34m|4EyS~QYr3~FUVD$eGvzbV4#)9Ub!3?&)<`E>KEx{u%-kPzD0b(L|F^ z)n>rc#^ALVT@7M3rtbvgUQMnuMZot_73)N)G8hd8AB*5?Kv>gSb3&;9@@pgPsb>oS zP|D3zhM}1P!okuEP4y@(ymvg-FXLXGjCRPR!|iaM{!v+VwavHx*9+jLTTEST-O_cL(rV>AtZMEkf;UQIw&*_SO;j= zupuIWVyNFZ3ES|M=%E>DPmp~1a!ubd;HeAtP*=Y^lzzVU+ux6W`(6823<_6+qo2UK zfmb7+6uwJpE+Jm9rtee_xzlIyH|h0EcjUVaCiaXwt^7HtoDiI~F0?H0_y-^4>M2er-xSG5zArP2&9Lin^=gx8M7 ztdSHxqpsdxb5|zse)bFmg>J4TE4qPuWQFi!S!9+EcybGJa3hB8xf-1|jor3g1{DSt zTN(cwqU2TL05I)S-{q!(T+=-{k9c%x7l9a#sf0in}!7R|5 z`0L;Q{BNnD>=pahytLIO+{mpBifUc!P8Ps_`2~wEP!Qk(^?(Q#<+RVgX0{SzLFMRQ z|7w1?YxXmbD54~;zvj`5;V5-%8;subVZFnaV4*^tWxbX_>U}Dd)H3N@3CCq{_*@X~ z86*lR@S0n2#WrGy4?m7z?Nkh|+fz8KJFhAGP=sRBFx@MNSb)q*!|s zMjDaD&(e;f-ltm3n$ESad`4F~gB7QDo?x=hB$}L$MyBv7{FgSAQ>0+R-MGK->UK)w zkfZ(!ar}AhonluNyn z0mp%Qnc@&I{<0`(Jw~u_k^COHZTF44e4;mwp6D0LuGTZS3Q7o!h)x`&F9z*cFZ#UX z!I^7;3wXA{T)dOg`^bn=^W$;o=*q;Ys%GG+8Tmg-}(~PJ-*du609Y* zBzl8kAlG#Y*Y+oy$K~BoQD9=&Iax$HQr`(|RTJXtD?Rrt*Lple$2U~$78un3Rh@Y| zJKuHZt9xLd0QA^a;VJuelWFHk zThc6(8Nw7rXVC*Wz>pm?gz7P$SQ(|vV}tJiu2QOa^r>JJ-dos28!zZ4 z)c+hjy)0S@G%j-e_->Tqh>Gic530i!R1voiJ{ z4m<%A(_5=PK=rqYNDc(A78O<6uJvd_3(ICvzuG2m7*kOo$ZFp3^S{1?NRx!fA-F43 z!qz^sD@|?>XvvPBn3PGBSX?1aC-c<9f zWgKVvA!`${LFJf->Ne50F*ixaA0uNRIRWM zw&=5VGJpkjt3f8j0j+(kV@^L?hjkfm_KPl7mU}p-I2>fRn#BbPX%&(x8=sp?MJ>vA z_|NMh{Q=r`ZE}TH-4;NTaA*?%vHZt=-`ls>z{fM#VJ`|MJ60k~vE*`28A4tox9xvT z51_WwTd+$y^^|I%Y|(F8kwo~Sz?BDgv{)m%aP#hwc9f6EYcN5F65DV&)7!grWG=8yQBZ0#-zMJlYg9|Fl8T|A#m;gJH zoSd-C`W8?^_W5V0oI?8#f)kK|Ud4VcNcmpwX$#@pw8w{vQ>GbjUcu0|< zGagxfA9*=w(oc-+tf@?h%O zvuD13s{Qx#o;+>d3Qtwc!|KO>qTM9CX8b4J3fkW6( zijTOM%bjK%WDpoK4D=*I=Z-A4Vq)$Vy$)SET=#iHKU~^1`@Y0tc$x%pD`fJS36Z33 z43CxL#zvd9sbV3|t<{YQCfG-%9+4J0<~)?e?tn*kP*W0@lba-Kk9z*%s1uAixTP>K zT*57xa&OUi-F9$raB+S++lNOIO{P{I4Ah>qHYh4)`%W}ee16;$tMX2cTR zxL9g@#UWJZ7?E$nwQ3)oqcI;-qX4LhdUm-wahe(_!o+4j?>E@rq@^|dtJtm~DxJi+ zARNL_OgBa>q+-P#Ekkz7{H(e0{RvW0z->>616x5C=K2gZZrB$ID`>o^4;qR|w2q3u zb%n1x*%~1``(kmcj$DzvW|SEA^$#AxH7-uE45CSs_}7UgkrdlYX|E`>VnVMj7?sz1 z;c7jO`?-k<>Cu$H-Ti0(lsmSxu&yq5v+unjZm3^+=EEVg{$9-E;BzvZX9#G?*)Acu zSpEhWOp3SW&5GNe5db229*Y620)TWYZ>tZLB)3b53gx880FLsuqvD-Q1j!k+e`?XQ z{ptZ$h*F)3C(#g3sAO)A7?1aJ_Fy+IW}mZ7SCV{p>^DG+Mt<5Pss_1913Wx*{T0WB zPDs5|(?a)jk*|Vb?_uZnC#qKU2C7Q^A{|})XoeCBz`KY_u;Z{G!h3tOri|Ly?h?Gi zvEPfpj-mXR3fpm3Bj)t=%0PoPc6+ZDD5ue(bBlhq!Y)lCfYr3zRb675`I~82y=>0( zzK!Ie%n{V<$Fw~^x{^(byTxM{e31^c%r*Mb)v+zm`$2ff;!`}Zw)TWSp{0Y!!cBn>0dMBv z*2n%SV9FlQkI9%TJFH!(`&^_oyCOGLtR-B53|ji=NAThd8uc@p)Zp#|ffV+3r?v|v z!vl=B4b3ai?0%}1QnOVHAOP>^b-kdxg$AXf+TsiQgpl`@JK7*ddFhCjbOqYc?J$CA zCjWtO@&FadFSF7WdFg@Lo4KMzfx4ptR6!vjrR-}T+TeoZrbgC#7XarIRP^~WE;HWh!8gl`*gyA%U_#Y2QqrR>Yk5*)Q#U-cCG@re%nAZx921^Mxodda#9)MR3l4*nBWR)=P6lW8yO3mC2pI2xR6I^=s?q|)b8 z7YC>l47_>zO|);se|3T@l!Letl}|?eN8{R@ zG5*t6b-m$1WL26uh_* zJp@>)cpEYeDaRfD>!4B0!x(uXB9K1uhefz$%3UhosdUfP!2pnXaLT9^>9YOm(i>6M ze@qg4&M_VWT193>ET&gC1u2(=$RB?8evL$2w0068h*&3K#3QJSlB9ON5dWU;X0uK= zJv>BD{07A#Nr7<0d=<)LB$YXH^`mf#TZbFHqzFS5&7vtOfFhFHRWZX|v#9}Fo89lf zDKH7_3l_UiYF*=I1jE9@YL26rMKGdv-$Q~k&5)#Jn&of%06FjU9#>kRT*z40ZKu{% zp6tgqDZ{gcHhd}L?8J(6!1agGDOIDy%USzcgjXpaAM<$9Wz42Jxryryvzv;02DgxG z%?8cIv8I562hZ|wyB?H|;&isktISEtyA#bm118!k)}v%g%GY$ALC0bSJr)upZ;1~i zC=L$JzI|)TSV$Rl@o+RNN+uCuy&y+!0 zA87WMu@R|l5krO~iZ2J%HbqRgj$N`)^hyQyCt>fQq{MIkX+Q>=mKOL3&mtcbx*rTD zI45crKIC@~Bu+9dwSpD@yX*{fK3-b-DoaxL=CrOu>aDmh%-l3&gz%hj7;f4j+XVc8 z>8GH!PPM(^4{OptmN;<`FL{}VFd8JK;@z!m2Q`3+*kdb`EZ-bBfz=F(RIqYce6dzVww7oS|FYwQt0yp^>(45z+};^ z)3QFz=r0!+R~EBpq2!1e$5v?cV{V{X=U;ms_vX`l!s)0kl*nbY%sI{5W~yJ=A#$kn zqkh@d@D^MM-j0KLqfyLn5|x+E!du}X;MxaWx%YMw)**L*|8|InFo+A;m>%V#9`YIh zCq)%Pq=*+9uY&zzBTX#;0b0XY$>WNe*sgs4z}?xn`Lqm4tGn5rs_|a!E6YFBNYe); zK*tm*HtJ(J~ z^%U|E^raMrSV|rAE}-%*BdQ6yD>g1}tBIM8LmS}4gQ?13abF`nh4z!5Q&!tu{Oi0} z`WlhB%_a=zUl9%Sj1bs<1BGjxd=#VuruX(2Mdnfh!f0#dMMG=>Tszq;3fo+VW)FS0)llmSZIdbdMO(*N9 zl%Kgsoo#lwqc!Z3s_lNZhL-uU^upr2(_$OwS95V2(%KCwdgteD^DfWg{}wh^GrCj* z$a-AccKym>sE7Byc@U|aQY~wGIGQitqtDS1ZlbB6zmp9*XjqX^R#erh_O-p2U9fLx z-X~nmo}5~S5|3CRfY^qHFBxy08Sy$0bHT59s%m@UW2V(2Spbq?EZ-Y+q}=r*Q~r z=-~4vEHATXT)nEB9baF(kpx;C-99<-SGE4q_Te{F;5hAscfqng$_3pSa$ zuKU376VjvkrOE&P5fp9<@}L^5<7dg+wyQh#~u5s2sr@NR3n zCL!c5EoPN3MIySflr6;`%6r<~@)M7#Rx_9xI_Dd&(-`awqPmZe1vo~>h!2iR$jj_L zE~%kJb?%*vqM(50WLMSkf$Z^*zZ02^WEaV}iG-5;r#!nw>vN>2`L;MXYSU5|v~`}J zl>|Vxfy9h|68A#AA>4bs!F`{o^zE6 zTm&b2ii+b=hSR-^xxLa;+sz!1VwQgL{$_g7e!aPim2{;Rj-S}^FX|)79USq2MUcB> z$u7@{)-00<6}h0*Rc|dUQa9;{dS9^rQmlMU2E$`8UeoH6+$)TKlPu#j#^j73MW(j8 zuztQ_xc;hnU%vUcgIrfvO#h_B$C{3o)+9-IG%d;XY1cw0vZwJ7yi8S-LnHI(C_x+M zz#+lb(zuDg`3bUvw-rwsJ_JZYfEX%1~<<*o0zJZ)+cRXu-whq9;>-*VKdY=)+C@3`0u6$V zDS}q79<)?Yxy@A;<5@$cEgr9b{KyA)tS49&CvOIox+FQ7Siy`#PHj7-@JSi60}TtE zU3Z?7T18RykA=;li{j3NBlax*M&+$5?0VL_l*~VhrbXR=-J6IvqeD6Sys{zxPqrkh zoX5g{q9ll+baFyevA1YggC)Sz&t!34cm+|7Y7||knVoir*YQ}T92LA|l}k;{kZ7>d zZfM7NdyMOv!Wag+CYLeI2mC`$>zr@$B*$GpDhnI9EES*rVk!9Qs&^%nqW{A+7d0)8 zFwxIa!l^%s9gN8*a}0%gF$Cj$1l_*949(g#xP`ZDpLM6LW#OR|2UYftHfZ%5(oUox zo#7UUIA;3qUyICetQPvTQgX$jv&NDEMml)9l7-B(%ExKp*EKny97EXCcG6L$v;y8l_#=E)*@x*hF9G zn0a42B<`6>JFAXvH-+&FVGdqi*Qy3j#8yb~$Yq2Mw)|;V%(Qp6k1XedChiy0?%Z?Z zbF2;57$1%fpI;R*=ZCtg_uBeUp6lf+xiRrtuXzL> z&F-no({Y5{7DqR$+I3GqAQw{KWv03H%)z-xEqLNNATG6Mq@@WEA2TRoQ{KBaq|_R4 z>S_*Oc*kRrm6`qA#`YiEY-d zfJ0PKj@EUu_qXh6v*^SsCXL#<92A0;+?!2nJ{ddwCUeZ4jP6bg(SS(Iu0-toc-Amo z>|j~D>h@T4YWG5jqlf8Mkhl=`5MuL3m$gd*G;9`4;Zj0}XEVaPbF7muZ?r_2Mk$N( z$&;~}l$qA1OUSHO=y!ZV&9x}pn|@@-fb8kV9qZ~@_geIk@L z`eSRYG3%%8llg=Ecd6XQoj!Kq1U)uRQgDX&`}bkjex0zO`8NGb+6Rv2#}oWi(f92f zUVf0qb)UICvMz6yYSH5OwqOP*oA32RdLlLyuI>y3XFf_OdxPdF?v9R_NF{Qa1nlyv51zejjW5ky{e&U*dE$^0}nU$wcC&Q05YYcS$c>69STBBY!V(o<4BRPDD zNr)_mv%`F#^YwHuN(qrBRJbaQt{A8)a(zS-1P_S-(mHgzT1?YgpbKO0mAS^k)E0Zk z8yD6yGv@QCzCq6F!yI$7NeH!vhRm+$r?Iib#isSJGAIAl<^9tMxI(oOxmCG@|86CO z{NW7~B5u>@8CktrSw^x~pnzzqX<_4jJ@s|}5I5l-8moJ`S+d-HKwrxiTw~&aqIFh< zaW(&2pNHvbb6>q_QV^~*LUg(Bon)0A0`Z)Mh;@-mXJ_XIMRF=V1+K;To~qyVTi#aK z4|yX-_(Jl^NYRFhIM^o@CQNes-N#IDvA9IE3L;fX-`k7xfa0QNT-bxr%6_p{AZp-?EmXD9sLUXh& zQb(G+goIWc7M*UdN|ObcW$4CaTiG;K^>ckOo=d|u{I+H_c2n-7ZKa*=O);b#V=CV@D@@wENCn_>kT zG|P?L2m;-#=c1>@UCN?p;FSwmQCK2fBnl_ z%HDSkgS(UfE#2|zfIh@>uxgo9gL0V)uR>~^jm`ep(9r5BjJj1va%-VI#J_wgvfxf- zfQIItO?ng#XyaK%dxwTXs9NGVahDq@7CQ6m|%P_{TN-p+ZePIIc0iF2~ zor&qURac(8??!AsrnySU)>J-VXr{wjx$b0q+vcx(H0U#FOv@0s@OrEy{|LIAXHQbw zEXDttELgQQZET?_0&gjm;-K1f8w#b!iw1-2o>BFzHR}-VZ{1P9^#iM@EnyVr%~m$w zrv0Yry}p!^i~f+LTe7#XZTo$bhj?%1!2t+DvFgO+Z3C!LCZ8e=c#+Q%Og&TFAgNsi z=v4&oOwHQRCs*`{*!3oYM^TdyPB*Ujln5ee8auHmr=p^wr1X-P29ULa4K-hfSAx+X z8VQhlUoJy1mNYLCRd`u{f2fc)MRtt z^w?;XuH<>$?p7%0VWtzqiux^l2<>XV(@r)-a}dy=p8hp z@=c1T%trsS_$gCJ4WW}uRjb=CdqCb_> zVMVO$eJHm#i6#w073|3!T@tP}cEtIQCKIY@ z$yc=mU5s~w-tae1Ml1#54dq)4ez(3+c4=*pJ0=?xsr%+!P2xQ~UzY9vsYSM~S$8%BTfY$D z=Kj}InUEmc48BKA?-j9ue6<2fK9|gz*#_RpdH>oLNO7XspA#=kv!4pzgA!rF5N{4N zqfvOR<{A{=EfEosX|?0aW&6O@TL$R5VhP*~KsmZ=Kbq?vDBm;6PN@9;f4u;1r?Ct2-g zJD&@_l$)o^j+qDi-bHXGX9`wpMm~^7B5ar z(5w};I89n9&3Qs)@ZpPx6!rnK=Qu#iy)SipWrcI_#~ATh{qZ6v7Z(Q)7bh>&AWK#%IPU4~HrZ)!T6yZURsvNvHV@;m%pFZCX{Nl!&N-AAs2t!S z9>mTY{b^Jxv&y+)*6VOEjbUQ)#(Aj4;lAY!pIOX3siV_v`Rpd}FKm-z$ewxYY_D8!^-CS{`Y>tPYAzGW`7!{ z7lq9wjYjSKaLIdgxzD0l82Wep(bdeeJk`si$*1RolYDGE{+;gg>QZ0nJu7m91&F2tLlhx2@Y`=1-C`r}WWuiF1>`tMjT>Z@O4H|j}46w2K% z=yxC5(;Ml2!20*wn6CE$?0yKV!iWDC02V>%zI!*?3@rUBJ46IJ5b>l1$l}7&rU(hg zfy04Rd+E}pI@i}sNJ8ZxWe@^rK`>6iG$V^5cO z3TRkKhfE8kRgv9=*y*v@E*i*n1Ij99#v;(Nu+A(L_iH$Iw~lQ+l#S6wrP$U_kr-3| zvKF?A1F2+-Szoz+^UIyOFb@~J0(;=IqEv+}0%zWeP9e*5#w zH#~9O_GiET@`jsV+jz?#x8C}1&)@dv=fD0xwqE`}w_o+2zrXSS{?ph0^y9lDkD=b5!3&TjE;|tPTf+Uy1zd> zw4qZth^y=&F@L_9kS@&BiQ2)K?|H>=uun>SlSZEcpvVqf3Rw)L^ta;A7^^wfs{ zbPr9j)>A&#VsYfJD0Z&qmyKWI z2z5!$PJ)SI5K`f$gEn0Tww$L!y^O3BZDI&Bje+fW1~xJ zLt_I2)q#O(N8ea=bm-*wkDYtY`)d{Z?1bL#;o*^qq1sq&cw&6)_@$HYo|srVHa0RgUbEd-&6;Ay zSq`=rHY67l=s*-mUI&m}2cQ)pQEGCPC>^o&Vrgr@vmmgs7DwUM$6~EdTecXikHvU8 zV0|3s)X3g%;8VD4{9T`ZbPq}+Hr<~k> z?G>m0`bXEku=dVBJbU-QY`o{ijVoW-a_cLb@7}WR?%)3E_U}A+<7F3r;bW(LaB^a7 zXt3H}sSejBCMTvOdwhI!e4-{TQ=PWgZpLj#tXnQ7(19qBybhqb4nQkHqTt8D_B6fo zfLlQTe+tB4)1^LGL!b$rD+8%|CEgY>E4Lm!9#Wt zDJe3ia@jfmI=!X>+#J9m1K5yAvgIR^x?^WaoU;azNv%7|8dF0?a{G; z+VIqK9YfX8o}Nl)*P_};&&lr}TmF^LfB&8@u7CW3*PgrZkJ~Q(-~Y7@kKXh0>ib_? z{f*5}FMnbEEw5}^_4;#n{(jp7+txqui=W(b-(8n{>Jz7&aQx^%Z%==vIx;jdI(2Vk zcywZj0i=Fa?k3A!Ek0HRIuJ3C*8$!?bO2gcHVe|NC7MX80vQJf;4cW2muCujpEK$& z=Y9HXJ7S|$fZJ0v6`uNQsi(?gJuRk;43Hz)_C|*!8wE$TxnZ3i!=+!`9&u;bjC;hX z@X10?G+4Mrl1=@ZONDddCLACKJBY&MbwGj49Csd^g?FOuQntl7TH8#E!D8KP#uVGU ztbV&aWP}-?2oS41OrQg(vr5%fjLx}%W>g;1K)-fuo8ih}wKDxidbLvN85yg5>WueZ zd(-Dv|MZ$|Yi{25%!*$;eBtdkesslEAN{*~KmUuLUAE=7H@>|7)|WQi@!Z;5wynGE zg^hPT`_#&R`q9NJuKVIumwxJ+%RlUZ?1%ddRk!&&05p{v=>CTcR@^_Mr z05UQTz>@*WNj3^-?@IH|q@D=04{IZZoU+}q5r=|+o@k_qiX?krU_ieXu=;i2BG3WN zjT^_&(NX6{lh-XfbDZhy-Ico1#)}sHazHB>jg#*1(F`TR$k?U}%dI@OG5AH5jat41Ug_VX9_Sn=LVW}%S(-Xz3sqYSEaA3QmOR!4-VD(-~YkM>z1GU^IzZb{JJZC zzxA&5kALIFE51B7IKFVfyk#dY{_K~B*8KR~?N46*`wcg}vhMm=3wyjyQ?a9ktS$EmL zzqI^6UcdDZFRt9S<;M@*clDW{`oOy;C&or5YqgQ-2UG^=vgVzMV;RVS9^qdQ5a>V@ zPF@F?Xa}Gbp^LIJE>Br_Zhc>nY);~7@oD``kORbO92l0ml07uE<89}37U0PMIg(AJ zPNp2FB@_1eEP3J+2X)VzuAjCk5kz_Iy>-c=2%SU{#Y>1RVpj3Oc&cXWu;ctS?V&83 z0{HZr@-l^zS_-4HOqdf>Rl*E0qqy0rWmu-)B^#HsVwn!89KgW=+{ETImz~3l4gL;L zc|kz9%ZuFsSGH}+Q#`^WBO?g$Mtz<<1v3F5mj>6`P;=%4=Ic@z2{o_wTP={GWeX z@&EqoegDrNzx6+#f9T&f-2dXH+n;@A`F-C$`=YO%eBLGRyY%u8eCvTTU)*%V@3&m{ zyWigM&HFC>)W<*6(_QWFA7488?pn3z*0sN-X-w>B*tu{si^9r|CvJ8;HT#yCaTZ8_ zLWrlz!|njT{n&aiI%g@nU7X62@sgj>FDV!wI#XxyCyUeoyGo+tc5k8v%#KKGd3FI? zEQMiq&>1*wUK=xhUEB$>8F~C8U;mG zR$?&@B4kBs(WuGGhV2D`0(NAIV8UHq><-wPEl#t`GW8~&`47pKj!%C;eYjSu_V-tM zdb+y0I{F7{l}dkKrSrY-8M@-)kN@-sS3md69WQUZbIY1LwyeGN+10oH(@$62d;29f zUG>?!Z$A6S-}~b0TW;F&)K!l>{FQIscJ|Fze&lNxocPuACNBQM$OWGs`P%vKzWb)r zfAY<9*8cJV4zwX8XFs#M6H++s~wDh-1s0k6J)0V286%@rr1q{n#_V@ zmYwfax9J?V3>p5ezhrl8H0_5oNnte+qX2^dGY;A~eC|{val`FNg7Td7+X;_uWWmui6liQvhqo0b7H`xG529G?i>T>jH%r{|Sl9 zi`@ZRv&Al)c_m3=a=gs{`nDN5|sIz`GW83=CBVzI4tDg6V*Dl}o%-x$;-?#2JUtj;!)!R2-`O2oNUwroJNB{9}?^=1<$~{oUQYLxW3E5I#fB zCrwyFS_V3oF(w)}Cc;gqWph((N0M+Sf~g&T2U1U!ZS58#RpQYljMh^)l59NP`mwZ- zi(iFFUZJ&PYh%p<8?z~_Xjr?AwRxE@2khjs&2`qcGb`+3cav-@+^B;El2nwG4)8s8 z_6CIwjBqNfvZxY%a-Kze)eTP2^a=~H_SFS92pKP3veV$O#MBmGml|`Rp1P(b=l->R zN1K?KSh{p+bhe^k0fy1lR=lb8q!q@yG+Mzd(+oDYNyZ(CcgvJm_x5&ocXxJmb?Cn(y%UQ%dQUiE_?DYKx9-VXU)y}o3+q;Fdh)7GPhGri z^{U@JdiUC2T=U$T3;%iBm$yB2(IekJ?~G6MPY%zTf7E|H=J2;3GwYxu4}Qn2L*8-p z5r-Z-_rPP0e%tI>e|6}=2h2X~fPwDAKmOsdOD_EAqYt0@+V3v=!`54V_4ilax9UsZ zy61vN{_&!9YcG6h-5pz>zGc(X%U3^n(|z|}aQa6ldwO~*J>y!3x&t7cMNL>j$cnbK zT}uq3CRBriUi0;YZhnbMfrg#YM#@<*bpbrg8WsoGGUCxyPN~*eRCY8hIcpULDz_vS zYdoD~OTko?-3|nj)a^vGx**a+JF1G$GPNmX=Sa)_V>FVm} z>FMh2?OxJ1I9TgB>&&J9?OW$d{py)SI|;%i&a|J~~I)<1d4=4Wo)_{yku(uafo(`sT>Hd)KKR>VZOyluMa-|M<+D>U{B7gQ+VWlwR^Tduex9JLFXGS2K z&_?a_oO-`eVqL50yUY6e`ztzAcXlp8uPc?FzP{ehO4qyJQ@Q5KQ=WX}Z(rGR{qyUu z-nxFpYcKxYKX1SFl})R*ul@S-t5F1VD6j)j-GwMM0fZ3pC0|? z4?g{;tzZ4)mMdOZyL{7c?_T@JeQSSp-R7rOY*};T^BY#JUvtOu>p!<_*>I(Ai0_@} zxhD0C#lVu&NV?|ELD=#9IC07SDrozy=zF8kGL2GBrj$4j@Y zz2doNuKtH_U3A`A@9XYZc+f!y&71u<^N;$Qc}E|7?9uNydd}NtAMw^Bj+_$fqYgj( z=pzn2X4XN+9P!t4k33-BQ3o71_kbny4>;zC`6HEMS6qJ5wkNOnzVhO_uRrt1)Y=7^UDuC_uG~0es#-B8-DPUAKvkaPoC0QSu!v%(BI#$ zKV3aII5<2!JU%|I_crVczuUBKH0&Y64LCEaab|d(8?%50DUc`}9EkWyTj&~zD5TfGO!QscR1x{5%n07i$rk%+q#<(y3@}-|GEd3p7ps?fAIbD zUfi@|?ISBL{=#Vs7tVg$JKxf^c**If5B%_l=dStf@~bX6qi5mbS%(~S1*rWbt{@khm<{fk3u}8oCm^p9hSbRv= z!b3j%?#1`5{J@qq=e@Ayf+rrm;O~F%mEZj4!ZnXy@aOF}{{ES(wmf?6WB+i=xo3ZB z@#6m8-d>ev?~qih)o6ZMqHwrujE5{$fcV@%M!Y=0XoOxe5cW!F_k9hR;53hTZbw=66`m=J4O)TB_}g0mJL zJJE52k>ZgLn<&9M{=gMtEg*iqYH57cQBVQBdCmvF@}*DSzUnh;)?Bu6!;0nCoYmjC@X&+be)O>i&Yye4+@lVg zbHu?%9QKaG-}&~#4tbmYJLI7Mde|Xvopsn-kDT?k*+;zXsM&8j=BNXYIqJZ9$G&~u zQEz$Q(qkW3_0i3%FZtC^K6mLw$Dc6Xed37=&O3YP;rq{g=4W5o_Qdi>f3)(mXPnmE z(=WZQR4V#2Py7)ay-;bTSy{A;(5Zu(cG2=7!@8rI>H@F#Hlr{S=|JjfE$F5d*0fWI zJ9^D8ok;ewWy|zk+d9o4@pxMGv>mT2)*36`K2;W8UDO43w>>@By>A`R4L2zoWC*1; z`a^VXrs_@yMhe~~+3C48RcdRo-LRN-BO@!!N~Bdu+yuCz;uP7YsEhRml>HlnPO@!b zwOWm_(75a6LAQ769%Sf9I%kY#5y`gmL`fPDZo+7N%P1dPt)@S+v+K0ASSteQPqzc> zHi?=pBj=Ruc8C)TQQ0iA&_Qwmc6MafCmZ!PzV@kye(}q@pLzU&jcZqK-gx=rzxwjmF8x5qaYw%W z!2hyf@sYC*J&6Aff9E@99eU90S%(}w`>=V(9C^%~!{;1v@R5ffbmZX&PW?CQZAZ>} z+uXVDoO{$;-+#i~Z{7W=O;2C@@Hfx@&`HCG{2zxMaKKxtJqxbB_|!)p{>lr_-tn^^ zUh|35r#?`FWJ|SmhorBsPv82WTid+l;9kjCcv_QoIk7y_q1M1M;0`eC4p<(Gottes zH!TdMqet?wO{<%1sHIDnO0v0%WMg3?YcycSZnqv~s9;yBj0!}oBs=N$XY;1~ZfyD0 znUCzDDygTl*vZ{>FWaf4PMv5OH%zz-tPT{G zz|`OTnEGqqb^d85pl-|!)1w%shj)ar5No%Mu4?_Ub~W_4IcCo9Zt|ERH*-arb``St z6i8Keli2kNw&xvWcUm&?C7UAkB!I2K*2bo?O60}|D$TDx8Z$63^-M@#UvFRE)I--j z)BhyR!uF?=?18?)kDNO3y$3FOb>pquR$sSe&GMI@`@2o+A9#N4L$7YR>y_u0Z+_bjymGdcfMoR;Rnw?^3bE^96o3EVMon5{FtMUn0M@)jwOp0E|@!i z-q8!@PyIJ{?yRGZI&{vQcg~wPue;-jPk*fIAHI9m_Ki0^`m?LAzVz(VPWjNXW$!)r zoR8mq+qtWMbIohpzVYn`FFxhuiNS#}G+NrNYI}Qo_2;nlWfX2jF`g_Ez1Z8Pusv)} zn16N|6vQTaHyDLmCki&RIb~yAv73k@M0<);Fw4>|V67i@nT}JKcDGd$_5uaKMiiV* zKCA+u8yxc7E~dW%Z1xO)+Y5_r8M{fg)l+U1pxU}YVe?rcVKE@P9Ih?1#SF3S)$s7J z-nvvS`J}n5g%4BM&r?hvx~rJ>r=OGe)5KmPb~lW53fD% z><=wEZo%w1$Id(UsD%sWE?zW$$>Ifz7tKFz;js(mA2Wa6(Z?;EzhM5ci;i2++tX3$ z?da@SxM*XURt{vhlC4D+jkUEisampjR#;fp-(ot8(anu( zDi_X-Qe>w9w`a(!K#ncZR@6K49BOdOy_Zb^B(kMqgwS49@0b+rI{oTXtqu$f^!4@i z_V#x35Xkf+ech!byVBQH?eD(i{7*mq=$$WbzHP%(S3dpNRjVIa@%+;dZd-Hjw$-b) zue*KY6Sv*F>iiGAZ*s}P z8%=w^f;!#NM@4FWDHsN3-}Ok#!y4`BRpDe5t<=MY$bnq=+ttgEQXA_Nf2A%W*)F@9 zsbph!zzXJWr)(&AXOm;HD3D!5&;f34ScxY+M(*awLZ9K61Fvb+Tzcd>U@?WyE? zAyF313e0ZWI5=olSPe`P{#v-anA>^9NEE>3B@63AV+9-O@YJQq&YGh<72^omz;^pt zymb1XwzoZN=SsE;vsALE{_Lxal1^K?_ooL*b*z?H>vN2H)S6>yPw>y3vO6msJv}|A zpLXgu@4M=E>u%k$;ihMPbK{yvZhQ9eRqG$W<>ifc|F1uO`#=Bk{g*b~bMLAzeCVX9 zcQ<=_x)v>3xM>L2Lo>0Q!W>6rdD*Cky&^M{7J-*eLFmp*^OcOUw~ z3maDa>()D7fA;QI*FEsk@9x~P@wyi_-1_>~`=4Kb_jBtWdhp)MPC0qJe{i6qw`!lu z<|c{mig0Oga8S=Gu&$VW#xq(!OoXOV)2jFJxMYE2rfGdF#=!wA*;?~*u**O-BM#OL zHn;3q-fR==z!OT=sFff6q$;;T?5?qU7EB7si|s{SA6sz7*L%U^fDyW#-{j{`wMb-S zhr$6gPId~F-QF?!H%F3gDmX2F{;tJ3$bWyfE6`Pq*>a^sebH?MvC<|lrB z$K$`e>iZ9#{orjM{BQT2`oz!AczxSV+t%Oyoo{^QV;}qINhiH$XlPJLbqk?j zr{C(XALeuqOSXPXV{>UGQw)G}H_M)dE#Qt&7~OhigNWH}3Jsb<>`x>f)#9mb$G}cx z{BbBK*^&{3w@k9Rm0^JjNVLKbmzLax4WZb z@uEcwIbS=lsB3X$aGH-*@i4X4^9lZC}4?^{*~?;NGu|4foBSJ->fo`28Okx#!ML zzx=yvURry>Pkwmgowt7eqA#6r+J{C?ShjS0_{5RgdxnRO9~i6j*D9l9)l*Iy|LiB; zbNywf{rKDGZ(e=YlvrHL) zbY-e62qPdj7Q8kHyG&8^kbB>hM+Y5X4!jCfNtj(C1oEjTW{3sHV$x!DONy1ZGwGOpyp*e2G)x=h zoI&sexE;unwXqi4F`tgeoT z($TTlDK*Wm?*87&U`Jm*@PzT&C13j3KRtZo)^)dUT66sacm3_sk;`75tGZS(5u zUtM?YKR@@q=byQK^&?;V>G!{K|LtG8>FP7D`09r)z4*PCTz>jxSAO!w8$N&k-CzCL z4{vz-*DE(aedD%guYKU&bI~T$HbLvt(+Na0}n_2>`6wqpR=!mtCkB?i4w=V$N z@)BqyoAOFXHn%KzFHsffrz~0O$o1_#!-QOLF^r=O}n)QHc>&beFb$54XN5|sDi;wH*SgbGML!%w2 z_ATx08tCipI`R0ibI$t6<$wG6uU_=o3(x)3sV9GYeB}K-9mn@{PQS%B@c)zdCeBqH z`JV60yqJidH}B59z1{9MW|PiR>#6PR`;m|kAa;zgaT~k=#$X$~gBP%kjoECBG2X!# zYy&nnV0MtuzKb1i?e2Ty&6}8rd4I%jq7 zWmZ`Atk}VjVj5A~bWBwmm$jZ+I%D6?XL`=O@x{lFuXuFUtoqXIspB7iWbujp;q z*nj%9z9XypPd;<0^_d_0+!r~1*SG%r^RN8${fnnhKHqry<>pgsJDOg<)VJ-&3)^~H zR~^~^z_W+ zqEsMexhj)LBxtyU1%|@|`+_gP>2$^{A?nVe>6wO+>ucG3Mxa#Gg2f6& zn0E;E!fRoQ0kuVJv0Q9Ake`*#2)H-HY1tS>+0YT$calk=4$C{07{M2&+QPNAXvDr~ z{0dfzdUPg}%4A#%4S&L~IPYum4uhwXbID{ zLgBHY;Mk}gGt8(I*5t5e>5-@&uF9xSJv#fq=dblOz0`H;_2c{B_^r%#ukp#AhNoMOu538;Oh@DMm(RcY!-d!Wa%J=PXW!^+UfbWc?sD(u zuBO$8_AQ=1Yl5z;p|QcJ9$a$YxFdU?Jlpi**)uPEuMWwo*1r@zyZRPT^w;Ba{c&l92@>pbZT73EZIjVB?f*He241aE3Xu z-=Rbzyu>&}Hu@Cv8crDI>ua}2pZYR0WzCc$TdZV;kpguxT0R-U7l1sBhFpMFvB=Oh z1!}ow+Z#f*cn#8}ZtE+p$ZK2$XbM^jn;;jx4*Oaf%#R%j5J}qwQ#}26JI=Zw&}&oT^qYkukAdw_Cn{@OWoT#&aB(F zd*g;R55BhguC425AN%s5AA2^oe)aN>S00&j+mx8Cj~;c4Dl0K3icL{Gx5b+xwoZ*3 z)W+LEu?-p8s;{B))`$T#TEx7;t9<}fG|BlFJj_fH=E_vP;VDWLD zt@>t>jqJoe%W9AAl?A7eNg6C0Jr=TujPf)C{K~ctd6>Q^9^-gd zT}8G}xyDu@wrv`QuBtN4*5Pmvq%H?^`58&BtQ}`;-E{Az&UKgCpX)sJXixKVJuNT& z<@@z}K7C~F+(Kn&E_&@%K|NI~S!!IORf9utmhd+P3 zuj%!^rp=wFU+-()+TZead&3)l?%RI0al?1Lo4!A{=1SkHj+3j`J$>)&!gvi^zj}M2 zsH%#+)v(HONM>up99((>uM*Cfp|w+gVk_kh^09_r|BaB1e9?&z7F$Spm~#3$vZ!+U z;;@IJvw$;<;|us|22C`R$q*O506QQncF0aD%77fjenB{h(T1#W(isK=aU4Po5T{qQ zY@R9)l=GUa6RB$>PWiPw!#zMm<299TaPvlx%_jxw7oZ+11vMhd%)2Gl3&)AFfSVGl z6%z&A43j;9Pe8mYzFQ@J74Ic4JMI{l`0=xp!W@ zsfR36oie5B!>tRCe7UNt>CNuu&8?@_x1U??_IZ|xqifvq}qvbUhVK6~d|#3XVzGk%*;) zmCCSE8Lh#RQlk}c?}0%?LPUz`L@lSjW2gJu5NEy zcl6-8Pd<8n`-dyO*t@#%#2f9+Tf5q}b~J5lYgpUUw7#!pV{h|@bB)g&`Sgk1Z?ArG z>4K_KRMABXu}-XUmHJi9}+(1iXijdpnn%+ z<3SKpk$?jmoMPwYCG6~C!{e_*2G}*&!NFo!li|z2M;4lx!BEI>ePk0v)b`L9 zD2%UM%!@@JMS&D7vWEwAI-Mp+uOgenFQkOM7@Gvrc8o%Dvpwv4$5w(A;9G(PGE@P) zfdaS8b{xyL&1lqyitRH{uuDTkv9eHjT$@P5z#u$pdtcpsnR!20ai$rGMr{lj$T}X6 zrqfB7)x=8(U)C~zg>{JyMGW94ymD9E9MT6bkdD!aY>Yr~=|>#Ej`1msZ>S(TeSx3N z7wPkpm$OYHN1pcud>g8X>pwt%yg%vu2i7tho2}HcDu=^CRh6;W-CMpmG$S=V95H09 zKDQmcdR+eQd3P*-Z0Vl2o;do+^WDeReb@2&pZhoe+Bi3Iq=(jk4OiFZWc+H^XNWe}q0m=RyHu13T?y)Co*?{$M$R4gX z;pu^`?!f|38`VJxc{ye{5eE_|-uq|=dN$x5Xq(;jKtrlu*OP#_cvsH%*e|71BVV(yx7 zL^dtWvUP7IdPviyXw1y!l2xhjv^wj7d4;DRo4od=JGQ>D;NuUL@7eY2t{p4h-TLUd zSMFQ+>Rnw(mh&}K=nrkHSzA!$1(gu(6 zm^dT8(MF^;+b2Q8o{whFE{~Y}#BJqO!vz@M7ht>fu~i(}#h;-0@eHzKTf)>O`Yg3| z#9>bnF`dih(9RKnQy{B_ik(m9@~JWAt^e-ehfNZ$vV@%-17~+^cdNRS!0Yn@$h-o&3!SUSnyoM4@Rhnl+gED?a;n}=k z;_z}DST-s6HY7bF4>S@;OJu_#1mJ+1N<1D-xt?tUS~;r>rQl6sI>;Jd%RiBhucCQV zMdYy+4%yVilfG6cb{;XoA;Y9Cnk8y9q#!@aG&*Z!V4HC^2 zNM)lXTPVZz0}udvcC%|R5tNr5jbLHT2qvLU{+}lisQjkG!srnwRF) zYG-8_zPZN$NyTy^tEA4*A4Go0TC&zNnuS>P0Nho6}`HyLcgX3M#P*L_BJw6AVwsj znPvnprIR8NDG~{3TBR(H4hBb6hQ@~EfUJjtN;oXzPnK0xRSm=N42kY8?RW_T($u^+ zyZcDZuc8cpOIVg=UDsjB6xBNPT(%0nl~in6xL>|@jtE0yT0A*qcR+&tiFxrtsA7~8 zQi)#?lUgbp9{Dq5WIW}=h=EKo5e3>3*=XKb@1RJ&0A)sRWd)+yi>;k~ALYe`tWwA+ zrY1%ZRXw7^d!wnlBvD*$BIY=NY@!Mh5car{_!ZKl9%&92*-iXWP|n7RHfTT=b`n^$ z!Ew?&9*>eZ$WD;wsiaH(|48eB{CgO*wIfk3p1^ zXHajEh$cc4ybgzhe=lT*!lT2|7+G-*5uvcVS~Bd;?75Z@!_fH}U(8{8^c)(D@Lf?n z?-Wf_aCs!6$x2XBB-MRGV?FrdCl*P; zFNK&E14B!5^Jih^#tS5|t6D0R%H?vn`$MXJgb{9;?`hI^quBs_0bh3zzp_d25|KNM z2{FWe!T8udiKEVtr9fnk0num_dtsmQi% z(cB?>-g}Z1^6^?!w6E2m-Mu)j|EHTlHB#yQ1$8s58Iq!hBsBm(XsGSvwKsSSjYG{l z;DZ6L4At{JjG0Qz)MAF==!T{0hOFx0uo|iih69okR&_-;6fGiahNKyiZpxuh2nsKj zDMq}vr{jGEBB>c3S{mJbK^iE`2)Kk_eF0?TEvj_i{|h4t24iZbZ0!V`*f`Nuc^}Ig zBqNIf#`gu-ZhcJ`=f%i4<7-#Q0<8;?DKkqUc2fSD&1Os90iSEkD!~JU@nIPUwZ*cC zVdf$Vj5#Ov1?Yu{DJ~%t)nDq4)N!E{lKZSE^jzBO5e@j|&ZZc>u4>t0P8f2@Yag=t zf+$gFU)h)f@)ivvDQ}T9b!r64PO>c51ZX({iv{EO(8#7gI4ml>oc9I+-VF^RTju8cvaD&EYhkh6x3*)ci~CjurBate5k>W!xlKEwTM^mR1Ey^lRs?^p-=3kV zy6Z9s&SEDJ%kyMZRaKI1dioK_CbfSS@dUc&y$qB4wQ|Izib^dC{htv;KKfdt$TDBJ zyhq>+k;kOijfaddWWQsxACi*nfb7fhcs!raS9?b$lL2`|0Vpj}#$ZOl!~hd#e+288 z7n4GOgoUn62L!~Yf{SS6CsRY#=vF+5lra$`s*(f9_Dw&c#;Gm=*(fJ&t*@)|kpcP9 z&yll{+|vVQ>y$@r=-NXfo3~snj90}2rf|X7!hb8P24JVJM0c3WX{wD`5kHS`Bo9o_{YVKShtqniG;EK}ioO zx}@ohp1TDNRpDdzQE7}$e@;ejGLs(Luj(Sq%qy#{6tkv8SmifN`&sY0PpEEZF#6yQU8 zvWfZzEp{SArL)ZW0qs0U7h8SL~|`m(zpG;kdiS;1r^ZV}YvfSKl8kQ@%ULydafN z`x9>lWMi{KeB2mXa#=>+<{{(bDnNcu~4Ba0ygIhj%PUvZlk*IvEqsa{Jj?Kl83=|3lSVAE{CX>OC zmM>3k|(NTmzOWHBC(+qSLidN>>oct=TBFK~x#4aX+8v^i?&%x#K zSqcgUO%#?2^h%_|&OWH^#eLJBcrGD-VH8CQB94hBoFt2pEKZ7&v#_aDN*wBNp%@c2 zc@^0-UNa9EMrc-Nwfd;Xui~10)Cd-dIph#gL24$eYz`Z!g zp~m3#h)<9gu8r46HsXWe>8gZZzs7W6@O9NkO|*6eS!E zheDxnI4ljmNLLx^P;dJ9{}-}FX#Oo>5x6%MMyA@}fot_a^&G!OA`vGVccSrVED?(* zy4T8=t5nuw61uRz2GmCB(h-A)8MLNCAe3 zd_GV4#XH0%!duJ4heI|L=bX1!pZDU6fjzP@WJ1Lj6>agn2yT=sJ9w}Z*<3P{9oVkK ztHyLR8n-M*y7rJg$2XX>m7$KCCbqZqMo_Lv@P8jI8%+G$KW_@t*a`~o7>jr=gzDfM z*@#6`y2?C zM-$_eXT-$CXzUd1jQCaTbodFE<5y-4lwpV>8Q8&j24!IiqHN$B;XnqGu+VG4SsGpd z`alK0#77y?Xu^+onI8nzw;m;zykCW184F*2D9 zSF-SOF#=cIvaL{t>mxgxb(e|5{~gaRBCLNl?3r285D(Qw9S1uNq*AVLe=?ag3`3Hn zpm&5kelhW1GmlGI{4_|^A`7R&hM^auXfuzdjv>C2kHrC{QP zl!3XE*CL<+Vj59d7BP+}06g$SHhRyR?g#Z<0uX0#xrk=uLZp!XpVNQ5F2^3k-*BoX_QQ;?fo51vvUX^Z7h%6da-;?QqDZp#x7U z^phD5)6mDorT?gHj2tMGIJ9K4`FJ9Qhig@f1cKo}D5z*^Sg?dp^@Fah{(TM~srmJP zFJuolB=GgVn&&aXDz_~If2N@u5zVp9R5G5=xtornN1%^T14G{-9mKxlgQkz^B*S3) z95{im1OhS@BmXS2Nj(vB%mq!9y#p!ZB+9~{#HU^gPdanlLJwtyFn!bszKT}?lEZ1) z6ke=nPE;Zn3c~=oPxi7JjMlbtw_Xc4Z5XQadav0HG%z+C9<|jvBwgV&u z69nXk)dH!Z;EaqMIR+rU*idjr)LA&F!11|QES5^8LZN^);^K54s~W=wM-j^4i7~Xt zNGg?pIa~A?;cy5pV^BoJia&AsQGDN%*so%-*jP0&N{VXn;>1~hoV#Gj2Dg%{uqht>*d6U?pTwiQq3F>p>+FQVls` zYgUZN^J#xHzorKdGyp(=-G?agX`^f{?EC0eyin{ij7((X40|`OV#g8tEae{*)BO(< z2jh!B(HM;m&XmjbIY`d)L>USqT8TxQ1`|Xy7JmJ)GntGiB7Q}3P^CGDaR6aeLTD^DVMrVj z*(fcaI1q=8fGv#PLcGT!rpucYFGTx5g`io84`QsAoOfUsCfG*sDay>-kC|Ki#P)|Q zhSRd)A0q0`*=#zW&l1h3Oy58Vb4o6k$>+0$LatcMvp%7fM59rxjtM)}vEuZ5mahD0 z?~zko7e3f?VD6%a<#?7J!Rp{q&Jppw@QMOZTkUnJNDs)@1P5QJ* zK!7Tp*jdo=*)K>Ru~mz|0v+NR@{U4^$`IN=QlqMr9z4*^eXbzzZibNP&S>7)gjU1| zf2G(yc0(k}!}t_cEC^2`8cNEO%!2U5u3k(NLZXaAAX{9_Elvp{D%?|mZ)Ay2CMssn zpKuaoz-^$3oN`0&g90x4jSxvb+qbBdi#j8*jtlXUs%X>(WW{=C8};2+8kEr{L_>Kz z9`_VaTR}kJ!Wj4t&@<>-~dcV3}>eOmk5SD@gHcCj9^$v0G z2vjfHP&VrVw@}FC^KLFo-=p?`O&sZPY)d7JnRLM=bv~8L#j=@1A(Jg;3b|Y?p0MJ{ zL^4;>6UC8ga+F?Fv(x6>y=48HADn9H=;}M$-rjz;r@Qg!v6ok@R0_ok)6yeOXmrSy zBgtrNRORT9bJO#X+VBVHu6PH+nzz8xcLoUz2hHJ6Q=PUHIry#mt(~T*QbL^QCdcQal>VWOA-AU@QjL1#Sw+*SCvG56MW&0ChXkkX=vg zecV)KNn;s-j$(Or}sMh*k%5Nl}$V8M(A4lgWUqgf&%3_IG5B%7kW#WRuC{ zfR;@%mT~i%9q&+7LV3sxm^4RA++?irBnT{vyR61HLCdXA5s*0sTu9(gj;^~YTO9dm& zh+w4B$V|Fp!4qrV`tr-eXPP@&+B%wATROTr&$`F?_Lj~yTi#M*iJ+_{;+cr%?rCRO zk&qe&s&4#K8~#8digzGPWHWtUO_KTojNl9Sq7CV1xYe3!;Z%s*O?@h%I0(By#r=XQOhH*@e`PUhDyzhsv_A$l!ISn zAHJe7FO9*q-q4cF<1rT@z(a;-!!&$ zwY6U8?`dsmY;HT#bFO#KfrD>v|MYlEUr+D(m)5QuS3f0aL=@YO*j6AAaNNzOZ|)!y z%L7PA@eYK6Y-S){LiYIrVjMB-i^i{F9A6mPFj~3zk)2A%?5Ghj3efNmQ8IJ^du8`3waraqv5Jp6q7X#wnxRtg{fHT;#fOcM39%v__ zvW)3In34+x_oW!(>?N!&-qr{1gevVGnM?}iW6_8qhS}#)1au5O1RxjjCxAYiO%vAn ze0DfwyXj<->1-;S&*Tc(R6ZR~r|e|hjK>33)!0ZOlCGO`?~?Uzz5n%zQ%zl6Ej>N0 zjVJrNT3XH=Z9H@Ac;m^3o?MZceEaiTcAf3)zjX1t^;_SHKFske zIqM5BLU{l&Jz@{oTeLxAuIkxvafyE2qdeK`Uq$hJ7m}^m;{gvf70VQokbE;zKx|+_!t*CA%Tz4<}?@}Qk8AW{yh(s?IpSID#iCqMUY#LW_ z2@y{Plkpi~f{+J>X>?K|6)eMDz=av_z_o}5QBf9%f$oEuC$VUR9#8U_01p;eUh=Yk=feS#LJH8basRO0B8FDp0~p9SM6)TNX6fC5K>~R7 zUh_8K_CwX1V;&T3=7q5e^!Kza_pOyw)zj%@E|)15^CG6jFqAcKtQk;~QI@oKh{y)G zA!iw{hh2bPsxGFpDJKz+rPAp_DN(4>;>oe9K3dDw&b)8MD{p?X@9@#a=BAF0j^57R z{;rD`&RxEAuD7?fq4DV6ufLcv|GrUHVew1b+Dp$Pn-oA4ETDz(ci0H{g)>dt8 zn1d+v1%`?4o<__ekJ1rYOkZHg$n=@xkicj#J!6HT_>R+(cT|-f(92*ZcCAK( zJ8EWL461Cy@+k+V4k=iWl-r9)J9kuMU0k)uB}z-k3OZ&S+Vk zd;h|&3zwHZ^-M5Qkj$KBrYb6f6%}I)ON*tWnNp5OC1kyZHeg~V1b_v07JMacFg{VM zW3*H%C3>Wgq_7+gNo`C5AqC{_n?+>Sq%+YB%^Eq9m`DW0gn3#-HcHJRlVijn_i3W0 zPs0%<;V=f9HHqx2AD$NjjPvuzh6x*v9MF8hLDoA8!+Xa1WvOU6@zESYa5&|@C4-G4 zMi7gb7JVLQum%?S1R$!|)OKmZ9c21IYa=uPaq-@ut~u-@KotX6p@1$oZ${1ti2EL1T+= z9unGm);o|I!r6SLR5h+xT^CK3D%IF%*$GFp(bD)Ok3YZl!_OMq`_Etbq5s0=?%tm6 z?#{06w*5!W95`~KqpP#Kx1+he?YXrZjMCIe_dI$0@R9EB?v9@BhW7SN?`+H0){PCx zs%DXKzJNN+p$&iF3Lmn?=*$9k27VO-Vtg?y#u39lSVJ`isbPi&H$iY3ruh|%6>#1( zO@f;i66_a<=VkN}$8liw7K!|`;gF)MhOI=bkQ#B4nK|?C+3?oeUmZWOeeeF;?!NDq zN@-+Jax(e(4=mcV|LY~omycAOkP%nSXiaThb}qDP|9h`T6qV2KSoEPz5DvA^RC zRWWi0{hfRed5yV2XiH2V9Ka`FC+20_?$-8b=Tx`xpiEsD9hN{Bk&W2}aY&%e0S^;M znOLLi3ph^tAumYIj8HVN6{UuRC_A)lME2DoQOQb!%t#6+eKVqB%mKqlIkKVNidB!> zL+LpVi(?=PDQ18$L>J|Nl%lsEm+Eophd{0Yq5AoQl?4T9#AZ!dyP<(ajl) zt%+tL6$J#WsU1UQz(Q?tpFGG`EatsE?=o1i3CVLgcN;yi9dJBggiI!dC!2ISc_X&$ z%(Vw*QFuqV(;jquJPp8g1U4MlSVeH>yd$1SWeekSrFt`78;lg3!qht!KE7i8*2dQ)AYsOefK}P;r4}3uGzG8&zJkVdb$svYMy=Xqe^D-d)wc?{OzUo z_V(`1o=X?Md+F8J62)pglNIqNhKC`xyAR)R$MuoT#6dTH^#z7Y+!u{s5uaudAehsM zFmdR@W=y0xx6H;=Bv=o99D6xnSMI^rj}16Vb7P;MWwbwn9n(xlj#$N-y60bc_0Y-F zJHPni(G@GlDu$gZq)Ou|C3SRVAeM;Vzu~$djM( z7(wb{)e{q<9!iZ8H`@njOpI^{qOr_-P;y_ChxhE^%{A2VMeUpObuqfswsfEEc?F zJD@gHa(6$~QjKQBZyg;8sQLO?4?Vwb$KDg&O&9<5Y;Q|b!_hDIe)8$g?S~J1-E_KP z-<~hlzqYY<{tJK5YvNT?=HI_?=dMrBUify^+O4tTjHlN;+tS&3uBWfFv9+(gx23In z}9lzczvT-4RD^mFCI}iqWjg(m~d}Y4WyYUJIDwRYz$c|6w z;4I6H1Z2&!W9fSqEdFHQ{==uwytLu<+G#T+JE}VI3PqQ6Ga$*)cuY~GsAFhqI5%mM zmW<1`@yTbO?)h@R6VJ$cTrsm4LVzJCSa<>u87e+T)6jvA4@B}UDk3+iZl}Ei?`cGB zkWGXa1pwo~R#+)9sfbT>TlQA;XkZ-=)391#XJCkp9qahG!*U^OsK&Uq9NCbQbDN^W z43SNZUbMR4R}O?&B3@o%l>9gl9w{`b-^k3@l=-Yqjt10)))hEuFvS8JuJ04&B z@S~@Wethc0>5o4CeEhUON~uX|@wQ3xpIG|hHoY)&=InW=PB))Ff3dmYbZ2XmYwzyw z+4|nwxm?cmJW~|Qa(zfNO-m+|;qXm6|0(VZ7~MrQiXutgtH=~Z(%d)Ux-aX6B|-5H z&3m~FSt*iKQQY`L9-6mekUBDK&6=h`7Y3k3yNBYf$j2+YOw-gnQ@gI~rW%e~nxTbN zC1g3K;n(GHPf0axoqbbLTMk1!FM`T$FNP)4ICg+kd!;BfG?Y{5E z^xjeyQ8nGrbUS8e!XYgbR4hAc$75k#4n#s)JW?2!+w$(#uKsg7KKtsnyB28Ce5GcM zRo#4Hd+}cC=57U(OeUvIoA%k>clUj{_hGSm5u-fnn#A<_^Iy7(iD;?$EK|w!ndbGC+&RSIEEw!7f%5rkYVq2#KE{A!-$Gs)UI@ z8jX_C)P@Hu*|S&;?&LLqY$S~VkTvBA;ZE++uY=}e+MNkaFpf|rYY;&+yokuAYdy<` z(E_P47swEcIT$u*K_<(9Y;v3gX9_q2t^tdnGmXD=0^vAB_YWWv5pa@`!A+WLsO;ks z7*F7-4R>h{q#5Dx2<}?XARbCbwH+r>^PH}v(ZiQTJ|E9!T-#qhSIXx~>2%f|W-{@* zaiw%BmP|RtnnIzbI+Dl+BI$rxl#+Eb?q2f7J3AX&yT3Yg)XA1_q1u#6h%oS5|(9!!(ox3>J1+ro!!@^d#h(8 zSq=l@nx;Wfh4Y;1xsHHSv}hwoQgujV`%Y4^C9KJ7{sfw<-u96Se@7?cft{ItpUKD4OgT+gRpeeuv^PsXz2#su_`YN@6Z)^!Xg znx;W>R}{sz?P9U`?DLOpeskSB@4waB-Ffc2A2z=8(UUK3xbKmbbLPy6Mx&LLm8zP~)>BwP44w5{Vc(5n3$R&6rR&p^pG+BI6Jyxd>t!U6B#BZ!rR~PSvz6NNLl|Z>@#TMC$#gMU>0~LTSA0)fTdZr1o`-}`IICOaqOFW6T3+0*< zjFc^#bywrCIikhj#(>u%vQa>c0mzQeF21Qn3<;1ko^)b~Xfo}-UE3WF)3J0an$Jfw zg@}{V6Pa|XSf@EPqe2-yIi-H~(%0U6_u%oy?|%B%uD-LcZF*zweG8s?@s)#(ZH;Z` zk2f_heDuMIGiInx-pEXPf6q53diyV*?>~9s*mpmCf8olvjV-OaKKpd;+&i+F#Au_i z?1c?I7k|3+-H#0o4Xv%s-QAr%eceZo9-TdVc4cKHRzgdX`?hkZoHvYXM3i;iMRp{j z>F&$D6nus13bO+lO{yZ`!|{+`sa7L1S6?EPnzrLOiX=;+a3b!$U<{YT6absJ<2aR4K+@%C+$ogu zSllu#RnxW^JOPCCamjr+)1QO z+tM`m;YRlM=Nf!3n)@PP!!RlXqhkp>o6jtLY}u*Swrx8;`QWpCpB_B6Y15`zvu2_A zQA$X0GC=YH4#y3=!==i~9hvIk+4-KDqkP4IsJz*vmkxdT`z5#&456sHUnkqBK z31FRcMlSJq6h)?)f;u%P7-`AzgmFhuJSZW6K7hfGGD9V2QZT}x-ss9rBMd+fA(Q!Z zG!?Vrc03tNrDLgdG?Q@(g;=sG5zA*}D?2KXu8^z8)!+Bjs?8sMcA%@PtM6=o-`W0S zr%r#oXYbDaUw^o7|I1t6S+REOH>aBq96EUDo3CD4^XeGMF{@`h`TEBV?H%X8|M81& zjo;kT_;k~1yhd! zApnQ$y&IRx?~Me);h>^Ox~>|A9*Jm%p+k)YvY}{Gx%MGj{5mABVO=4Sp)zBtaJcvY zALk)eRSktgW5>8@+F z_sU>Jku1xI#VyO$WhEGvDh)$VCgYkNiA2q?t|oH1XIHN|)zqiIY0|`W7#LOfv0pQ>MGo-^z@z{Zwe0o5I zz}n7|A`X7SpaNoCgKRO&!J-Z<{UEjgVv$^c7nIXnE>kGv#2Go+4r zMQ&1&A4I&nH3yYkAF^?kh(AV#0GvO>NQ0B*$fn_in5I6?f}=uw$c91<;8M#5)5Rq% z;vhU|;~Ut44_Whb@G94|jT&HTG|pfw9MHjwg;+XnC!9n!o-3r&*+eX1J25j^RWIAs zBZJvUZ0fuRR=%@i-y;n>(%sW{`0(K;o_J!ygh{Z3@TnZ;1sJt&gw%{9%VAX=P_%Vj)jf^d!}nDn z`_$p9KM0}W5G+mua`Sh~vM7M>LTJ|2)zx)%ba^ytx*m6g$Gbn?uZv+tZ+J-$v+ zbw!e+re*1oh@?;iP16+bkUizsiACM@<+>&*vaD-{V@Hz-cR^Fs-QXpi&7`xLSR!sY zwqcou6$zVq$k6Uyu;9?i)6Ly|&#r#eNfbwnR+LyuiKS%A329m|?DATZ!iM6Sp^zO4 zLc>v5QsRkJFeHtiRNva!wPgA7TPrFQ(+qlV?8M*)&|}diu}B>Y6hlKTN4EIXPO5;I zzKJUg0H6&OM-h=km>9@=%SyRC-KX}Fk5uzP6#|#U6t!s)=*-IpZVowIJcSexANh*p zMZIxUK)JXSlR4r-PKweJf@HDslcHXOY*aLjJ04jEyz7W;OeYe)v=IZ805tVes*S#A zpth$rCV58zGE^>DDGmlmA7Y4>4W>*9MWZlrOjVT8kT}m{7$C$Ejp!6-Uy&vTCtePK zieHf+2@8&MS_9MHg+c*S92`p!O)MsRh0kKcQAb3!r+UOwnRvcBSF9<;vuVYSRx0Li z$HXi2>M64y+OTE!iKecuzTWoUGaWrA`Z`-XTAI%^x4!$)&J{1M-M)AK&VBoDpMT%) z6syw8zq;|m_O1&TE?qp)a^{|gpSndZ{w|VFOrASo?!t}l@9Mbls`{?`+e>v0I{=y5Zr%#`$X_4Rk{#M#;p}Ok24!zh%z@PmJwR&&?iaQAjg4?zY zn}e?FG-~@&BQ9w<@kQVqCagDbD!}Mcj%=hR%W^ChD;A5HOh)$Jnl^Lh%vGyaeYoS@ zk9U9c;+j=cr%keLQ*tok(rI9RanNUY3@E#j^k8RRKUpr zJrsH+w8h~JBSbd$)&Nz(CYp4~EFzCEC9TMDF%Im096!iPoZ(l16=oSc&Jyl`FW0Q2 zXkvma0;tX0`G}BCr?cLHF3hqZ0v4cf%s?CpMo)a4!MFvp2`*2* zYVQ7j@bboR1*yd8RtU_Yi#3UH5w0oOcruqt<_qaUDId>f6(?C?Bm-tK>{Q?N!1A5@ zzCQo$RO%~Ve(g{H`v0_bb>H>y@)2q# zTA2IF>pL5}y3YT2@rwh8pL%-ToJCJP_uAH@ja~g0zi;dA-}2thx%Vx-XX!Iv968o| z>B^S}zMen-?qFr$mRoMM>_jG09gRj+RSg6Js;b(yyBJbYlvpfQ4$bSIF}(>r!_YNN zQB_&f6vNPM+vJ-5LQe9x;%V8@bpkD78fj7uy*a* zZQHgTJ@)yR`#;*aarL4H@0mJnQaqXPUMyhCvJ8s{7Sv#GId3cdINtIjX?msXF7(&q zF(Z|93WaE)+DKIeBFWLRqs0poX3e>0>CyuYtsm_>uizhAM6uJ;Jmt!?ab+wCs2?kqZS?Nsf_uP@Fl>21tQWH;Zgin?Oh6)LyClQd=iy5%A4J0(YW; zg{BPJTYzlFgydxI;4W`D3?9q{@i9=b#!zX1I8s6r1ZGx1ji>@=NmZ)PNCzS^Up()4ZX~X!pr}6r zOq@bQI<&D+od>4*6~e%l4XZkYq#+ms0C)-r;##Ip?`f0>3F2WQm&;UFm-6{6hXhgc z#YjW{LR{$W4COAg!Jdu9V$pNfb{9;-paic$R97yS!E#Ctexx=>6k4LjjjO7y9al=G zN|{U{pH8IWp@=y`GRK%jEj#o14X+d(?d_eP9yxOFvX_53x+;>Nv*xXLziBw!-`{_^?}xVDD{Y-; zTU$EXn_ABG^ffoN9r)&CTkn-4CyuXKyGD=5p^DMDRMOB*O}7JKGaL@X>4LUYS(foS z_TlI`%z4)sqG<~LEXznFVqVj7*FeKWOKS5g!97fxS5I^I4{dN|ya;Qk@PHj00VPSo z*J82w#1l{K+O_M=H{YB$Z{C}4JoD6(^Y58I<$(w8SoF~Slcv>2Y)3U6_hsjf6OFp_ zkd|cu2QCfeh!Js2D`v%#<0jNUxNP|w@4f%&*I#e{a{sOaN4I{wZ}F2akDGS)l)3kB zcz1jIrOPjDe0$vVJN^(*#>f#XmDTN7(AAtxLyu^>r0HSPl1;}|pcUO#BMC|lX;Jf% zBw2A&w>8&^&~OD%6|=HJi8=0Tqjg<}gu1T7s10u%ip?c9p04G3;-Y_vPJXaQL$#zk z1PlV@h7ni~pt|vydpIQ*5ny~^E~0%EifzU_u&x5=z$F}kz)&jb5C$498H$mH z`Y%*WAPdq$RVVZrAFT@$+E``7O$u2#@p#-cO$-1SVDJ+hO9=XFcJia12x~P~xB%r4 z9kqZ$CX;d8A;5ajv&Y>9kaUI#B^tFY%b-)5&(@Lk4i*wOFO^EsR>jAS!6%x57m{%l zL3Z(Y9M1=67Tylm*;1(l$;Al`n0qvo_Rf{8}m%s;k{M)nL@g=d-SJcPX38r_!0Y>-&*$-StxG zSTYrj<%)@{YqpN3%v9Pgr^6gLd?LU6Hv8B1a?aa>IJN0x?N|p88M54N8>zZYmG0Sq7Zo?S^smZeY`kQ1jSt^yrdB<(Dr$r1ok#r;_ zD63LflVYjl*lrJ$v?y>cBILC#+mD>AB^zRzLl~+gmo( zPo49-TaA!vC=n}~%tT`e_l22(0F-Vi640XoGhH!n@f}|rKX~v=t}I23+(ws>5U-)n1(Oed5=0ZJKAq_~`7!G{}HHPAwj!12jPu zW+4VRFwpXVCw{ChCOTO<-yp&BBqUIVuYf0=LqwlH3I+lAl;9JCBZ?S*z%W9uJD>-{ zrsG(wGLBtDHneOYo0G*fn9!3NG^bWe*bOSPF0*M_M~#SQSiggn&g85rBCep`rx1c{HM;|{yP^f zlhU=%t$VYny|cZorK7X^qtEs~{mSM|AAEMKsk6JMudlbeskPnF~fIlaDqVpUbKP)sM1cJ;VII-5{+<(5$+HPa}KuX*PAr?QvYB5Z! z3s2$mjj7F4J{j@E>9U~%;1GS+m1L6K~&HT zVPr9YY`R{E)(_8zdZ6;@(LrRx!`bF%L=pg6|j};01^}$>+1x)unQK3uulFq>{;av6xS#64AJoOviFn z`E0RdMKdAAxn)dxbf}oCxpUQP@9aO?aHhSr|9pE(+tEYEkM^8Dd-414+xq$r96!14 z&8>Id`#_<#{{Q@auuwZ?-TF-@nmX3MzgI6#pFDR__xbPJn;ZN3`Z{{gwe?@_yYf@_ z*^7;hji-+vX>2-k_WZg2b7yyb_UVE}3**T|AQY?&2B6=;sz5};Qo*k`5{Sp6k%;Cv z)*W}=w)xGCpMLi7Gb@(o@^QmdqA??vPfnOPZpO^Xvu>L@b=t%U6USALD@>eJTRXn0 zwyq{$%uSgwefg75yt{q-%WGC0IQZp}Bj4=){Ikt(zEwMM@~{7Sgl5Dw+f3!M5!;eg zC7v8u-DBIfC>vl+WP^9$HNr4t2ZKQ(a_Q2g@4x^4bI(1es+HMvWYGh&S3I@o&0F!x zo1L8(9$NP52)WkIO@Hjk=f3~$&nupP|Chh7|NUq=Q7Fz^FmKVrOLQ~kI0Z#D70vbG z`?pZ8$$BX4$OTVPaB3zQf$RZT2>;NL2}<^BU%(fE2{2hP9RgHTC;5#s+i{a_P9BmZFrgqaMqda3k*N5KBLRSm2#8GjVUU2cBUO7O!W8&*0NLV-L{i&x z!5+9NMD}1cU9$rp?ao~N2!d0owG@%`DwV?I&ILvZn2n$Q3CXY3Xd^{PSz+9st7-c$fkx47jJ0j z-1SM2)_qW5J!4d(?Hh`Ap^)>2hb+rp^!5qy4E?E6F`G`gM#XqC;UqJPm8g)N5tR`; zH+A;i%eL+Ks^{WQJr}PuG&i+$oN4boeeuu#vT@tH%T_+OO!$Y>rbdGRjT;0XFA)QPhIj_NDu*@Ch>+!l zoL|j&2QZ2yEfBz`4x^;F9L5<)!h(oOHxj3)(4*m6n#;K_2IAgQNS1S+sOqa)wolO> zRG;IBM>_)s1R7Gn9k9=JEsEOQ*2BkED#aijm_=#mj>F*#bqc*3z|Fdc`*s*=*+|M$ zW8J%tX+1z0)+n?IT6Ks&(NF`M1NL|VvN_UVfN|HM#a#0pT$;EB$J?Dul)8&UjxJ`ZZ=^LfkGv)Oc2bxkap8(AU!_STRd zE7Z@PzwYg~jy9dS_~VbKn_CZjbG*0r(uE6uI@8p%dgJEmDKoT0CTzySW^DO0FEn-b zcl2K9y7E7E?m6_-)6bP^ru=g#{?Agj?zRWs{_wMNJsn+b%}r+-PIyOqTg!$1o-613 z-g)oc+wYhY42NV@Nv2blV~1r)c2{2yZ1(|m4EV;hl}JE_%VCW(VX5NPwJ%=2(%;_E z`24CTCQYuY8kd+bDL-{u-He%&X3U&4c}ng0y5jh{;^Zl{GiTM0A74`}<^zF>TStxj z)vtfMXvxy2RzClazxmyy@pVxIdkUBo^$7I%b!{{f8qQu z4<31V`4gE!$@9=~*WF{OPFNaKH!<7Pap1tQ&*$DhZ{{EGeqi}SJHFc4+jsWu9XpXr5F-CdiuY}oS7=7UF$*Vf%0v8t3v!i+~P%fdtgc#4|; zTNv%T77rP|PnxzxM#H*IRIvjBXJoW5Kvv>BFaPV1O&rrqA)XP#RG%> zBAaL?f<X2j?*?Y~qA3q!NvBeoY&P%h)>mCBRmamQGa8drb8IjYkeqzY)Tdu~ZQsEY&3%pMzU%3~ z)P1Vqcy~{K-`OAE+V=T^hgLuE$g(dEpV;-~!D)BQ9~m^lR(kQ{&!1{Pcf6(V?1gW? zy?kZ=fg_JTyLRDIue|r^*X>>XogHnB4X2u$oBR9wFJ8RZ+uOT$&u1%FJe^3nuc}gY z&5k;jV@rx0mLJujquix-;{p6Zbb#m(T+UYav zrcIwTslIl6T~+<$@iS*lnK5&6-Gu5~KIu5tm@#91@rz&l;=laY|MY+S=gHG&u77=V z{q&iYmBA4sMkbT#La{29&OW(f<)Nd;KHmN5%sXzc2nB<(l+EYd*VXNLgs){+!F(ZswGyd4o*?07K+k{E;|LZ?0LAA90t&czcs4Gh}2v@LslO(2}SWo&qqG$tO8!%qfo2|zZ5 z_wo0y`^q_3n1f&hLv~muPCSVO7uiIZ_;^j&F#?gzq{MUvZL=;;!C!zC0+6cYFEw-@ ze_{8a$M}4Q2-q zP@79y07`1XqQebtmAf@kKF&Csx&RLr$N(Wxa3UMdb9B2FrxxK2!qx2<&^9<-NvQw!{DwRp6v%q&Ek#chRF>>VANP+K_)|Q4JfBgQ?u~T<1S~h*&;%|V`sJb&d>*M+_-Klb*zGnS_t&a}0)_4M?7^UXJ# zHf_4&&btD^u%yU#)G;g*R*_gDo=7DX&D}Pn90Ua4jRzztR8vzub=stSA)POzX5BXV z&bc$|C)bQ0UsGE4&A{sc2nbtajhMi%y>GIC=WQy$e=XPnfrD`xm=DZdUD@ z{M6gu`gl)A=btuj*sJLE|LqU4ii(O6BmQv5+&QPubSzxF@}FRMwPVs2BMQoe=|1k^ zS1J`sr9xFz(cQbp-41)8)UZ|~8p;R*3+jZnY`BqBSC_=$0X0l9sB4S1?0l}2%NDbl zVkTWkC38_H8PRQ7(tleS8YLSwljpp;@xwDM7cN}-m+qc(jc1yh8aghYyV8E9`NMbL z{(R3TJNNC{_~Cnv7tekF)1RJO{bJR`$!j)kJ=S_|{-ZDa(^yBzPFt~RRd-iwcgyk4 zwuaW;zJsTmTDrPUojlTe{&IVFZ%=Rk-hE%*IropDuC5z~mqW0qsfsv@h3 zX}c>?fC)@F!j{S zJqMzK%XI$3Iut12AQxnoWjPXwBoYb3FtEH^QY#EoNhRY;AA0!ZmtL)@os=k4{cdb! zP>GBUN?|qPZmDWm*aa{Y3Q5u!MIGtH$3F7d{U^_yI?>#+d;gw>?uOpJ3m@&>@#(4E z$GVPu_tUpeJig)&Vu-Uh8YAeC7{EDIERUoP-dZVb0a4hyP-?cU;>uWxzK0*fcFK-NL`pZ?BHab zyC6jjLpO&DV9`5pGceGl)9Ji78=3dEEWkdKaH_`u;A-REmUwuE;xL=@4)1=rZ=(n0 zMGJd2n}#g~KcSd~LJlWmF(;i)V(kpvy-U?qu)0)L74x}NE}Jam)46o4Dwm2{S|OjV zt*fzO$$%OQsF_AAdY~=G3v%$A9?K_h(v~+b(t;ZR&aOu}wx| z$|FxbbE^4BXGim2zWd9^U!0a=`Q^_)|LuSO>B3Lne{-_wp=GNBQt7eBpV{}tR~IgR z+tuBB;?(goEe)OBZB1xT_fi5TuWOxfKAR&!UR=(eW1o99I$kytD?sea1DNmETHDXI2o zcf)W=l0uH-dOucHjJI+&NcOSLdK^2?+@y z5IG}qP9_Hv3>cHaWH4ZIHaUZYa?Uv+FgT6J6L)rYX7&wls}H{JmF@R-wmv>lU0q#W zRo#8=`OiJ~{#uoR*>hm?*Wb2WxO6e0-w1|Jrn5yXA)N;g=~+TvL?a{>u@U=F_{2ln z|JPP%H{#kfI2O8rdmH|NYg6}aU+|@MBB8)&fG?`&0duq`K|diQKn*X%FBI@I@y)dPPALN}i+c!T zB@Xf$vH{8fXfRomiRU;5Wits2T;DgFa)z8tTE~OYH?&Jo+_rM*)t>$l7fttA%$sgratn z#jIgiu|g9NuGI2od-UiL931@ayYIGZ*G?*x`uPXH*SU+`XD~Lcs%vXb zoH{>u?vhA}`h&%*4j(-^VsvVJzvRA21MJc6-TU_M-Me?{)Twg0JTfxU?RM*Qx{#0% zo6YvGUXem6(P$M6qXXI0>sg(a(`tlP)S;oFN~PLjwWm&)viIPTMN3!dc?&SqYPFKS z9~l|xa=ENlYmXj1BBLZGn>}1AmFlz>x5qy+%3!ibh!v3%Wq6caqvw~dSabW{<15#0 z_l(p%t3+?l3E4~LL zuI(!d6I7AVOmNm_1rSUaM`=vjjdlQ*{UT)3K2V~8q!31MCZw789)w;+E9hScG$65? zo~0E!H(#*EvxotdKBd?I#R4bu^S?MCwj)m9$Rzmulzyby1Hgy@JrJOgRK!d!r0v2W zjKUej+Y2`p? z*N+Q9Ha-=Kx&U{lcL5*AcL*?z)+VR=M=BoGI( zd?|_lJ51c8j`RZ|g!@8{pQ$|f#vU2s^`*+GKif`Y# zwrtVDNR_l#s6@rZoxJ?Gvgz5wCy&a?i=I4soH8agRHn7KlRSNg*gQ##SFFBz`*w9h z&6BJrrR60>C57pk8O5a~l~pyzPn;S(W}IHHS11%{H$izenM_7M=6`kN7a<$40@4jk zkxIoqdv@>ArL#__NlfgUk}{xQzXZKr8xau^6cp5@OP6--+I8;SIV>!!M~@yNk?760 z-qADM!o?pPJ$^VRKkNC+){3g~^vsM=V<-Cug^!ys^~{A!v*&;C;ku7*-MhbZ<%;gA}^GBi1XaI93Sh2Bs~okSw>c2eT4Hpk~DPk(XaX8)8y zsZ*yqoz9Su5SdKoa5#YS9LM$S*)udOg5~&W(`W8Kd}PeTi2-3@Qk_<+(?-eUYCWSj z@G6}?LL$|1hDFPkXXh83xp7Zru!&V1V{ilpMoJWFrCuMQ{BNHN!8F}o-#bho3lzpf zdPy5(|23rk`F50FQk9LbEC3h+RuaawS)pP&AUk0hkj@tbab(&~>=?gO8amIKlA&k#z7jZ-?!4jQ|HQKTvyu5u)e5JNq^u^d;#AgMow;Oesf^1Hg@I ze9f|g>PunBzi!y04v8+giXEz0!nNMtss133I*UG-VVec zVglY8ae~5tuNdOHj$4552eD(PQ|P4t)TUc(_b$F!N_+;ubb@R=gq(s`w83jAJYJbz z@FN0(A#mI6R&qch{J@_BN6qWwIBlNT7XHCWy&Ozun=uzJ(B%%aM? zl7?OTPxl!(k#`SB88u<+u1_yrxtyN%C@(AX`lU7KF?(s>~Olfb?+Sz80w0SG25b5T29ZI zcYM0<*vZog0|w}LUZ&9~RC1%4=XjPk8B7*qcx0GTt(ZJ@Qb9$TKo9AS02gh72LUm# zf|xrc&!9o$Rla}&r1s^}gi+KN1-cLpMSK3#77ED1^BlwISXNJVh#!-Cue)YLj|QXy z%>g>3RzoKNo4tJk8)@%-qk_JYKyN7Dk=D6`Q7M{L#r?&OwgRH{IvlfR*m;ocE9X)qF zr?e)oxU{0OIxX$Vjcd1?>sqq%3T7`@7@^cDILF5Ahl{IPN-8Q#%L>wSvTi>}OV27R zDrv5*dC}1Lw6HiMJMUIqV^vv2@qO8;bLY-t zv3T6LaVuA@3=NBVw^NrfW5+i%HvjY0|M|Cn|Ksoe_?x=MioEXkudH68rT} z89a#NS*cv&a=8F)EGu-^gP;0;aXEUu@N%Ra>0SxueSDp_=$Z<*i2ZcvSr82dFw>n+1eG`)9YQBA^Zs8Kufy2jl?%A)_GcuK0!{|Al z4Gs;G$|bCU5lf?#YGLM@NO8od@uQ#Q6kNZZkvw>6q}(jk@H#Um*GCX^(zUd?;lGB+ z*dNal#ipaR0qCDUB(SEZ@LEKA;4dlKAc+LizAL_v2a4SWD?x03L~JWPOGFq42Q)(w z2G{|ViDgrA66Z$4YhWV6jNNYc-Jjm;*Uq2b8m(90xW@r~-yQn6!{HF5&L5XHF#wxs zkU=Q#YomP4vN4u7nRu4fL&6560)PmS$qnMGJNu$G(uTf6ejL-6S(E4iJ(pOj?+Wb$ z0!|E_iYkHoq(wl2__;7b`9owNUEam%bh_Q{XtIM?t$=T&9NliW$K!#{h))YC2!K1{ zs>8c@skZ>xzIY9(1k-v!d`D=3^iMT41ldNTfo1hp3-56Y)3jS`RxP0qwOya;WsrG{v8?p+k3rp+rODeA2zPIPV;mOnHjvhVb(4jLm zwN1Ij#REr-@C%n2Z2cFl*pgFNT2z{oTUeA|Tv}LEo|Rqv;C|YjJ9pC4?w6KkXXa#H zx^i*B!ufiZ@ed4;D^%zO3Ktr{+Lyi&BK)f>Z4d;IO&e9-eo|f*FU%9BRLXnx>f!I- zJ3KtJM~`k15n(fC%osj=cxY&-NF=gat$X+G-MxGFfB^%#bnPw@z0I(uTelzlpMSpk z=c`xEPn&k`-lo%XQi)Q?3JM)dv}Uu><#P1x8y6iNt<`E_hQoEiWc{yR4$Bx-DveSp zRK$3jt0-hLi9#un$O00RTr*~+E?79XU;iY#D|Y?IJJYjDZO%R-(K~(n4H`6b49nYx z3?FAOIp6Kvvt!r573;R{+Iw{5xXB7NBao|gMHxe}6 zCWiYXSpB#E0iC~yiM|w-fSX{n4P+BVH5!G<*q~ne?gJe6Wpc#paZIo@=+~q~;~eOW zNoyuq!x#Fo5mE-_Q9+q)Hd}ObbWBVP#U9^t`?2K3h%>=cI5N!*WVKp;{~5@_xV+2GeG_5pVLx<`JF*N7$1*|ARUb(Gck zzJzY6)naf*+j*W->lqEphbdH+*u<3^x8>(nG}J#Uuc$qJ{^ID=iQ#h9&~Z~rYoAqC z)Ly*w#qrNiEnBt5?v4)%Q-(?S{)48TK6B;S%NMuP?~b1_%Rh`Y+6SG#a`R!v&5W$v z^o*>>k00jbKB=lKX{fKREG@f#>%q!Zt35G&Lc<~yDy5L*)Tw0(sZKELy`Iqu4W4L- z?F$G0(mJ6t@oV*u)i+QWWHOmVBI(klb5vABpFS~CsW>pu-`~G?P*A|imCK(#eVUz} ztxzaLBGIBni{{Ut->Fllu3fwK_V)`23=R#I&Y80`BeV2LM$zgu8)R~INJ!X_A;U~2 z!TQ;+Uq1ozOsqs25gs1SFha94qyZs!{x39omN9D7j7B3&?ygp=rBbm*tFYNkDMRhs zcda~i=0JMp!;;eSlp$j~bq-$f;f@=()7-KBd-{d5ymRP?2~q_sdgI+;BPZ@Ta(3~` zO`e3o?zp7E!$$K)b8xUQFGN^agxPG>YV}g7++wjY3?~*#Ef$+jqt$3Mj+mI^=Py0Z zFCIQ|dW4*1jUGTS0dAX*2HOdysqG)(tS{oX+4<)%?Yjk#jkpC*5#9wSpz}Ho0es-v zgnDgOXyD&w`_I#QAfEpZ$Oi5cKP71bM+T2ZA&f6r6G{@8`gZ!pYk`|MK4>^DisJ;g zC?@}cB1fvGZcr~tYA+%84_Ng(StRm^DT&sOZ6VkH>>S4e|ykh5C_tzwT8+cLrgJyxXALxR#h0H#8q; zCK$Uoopz5Wn$aqFgI*?+ghob%$rKSv-I!@}o|M$I)<4U6l2c#XaPjgbwVn~Hb)W1$ zcsHZ)_VpWu`2|9K-SE+K7cO7@@g9qNNN|*6)QCy@j~r;2ZEU?GDqIM>gd(G-_e8bCtIyMy*z|tUh@_;_NxoKG{BR=bmMm zIX6B#zJKYm6`Qvn7&&ToM3i~Xf))23uvHpuq@jKk?A2! zZ@#_=!c)>o2y+RPfy=%Oos`C9DM5_>q9)j_5R%C=X=%gBLb$89)NG{HDpIeJJIa41+G-W5s~JW|(F;P`v#1;tej#nrXz zwrq+}$|4l1gu&ihW40Y1*1qA>xX`qB?v;xG3PVKv!!64LqXf>=(Ym`Z~a+%KK zj+;Gu?y5D5IHOMVhN%5J9Yt@vrDt_wS@?|E6BaF=larfPR$jPz&5Fp#@HgLlvsW*_ zfPkQ=NExH&wOYMgt_%wcQz#TJmjho6l}ZsF9%?f2I-MpYBnVE>#Kc6H@zFD$`QbkClp$?BdLMGvDHmOo!G#Z3? zeZ4agwuc%a#R(n+?{)5Q$u-m71NbLM=49(rUQy@Nlv)0zk!L zvE6Q0s3XF{!Z^mR*BF%wiJ4cM3>vLcn0?|G7Yl1O=!}e-XJkPsaE|159Cd|NMFk<{A#6&ujWNUymW^W*<1rXzW0MIyXn9va( zDCbE50Q(yZLgSYj)KLA=A^@MYPwGtHg@Kz|L{fDeEpu#Cp+zP1nu4tUCU z9k32NAc-W{0iaA9DFA?$f;E$;4I7a^g!~N%CMg_#KA7ad%3&)MDp0)XJ`^01v`zMB zL3M}Ub(I;J4{~#}%Svk>KFBXBE^T@G zEImDa)~s2WCdO>EXjED`W46a6C>c`^|6qnUFZf{5_3JlVTU(DGKc1MF7#0==ho3^B zKxG~9nxxPFA!Pr2xA5>#i9}-Lt&HB-qq~3q{sYdQJ-cVm?k(Ftx_tHgh*85uZ@eWE zy=}EQ(laxvYAWyCz1q-N{q;A`3kq}Y-Mh1H-8!XG9UdNO;LH-SA}~;}xNsbYS=d8D zf&v2kz#gPhad>#B&1M-qIK}017>&mM{re{-CK`=Kl}Z&I9gS;=ii$88*a;IR95`@j z`LYjVJbg84R;3gsmV_5L{uCX;A1y4aY$^XAPv_W8cM56+yuwEf_o z#Zyz`95%_If$otbQ^rq7-M#PN#jCd&gGD0OELgPs^3_{=4}4~K#dhuCKQ?vBzJurX zA3B+o+;8c!>E};xUB5bY{fd#R7NiUx-e04YN6E$3XlJBct~YQjtJi6TCf#zm99}w! zMB;Y4w{G2(WCNeTmE{n97%)f}&!bY72h^!TCGQva?aHL_VM4S;qlTN2|xm;$ma5RNN zhLkdx3VvUhIvwzY>E(O{1YazsBa_7fR%?PYROt9tprG#s%Hn(n#2{g$7b9|GPAJTo zfJlH?P7*VX1F%9&880CpFzF<|ES_-LcYJ^_;4Apx(!i;G_arTwdi!Az^BS^YW1y*k z2+;_3Nn!?n1dRoDlblUC6F@&mI#3vZg>|4L02kmz1RS~n$|#_0cs$XVs|A*Da3$a} z;2y9@ML!wFUa9ivyOG%~qTCRa-p=27EjT)KAW zNlxC}MT-K%!<9OA_JW0v((`i*%ByOdD(jlA-nutq{xY*OQD=%heBpFPQGQNQL0a0A z{G7s^%%ZG}(uVr4@87?_Y}qoG%gwPS17}t#^)jiz!kjT9JH8*;%U_W?dEV)Bmn*6& zTVFI+))c>d`SR$|qsht1a=BcsR-4Ucj^i+w3gI;%3~)@ey3GplYhQ}3)oNLmb-CP1 zh1SShw{PEh?)<48J2&0DeSXL8k5ea&+OzLdPfYy#U3w~&?AmpkpTGF_n{Qv#)mMH0 z+iw~h>woy+`#=Br&+FE$V;Ih8G?6zE-O>K0e-N6G)$4uXnjz$;nA8R;;*k<;tm3XR@<%Pn|q# z7N<2#BGK`@ST4*CtP>iCsCizHL9|+}N~H=43UW9cTeog4 zt81J(XQ5Qdu|}7kvr42&A@(x@#G_lG#bOBy3-j~ygAjE1#Nm67GgMlKTxrsA27{4d z4U9@DNb|qAC^b?&r#4wRtHWrr7&u-i9?~&dM$fa1(ZHE`gT=s^Io8DJdA-h{XVhAq zQmv6|bxKxX=8S>Yvz*qKH3Lu0W-|m6LOrT~!E}g#V|o^ZgOC)wm~<5YvD4{99ujFM zr_)LBN1_V+V<=cBft&PeU#3s#M9_TjGjia;*ymfhLoy2vf`^DPbQ-=y9w|x$Eeb`n zCxD33p$3EDHDr?&ge)153kYP1DgxY*Ln9^*%!LgZLIlxjfIa{kx(bLhK$c)qKvq=% z03ZNKL_t)SvXL-f!~5Y|G6R(ZbemLfLU0rf8VoF%MhLrUG(f=v#2C>Hi-QHefV>J4W7<%d`L)G z-@b`AZ{9w9_@LWkoj7^efy0~o^mT-U2c%9Mzj@2H!GlM)Z{NMsyZ$@2ANlux|F>7K z{?Fh4{vY3c_uXIq@|W}H&#TpHZ*vdEY_@vm9AHL{9Dd}p1NjBnx9?n^J!iUFBWGAm zQvbdqM-3f3WPm5eIcoH9 zTJ08-N#$}XM-8*=+&aCv{^rr6`__H*;nI~WtkKb|$=cIDAUZl)E!4*=tX8X9t(Hh6 z2sxplp;D=I&Bv>sfAh`9TlR#8>l7-h(GqR2@Zr)xnM@{?N}+MZ#Ka63Fd#ZQx<`*5 zBPWl0kdc=#V0@&+pkaC5YSglf?AIZiw;DC9R-%+jWMYL%snrW*pI&`{XIX<@&tfhi ztyXC5$1ohrX*q+AHws1> zEYK=(G#WG$bEg%sU264=-#FQ{!L^C|L)2zj7LfqTJ_5P#iGfz*1ZYt1dkF-@IDb3^ zxF@bn(Fo7tC3K!YRX;-gAnTs57((SLRQ-WE5kg@AF|ZFvO@-Q22xBxF=yL*w!UOIL zXXuaz6s8zJL>M0}2^}QP&~#sj0d%(LH;uso{(?#)ALx4=oDUG3(!PY(Al)zpQoCx0 zcd^^;9*>7YI`t*+O5Q@7LvqMKsDToq)v8tA-V_RjOr=t2wQ9Xyu$=+^gn^_|qSYxF zR;|-3WlB!R+F0H>ebxurdBtT_wd*#191|ZGsWiy-)=-&VZ}fbyeEr4i51-_f6<0Mq z$FJoMz7-ytix#Z=vbRf$<19j@9x6~ zxrN2~MV0l9-yAr6DS69^r-y@KASOPp}(I*9K{zE zmHh5^e|YukRYgU`+_`fV3Po6082VgCMn=gysriHS)_NXX94-nDC& zOeV}&Hf`FJojbQDBqZo`IQBucD^cE>TCUapi$WWv0Utbu_^T%%K)ZP9!79^ATp zo7-cTNc|05$Oj9C&YzbuX7sQ{i|23NzHR5;1Mav)i9&6$*fc6N)imk#dXved*X!kS zx$xyN$d|8P(e(7Iox48|3DZgxEMqdsb;4Z9F)=YZolYzkPn|mT(W6HX9z0mTe*M<{ zyKX(q7?nD|cYs{O@~nvy%Vmtg@{1H(nB4n)ij25IBzzb0?4OoDW%NKtkc_Wzw zWq?2pxCxAIGXjR-fY*|F!)CLAxs%-Nn;s-B0>5;CBl*gKzhK`i%Tfo6Hg80^O?qpb zvoBuzuG8^}iIeP(@dQzOY$q1~Qz;GQ6=4EFY=oTyJ|P)9(Ry9wWc_}*7ph`&>wfMxY+wNmNr5G0dHWHJd*TiB?Osg!b! zTB*}2^*WVKtI%rX8nsNR(ilxPrIJ-BxS2B-rKRQ8)-|VRWbZk8eD9GHhfiF%dG|?a zRYO^2U3ymb{l||=OR7o=E1os9<~({lXG&^Jv~K*wKC9NHdZLvod4NVKaXH*Noh3L_ z**|5}(Ua%13m%kK>BPojZ3PK73eGQc_h_b@l4ixpU_l zjmDs$pf(UpWpZth`WGJ(UZcsf*=%(>+^bfuJ#*&Vq{-uLcEg-`6DLj{pO_RsbM~}N zn>XCPd*|?x&u7kD)U9i%%jr3O?Bw=syR24wP*8|eD)q7tp(t4_jvO~`Ohsi$Lu1W{ ztC#gp?wgP(wAJpP+;{YtVFOe8d14&>lH&R&_wAqDcktlB@$vC)w>vB>tatC;B9SO5 zDe2g;V|Kd}zap7T(yw1awA-%HDweNUeD&(pl$4aHs3^DF-M@c-)JzH!h%iR8$^P-i z&1cV^A3AjSs8OSa4I9$8Z`}0h^Y`pIvUtf#u|ydeC9^xCRcftLr3nrW)N0ijU71Y0 z!(n3>oe-W?N}I!e;?$XyD_3gNa)yyjOdUKR**h#keuj>aT%?=&Y)8% zRZ^8&#;_WTmA5<07Ap_Ugi20;s>mL}2!LTLCT$^$1(4L&0|s6U1f+Iv*uiGA5duO3 z@oh^@tQK}&v;u{20r7;~W#D9Z3qUrgy47kWF{jP(iAUpIh~pz0(MB`DmC{IpZUsV= zziHnPatIW&bUbpuXW@t39dc9Vs(=dz<0xN#KsE@!IIvr-Si8UD+yUl2| z@GPUzY7~rKZFLwU#Su!CPOCLbCEV!I({A2;+|=~q*>^9CE6cMBii*lAii%6~^K*+! za>~ndOG^q$3bS@?UNa=gwP4ohySGl&)aKUI72LkDXUe3c(4g)?0m1$H4gPrZr*|J^ z*0emUtSTufEx2{(_K*=HJ9qaVJ#ltsesyMHU3qzVj&~_4DypccC@3iS=%bJD`}aj{ zLg8P;Xy1*rClJAVD+C8y*Dk##O`Kj;RrBG8A95U%l-z&LyxHe3o&NUwFE3v`KWWOu zW5-W^@WBe+VDH^4NG4UYj8QC>3Kii77CFPv&|s&_x^MsP&yF4#Gj@1fyep}HpJBrX zBqVxbV(o(l_ZvJUsb5lT|KvEg$LjHTq*AHBzkfhLK+m2%yL9Oi6&015ntJNg8NHtM zx+$!7hq+%;+_dQvE31kgK76=h#fqe)q&|K6xLhtYIF(AJ4!fssd{RWXR)x$f$-rkh{3+ zgMrKRM!qTv9DyWCkSGdG8JJ5Xof3>V0eB>s|b4`BmWO70f~002E)E;Q8ejZZi} zK>Rgi!+Z_#0lGF=Dj7V8AOlQ)&E!WI4bUeLC(4Pgt!TAD`Z(YcPH>CGL>1?xiU8Ts zo)o+o;7%{ZMi~BLV?FQ)l0_QmjO&8K1XtRIdV9-jqG7#scozh7*g}wJz=uS$RK&!@ zz|BqZ7WAB=l+kEVsT5MFSfx_1f&oE`!Xl3+Iw2uGIXP+2pn-!2r;HtylH4ygF2{^ip_9&^zg1X~myw^5Us8}?Sn%-S{jAK# zHB~v~WsfgkIy7y{!0{v9=TCm}vZdhbFY8*GnqPeRoA1BPIe&WdtQlh#EnIN%(zVK( z=CZoRwA{SXlA5Bz%88Sv`v-?jnla;EMp|xJVNq>)R#sMKW@b@QQC?nNc6N4MUEQNc zkLJ&x54@&aA_1{4I{)H2_9R5`&dJLu720T5yv^zvJ!;~K&rh#jy;h~x4jn#Z>yAxp z*DqVWZpoedH)hS5nU9=VKoL`7wxuq zCxrC$O>hrPNr;Pg4H(!rF5YE#@Ck_?hE)ax1o->=w`K@!e${9+;Zgott#;vpRhQ0RkB{?kdYM`gY2t)0=r1k`RVd3zlKSy0mW=%3;>McN zlP{Xjzid3y+HkJ9_H=#a=e6a>>MD*m*Pi~e`QkUvufBSf^XK2+c;0-vx$g64jpv(d z&lYCwyMN>3x$|Zu4@l56Duq(a8MGFw!D{0zR>2QP3+cSRa-F?w$C1e*O$xZLxQt_>5fzN;By$t3243T69LHf? zPSUyW@qN!0+i6UIknkF^V`F0x4PcQ$Q1Yq-!pTEwAb&K}570x>j;X-iS3U+(qk|ol z!vH|R&2>7B(P#j+f-fU~h!RTRGJ*sWcf`uUUKvKm^BhEQhr{OaM7!NCyd91M4-CQ& z5|XglQS~F;JA6ps)Uf`*4vCBtxlJfwU{K;RI~*2koX72PI#@>Iu$$xKggY4>@6hO! z8o8EL@{%AatKq^Tg00cUkwdM^J{Ym%<2i?SEk1v2#f@`IuV0vX>+Qvw3yOf?4r{2N?SH)tgy^(`wUe8L3R6VGK$gr{yd$eUmTWy_!>+S6Wm0Br7dD zE4{2B@8*T`YZomVHM-yS9jmi*Za24-v_30;{$=HtFRGqBuXy^bpt?FgJ1ZkABeSS5 zCqMs5UQTXRc|%QI?YRr*m1>oqWtOd2-qg}uQC0aQE3>>jKRYWuKc}#~q_(WMro6PQ zy1KZ$B6I%y`6_R5Ia>YUFS^d4R11vr4rsG z82;dTwA<}&x7%nm%4D*zurP{Y06ydiBO)S#gM-ClF`Us7nMTgWt3q|LvD2fB(&`zkGk^ufG-keb;)ivhc{G``fNw*|2=c@Udf@4!exwWj2SI zGg-w_HX@2m>_6n}g)eIB8tUt+YAOrPoY=Eq_Q(Y@huye&s<7xGz`EsWY3sA{XU{8I zo|d+><~@I2)6`gBT~$_GoSBw(EA8?9@{;PB+WJ#x&IN~ri6yc*bLSVAlvUT%6&07> zy?3LouCA%^*|jh3@85Uy_U*fsRV4*QX}P(%t5&W0uObeKM1q{muYm|{_a)|-|C?pm z*w|Q}=Ye9V_0VWEiHV7qFJE4=WQoJ!m^W|Uph1HsPo6w~{`~m(c!$HG)oSH(IePA> zya`&~xN!0EkfFmJF6X$^@zZ8ZkM_7HPo46~md!_w zerC2>R2sEdDp9HhaD>_MN1u;SaYM>JLKJHK;gk@Ig=r2T;_JNSIdC+a&F09+NP|I` zo+&gmRIk^sT)Fb{<;&Z)?w&Ydn$7A`tAr|{sHiA~Lh$*~U2U@>kx1Z`W?42eGBPYI zY}l}2Cr_Tdar?pOaZ|SMJaX#H4UYFjNf?dZWU>mqu_%uE)~{<6Qjc4BR<4v;ZJbQn z)1dcTziRxGwDqkG=e~dOptbHoWzoKptnFpl`x}bSKdrk`SAMp-_)J69)vFhFI!&_n zB2fpCsIy2U^%p(3_Tg`ypH08Jwx;m2)|&GrnV(h^9BisO+1hZSAm`*qAI?!qqk4Al z;jr1GJ#LH5%A16KJ19337^Hy*lHyJx!a-6%Gfq^H6QDy$fMeR}?Nk9h0q{yN-Dbs? zsuN`6$iALG90U*#`VX`vB8<^FsWdngv2{{)z|+Y(LODsChTU$5Z4sghaeSOJ-u*RX z!@mNZ+hj69arXu>{ud<<(zx5KAph&@$R@k;LMCZH2&b z@NV?XLvang1=MPfCz|GXL?j?DBP1l;Zd9ndy$e(@=Z_00wl{9`h(jdY;~b(rE{Dr* zF!BZ?Z?iki78_?Un#@*(g6rMepVNtl4&ZluJT~LOhUVIXFP~M`0_>7)7G-)r@8eFMU4&Bjg6JJ@0|Z&;iTci2h5o@H@~3xNoJ12=?)2vv^%0d z-E*L*xU8Y^X(`GQIdaI5 zA!f5#EEdCS2tKIMXmB)@O3}Gjr!xkIs!Ax(7iGBO^OE4M@y?gh3@4a{Z z{CfHM^?LW+4#6RQe*WEi^nCxVw?)H83|g~x#l8DCE2~OAJ9=`!z`;>sdB3FO!$*!T zUA`=)Pwdp`({}Iq^vKcAKH9j!YPa?B>#b**m_D&`r2_m5sIBrYdc7X4OLX1^=#1J2 zV6@i~Ck$-~vM~u+WMrgFCd05AvziIkZ>26GToM&2<9Ug$Xust08KK zg@rkt&KWai^zGYMr_+raH}2NGhZnEh$SbTmbmW}DYZFpwIjK^Zd6EPWqS(SL7HVOx z1_3uYDaQpR#*24s8eLm-H$4cciZ7 za&z;&vu8GQZ0K8Wh`M#_*t30mO=Q>8M;F#t9?MSKR#9}MqUcao+Q(&?`zrGe9#R?;*a}R<0fEZ|n!rZrq7Wo}AsfB}3LfOzZgXykKrG8b83)Sy>OaUp zBKEXVNJw6P4cR1zleY$M21F+MOq`dh_)v2QJhj;@R9Q}ZoS+$?N%Aoe+3B>K%|;~R zoK8Dr4Jh5Tr!PaN`4&K#!R{Rn8$@m2c2VHzBxqoN3K*cz$St7Ts>{1jg2Lflpm})< zy#&)96mXz65ZvN4#U=>zoolpuo84)(Ih0CeRFqI{92d(U*s~-vZTHtLr<=-mJ+0VY zowu&0U|-(DHANXK%JWuKkqXwo;!MI(ZFP0&qS!TQT^;LX<%RVRU(P9+pTeNu`ZWGt5pXE`giHlxqJ7n zojZ4W`|UTobm=UWiv9e%zxB4LN6+_T`?$`XKiSk=`|_*SjLb)M^)1=C1>3govRLi2 z=ghlwQXEVQfdg?c=$FtIR_VYyfzb8tt>9?$&T%LXSo0jwGch=NZoTw@}nxB23tng%M z;kiTmmLN2nk4BrHtJkRqCBgkAhX9N!%6F&_c z!MBQ%C^la88nT^ECtl|C8rpE>Uig09_6XQb$Vlv!gbqmFM2)dR5J~Aiux9w)0L_%` zL_8p|_%$Y4UbpHd#Kdlh8QAD_+7VRn6j@WqFG#0>_+hhIV9rCT5K0I}QuHN27$h=I znM@Md5tDQ#wKK+Hb=eF;(wmn_BO@XLj0X9_MM*bqZvNBnGyn3(j8}ip`{CK;@9R!C zW`9~=c%(9CS3~KJ=8Ekt6?s-z)rW(VHDaqJ@+D7d+Tg{AhDi*}k%@ zjg@8F3UfBpm+bkf;mp&jGg;}MuHP`qWbdI0>o{((2wOW}>_Wu~L6Xk3J5Wps-QZPIsrG~5;uuQAfcI(zH zA|fI#E-o-I5XT1^D!dCY(W?S;GMU8RzxTWEc6k5&_vCV^$;7MG%D_PX(9qzXJ-c`4 z(7t>3u3~YdzrSGV6NyCO;h|w+AtOf)zkB!gU;p}-AAb1$AOHAURdqvsLrX?huElD9 zw^Qe#!-s9&x@GXtAz=~W8l6_5QmVBYlf`UzIut5pq*!R1<%`Q8-O!XF+2dJUweL+p z45OE0qDV~A1~g|`Hclwpi7}ZhTCLC~P^D4`Syr9W!2i@?wGC>k)oT2(9S+Cf!Gp(* z8<(1zI(6#Q0x3M;NUt{s{FRL#8?fcwU z|55jE-{duyUH$&WgKuA4uBq7d;Lg(Qv@Ml|C$b;!$$YrIzVK8@+VP{?7ard`_p7F} zfBenO^1RO~axbQiOwlSN8kx*(k2V@C27}OUp5yhtXhjqi=|S*f_)L5y5prMnCKUm8 zKmXeXYRRPWbI3+yMfL?>e)u;4n*e2;EuAyY1nLUp8jxu89>EK7C=3yN1#3XIZ!E#d z8;!=-knMK6(J%%0h0-Rko9%ToXdp7NY-;^MSPbq7xb)?=ptqpdu;}4g)GLyNLRJ%E z^w=5O0pGp{A;_jvLiQ3lQg};%v#<~P9>?2x%7H))$DY%>z_$@6Y_2QQLsyokH@>?28o;FoKZE0#~XaG{T zJ}Ym1RxU``PfMS+mI?owbH4hrthKqIuJ%Dy)s?$<_iXrRR_d6++jeX(Dk-jSY^bcR zdX)Bf+m7usX3d;BecIafpB(-COlD4DbzO6HeN#qG?%ECOIg?Q=7Kem{#Ky+z_4?ku zd*fS61`=O>P3xpzBbARCq@hMDy%Hbb6IeufqHO{I6E46^q4kZ&^)HP>{dBKZ+iMg9E+7i$W$Szj^%6e@lP$D(lt1KWr*L znRRz}!Q%ssWhb*A?6qlwJBdV5y*dnx550JL=JzkIRTrL4zkh1fpcr|0keOvoyjibj zjb`3r6XYOd0)d0jd8yqJG71=B0QVS(4ak_gETfMbGe%Kl+qUFaAf+B6X`rSd4b2lfp;1nETD2i_Iv*C@S#6oZ|C z+R)R{;sc`rIta-%2+_Dqd`NKJ!y4(Ee1N(Q{|Q|(4JJ~C^s_rm8nsd(iDZsmL>v$Jry5~0omFqB3U}TFH#KT&x7LpjN^UydvCYfAPO|AX@?XjmmP+VR= zL$JMF|2hD>E|Bj2vba`XDWcjI%6#pW-7-UbZMyltX^B*ZqN^#r4(9P4011|9Cf-SGE@S zUfORzTR$~_i}{h^`*=_SywYSA#bGkpP%&ie{M8D_ve(N}L;qgq_*p$euCJ={=Is2u z#_!*NF>~wrnIGtt(5JR<+Wc|db;n<|4sJ0_VnBGQCK-bQ1!cvKK`mCI0+LZSRjDB- zaD05EivffJxCbC>5>EU1)6W^COS(7!Ch`s?Somb=JIc;?baa#-KY(K96Fwhs3|T(> zZyR~GX#e@%2912BAQ|R+Ud2(QbUR-h36wqgOdp}q>gor0vI7H&i_n&$&s}vt{w)!F z-CS$7Tpl4DZTSdscjfJ$VRfm{vtYeQ+9!<}K&eSY6j~v5j2WcR1b0jJa%SQBA#=iv zlGkDFDc~x}{w7V9)`wNBSTd+nt617=L2O$vr~^bo>AceUNo8z+DfHE`b{MmC;m_?O z&Vf6Ai6O8>x(8i>&AYbaOoFTOXYsVO;H;9DiUTg472-Txie;J(+wHX1fk;aRTzQp) zOPfDjnwl;pZAYK4#)*lB_knwh4dfZs+3N3`3+LNx+uIE$Yendx$`}R6msFQ8Hlv=l zP)_I%XM_nZ*PQfYc1~|m%XjcKpE_S>PeU`*($Tm2aM1TW}{2E;FuT1x5Uu z%mg-+W2;}4x6?1*a6`#?mg*@=9%`Af<1ys?*u|oPVaWYUgL);MSaB2O~ zoULzgknIPED8b==AVJq_CAAbWaUjX8L8AI*VWIkNCoP6a|m?thb_=)R6z3tCjH z6PlDGPh_C^3O8QAbaBFjByx4v4EN}=5!aQ1PzU5NhcwEH;z)AfAf|so|3`2uG?$$JP57M)iAx!7`GQXe`2& zfRqfYKyM#wkuT>92%3G9EmayDEHArBf;bM|ClIK3E9gErvCY-y_q`vu!rQ(gJ;T|O zSrZ~v3TgKBy4=qwz(YKQ)?v?ii`_Qu_E5de^_}=!$hG;nBzV&4qIQ3n>HPgQ`nee? zLzf(SE{${`u$uE`B%%J;Tv{B;;LUCQ2r@}e{5DgYK8OHBhhkV$7BIWwyUkrn{!gPp1iKp;JuALI+ViD(3tD8U8}%yF)m-RP)P1DY3II{C%O zA%oWB-9S;vZ)aTY*}o`~_<`jtW*;&)HeLBou{B{P)Dg8*s;W!~hUta3j(2CZor3CT zUq(X1lJN@sKUbfB@6y^s;gg}6I{bVeu>vKVoDKX#h45E*@+%x-o7)!GPc|(&ctW*XF* zX$?)CX10&}*}6^q8(qeA%+z6XW}8=7RXQW-h#*37mN&)-k=P+b9IRyLAj^cM^ff#v z7El^ipTs)fnw3Jnfk*=3C#)!|M$CP&AP10Uf?0k6Lg=`rVB2_c5Psk}F|0&L0e%o! z`M-&xrRLeu1fIn|R6bzvMZYTu`EB@^=|ZE8*9$+9y;~;clD^?-=qhFM>7xE{d9y~<)K@J%?C=@9Vn6L_(M2?!%b~$AQW{x)-_imnRnd9 zuctPp@B<(2O6rRV2l3=5Bwr{w61#(oyzL%q#;5(o2W~EFs_(Mmy}I>dT@*CIN=jA^ z=Oq4Lb@ca~u<*0z(~vq0u8yzQQfS|=fdO0G8s4@}^X)Y$n$nU9;>ee7V)@ky|!s69+STFTUbnf-5IY&rgWMj zy3;wk(;<>o(H$yiPT*v~TbwoEWJu#=%HZNeX5zs0SkZl68K0(3r8i-;%wJu%d0YQm zg3qMSS#`TRS(}NqY4yIelbXAX=;u*5|L5p%MZjC{x}6`G-o_m!Q;JSWXq87npZL|F}B`hKFgU0PlQPD0CocYD!JeEt~sKkBx-?x+K!O&&<#A5u>-+Vz?JGb^I=H>9I}>5M*;Z?~GAxxiGMUa(2=u!z*Sh{a zYT^OSEB!Q)e&woP6GqJW<;oScYf-S_-U+Wy(c#YO*5ZZXZ0TGb15rKRdmHkps)ecm z(WNk4l`3gVelPy#PgIXz6ti~48YN0HgVK?!ef1$>VKB+kyL4VlA|^%oP=Y@Sqje3Z zdYZLM7vA>-bWeXgA+mlQ6QDF>Et1FRKV)Svoh5Vss$xl_g=%8o&_B6984jJnL0ZAQ zuB7ADN^x#1*-;VuoQtSzki*DLKB%s)*mzhWxNGrgl_Wr2dqDgdJ6(`-9r@ngg)v*G ztvB=d{2loDG)?@4U$CVu>XRLG-9shoWTbjm(Zl;PVT-@r(P+N3k@TX>hx-eNrM4cO zT2)i2rQ@*v?K~F#g(FlFBds!lp@C>w@8JEK37Y}xegh9uDdaDeN0@>*NtWlQB23Jt zPeVlBSIpo^f(dwiC!hfRF=At|<&Z0iAXan>IT0jE?7yH8DD{vsZVmFC!MHO~RK!Nl z2T+*;sii8v@ z`rvNWdTPlOR~mWw;M)6_OL_6DqV`zdeP$*Dfv&UF@kXZUFW(i1LxHcGliSN|N2P2f zfuEAlKaIY}>w5O}tyK-+X0P=uH7)RfYHu@D1PZ+BImr#L`gTsfTAmM-S8BJ+RCn52 zh&XRm5$G&?{p&2xXD@9g-!~WeWobCQP_kD#Wh^IWj3`HjI3{ znP8iee!|w~kLTUNR*rV&k2&&WaeT7y!Ta$3&PI*k3G){=n7m7YP^(&S2Wi2z&)-D2 zbj*Z^6J3#jD1G7(0C(^K0$;$P4v@BZTrMcl!h?tfqlb45Mv9U6os52)tM~0UzF96; z)~Q+Had!e3Tw7Tr5KDJaQHUea)N$fNxH=7z6&4Hd8V*eaq*Agq>!(4^{XITFCixBR z?Ju4Q%y>Tp2YbhNGBzD5ofD_>xj%^FTQ;ucDgmIVUI92~-zp#xOXr4bg#Oi7e~EQ2 zpXwY7-GF$H+5}{wLP(O&!nY>BY51Zd4jRE);$S>(VtH-Zd?sxOV31?A=2sepU0Z zkySsPcL{!UwWHtyf0^w{I`>2Sk$!{6-}wSuw|tvFWj^ZfJ2unNciJ4)whSGwV(zEY znTOES6G*x}E+@;;0j04FTRqzEd+O$f1A)`kXTW%KW$^BHfQmesIZ8;Q-B26ehfR}Z z_xIx33k@n)e%0Tov9#<#9g* zZQR5mHa2!7=1eZTH{6Y7T@b_Xu;g&1U?pb9UyqaOtE&s-3K>~k`UV~z;`O4`d5W+^ zL`1*pICbb#>2>P$j;k5&;A7--668yj0XbA}j}Y-L-Cw|L0&viN2{_f;<@>;9_?~`j z!_~jg5^aemNEJ9@(N>2IU;umz9JaEHz4{v3;%iyA#oNH!D~=2QA^GS$cIUVNgCBq2i+32(vmLs<9iV&q-hP~#3;1BVX&WTbkj>zNQO|6895`qo zM*8p|3wDftKN$sTy$Pso0P2yNyVIiAS2(qo@ow&UWW3itlBqQGRPx3@R6yzqIKA9NP zfrU{xrrp)T{_e+#kIV0`849k8KXA>aY<=2$Iv(v@H~l}Cv#z&OIC!~Oh43%@^?h7i zf_eo_WSxY~?23A9-Qr?Hu)2QUdZpTmrlZV#3G|5z=cdwGX!!Urd~k({2x=6B$>+_IUf@mS(z$igDN$wI9D*si#NtzO zl7JDPp1{Sgnp_z-CN@SjE|ti#Ft5tX56^5sE}K^CyPfmeUY^Q8kfOt0xQ9 zpe&^8X+O2l`TYqFdgdu`nL%SKJ(7L=EOTT=j7vA(HLKFtT23~kO-|;~x6HI?5A={y(QSD&J znt|~7M}w7sCIomPjI%NO2u7nq)PxxnQt_kVqV$M=euJnV9WaG|rR0H9@U5e-0o0wI(koPU zA+Nws5CH-^jH}T(6#rPS2)Zn|60^(??mCbb(h-w#(R5uE`rtcdGxRoVfE9mkY}78u zZ5apC8Hr)!iWffzm6Una;&f1=aGV?hGA;Mx%k>t&c@^K>GjGr3Qd>?)LsgB#n}xh< z=k$3s-|I)_dR0wqu}r`w6Ycx})5gNoI?~L^gWX`jdsaa|p8+wSK_PG94?73E3%_Dm zLxmsjl}(=^t18y4o%pP*meCek_l!^*Nu1LFXwL2e-?Xx&LCvR@f zAiRcf3|L=pskLyau`n;b4y$}!$bWuLt*QhtME{sH9)@?9#Se}AUS;a&4)!_I-*}k` z;}t*fT6(_w6F2VH!@E+!}m@Wf}yvoXn zObGvOoZ8$@FMyrd=likm*KX(+&W|6JWo2os=1NvptXqiL;=2y3ZbYW!+T@9{IlMn< zcVWb6^TWuJZ&k+T@1q8zCX1pbNd?auosy~5aNHX@0xP|xj^%!+t~-gdM-gGYN#&vIG^6?SrXgacLx;f9+g|X)!*wcgqg>)mhkxt0uJfbIi@E`= zzu3szCgCQ?U;2KtSr9=RFf=$+up(YTL5$O`(Nj=q4q>mG@Kq&k&8sNEZ}u*uy`nfE zy?hoT2%O-=v`UTo=%6rS1<=g@`cnMuNk+vZ;P$SYlU{)(rLQk7L>^oneV4cR*Kb%s ziupo`V1j%uZb`&hS>Q_$+@(;VfN+C8n-7?zxIs$l3NZmgxfG3P1~z*EU@(&GXyKxI zJtE~WvS5`r5e?4II6D_R>%y3}MQ0%Y0$hw4e+p{J67EnXJD`XV@<9j0S+TQ-jha=p zE#AD|gyrvT_t<>w^87>g#r|A*S|Z^)^mZOf$vM|>9@|R?`;Op95IF=9^vrE&PlUf1 zlozCy8>U!VrWbmm*FpKk6p&}XuTJFoTfx))+R65K;OMc#8eBnc+Xag*yCk2!>ra<& zUR_6NyKml>m4)|PiHxb){8>g*`>(|OO#`bXOG{6l>lU`({B7}$fO;vxF;|;j$K~bX zuHu-VrmgkQ#dtN%cYB|Y!>)kxmEVhJZ-L-T;*RGxk}dkRk5h`Ft3_8=fAANVdwkdR zvAlFXF8Yt0)&Gn`;LPa~=TT!A;6$S-gc;iVFeQWMKT?i{;KCZApreS?KFq+A)Ya7q znvNRX0i-QzYHA3uz9cH;6gpjW47?EB6m=E$&~CHa_i@~n1(t-5kB=`N_xjS(;~L+O z^S7t#{~#NH&k+MdjC3fT3U+oUA|`dV(4iH9cS3$xMi#BqlvF+=i{02_xM<8AJ6($E z&mEOAMO1DayS>uzJ+^YGY&IdfJqfW$XXowoRbq)Opf1EtmwYvvj>60QjgG(WcKAO1 zUcg78a9sUr#nt#xJa^;Jp*P)tmo2!%;8HjYBI0RiX%q2r(EWQsoh)5!nGL3 zCZlTGJ~63%NOMHNZJ-txY8n?=ND(qMf$%o$@TYY5y^>Wd$yL#>!qv>LrX#W|x2Ciu zwIZ}5F>znblV@^HKPs~#uqM`1F;5{cw5umHJ2y5k^cd?m2QBYnH2OI%_5sTAj?jI7 zPI8s|Ix~0%N8wJ5jf*CSWEAa%?L`0!L4qj->1x79q=zUp63&~PrTrm@ zxO5r#7ms*F5*c(AA|jsH9}MMNR?%n)cq)Ju0iYeMll|)cxT4_#2M%rMIf}S2&-GPQ zXx026d{N(;d!y%>Ic&j4$SiAts~5>JAgrUNkZluJxt^y z8m{=C7J#Z?es8mV+LYY7OKAK4sseQ4?X$UiE$525s>FV@03Z8`F-_wY+S2pQ;tl!? zv7Nn8$9l2p1p3Tl5gE6fUZ6eIvBPS;N!gPAh=I%1>#FUY%k=Jh7M+&;;YKqqS=*Bh zf$!tJmgB_mM#!T`g2m<^IrUx1VwQ zBZGlxI(0%`ukH^zPW&(-N##p%@Xt6z9V0|UV1$NnFVOojr}+0~^^3l%M2 zFegRoz#A+L5-Dk+k)Swu2yc#tt(i=m!^y?v>0$DCKRKqX%tAqGVyvJCV%E%})Ji_2Q3zaynxct>Y@JG)mG zmj`F8E|tKn%FN8pgvZ3#6ADL)x_40={8p${cV1fhq5o{*yMHKxi>Z*5un^SeN`F1q zsBI1GR+K#NjvflBr0u<&WHqGQmHvprF+{Br%7OR@xx@OA&;H!Sm+(b(5vfE5$(T6~ z6b6$;4|}1U47LZOqVQ|(4bUeMyadHXHO43NBZP#)qbq9}bqXs8Ik`bG8fXL=WwXc! zQ4S>_T7TpvDuJ!@Q3*t+l3s?~$bvqU^`93`fQP`+FBmsrAqs%52M;3albYJM7aRmJ z$3oMI8<@d4Oaz+?X-JSRrcS2j;#yt)0@Y2Pd<9vK?GINZ8@GUopZK~mfvycz>9iowGCei*BO56)*O()qD55)9EgFNqoi^M!KER8ThClt|H8 z{^#Pt-MHB)jgGIq4{1{`R-J>hXr-sYN$q~h!#aCx){LnIOP0<@uy;K>LbW<6Eo^=hxd=3hZLDOwob16>?dcF zCBGV^tQlR-qP4k2o;+nzr53n3|C%s9rEgmx4tQ%AhAx-+*t$RO-G)z{*B1p~QFCQ6 z6u}PC5+h#I-JHh)Glxk8gtk>7&KY7ks48EfuV3M-Uab;XJZ|8{#l*zK#jk)!<)w<> z3#PL1;}Bz15x|LLi9=;+u{(>4#&YXDorBu8Mze*8m6eyCo`{}4Mik6GojU$*fkovM zn>s#i;*hC`*?(ir%y{qM;PzYMu!3v`FB=;$f0i4gCSk+N(e00(7Y9kxg{gM$(zf`4 ztJubJ*~g;!q{qw4_hlR-IhkXmv>4i>O*E8KZklkjr>>`Ie{RosVcAwKx@AqhlbI+- zwp5vF5rTEbuZ{OE`kj{kYdo_D!>D1^3W$t4bd(g$2qQ_X%d`L2`6xcC`OtY8tBFE$?zLOBj&*eP|{cGbA}Xled6N+ua1Zk75=a z_nZUs-(YPMyjV1YqvsmEkNdf3LDW={QVCGVNDJdI5Qlv9(;{(**n$oUUc&<^^j(pG ztYvk>9-+;I=>RTY|PR1F@7W35cdn2C~0R@EltSjRG+d zVz_&mLHJ?Bgu5sXZotz*WQCtcx2xRTw3P`PX7v!_@a75qdEkS+Fe5<+z@IM_r@5mr z%T^E|5Q>$U8fig1kVr^F2T&u2033sz5+!-0_|Mur*kEBS#+`aKAzd*0pMOM2Q>EN! z$%Es1NfT>yH*Z~@SG(4sVVE9cu#WUOrZ-p;zmS%a* zf$h62?QxskDJU3utdx`yqnew(5A`?Oq=DXb2No_PYH)?*6zSrdL}E<>=5$(aZX8aw zMS%zaHid*FFDn}r8w*VUxkzGMSBa5PwaGxFJdD#ZV2|64L*VrXV6J*Kv?KnjZz|v)b-%lD3 zqg)~@Eib=kr>3s1d^DYH9nC>qYE&$j$+T4-ZRA%E?INh)8p{Mw*e;%Kd{&WtKf0TW zy&o%ISWG8*Tp#BT#*{ZVvb{dEO=hxLeF_pJV*uX!0%Y!Fn|p)9{_vC$TK3R;8hD^M z4=ecx9QPObmoN`b6X727DJxuXpOGCTD^#{{n4&|$aj9d-I(^1E15z^vvQsXLc{TQ{ zG_(eN+M3L3dv!Crjy5CD>d5Bm_WH=e>XJUf(VpLGtfPaygRA4MlY<=|$MCdGWmjTg zVP<4Sjl`td+AF0Fr*9~uJ_lML5>XYq0l3U_4PKr$1NoM z94zth-m7gbn?)^mr{l`B2~)+eZ{*SmiHV?mLO%#KX#zl9A-o`d1f9@x3hl0dNkS?j z!A^!<_Lc0ANJ&W<)L|t+^$LRR@-sU3&LA(sJ|`EIz_xa_1Ph_D8egAU5Q8p}L5WqEs>M5od4a2Na3rB(m)aBF^ZMYroi2kur_i>-a5w1ff{m}Hx zl_Zsxl?}4pY+lFhfX$^rg?FbVPn1Tr=S=?Ha`r0y$~~RU z$t$3YO|TbkAI9$vof6}e^CqtAb9(PkYM+J|;?Btv_II$=E_D<{LE$?OhpU7YE&KG? z^wJ#t{0xol8>aKbg8!CAV%?OH71K$k>@ay`+mL|`HonEmdB)Um3`YunL-SDCA6zE( zPNpRejwD`h6*oXh_ufhNGJ=`KUAHs1dkXDRa(tEHV03-orCCz>#cKTaT3K=I;>^1B zsb@ZCf%DLA0=$5MjYJ#(hxCQ5f5@07QqEL=yLbuQn6gwN+d$zaQX-F2Bf{vJYx_YI zI7XHrh0g6ylP5!(0Hmr=LV>MDAwY?cq6x9@FaA+(v0hI}OiWBmJGr_-!uAm4lO$CF zs@F-_p#KPxrGv{+n;U*7O+y>f#Y+Nnuyo;6CY2rlZO8(qWx$dD>(_DunT!hcQWlpZ z03Y;xxijV`V2B8?ssc`9w3vaiMEkasR%gJmy3n+0bQ=yO78`HqS!&AtQWAPv* zj{f~d{%4*ABez<^gO+sUCZ2%qVv@Uusr==LwGtFE;rtql#=`l_n~Tsg6U#H^I|Z@%yCM<;!%pZG4I zIy#?Q{QHcPKD0*%z*@E!B%qCFms;MDSdm#6SrM4ccXYrxJ+ZK~J~1_B;SWCBn+wB0|YD4%_&aPeW!#M;B(3zSPraCDWmu;tG??@@C(gb5vvgK1T6uu}|R zrX|D!krfGmr3L>3MhakV?c_kdy?F79daqis6N0>p5y`0`4jL2AQQ9MmVm(6!yo2Bq z6*cAPs;dDC)_BIAsp(68?%wviyq*gWpRlAk40IvIBl% zXqOH$1ahRm8nKB6Vt_7_Bq<6qLYW8c0pldwq8j}(4#f($Szf5uBk2g~9VZy`=Prfb zx!~FEKBLNwTk8_^%9L(H&=C{#KgUl zi-=5#1iBV!nftB4KdK$QV_;k#V;r0c!`*SWnye12n`V~Vn!lAJu8C(i3sqRMr!AGl z%V#(1yOk{%SuG&4cjGGc;M$y7bi7>r^f5lI?(aNo^E5p^rscFZo9?zwhi-`$Navw3 zUAc(PEvZ&7r=EPNtUG%R-CeGc;HF!HD$HLpvJyeZReP)vY<6$etgvlN!wHFAV!+3= zRp%37N%NzI8FgW<_aE@99&LJyS)1qQh6h4UGinH~B9 zAo1|<=;-JGz{_Trr>ltxxylHXVCX4bV4q*a-_h}CQsEsOJ4=7(AW`BWO@gbdD*!FX zJ-VMjUpq|R0Sy|DKjSnQBgGj-PzF45EvL((-Pa08(WAse2jKHIl9q!xNt~w zEFm5YV0h_uI&b=iSTvifpC0Yg`3>jSW&|)~+`du72mqesrHW$W{7H@2Qvwi7qGy55 zx350B)SA^ zM1@%GRord3nSeM6B)}K82->{Sy`Oi1grN>FKr#a#ff}*x(A`;!I}2Y#(`=76dLmF~ z&uRnUc$DZU6X3A0^biph{T9EnAr;i1E%BV9@RvR?xuoKZan%?H?**ls$=1psXe5UT zy-1{R@_9k-%WOJpnWIp4$b-7n?6qK2aJWPJ;z)pwQ4M_rZ*Qe=zGClFL@^;4w5(`^mC{_a|bAVPX7%RLmGe19%LGw!% zh%wdE%PTLZrl6ppp@A>ww{O!ToYSKJ9$^sp3X1fN8_(7aW`J&U4cLeeSK#!~QD8=j zh=?3drYi%^`d_~ufyo2_2PxEW@1UTd&|n}M?TO>fnw&@KR%MyfPfky5Yz626y&U0A zaZy=`Y|iL0Q(|HSvu=7$8Ko)akU1^ zxzTO@%rb4!TsS?w{6dNGW|!-~-abAc9zC9Bu&phWhI-t=!C};hI&mx}nut*9!1w6# zjUce?(#JaW)Cetf%E-};a}EfRVZ|p&!6%68ko)|Yy{uj<=q`!$p8CywCNI#_qP*g4 zqv+jUdVBC>o3q{Hl7_#(@2AhNv&FyV4;UW1eeiR1s)1vmj}JdE`1y5!QGF#(r0?(Z znPXFpB=o5x)SZJLW7w&EG5;(-V^hiEoITt4WCRz=VZl|D|CSZIwk3zhmhAViDP@^qUZFRRyf zhNUt@8b=-nbeZ%iq{xN@F~-Eox>+qbf-mp3jq4J_N`LhZXLkAf?*0Ks-x?M>Nio}GY#05t8i=S3&F{As#31A)%sediD6 z7Obf%?m`b>Ch1ubVE@XDqT{w6$kcCY{(4D{4HsjFEhF1Dt@`cXQ-k7tw7U-F zYK&XA^UiCrmdGzBBwCO!K8WSU;Zkc0hpfPI<@FUuS>dvW_HG~x09W7hkVxAxoo4e7 z9+%3zJb+4A(%Q;NN@@h0irCoL0MI9=*YnMIG7T~TKd&*|mTZbFxg+NfY7AQ~5V8Wn z4DfQKHVVHBR!a&TI7kLTI2B+BrqE>Q88Fph;$DRNorX*(5^?lMT!XR z8=zI?}xm>8sVF~FTUWzgl{?(x0eA3+Ah6spv!Uc5xy z+$kg9BuU*QU^p2DYreivrL6SVT++qK_Q}?OKLL+HgBZOQQVTBo2N&IvZ|z}L@v+DL zLSc4Osb}VlE1>al(f)Ed8Oz=3dESkcBk^vDy;h$jhivCI@CWrl-R%S3;m`P8So>R8 z`=HUAwA#4QuvsjIr?MbU_T)j*;X%<*H+OD5{unHht;4ND?2P3uKE#fxF4JvgsN)%!irtc>na-A9sJ6arJ+(9%tM&7(xkKcZ+tC5y}KlyCqcOiCJRl$3~I>=Tf z!i3R7hcu;LUKl9WS#i7Loe@TQ=ooeS#Il4W1O8YcB1f~vgietzw&baqyUbjI%PN5i zALsg-y4DBPn0D@-nqt8fRTVF*>Rg&5b|iQtAPwW+&C^qK1VU_VOav0VJPb0*TtVuz zELUPjUEP_9?i)*FxBY0)#Hx7WnwdEVLX%|^8_B>Kkxa$dET@shiA9gHhx>Z9^=feF z(e*R0^+Nf9w`N0+8prOxLn^V6Ulq92-9GCtKCPRKYU}F{(lwUvX9K;XnK|8`P%!Mo zMNt2(PV8wK2*WN_-69p&y_R;k=g{p}O^aFUT|O2Wtkgt{@iNiBq#=MFCIDTJhz1-u znNvuxu; zmj_BzGzb#nSqK~g8oC4EPY7GdN+;0L{vBDFuz!pSPdAsgMLw?06LfW5sWTh_R<@AP z5H9Y&V`T5%p6vYYijTXv(c;@{%Q|mU*IPhvDzHx^ARq`Ab-Ft^1>P|QDaxsniINgC zur5W)?A$_}lmxQ`?4Zd?e~uu$`u-Dw3Is)n5ii`KYk;)s_8T(!IhOzT6H&RFZNt*t zrMBVG&GjQar{pdh*F<4z$3}47tJa2ovwLf?!s%$03*UDq$rNW==28F@80z|xog}uXru!OaY zw2UZosF&7j=-6gFTIk2EDG<7j9Rylu8!yfz${5B*T z9vAq%rEq7n4>*=^*le`w^#yppJua=R0319@z!6JGs0T#R05r|1@$oglJp_oh2~QM= z<9mA{b|n@qfbt+%l42z?#43s`P>5LU5y*3=fjJpPGOA*hMudkSkP%zB&7({*3S@Q7 zSClMOZqss+l~u8`)6>$5>glN|EcBL?jO%DnR&i5Qt5vuiEA)N+9MIF{36;VQ)%W-R zL<=_p&R~wFGuVL~$aiaP-c>%eQ)XAESLPppuELN#^E-nM4jLL1Xl&XE#0EP>l9;Gy z{Fq9*Yp775mkRKP@Rz?9^`EP|=B#zSDl8R^Y3s z?m&F|h{U7S^B~4R*6>$_PU7BmxJboQ_;QD%ce)aJ4zU=m_ZJ$XmH9;e4 zQ*>C~d6dI1AyTkvCo5d#WX2H_4NKg-+#lxB=Vb6v@$=(5_xjl*`LH*~m^0e?X@Wx* z`|*>Ez}PXcI*W6|?%=ERJpZ{xVzO!UE5ZocWYho=3H>VA#f}$KvBn_8dW>mA5=|x2 ziI~O4BgGN+69l$&jFNuhHs`LGFc5^aK$ppLz@j9dgoGuHTX7uWpcVvEb3$rN&{%wn z9}vwRXwmD8U`TSSN$auoS|(K);>O9!4n_(JE%7BWA;Tcya9ChZ9y_X1V=Q8TrXc>7 zpvA0Ep_Z%?-S$_b1&YF=udwg@dVh_8Aepn;RoQ&MQfZ}eQDN?MQ3^B)Npm^|286Q6 zbqnODW^}e5ev6Z~=Vis$JD(hJ@7?wMyPo$?^?#8pXf{zjHHMO{3Zh8@(U=Nh@Uby4 z=(pyY>{V_rXC>3Kd2`L?&Q&;c)&6PGasw%tfz>8?$E)itbl~6&5ACl&?X9FmWBoT@ zQO&|VFWsniy+gjyp}}GFd8k0A`OCmHbm-)>X;UDZiDBaEV&%#buB==Nhs8o%yRNb+ zYvUR}5&8>F9AClZJLAUFqj#)576Xb|Hut6eRMQp#r1q&1I+%bg?=rgASnf0`^2;-XY z5WGmChgVl;7Z)(`jsgM%wze}jy@EUlBqI`^Be~r#Grn&wc^!0YKQYg)dpsV>t=F6D zR;?(YC3FcGkbj4sNN)FS4S&6^=YGBCe!br8ir^~<63^RRlWcKh%M!7qBhV-IVZZ?# zmCP}t&|opY!XH;8ajv6A%ww<51cp~%cY#*y-#OYE(zTERhf3zKRH!3|ckJg|_aJ=V zoO5dtE+y{I3bmbwsKCmP)moU+G;3Q*p+l@SB)?4Z)V32WPq_K=_%*-EPqgO7XHq07 ziU%p5{k_Ul!*)|iqb6maa#{KH_APu~g2^_ULVH+r@NEP>Pxd;4r3Tqn`y(Y%ziu}_ z1UebqKLB*mG0$4g#kCpjnFaNFt%FWjY^pSsl+16N)n=RJ_jJ4bG8Jm0!5PK>X#uEr z;a|}X!q&M1nE)hWzrf@C`WQws>>nb(|l@ptFr&pAai3xSA z+f1)+oa1Y@1Jem1T^5Yb04Q`E(V)SCY{#cWzk8v`i;lwQ*wpHYd9Jv9SmhJA z1jzc^IO>;3K>>{S%L^SL)xTTb5_s?}y29=0ED;k8m#W0Z$f1qL28E)ycc(t-7yCVAdl?i}s1B&@%-76{YAem$q>>x?BymZ| z%4e+c-GNXb@Ge5(H-H1WP`N$LA_;xM+ju$|8vrm_tZZ!7YmKmLv$Lm8{JF@Vyl}x_ zlQ3F!Ku|qgaKMzw#GwOJASyOC6mB~OHf z04pPA#X%&XdlprVV5FT##tr52ASUcU;sT-d(af>%B&A@}dG0j5h{`;E6hkhNF75ldwG%@aE6pBI!e9c5AE!Q*GjQW4U zGRfioOg?H>Ana6gUrKYGea&EwE9!ENb=8Lkt{+_1p8n0AvCWQ-zURxsr4_j<)4ukO zI!g_gn{;g-))I)?!70`7+ZF`;ZAstEW4R23gyi`@v6{_6A9zISN}Rtg&t-TP#WI@P zv$S!k>OkR8gXN<&n!WnQ7Q~3tS%Di75vY=epQ11?w!Or`pdS_#GxGo*A}P)RYOhvn z0%I{$DohX@s16YlEFZ7+7>|}h-Xjnh00wp!u!baH;^+2!R%P97Z-7`9jTAm*B60w= z1#J%LVcbg?G#NY^3!{Zko((7~mhXW0#)IWhr9VN6;ApF$Wd7dZ$|0_bE(l?0D2bwN*91exZLCyMu+igjW3dDJLc4sN?$5;W zoRFu&j8Z}tY-RFxZgwtqyov&n)I%SSZZhh`RD5*C6T?lB-{ocG_7?v9RKhPl`#cng z;k~Zjtgzy&V9u2L({h!aPd^M>ieqQc6I zALI2l5ZOGZIa~f7=*?#0?d&_Unfj!l#nslWH&Z~OJ9%!_%{Ke6SX4#8+?;V=1&E1+ zw)NOKx_r0!8E@vzD&KDM2aL*B%ycqkAD~34ey*^>Rr+d_6|VqGZ}DHX?GeAL`WqnWoM0u ziHCG_bi6*hxqGyGdbEEFhed#*BO;;)@YdASa3z z39#Z0q&cc<3lbz7BC(w~XyH55#lGTit@|gum67?qrM%+b_NmO2_i={q4>OOHLhBCJ zMdg>0>obm!`TulE56SO0whsdDieFW`MJ0uLW;c_Xn{73+sZpClAfaal6f@6!_F~RMCiuTIHQ30Q^!72(WqyqfjTd&h@ znIbK^y?aq?p9)CU8sJ+V#$CtDUlllrB)s^HHx7&eCl`qGH)6)Vzk#F$kH_bvN_&rU z0Ts7G2ZtcTLDh-N|H(Or`K`|=U=bN2=?2LPROP#$IS`Lk{#zu0^qy3i(ui8MK#M-u zLQb*{H5>xYatZDJBVQ3bNXdHjY5T$E-7~aOM$u65=|{d|T2|Jiv11U}R)*>X($#jo z;kl{RFH$xlqsu*WzK6q%<$vIEFK-;A;_f?B_<#_+kANq&;lx^ZRdGAnHAH$}a7Ere477#N(~`V+yyaPjP$wtzWN<0NZ@QtXyKZY3T3k?F(+5)r4KH z{I&rTn-`Xi3Wv%8!7HmJZ{!G!kz$wXa0{Z~Hfcz~Tk=0`G`0C?PN@ zVjzKJJTx@4o#rW1RwH{HVq&FQL1C`&WE(LnOJP&S7NXR^HW&!7D@wJn@zSU3mAvI;O`%0HVN^nE}3YKzA$B&4Kx`S^Hw zcmU_CHXp1qBpA_;?4YmO5dxQYFkeJZ7aIDax)d${n}{J}v{4FUFj7`_dPcg8@gv6< z{=ebWniMSB{BX$;-AC}J2w2&pJMfVHB0!jCJrMfG=WZ`43FW__^uj?lRrq`DvG}rd z$0u(^$ZXY?SAlK^PMbnCIyH;1!EgSct8I_?Q|p6o-$c$my`;)RS$}2Qt)ug^tc?@U zn5&)7lfNECDak$gaB|QlifpiQb?#1e0S{mM3!1qGqWLDmS$D#Jc4Lc;xmMMTyzhf* zNWE-5u!SMUgKu-&ZkS(+?iDYq=^NQ{=pppRrv7@;lk%7VglKVjoXe=)#2p}9$NAJt zjmr$uA3TbuyBD|sVi}$yB2?Sx38Dht1sN|hU6om=pl3%mOdYDT8cH8kiLZlHNjLV zih=3uKPa?A~4imYg?ZptsJMzFypw{GPv$`}r(Ce`HeoOj1{4O#3&JN%qu^?@-QN(JXPQR##_g) zk4j-0FHV29MX2kLV(^V_V!O#sO6N7W#iL`Dadu6RKDcN7Qf z!`vS)Hsp&b3{9Ao9I6+R20Gh0v!}M*>HLm`pU$`aDg?6XJ-Fx7Z41HwtEL6&D;6rReI&0(`tB=D=bTBmVrcv*;^K3bft z7ZXHT6b-b89mS%@B|P4r2vIm%BQ(|D#Igyo0B$a7w;PZG4+x(I?{q*_bBQ8@pn&|u z;Ri9DVFp z91{-{zf+-&qFI5#LM>tqvPC4amQD{SkW*HL8{s~oQ%*ln4B@{F$75j zX>mIdU77NkaSdBX7@*~58aXhnPp8KMA1fL;^Z-TFOQQH59{hZ&jUIP!F(U9h_%PQ| zg)f+%HWq{6$lvtqk~l2$i~V+CMq}f%&7K(td2Ot>ss56K8cJu{N@p5>{kE%l zOhsg{E8dnuwsw<0n1*e_G=iP;;or_gn>xI56 z%P)HCnkEa4Y0(Vk-|I(%$H}S4bC&HncOTJ$xaCX4x&o6W{f^9A>Df|+r18B?#d<-IH|xuYhrqXtPXz}!RI0qhny?BPR1 zLqy{7gP+|#l5p!NW+=N_?v*m8q}MX<`_)t+HZNh%k5*Y z_d{2fiO}z%rHI?_txNygvX7u9eW9^QP0MrHdxx0E@=I#-*&q7{S4~Zgtk2K4e}5_r zs3~c|!9REi-l+}kCdH!S;*zDs;jt!k8&1$+T!p^@ghxhNT3SX%MoLOao#ZHRoB{Og z3RsFV)!r?HIGO?p%4E8Lz|+jtAMB^U2AwX3(^FQfiJp3#F_K0<)A&JiCyxUZz?4DA zzBJn5KXL=C)?Ifbq3FWE+`GY6y>-C0w4x3dZM<_FPOE3! z^{u>Ii_T61j?OxAmg+wyq49_>bJ8*Xg&EDdO?~1>-VQPzL~glc|Em~XY$8~$fL~Y) zTi|HjRDjH$4Cz#8J^H)%6h!IAEaa`4!p4?7921u?W9f~gPG;(TEAu#!zMsmNt?6dIIBjKvMC3<0&J# zLAOEM!hOQ)aIT?}2qxi+nLGf`0Q`!}#TB3odTNpXM*7oy8 zLkXkw+(TJMRk?sj0ohDd#?5N^zeWDQ-yVQ^k$vES5Nbd9D+6VsNoZE{O;sHrmGLjg zjTYjFICge^;j=*sC@n(%58J4E{!r>YmT9v9;PU%ox30h_qBl=u1hx3ACtk~L-y`3P zC`_*ScLK)Vr9q|OPnV}!u}p`QL*lKka(Nv5Ju~;$nG~T6n@_ug)ArA?uA%y>Md~)) zDa-b1gof;YHuOZ6G@sbtUmDTnT2x|*mR@fzJh}rv#&b3WJ>JHSG!2d(*;A3Ma$<1) zOthu01xN+?AcrEThXyQXY|+^n#E7ihN^F@2fht8bq^-N?bQnzn%2jUV_4$u6AWyIO zx^OhS|3fLai4$%8(7<#xEltR^i(0yXcE8 zSZYvd!+d%)kh8+P9&i{mydR)d>vB4Gdwbi~)&{6-?6*2v0g^N?uV-^JTbg3(zs8C{ zNCYTyetv=kGm>f_j8aL`E)_#Wrhwc&7o3w9fD8RbN2gJ(&u&)meut@D8t3i16UDR6 zDKC`J{(3$8Ft%W7i*R&h-|c*7G5s%$?xLoYNNplJVKl#9tLDdk1}run5+scf?#uwek%iL9)wm)C3X=qXw;d#vF&KQeK0|JL?o{jgtp2fbyD5^SbQpI=6cEWGz3Q8J}To~*^0xR3f+%ryps&A5N z?;`W-O-=J|pTwH|o>PZ3-Q(!TuwX|-=tWzi$A8zQ8^c-*O^ntbE2eYvyomb(2qv4J z{$_u_ao!rj$SZI=qsL`NWif6UMjaw82>rtcs#TbOUK$ZA%?jlxbx&|j*o4d>ze5Nj z=5Mk>D2}(&qb!JR$lk-dMrA6|_u8`;j|9%iDQvNG%t(>n+lR7Rk9$E+r z4m)tNLpbs%se#xdyVFr-4kJu04M&5BMoTKq4Eg{bLC1>wgMo=wrd*ZMiJN|g%kaDZ zsc?V@e}EF{RIJx$-w$OM0A!`BM8+8-u>f-90aKr}gT!|8gJ3=&Eh%d5xi%?YK}bWV zJ%ocx$00`V^4M)ie0ftkx@78f@>u@6TB>NT0Y__er5M7ep_}3G{<0Yr{~4K6Qm>%? z!oU%d{XpGr4G(pugoh8mJbmb8oc5$OvA(r6Po&%Iy>}i4`6TDQAVj~=w26ybi8r@| z&(Y{*S2e3;G26{)V-uahiy|2vY7PvO>gxVZ|B|KNfHmNcG)kw`?&Q1*kI0(K5`XrN zxRP8bY}sRKN+{!NX51j~f;8y0f4wW7OCYE%1=Oz4tZd%a^3=xf#(bw2J2z%pZNP~J z)Ycj&8;u-o-$&`d$rF%@HV7BZp91Zc7;t7lq#Gc512Xv609q1=6?yjl1X`wnEiwh@ zL!YmAfdSCb!9P-B#Oyc&9SEz1;Ou>1^QqktI>z@~NTzgt)U;#bDT4#Z5x1sL1uV!@8e9MZR26YxSyL;<7a0TZ=+zs$;yDIHkKbww!7)&N#En_QPXtx+yl|*Asl8J|Fsexwx`CUUvb~ZqZTOnkS zBlv^IVr$_6Uqg4lbE_A0cc+h9S0El>0iMaYqW~4?rr{&PZ$v#D5$ZJInbZE)CVAXv z4ismY(*VvGD3IVOv(1Eya<}d5%YQ=5YR){D9DkqCt)@% zAY7=2SDxdO^c_YVpX@gc7w8-d=(B$$z&Hb@3A=+a(7ouE%Q6@WQKh_fnl_jlff*V9 zH1cYgJf7U?WZA)p2)JTZB!+enu@F&TC#M9_0Q^q7{d5|1fQkrUL*Ci?WAB$0)w7x( z0lV_M8qLFg<@UiK)*{o;GIhX#`A8qxz zj4Jf}hIFaTM3rdOD+sTu#YE?JwqEW1b+u}!Df3Z*u8&yibr$9I=Z=9v0^13@u2A43 zi_j-4>-5IR6I$q(078iWky1+ zDF9)vc^3s5V3oAn?&`eoI!v07my{1r!(gWla_@dGD(Sx2JM6_Wi?Z^u=w>QtSPcv3wRtfD92X`GU&7g zt(>3?dII@DNFZowxdWZKvw(aD=;PX57Sw&cP3pw_YqBO~a@nt|$%=jS{C8a_JJ1qkPVl$mKbdHL2%#T=6>-*a;th%3x zq?toT2_E!hxnhToS{O(|Iitt7IAEYb(^ND2;AOjtP8r8z<pvd+d}_Vnd#Ge9!5+oJ z6D4doE^`Z&2dmECv8%PXjhxOFtoDzYvT#vOVz4jaU}9qWG6}^#e&8W;2?lzBI5UAr zrAdQk2Di0?w1D`b$OQ*G7%qWa)ga+~1HrY^=0xFxSS2wAK?55+a%vTZG0bG<&s*Ff zQ6a&wI`ki};S0|bZKG;=*r^DP2M-0su?4{k zFM~0ybZqsgMpP!+Aw=OFFeXhMhoUDsd=h@-qmd32chnV(HNzxrQWY3c0Mg5#3#co@>%8Qtd%_hYyOnnT-VL)#cF z&y*TCF*%nBeLPHDdwtcn><5Ex)gP*ny*+K_AMVDdj+y?nbhzeSUO|ib{JN}4`BUc* zn$eh{^Sf$th^nxwx2UQaM`ufCEx-3l>5Giv*8&&>h13Vfsfbl?f5OfhQC->B=ew3N z{-KO03finAj3ybEyMe*Buz}e3&Emj~Q{0FjNog$dq7b=b#RG{g2t+I?9p0mV&Xyak z8@A1Z6%sstMkEmVerV}!-YwJ0%^xqTh?^x z;sn6|7@r1+c82$N2W2dmhG|wI(CiGmMvZGpTB%4$cTc*4G$W@cGFVv#meUmxbXrYs z9~thF=T2_WRV^l`7(3mp9x^a%f1=*NssN%*aaDSXpFNl2g|p$}1*+wGjn<2ggqao- zS#&Aa*LYQQ+Qtd&GL+*Z@)|TDw5JiY>E&P%Y1C*5w6KCXj4b(|pE+7u;hot6P2P(g z=gFyc7SY6PP$qLGtZ1XyivMs=e0@GI;wLkO7BW7|~Hc#r=R5=w988oQcD5 zkBzb#L&3~^RoRhX8qOe^RL6*5t&Uav2zj%gt6(hIF&3CG&mL~%6DqIKZ_fvgr%MO4tTBp3b1+FTenh17F;W@1WE;!^X4`!c!%-3_V&(8VM>j95`=P~+yM#eH)ggp91nP5A)&|X6qfO4QZ&DuiAm5CRtpHv z23Q(UOe=aAEENX2fmqT=c$(-5QNsaohl1pQKCxhgGL{Rl3v0mb5Dl9fxC=VMN5bJm zNwyXX@d~JYY9JRdxhuuVWMx%F-MBlz{bBNXPSTJx5FM9AB&dIv+JO?9CrKj&&>)&h z1P%krJAZn*{V<&|oC^m46mBux6iKPK$05kog9AJzz z2ov88SxJuK8>}Krm8eWZ0hrKBzk`Flr^&zWis4UV{Ok4=_;QjiEhpJy62UG zG71Z`;6S+rHXlv)q%8!u6sfYspw7MJ?y*^H`tzf|qTBmn@7G7nw$0er-Q~Ve8u9%? zcB{eX;OcwvOBmKRt-!{-M@8w2o1Cka=6+1G!#ZLcAmA|{*Vkqj;I4OgcnBzafc|A4TU%RiZ~k<7MQLe&7g!Vl zGIH{&T@uc0MFr{b{kxx?l%%AJREb)5RX1))FgwcOXk?ty?c(sFjMT?HpNWve=8E{l z_?OtYyHv?2taGdFZVr4d9@|Bu>4%ub=+tHqkZ*(3;^;CzYY1x)oLW8NJn>>mRCft~ z6|?4x(#lLrPmRc{P{|IWb*WLw%O^w>lXYo{7pd-z!p^c7Z4o`jix9~jEAbn6yL`N2 z(lgr4r^LL3P;1Z|T?-FPuJ8^{k(zS!7dPC$(p z)Byx4+Mbqt8=VXz>YbR_yOo-#Qyn|SfW_QE^j?9))&I2s0BmTkm_d*&92rgi`!qT_ zy5WRo;|}RgE-iW9l6{2agR(=?ildMuGl=VcFqdSNOT zr*AY2vULqSWls(^{zxoRkpv{`UO)E&H&JHa(M%dWU82Iy^~j7B8-sw=QDr5to76`m z8yXt!?_C&E&(F{K>^HcTl%}t*uK_NOCIE~EV%2U&8jGhyMH(J)o zR~|rg}1>mo}(P6OC&_gC08gbY>cnyAut^E>~i2tkG zpEeXuBO=bKaICDauD{rt8EuLp0y)8R91V&p-U9+dQ&5msW~f*g%PToin5f2jG9klN z^)JWaf>;$;1b$O2qdMyu|^H#Qf)xF7#_F!=#;|n`IEY)T~*nNmU?4r0l)kAt1PXG z!J=Z1WYOvb7Gpm}Ebb+7h3IAneb!oj_s7vr8$qFl%W;#C=2%R2nD1 zCCtZ0L^WMk(vdSf+>e%kFE$oa{yIC4%LU5n+uFQ<^1^R`J+{eKTTKlk0L?TyI5=3i zv`&k@xVTsyXx?@WOQqKyxZ^eQE!3e+mE(!Uj0lAN5o9kG)@!c4FKq|8DS0?N>q>Qp zyWi+B`tFnbYY&~Qv4Q{BZ41XamW7!GqYl5r+I`j$8}!v{?`xu^?02b$6t+-PvsVnuQA;M*t+Szz(2f@kkcHXtGW! z<0XsJt5%qz?rJa;8(J=gB7V~$+T`>5yy%dK8m1~{^+K<}rfOfWl&mz`DUy~K2S5A5 zsI!ustif|C#0B-Etx}z&rBN(DR7WT^_T(6+)zVxFg6<_LaOVj4nIrAH|IYFZ$1P)Z5LJw!)#exF+Q?88BAG6!j(b{rj zMl#$MEGFc@vM>T$2U=0AVi7C@Hd(S0V{`dH@DW;zKWjT9i+KtB{U4J~Q{lO|;khLq zM2gWK0)&m|FO`p|Xap%WqFM_88|;UsQY@&5krW89og2TJ*pP`PwheS^PYx%Y`b6JD zCZ!fb%bWQK{|;#;nTynGd6B;(;C?>~gZR{9BtrIv0K+QoOB$7;I9#R%7paOL!Q!ny)pH@XXX0l+d-6@O= zK2z>Dzq{8p17DA&Mc=Q)7A+s< z*zNlwMiV%&iLc$Fk5AjM4yb*^&O3~HVBJY=PyX%BtljfNu7S>3K^ z1a+2Ch*SBk_6~r)BuOCq6bh=2J}N~TW-0uRBOM_p=W4!0q1F3k@Agm*_>VT*)r9@w zbA0?bYKnpXRNO_Xun|>obH-xwwjg}`Nc~vjb(S>CxZ2%@2AEYjorY7jL$3;+x|43} z6Rpnw?L^1j_m8&T7qk8U}7?G4=?%VZ0-%0cZ2kxf5qaR?F&fL-q38+wG=+c=x=sqm8UN; z7s}&WH{(uo5a(uPU;I07G99hlY=vD^ zjq6qU`J`x8BXef((^ e;?Lw>-6`BikAok=T^KmL|DA)2W>ec#ex8&K@aH2^q1yE zYZP=VOVn^J2zW1H7HwM}o!@a!DlhI+DE$3hHbjHmf`)SZj|*>z>ZB8I(C7%WPPsfq z3dC%~hWY;f9yxH73>Q-u7Y*s!NhWHSDGm-vhJ}X4;;W9v?6E@X+qRV!WMRaH|a7p9T4OB)P{S`ijE-#3bs)s__uS9>*Mb zq}Rx`%4OrAVAt_gzIE9d6JJT#n1FbJoJ*Adb_g5j%Tz{)=*}?4N=n>qfQm-`^-J7143cWC*b{1qFG?**Hj9LiepY0~8b$ z5s;e!=@T*zbI;%nhw%W6kdP1%e7>_|*s3>m#~UMAtUSWZgs*EIHtr9~4JMXv(8~!O zJUFOGW%BzI4}%Ui{i9J>L>VoYvPvUL4Atw?rbe<8)jJD=^M(#=sRjHxWHC68lbyi$ zl>8ie*3pHR@T^SBN>G$j%}_Ysq^C84`?1Hgmp7o5Dv^|o3_%T#d`^K1d<<-+?j|#2 zE5-!OEnrYNU4=h7Hg+K2a4m>pvW^|XMwl}N&eRBfCd`^t{2bRK?K-?nbfjg!O6bac z#5#1`e}Qup&!2-p7dndp3$3S3l{PH8aM60fx>&NXz-nxJdwE!nWDPIG>1~PO>B`&p zc8F_5|Q4zDPC_w+0r&_1ox@!86P5$m?qcZti|> zkDK-Xy1MQrqvVvX7KsH^*-gAurGG<@m-YACj;AoJ*O|$go0rH_VW6NcLNL-MjzUBh z6&}FV3QTyPKR#p+LISsn=6@SB)hpQ<8T>9MI~^Sihljs-V%2F(NlE+u;`$2enXjZ5 z%*J1ku^b9hCFT=J+(kEUTZSHE;59Z^Z&!NW#Vv5zZvIG1Nx?!#-#D_=a^YsblvF*07~iE6@~`~0Yp7>(!5pgYJZ;%Xp%)GmyCYAA-p{PTK%2xBY3`E zS{?Nk?puCS;`)v4uiuZiFriN0^_zoCuDB_KzuTJWxe2y1@`^1khkKzL4{R3Gye=(Q z(wnvF70XeSa50iVHh<5o8Xcy;FiHs`RpRO&)$ef0tc*q%EjL#6$5Y(SSN9=zlP@ox zF$$9vOUF-0t_iA3(|wB&OLp z-8U!A>WrZqv|`>7yb=pfQdR{LB%OS%>O%Efl79=#uhOSODZec2{eHOLo;-q^Mg5U8 z|F_2ab9n8(Gt=pB77e$%?Rp5h1hPGW=iRH9=6Yey6t+Ggliw!B-A(**Y6-ZT<7Wy6A_<7Guf#X$>ZgjFp40h`dWAr6!u9zf8wfXpWrn)D$`ZU%-pE9O{h zHF{}Ztc(c!k^}l`feOso8AsdK`*M5xzw~m$!*Qx{L9_VX+7> zRDi!Fl@S{c4~>9;1}iEQnV1LzBiJU>OuKy(iH`?Esby@!oUNZ3z!QPp(!UuBfD`#} z*ccbbryPC#^OL_C!oo_|afEX7?fdm#pYGrvpOA4b*~T~oSPGh0|2#M|4)@%7OAdjuL-;tabt!BWahMLmo_0~)%Dnd7mJ>g4jZ_}A7j~R# zBx<;pf+Qcmh^RCm8!=vagbKs~u7ir&|Bmzz?<0g{p>m?Xgnq>$K0BG!awcU%!%NMS%(Qej0!l+fa+fMk~i_66?Qz7A1= zSnTn4KwVcYJF~E;7#R_xOJB366faum6N7FFOOI3f$T|w&;x+d3rZZ@to6mMEc3-N1OXb%N zXx6N<^YctjC#7uqh{=itehSmGn8TZr5Rl&bvi|jk{PoQA-^R(c;>E`1;FP9MtY|cD zjXXlYlPy)Yu4%CW0`E#EwVTejRt^Xk_qH$GWmSvZU?ceF? z)!rVf?FzHfvGYxd#F`b*d!GlfJNZIB^&gQfguQ zb>yPGp0#V(`hAQiNJfyVk&puW@-Q%wFNqL*GKl zc0{7J?c(ZmwjX?cmk;xr&0X9-AI^4zpqnqY>MJ|EC(qQsllSAs(9z7cwV>bAmA%b*=TvOU)>UctWt>j;TiyQU2l20*uN>w*gw;SoeA2bp7Mg1t zi;#idMo1$FE(nX}MnQWUpN-Xz%KGz=nfsN8g2FpW`)vJc-EDqh_4>j~qhIGie`BSx zFOhY(w|w4Pc1Ly@5~)_zWr-VgYuQ*)pJbNVu^`74Xs}jTf(6af>Vcs4%MM=O0@-}aQg zUQ=^FKOBTUh5>Hj&j2Wz?B`FgAaWi#TH6;p$y$muqeZH3)oR}Y#Y7*VDn!cNnR0mXyT4#yN05l$r; z_cw3)SyvgCYl8+`5{@E^kr||%Z!KvzwglKwu%6Vn=17gb^7klYy8W)uNAP-*_87f- zj&3MFoRA>A1O5zLLhpu*oQpg4TJ=8#25^vE%y@!yQDiS#bL^wS@Nol?Dp}#;cEdkJ zguMyPnocIM1cv94tcUQUd3!DXsJ?o|-Qw|xV&Jg5?Bw|}`moJYZM6P8URw+;nO8ra zQYYq7{hcf1cRY1yvpli4q8yqa5u)4BAX^o$TbZSIhL5k9E7QJv;FI+o$p^) z_xAivL&fDyyMtdu$SXv91hXiS`=i;H&N!89IGc5Ivw)SIgO!aRU3AHX$I{YgL*pf` zy`6(@+gk3ui{P*Ay9=>@^?zfbnR0*@(*5h!ql8<5an|9?WLBoug;Wa~plAr+4lhKn zSQRpgvi^waPkBX!(9e!5>B;*n`4qF`$xQdNh4O*|vSL-MS}h=a2XIu-$j0Dd^jrR9 zv0pno-`a_*%8u9hb|a)- zx5@rHO?jT-Pc@fH)ha`mZeh;9-gUjHV;J)m6S4|&Pmj0?^%Fx1__3S>0*fwAhf96n zh}3tHPb-DShj7U=B12XjvJtCeT6P_)WEj+ovdOBXCYFt(_o&rI_+m^fX;^M-Cz@cU zg}l%t-^+ui@MOR3-$$NknH&u~UySZMl@w7^4yQ5jW^Sha#z9B5O8hoJL_{8jfVBS-BIx|^yr5_kn})G7#3h(MuQ)i_88@o-2;sYGxO(gY+wKX;7!-37 z3?2m?1hw!0ii--GOt$n^u*SX)B_Xc|59tnsvkGBIdYrr{(7Hz69;swbZ&=TpA>deZMy3SEwm&xcXe zc(LjioAq6lwjW(StrC1G4jatl)~cbamKDinu5{`2(iL!1ip07Z-Dl$ZyQAc~PxiTW zPEAHHYF>*jzN;AheYPKS1e<~KUh{n`gcWlZ7ALGGX6qW}KkVo~KOe9=vz3Ca58R)0 zx_z$2mNkia4LUu2a!CM}tn^E5{iRSU4PnfMBHAOmG-J3vrMeW@Mz%f^!TYPH)Uk73 z6L?FmOS8aR{&@v3(VpA{?SI`3MwKcoGiqj)ZM)StxsE=z&e!$PzZ$Yp$HL814y?_g znd}vW(5DXs-ya=S6t|CwiGS`7t;@-#&_76E0Hf_R{@=|9@ zO0}z0N%t+O)(Vh`F7v;S_A?CS2^+*nV&W2F;t&KcxrGHOqheylClPRQGM-gvD%l_t zuV~a$4d4ad_N1r5I!ab2a655 z1%U<+0zvPzigV=}TL*_~pwNA1r)Opc#c0#%zNKIUxiYv5^hGocd)M*jdns}5u?SiA zD&qo*R}g>Y_l)Hz^?I54i)&g04RhE9QV z1#?7TBCNsjhyMegjt>+2=7A)P&Y{FwmP!wDFanT3_s{<1J0V)kASXsfoZQ%UobW&M zf6FA73HK4-Ml33!%m$+_AXF4KG(;|{bmYv=(dG9PpqKpN)^i3*><~2>i7R-1ciXK8cK%wP$Rcv!haINF2n4PuyzVHJy+F8dkCd1k11M zPgjR&O{8(o({zkmLm?M|ui9fz&GmlGX(sQVokzCcXUm5=zQ^ch#$qL1YNaI_v0M67 zzU~ZYZMKMyKbx+vXz5^Fn6ct8=|2~oE|^s;66Bh$YP4Jf*{VSFW8?Z|YPJ8*|7!uX zwYA;a3GJb!>KlRXg5S^I8+B+CWq^65QK?tQ;CC0D{=Gp*!O}9kU(x2bw5cQa4qpI1 zGx@O}+0%^@1d2?y0)4W$q|_+JE%3O`R^;NOVx%Qqb%^%M4d~OWjsM%Pr7kVs;xriv zYxaxFpmV|dY3rpR0r4h+Q|X@(R6QdVr>GVMO_fG*10G_7202!g8eXd^!*^@UT^1vN zSE5QBWhqzH*Vp&FU&$Y#c{?rHUw5}vl9B85y&FoYS~qnnR;@~)J>dPp{3nnCjKuK} zK12_`RBhY?yxnrNZ!bX~7*{GbI4Wg;fG5I8UN$*&o(+qydcH!dlb=2^4%enGq?W#V ziPbvA#6?oW!W1WndFH`A7?m_UZNqTBgeD&{a*hsBQeV$o&28%0iVY}dN+QU`A>!kt zr(46zMIp>ZQLsu53WFi)>hjSK$6<9US|5qG2WHjB`w&PukgM&#CuMyxX7Dpk{G76YxDXg5JKXd zKZHW3zzNMQST2B8O-jp*b}(Rtt_>B|r`=1TXzc`8!)0Jm&0$bHB(%4W((?T!V0B^X zf0ArYkwt9UBf{6`W22J6g4`#H67Mct|Kd)xPdE`LdgqB)fgmLCP{6~6?RNV?5#D-e zA@@74X5WA3ACSz|md8R^1**K2ZAPH=Azi`PZ+#E7WIKE36*@P~)l>>x=GL|ZFKqo5Hdp87A6nY)jE>itx_vw!cC+_2nbg>`Y4}%bipzhVhtxxA zPG2xG>9DiJL^T9YQ!!u7Q<`I6`3XG_bEJQWDY|A?4 zhoEN}7)d`TXkA~6zcJ+3R3>HecsK;iMxv5Gwo*P8lS`EdruCcGgjRgg&U@njieXJo z*$e)7ydFw`NkbKW*kAPtR7#BaNTqPd)JA6ssFbw%#&-2qs- zBnkk&h%QmaloeKoxCf80#1>KJ-TwqsVjY((Kw1dCJ}^>FgY~%)6%;0lcff3iW4ta` zm^0YvWXc1n$&94cgF(G9-`v6P&+WDgYe9qB=PZNT$;=~yYW%jW zQ|l=YECnqQ*}CxtTOF9NU_Z0U=(__ei-$Ae|XM%(NY6HEgi4POXV>Ia~?^pQpm?;Jw9@9U1RWX zM!s%Bm3~sOF8?Ywxdg9(HmiU{8+Ybr3ysr!U0UA*EwuaeANn7Tj{hRzV<-)TIMB0cca}d16N!yh^}l#b25_shBbwN{udZGx$^KM)NJyR6$7&b}YCAk7Ze68J z#kN=dvlsB3alAD4H2GK>daXLnbk}QD_Bz#@Z7sRfoc?FW-O)dMt3D|D7yh}qL#j>z+xF+8kAF+O z6Pd?nr8%X-q%ObTSFaB?V^*8{vGsS8%Lo(oilr%I?U$WT##yYZovy0tT>Ufer<2^T zjkjq4*mEb|vb6JgC?#$;SD4Ocr<0Vbu&UB2R4)&KHG)c1DMqErVDn0ugGHQ7Tj*zA zTUa=dOP$_)-&+d`a~~V4V5OE{``zAUsyRCwO1}KpU^A^Dn>7Wg^CkOrUeB?E>z3M%$)RgW z$?>ve9a5)rE^SWU1&$<9+WTy|1w5X9YY&0MB!0K0i*lf+GdqbxkZcYQ%RV+L4tThQ zM<8n2nEvgDZofxO`u!hiM!@4#2C@#WuOAjmaC!uQg6HP|drW}_2@MIEcL0OUnL*^g zHY404d_(?)?L$MM5wWlZQG(K1M7I2r4 zLDUDT%nXisRhSbl&ff{e zTT4ONHMp0+i3j#ktU7zEM-+e8BV$p;F`7nQwNs>m3+8veawK?=caYe-m}ubZ!}&gk zleiFeDga6hmlkcedhYjb;=fh6X{a9^A1Z3MF?()h71h=@3}OJw;}3PS5)tEeO}F>v zY2o@=Me0AT+!o)zKVLB1R8s6!VvQcT2jAr<&$Nf^#!Z^4W0|y4wSF+)oOHE@Juy~p z)}L5D{IRik^1i$6i|bSpyccxvdAfcg$xIr!{xy1QR05AU-x!&hu`{C_wl}^S zig!o%zcU%=om~08_lIe2`+V)3)@Kq{aZPhwu61yJ8>35z;`jJr0vp9FHDJS@(bLld zyhB5cz`(%z`uhoE*)^yVNl0nfoZnv`Y*HEZJFMo1>Mb%$r$-XT0_DyBN7Fe5*V(pR zICdI0X5%!r+1O4R+fHLNwr$(CZQHi3e)sdvd^4Gy?7w^Goa?^Mwbrq0OmCkYkJIOd zi-80MY?jL~ru=(1_-ghJtN!5|gNMXw7Mjek=~QZm!QsXI@i!G!t0`@6FR{_FRY!6M z&Bc(vbRBE9$4!HTZCU>w=5_z=7yJAh_W5#jQCojKQi}cayM%JZjBSJ!E^I07r%Bin zFbw{qCs>h1j9AhkX$}$JYex>}DlR4p$G_Wb)p_3~oI+bzOlR>kdmW+M5>B(8t7da; zS~Uj7vnh~7cn;Wz7U!Dz&sxFP*JsF9B~U3lM5gu5Eq;4>`BB8NwGBuXU z2Pj1mkkXk6cD@giI#b3t+@2n%|&+?&&l z&<@{$c}lPTpg(&&I#TE*gdc}hAVe36V+44g9~doeISMjiOys;jH{=_v{vIK%FPG%7 z`6JYl(NQG1tgRlRXy)j|d_^<;UeRX}8~5u@c8rZUs(^d}4EGU1yr==i+uc540KBQ;yQO}jaj_SUv}UQUa< zzpA@GFZsW|<_GVS`zBQzm8s!i_a3-9Wo%h+IXa_EAOjPQ5j$k%l(-7DgcTAdO&o!O zVnGy(NG)=tOfK5;;UQG{0w#WDd!VCKmB_#5~dAX^+sFDxULaL2LIPqxTVb~H`5Lasec>wB-!Ch*D5+?3Mbje^xR`|5$mUHaP8nPzb7?8) z<27ly{ZMTW_Sif|J>o9Qxx&CAgJWiLa&mlpy}y5ac$k}#l8BUa1hCy~Z?m(oh?FM$ zNWe>^W*~i-I(fvam{FI{MY!pZ|4qJ-2m@nRgB&K=^ySNA#K=Xn!+{f%xj<|WEySh} zuaGKY60&Fk`LZ_;NeWpE75a7H#V8M32k}Q-B%|k+|5f%6##B3K2d2&o{J3a8G0w+G z0!YA_KH(V;3e-*UJR{Ij7G;v~T`&@KrU3mkB2Hdb@6jI>@fX4Y?8G&oA=$ zUJVD(bf_s3?SKhkkoqA|3D|@HNFkG62fzD)Izc`bBSL|*+Nn?)5f;psE`P6c4%)ma zmIM-xf$dGh7c*OWq-T`=UmGVJ;M`M5=9hoANJ zm&|jtQbj{*-|5?&Tkl*qmm<%Z*eY?G-4$NOQl*V`9Bz+p$$m5aIh0xHwBFmg)Hn>} zR2iIqN}ejA(e3DV{WDnw8BC+Pq+;E&(D9rO9Gn;48*6XIrpNwORl$|`&s$Ait84bv zji0^iOCH%Z7rG>Q-rq*Z^$@o{4X^tN+X$bX_|C1oR-dkZd7OtoMVV%9PHzD!Fj6P| z*TU<|V&@S2@EtC-T4tHH&(+Hk^RQZmxz^@F&D+3iBQS<-c115+l|QPpGJE4@=07`{ zj|bnklCM2OU7B&lAg+@1Xp{HF-9Q5Q|wVgsO7Qi3cSZX3Gl< zBw~6t_xj)^?`%BniLJE~B=JWa!a{1Bthw)ja?U5tE`VbP=&J~DL-u$roU8J}ki9CO zG`~d5hKTomxX&xp0RD3{hoUSl$EKEs0i%Ufgu7aWu?yI?vbxvhbXi?=z+5N+N$aa^i?T#yf$*#VS4N96}b5gu&8N%$igt!v+6pk$s zM$tl1Tb5x9R+e#xjH!_t_pn3rDS=Z2>a_3~H#PLBk6|Qsxy8d*52UN@>gf=LEV@r^ ztkIJV$ReK?n_=Dda(MQLV@}%P^Z>2`;ZL-U@`f;z1rem!QGat$eTF$z-0T!|UN=dT zse_1wh1!r*vR?RI>Lg`p4$cw(?#{=1ujeTd}k0G_13y5WN) z3%G*@3T9?7wfr&P;aZxoMBxQMz^tE05MJ8r{R4fOP$+I-2kdXYi)4u!)YS8RRD~B1lA!+v`z~3fGT(!%k!_FOE(egj~SU+bYO{ z9Y^B#1GyH=fm!GarjlF?>ckL~NE%OpI3!LGAY)>uAz>>VdGe7eKoo~Lf-H*;qB<*& zkPqkx6d8p)#d~_-&`l(gId^9 zV<{|hvXMF6=r@)+qgGS9*3ndGyXY(JtlZu@x$=C;eU`AjR?;u9UH@!~61&W#wZ<2s zq`7@Xu@(Wj+WvdtVr$df%y)9-y0v**SN~{ix;~#(MZw?U^L5PM^>sEHNF(DhwE*;J zw0GrNxM?5Gy@At26KJj2nVpvApHHz{ce@ql9qRNi)6+M2`_z};@BapA^zhIDsr$`+ z#m1Jr#XDtTO2q2D`%DFi0IVeb5FRFc>-lt*RX+N=9=Q zoLWWf?2Nc(-tG=7HCfd<%8|v1*Q(#CUpM#nWb2Oe^Jq&Iy0dn7Ck>E?qUo{e#fsN1ucu| z%g5J0S6ZBfx0*H(ae;Lwo6l$3U}JEUm-nZtjyLEepf++A&W|jhhAqQPWG zHdu)MPy)(2529@^y&mm+6oCx_X7aRFP)iHKHM8CU5hiAAx|FcQ+P~NPRRE1MJG&$w zDlR;3CK|a(T5XD@n!hxnVv#CIJ3r@uUmS&x%Vzynu%hScCM@o`R}$_OdA&N*U5)I9KY1}R27 zJz?!0ahW76i!bkfYQKFWWQmBQw6qwz-tKfbdiaYGP9dFXl$~Xqo~EC{ILpM|-{t+) zg2uW|xMkDg{MZv%gdZ8ad_^@;wZZA7JKIp_H|lX$|9oJ2y_uz?%FxLK+o`D=5DAL*H^Z0d)6dS;rqghyD8Y=Q z=z)#A9SrY}#852NPV@UV_~j~@Oisi8A=YHzF{;CSv+tKDiMSV2aQx%WCG@p~}kOF#J+o%W6{E!k~#%d4okSDo@-KQIA} z95GIOfvb@-Zuvx5BV2i^1fxQ9l=4usHBDibr%+!7u90-@#Ube6x8GJQVPR1DQTyhIh4Q74$ji7ZCn*dF zSE)S41{RurlQsy^H89v^R1)9AsTgK_b_9BdmVuEH^ykCnuoe_H?4^vq-L5?yY?ZF-n zQtkYGqlNc+)?j%9VDRPj#3hgi1@5j6zS&>*?#ZZgDon%r3`?MveY*vu;S`RjBdk%9 zm)qKgk3B5n7>nAJ8A@>l3+0a*_P>(8--HeFMSr1mu>PEYqJ>;J+fYUOAx#$vgVYS3 zaLb-!9tMN6f}BeVqYO#uFM@U@w?Xcz%M;a2M)23w@3fP24#LLr0^>%ZrxhhBk`Ni5 zJ4<>CrVY-F+sOUy2Tb_ieQ;}rGpCI29ug6kb{8l9;2&N?FRszphli|lUMIf2z?3oJ zJl^I9+iLT78@``So|{%`GI<+tWhYL_$uOCSGNmUOZFBjYqz_|WZ*e#k)$WY+E{Z+T zmThuZw;3IE<(Xq}7pY#Pv{jp}0dEcil>#1007Rc3cJO$TjZP{b_jrSi{aj=?bhkz8 zi;lo0<|e+}`g&GFr^j2>au zwlSHbbGPFb(FyrLOnUKvenhGhd6!GvHy@zP|E4alh+2*04>^ z3D(2nL65ttG8MQ4nq{s|U)tImKZVtPtBH+Q;x6JYnFRe7?(4r4It^Wv&Sq@gb=~Y5 z>l~%J1^hdR#c4@ZT8XKtt<`xI4!Wy_wO>%TLcpNBtiWWRiz&lFL+Zs=z!xj)^HM z(`JmGI+r&z|NoD>d92e7>Wh?QHMOeO(~zRQfrCgjH6 z9w#m+CSO?!1PX_XEJ$(EG1e2d9?U+>HL)Ib;!s}^aLQZFk6FO~hb837NJWhrLXn1B zLvS6)pTvw$j>AHPn=Mg-r)~oCNg?WBfF(8>V}&;QJKsQX>f_(pkwZ-I?O@#2@~ zBZy|sk`@G!ctF7E#f->RCZ2Ot3ef>oS(khp7){;YbaaOKc}VyrTrO|wt5>vvZsAK+ z6JvP8lj8NV5r^ayX)e~94<~P-YSGi1tqLCZ_ha+H%d8i=3hgd}&Z8H=sdb=QYk0PM z2ie|ym|&IaWV9U@=7(K=ELxd{*6MQ{R$e^5-TCo>lsOH|!R+E!Mdzc2<$Cx(DkGN$ z-s>~Zx7_p5;3|*HZ7px7&bHg0vbv5@=%=Yl>QqIQjMi==&tLkI08*io+ri?Q*2}eh z_b{LNx~p|{@ku@)hTi3eKMqbI3OM@3J!_4Y*ekZVQA;Sv>a{;bX=woADf zo61aJ*-mH0F*pweaE2dMPL9)5^WvqZ9HEiUI9X_o7Sft)1|nb zkDp`GW%BymPApDWlNOU>Pm-q!rD%ibqf5hWL>g-}YLOp!Gpvn_-1N-k_|D{H9(vgD zd#C6sTQvL%5MOjx;*d#C6v}aG5yTX9gbHGZTU8XoSDdah37Z=?)FlM#Ya70Wrv?l#iz)7eK{{|de%%zZYQ`0(kMD^?j~v$jXpG4!!>5WIxr|^ zYE&eX#YFXknU>MKf_K8IJ{=IqhD{4_WHO4EVJL~Sy_UB74GY@eL#Fx8>7~~mpYCq3 zu(3|)9V1TAL;c9&fFi6SS9kRm7N@PZX2mpbq>hlQ=yCsrOuWELuSH!HxUKRs(QmY@kCFi{m5hfrPp0_4bH0 zl!I)9?txzXC`hbvFojLWsuc_vWdf-~*u_=9M(CZ2K|Br0q5V40J9mvi$IaA*L}S;H zGP23QvXAQ_46D83VB~0I#liRm+m}5%kUGIb9V4<<&%d?VVVCIbcIT6^ z(M!`aHvDoed%NepPqO=`j@x@?W} zRp7KCZL|K5jU@FJmP##em0hLvp_YwY?*jKSlIQbcV-&j!pA+BL4B3EkW4Fh`>MaC1 zuE^G^*vjJTgO`|;?eFn*+b&O6AVB$cx0i=eu4YQFnbG0!=m(3YgebZ;KW-gSt>z^C zGNvMhE4P%*<#9V2p3H1Aar2CuuL=u}rFT@Xmv-Q(q5?PHf zK}^10w|UOYEHF*+6p>uj6ghB=cBy93av6`Kh2KkPV*^qNKCJn=v_h-Z#_(+bk8FIj zAwv8+wGvE!Afo$J&hg&5E4+TW3s;+=z(h4GVgIy3 z+0Hm-)0FyvSDsIWFN}*ll((oU1P(^odi{ohjbwXu{dqNao@B^QXY2EjbFl6rmer`d zeEB;ob|5%}*EnH8k7XWCRG7+46cI^R(n9Dcz#fevayo;-=3)g4xw@etAs~PQ$cY1b zbIdt#)dI-u(Rin91_O5V^hk1Y&wy#y)xE9XniduE2j@VpwwG0inBlk6LXmIGRT>vf zutxq``>!#e5AIVY^)Y1FbD&r>@G4mZ9QVA2=85F>Ord^( z**>Jl$dFnoa`y`AJ&@1AQSwAd%&fll!zM*qle~hC=Gxup65)=7Pr?k>`pSYi`cey- z+`9R3TifA#&qS%9-VUuYmO%eS-erZ^$2Oba(QrOB<1DbZo4wgj;H<-43TMoJ#ri zN)hoxcT$e1QHi!zt!@vioo`~x%S#VueA~vnh9@YRo1>Y4a04RlW%c!p9>FfR=GUmd!9jo>x(@8L2Q%E_ z4fm}yH3_J{eYDu;mQn#g@!t)0!2e1h&w>#;d1A;RQ>+%9G7LU|m}9M5HA@S+^%o}` z=odRds)86HYOx}+iyvn6ks?8}ch6L;RHUTBH${NMFju!YEhD3t%B0)YZR{*@9lC(z zn!+MM{cU9urg{rCrME*BNxfmAZ$|B4rL1ACVy)y)JLYs_<~;aSS5bnhA~s0;mYZU=S{-5j2P#B=I5GOx{3%%rtva~0;O+=dr*}c)e#M&#j*{R zx=BsOGDBIH_hAmEm0BsOsW>LhH9TVHu2GBW6-h9antdf=6u&It*d|KLC(5~FJg!wA ztLn($O$*n|BUy;#i<0j2-M4zigoNC94eQeZnH>-VjbyPXT9o4U_xAGRH@c6O#2p9LQ>I;GnqtH-<#K+D3 z6bESf5Vp|j6c(_2kpmQn_)ysb$evd3Fm?OioKOXt?$3n0^MK6!mu zE%o0QL_c|9x|ws%JRuOjzxyD9iZP^$;Gi}q6c8+HWjG>z;7HvwSYWZI% z3JwXpE35p_d3&KX!Y)h7KoN|*<~qQ4mKPAAT1(17%3+s~9K0N&@BjAn=yZ?8q*pR* z_bk(jtEqW~$EB>Q*k*P|IzAzxKVD2`GHhRNO0LbPaQ84ZYy10*aC^h&(n)`QH*)y7 zx@x`oV`gg*TJm@~VRF6Ixv#1NmbKmFYMZl=hrZtG{-ra0j^^IsPv!JRtM^{7_PC99 zrMZvCvDb8c(~{UfrTFcB%lE0J%IdY$`eueo_v?aB<5lkaxMeyd`c0OqCYE>k(-&~= zcsfGeg?sD$?vI$%gC&gAOEL!>VZ`B)F-X=zktFymF5yf@ofRGfZNdD z4-88*e19;a?;VH$TE`>1jQ0r#MXDQej{YY(tS2EEmOoKn4~gG12^=d=Akn_aSdSx&wBagI zIJ8c9yqE_kxr#wAQ3HO=WyeqK$RS`$c`@og1)o832jg8#v_@)+ldzQnX2*TnT7g0-`MVb~#2WIO6$lr)SQg#ZElSv^j%*Z_5r+=iWCuoHOStD6R<3ejQn zUE)}AVK9HsPfxFnAS6e^E3TSsdC0n&HvdD6>1+NHPWc-5$Ai)MeoT5v9R>=jxw5RZ zSntz=RSFlmZg2OetI4zSW4I`MEzc5%tJHi;q{K=78cQ4J(TOqqd1^RE>Lyb)t8C@d zmdi1j@(s3H151O79Y6kNo18W0VV%qU zJ_Q{MQW0gKv8K;91LIe1c+peswKNrtTnSG4s}x;Goal!EG$J<2y2_08K!cE>LTSKg z4PeCIL9b(%A&=h?R4zY|B(~@m{1_Dc+r=2m7O7~!lsd!vcZs7=F*PP8COzHbXf9Cc zcnZ&!%lT|075J-SyUzUVB2}f4m7UL4Rw^_>>VqmWBX=>%GR4#xs_%|yC+4~#;CO); z7G-PjcYl{x%jLAK1;3}tqns_$zlUUcpSSz=?61aq-7angm6*iuXeKkimEB8&3^XzY zZEH?A@-_QMFmM9n6yaO(Bf$C0#0aaErN*uQcmYYRwU&WXW{3Y&X7PyH)kwgCIAmHN zox(9?w($NMdAi+ApO*=RM8E-H3{ZXq{n#Ac^a^NhRuk}@5rYy!Oz7PfFIDCWk}5fH z;0&Ph(>hp|m4q?E712X^gVM|ZNt*&={3gy2b?kOG9LN-;4WFuk;2!RmyJ-U*I^?QL zO4VB=lY^Fn#19)9-e-=S3m%bPvY4~Wp?|kS5%UR482r=Un{a_SLpOx~y9_+l4f-!H z02jUD{fRG)?JDz9H)tT#>I=eKfXb7q{^mOi;*>+Jpb(OSFbZ~o)icH*WP;@`48*i# z=1uBXZJG^LS(c3E*kE@dX&^W`RAD-PAZKu>3mk-I2VBtBT%=0}WuMPN4Sek$lduqe zx2;PAPadB3yM$>A3y6Ub{gmMMQzT0q6UmDqTGkiVf=0S~BsgSqwe!JD7LRZJ(z^r< z^y%!A^pxr?c7k_9jY?t7)giTaqYAMyh=+1lY%ZOhZufIl>&t(%xzlxH(!GoH4JWVM z-ldLV*y8-C4qr8l*U1yCCs*2yJx_z|4}UX_H5*;5F;xAubugR^qOT@&|J-v>dmg{a zs)o>R-%pj-yl`Eee^pU?AHIpv1$TLV7mL2aFWv6eQ?pUN#c^CcN;%t`SgT8YuDWz} zv-NpDm+GuU+HU5*w!jQ=l$(y{|F^sTyh$I>%VK-g)CkCB?sJRx4dutD>+CMT#{b`V zcGuU;;@#QltL5=Ce%YFQo3-q0(J3S@K=Ebc^O>K(e}%tmnpm&**xb64!C)PvNJrZ8 zvfH&j@29s}u-#;#;SEiMdR(6ClZNe$7gqAM3P9n`ufO;5r6(XRi5!Pg2N8i&BuCyK0vfgOil`~)vb1UlR5R@()z~d-pkUX1bKeSoG5Vn)3H5p z1*eIaUu66_eC8U({=pNJqFQQPA(1eC5a@_Oi|Apd3?-L~E zy}v=h%mCZ*9bA}%9tqh5J&C=75iLL1Rc`v96DfovPsnEmpf?wMIJ#!0A3@NN4pc9gZLu#P1N;i13 zMWm6uQ8QE!Sr45%Zvx#A0}|OB=54n>K8ounLrTz#B%?A8vL^`HH~$4|n2i((gJwod z(Hs~E?6q&2jC%e#6A84TF#HHa3Bf_+lpE@-}BBf_m<=fr1c7IHADhq3LvTNI`i`qzkD3fh;a6Qbe`Zv=Nx;wq! zsJS2!q%KWfmZxEjtj}kMGoT`0cD=pWd=`DX44T4$YI%Q5e|M_YZfp5_gkSGr!OzY7 zcF7(gbeEjn<^FmxHBV^M?e=-HnO?2)#c0&+=5;-NZR6!^YT-_q-}uw2M*lwabgcaN zE!)faqgYMt>(N&Cb6mH}=l<>%X?xrKX>Vyg`?}l9@!z6Ukw3$}v*+W<=J~L#4xi`i zMQ^n2^}mO!-uvrntyfQr>yoZc#_}qQ_9~v*d^T2kT8DWYLD{#mySRY6xl8DxcHrU1 z=klo-DO=0^=A@5ZSNDJVHs$g8)s`%qqWhtvipR4Boh~g{*;b-NN+AYZ?kK(-0T-h(NW83vIraDf8*6{w!53M#yamY)lMKm_?#U|v{3G7t3ZEDV38YfkShS+d|b z=~KXhsRl#^3$fPFqfUkf#h*x@M8M`P2J~@oTV?+V#*c-Dyg#^(D^} z2`M3QPrC!(%?_yho8VMtJ$c|xWn?D=Mz&~SY-Yyr!cENQO0$u^0(MC0=W_q**{VgL zw}LF2o9tF+x83gp{1hkoWKk+U{ z2~H=lY^3llHn+B8W-6mEEseUM&-VYYlRcd7b32E6yh+Lup0?T>Kdo2Ob$GcQPnNew zRDJI8&EG#q2gY7^x4-IsJxz9hyiWC(8&VXNO--_TyO}<1-qZNFJ>MJy9>b3-fWh%~ zI=ODE)9v=LH@SISZR`DfiAkTe?f(2UD`(s7`3_f@-}N@0Zu=jCV`pl%pZPMg(ydWt z^sUUA6(jU;FkQ(2!?Le~#GfbZeyN$oh;_*{n}hM=;dRp1r{(c(GQYa3_3oy(SdJj` z{V83lxeDLHb}C-{6|X9qFdC8&{BAZBCEi8=ZRh8G3)`J)&-l*SUyD!}v>Ks~zeKDd zm?DC*Bly&bW9#ed%gf9BlpIvnV%kcMns487)pyR$@NyI+$)v-`AT-F+#D4~`2M+I3 zFT$Cs6%Sa$8hVIMXK~ki7?~+u3ucsl*0?%5vqN);eQ z5Bo(DnsO^DIpCS=yFdJB%&bogM$AsaL`vf!rmtYLx3r>C{zJ7oRIB}uv-HGUBrZG9 zZSUshhLt5lE;zJ+>}YLn-sSnqWVUo7<*UlX7nE1Z$EULu#3TnrfsC1eOb!hOgNK0L z=I^Qe!AUO!ehx+lIv-L5f@7d>C`KYGbz&3M2=hLIpvOHUFoPL{0A*xDO%!-_0a4VW zWrZ9KP5d+JKG{{?f5o~YEJqLK)~Q9VXV0DlV&mU9tRcz~W)fnVWyEq!kODu>2?8(X z1;$@Ib@&+sdA9FzAZa*}T$CXa;Q0)wC$KqfB_GAgV}U|L&ftZEF$QQviIT6LeDNK) zczEBx7payb*2+7KWkLTQ4#R>b;zN2TIn9W{83&oC^3KS?mPMK|O_UVW1tWD?{41-?L9j@ z+S8&5SDCxo^<8wGrL>>)Tr}dVNEUSCQt>?8Z9Zlvm7c5c-#(Q89T&SJ$(a`qk3T&e zM?0BD{xOdFbAe?cab+ouWhQY}6@FeFj&HuorJg-gD2H`D&hJrhe^I+d&zJo&zhBSa z-T8hW9o^HY+v)n?ApzmI)%kh^oEq0U8=jy2gKGR*uJ0Fj(e$<-BL@`#e)BMSI-Ae) z>0|bsUAN2Y`LNvOIlHqh(3P*q_&waCI(yUS{$VS<_<8Hg?)o71inm_{u`Qu&j`r>B z^6_m!J1||TDR7`_uOj+Ehj4OBr6#wOEvcjVLLuP9NI?!SEoMv^DAc=a z*JI<#lhxkt;p*zDq%@z1+Z>g}#og-jb`dxY6$GV$rwe?kA*68FA5RI(&r%C%T78&z z5G3B>>UIxjB`*WC;KH9SSDROO=^7ZxM?*M~h8W0ow0&Jl%(&%X8 z=ElCmsjFjz-Dz_sfo*B&>fT0oqrv3aDJit9_D&i`nz2>xw{{N$Mrt9_Lr)DT5(B8I z$|Uh{B0^Dw$%FciZr)(A43z5l*)^pV9pb;0Vmq0=_KTcx4VFl4BFjrCfnF`N@W7|1 zrk-=)(5bCqsISory8$w#D{FKvPFjCSmbbRDe64ha@%h-+G0}Jkme<#D%`>prkxO!Q z85l6Z=!iUYo@r_f1BL#!IM2)tcB`d>d{TJ9cs&<{pMu zS6g+xTTs@&sx-&OBqMn}oc6XF^QXJMF3wCnrY0IEWKN&HVMae5MLiisJDW0M$H}a} zYsR;o?X^9o2jMg$EDS#`3`M&fWmLm4ECd={ta>;!sm30g1=A)wuDQTFMCWRPu zn#gU+smTax`q0X2VjR-pGn>k*mt4PiwMEy}FxN2_H6vhI~i5yz;oY zk#+kOiYv8uFuE_nYLF`WQ$MWk?bROLfhrHz&9kXiEI>l?piU!8wQX;ao=}?StD?P@ zgG<`b*wnOcqfdmEnQHV;H%IaN*_e^cEH&u3Dp?q+M1XX!4Z-mE@cia{M0)+#_Zb3%yH_a><;qi4`vqdgc2x5~lX&OL9!G=MW)_bA<>A zLeWAXmk5wv;nMI3SX=d~d+57%Y8A*!rp#z2DwCUPib)oLl}1o)^dC8Pcy(eatoKKb z>$|nIr_pH`HJRn6$LCKn-S2%ol=5~0^+T(jm+?OuKRXj2-!|&v7La{(OcWf> zGQ6D5Pa4Dfv$IY(8r0fdT3j7!?CSV2OE$N&=GIeYeq(aW6RxYZw-&S6l#n^sb?>b3 zZO)dq)r)c2YNftCmBZ6#Zwp}#12dvFP0;OrdjcrJJ|C~Q;c6~juTNvoa<*M=?+1hR zV%55Q-p@~??aN51Hn7vSod#_on;u_&RFA_VM*r+S%b|<;xEUGNGPl(UmJ4JmmdQ_O zut%y^Fw~T>;=2ruwKBM*joaN2X*dNHlxhnb8I`J~Dk~=`>150*re~Lp5|XSctJV}0 zvJ@4v=H|3YDrJ#i7hwXl_zB?gz8{2S1l-@aZ)Lk)fkLQ5Uf_aKxb`1+QU_d+!~$Ul zLR-GssMt}WmS{{-)f0C2aIsdLn`2Svjmy3%wXM0dk6v18;t*D;C!AXJD10Di) z2624k62O`#~_*!oqIXSJQl*jsG4h{?ypMck%v~BaHTN&A+%U zjNL>W+_g}nZ$4DqmE`A3-XAux_e8|dNcDW1v`?R#Qz~!x)h>De=cwQi(}b}FeSfq)= zI!?Ur`Yhp)KK%Xe(slMgyjfaH9{u|d4$z}Oa^(d(* zJW2ECx2NRBg(R7%h9{Q|lV!@i_StUW9aT@unpIV;7SHF$%HziVSkIf!KeA#^%0RNN zMT~_l3?1c#l|AI>v6i9lN`MDHxN{QQ_6frlcvHBLA zKWjFX&Ck!s7@Lx0{}p~-%-4>Eirr~0X%(74uNE?ZN}$_w1iu1C z989klPR0|c_%j~9)te8lP`wJdG6D`C9~aoj_1qrSb*leOBP!G)jvoacE!eEIx~<=n zUIJurfll~FE->s516VntgBO@Vp4j3Zk5SFTFn#MW|M~sxP0ok@WXI~R)YrT4eM}^2 zHjKgGFs;@pJSyEEN%b7wU3mPue@CYI1zP`nmM!2*47S6SH5_ufl>(;4SIAWD&B{xB zpb5p+$<7W$kzTW51c)W}&4`(-0yC6M-`v#HR9pMUNo)7$$PWVhTQH>1zTwH&pusEA z+xJ}^&o07__5iV+K2JVfYgegW{ZPyJH$jn<4o_-~{m{c(*OTSI5Z+vQaUr-4znvZ6 zb^>J<#3-=B3Km$)LxlBvNIolsc?OM{N*WjE8v(<9i??Bvv@-sGj*6l288?*hVkwce z5&n&DRCnFR{CO)F$~Ki941ovswbGVIDpfCS)4ihf1n45uPM*o6F z^sO^6>O0pDDhj*2zB4`S1@qomfi#Fc$5t!h8XRc9oJ%Gt=-=sN**~=!^l~N1X=z6B zFKn^!frr#;!V6k!%eB>Yosx2KZG38p&AO|z;^M3Al+UBxTKM92If627E~Qpe2E%`L zPY)wgvr`4JQJ3w%(cW>J9u{q`mWL4+DI!>`&n+c+8cdf@g%KS+9*2<{w%!e%9-o(e zyzQ@x)pVJh#dS7(9-nsa)t%gF&;9=Ga@o20%52WovP7byT(*KL znudN$ODR_UcV}mwnWLzp*@eY!ncg*Jq*#HwhID|VNnBZxXT46kvSyrohoxmATc>2Y zhIV|QkILEvwRMqda%K4>EP^8Tnk#drBmx;hs^8i}%a?G?S1>cNi=Ujn9b(#$K`lT^ z)>|7NhgUFgc=9X=v_+1|k&a=PVzvdRLOR)i(1s`6M zI0MWq+21!c}NR4l4CriBlV z`;QsZSjVF&kn2blyL0poizd&Rn3V4C>g(&7=jRmf?(fsn(*Zm=@cz~Fiz3_eZp-7E zR;$JCc5m?L=twG=u95BL+;}``b!BB`eZ3ur4^UmZf})#yq0f(pS^Pv`5G9vUWqZ%f zCTM!;fQpO@uq=5W6n?=bD38bc`}?P-r~7;Gd$OG33CyqxqLd#WfzpCTsaie|IRbz5 z*ojZ8iHMHuI3g+xU$9d0$Qfcn2L_@dWVol$uaNCLKfff#Qe$4e5izj| z$xqlTI(dzJmgLA@1Ed@re@(#(w%h)=AjnX3pHl#MtRf!LvP=N>$Ts>&)(am)^P7!4oOLet7O+v9d{pAFfqw>|JmK11@nREOXj^6T+2jBPg>^=KO8zWPI3nP?o z?&IS_NJz*rtcSpYgZNk!D_MvW2~d^kQ69KBRlW^QI{e;NF{$n_VCy3EY7 zcevlkz|z$K@D`7|cN~hs=Xt;h7Cr4JBy?q_tj7Mph6)K)%0gZ1dya!KhHW43;z9}mNFNy-oN7^lO=bCVQW8d`1}+8)N|V?7QdU+L0BZpV zH>Rehl*@!(4=D3>4{9U8DN{G16}zIRT3ApC|?dTBT_&j#s_jf&A<--R0Wq3t2LOh)@4bHPj-0k*-sor+v8y*JE} zpu0TPa@HUu*0(_CJ_!J13k?nZqdag<#a9<5-uFTvQDP?ne4I^{mJ)SpTlW`72nTW) zR4$B=$R;RPtDkVvJffplcw>W-3fMj##8FQXsw5KRy_ zk)+P*@T8(7<}k&fWTBgAWAn(M%9(KMI52SG!}~xvubi9}x^UWpkEOc1c@agB!dDqZ&byL-rItbhDKLK$}Q>146j0$ef z_1l}bT~mH7kK4VY`(>A`uC{-Blkv;8-EQ}QvtgUx_4#A#|7g0V;K;hJ9ou-5iEZ1- zB$?Q@ZQC{{P9{z!wkNi2+qVDnUHnz6`l2tos=N2zXYFS_n64rGVFk+aGqC&jw)Z3k zq|e*MZnQb_R;S;~aSO7ZkNe@;@jH?%yK7@nGn-A#^5A*-UgP0JcV<*bW)y_4tnh0! z;_8q5b@T&mBZ#aeC*uO2PS)(IFi@aYErqJOpxJd#Y zfBPf(GQT0l#pDH(7%eaUDo}awQ3OTBrl-->tX$4gl-3-5-}nRl&OCk+}bgWnzVXuct<3 zApFRXpu(&r2O}h2*6uT>E&@x@Awy$%P$xmP1OrEFu^XElUs(FBu5u+MyWVBk-wxo$ zfTt3WNHuCwFE8*~YrhlN=OZGn0}ny}hI_5aJRR@C^gU_oy^+f`PLVYDN7eswV-XVW1CnSQ@A{ zpoKzU);o{iWHAXMAfz%2Z+IXtgYC1z*eSPEo-2uUhAREsdA72q6eleDH_VqMx{_OAb{&l}yq-1m9eq7@%&jv)>(O0PZrL%l zT~Z=n)RpQf1pQ6j%pAO;{I!y3Y_nKgD@e!{|Fo+%vGV_OQn%?8Xi`hl)BK~OnW$AU z{YpB5gb2U$_R6BFgHW8T_;XJXdetCkNW}7=I`BXTvSKzj@!L)X1OzZe+0o*>+Ly&F_p}-vd_0`3%*?g9S#DnUgWELu^2U@H&CJXn2nY|-e5p^7Cq(A|s3IZB z&|oD;SEw=Dv%>AzoWSUUSb`sw9f(2Mh_VtA0bdIIEWgo^2Ce+A6*DW(_=X3Rn$l1e=al`MkNo^nq}p$U#2Ya~mGCaO1qX|qU@ zw7&`w1_q>!;t*d5;R<0HE?uChW8gNSS)>B}BzX-;w+H~Q2t&N{(BW8Lo*$1KHuv;u z)6&WWu4pE=B=GR8yx!W=E9tK7XS&{$Uc=&H*}-Yo(}sP z{kW7h`Wx?quYu0P+DA{8=0oG9VQ>^)^+O%*F|I{dcB^9%WQefAvf3RF+FCT6h)pGg zn>B*Yt)6x@Uk|r&@9s#QUXJ^d)+I%c=UC5M|5`uK!YlN*SNwM!jvraQw|u-mH|O8C z{ar7^?Q6RIMjIvk-`}=4^?koy+iq_+Q>t9cCfT)l0dj2l9*vaon3NICILCR@`q{&% zm#vcQ;Zk6y?;Gls)C1u6Se_~Vl-w$ z)CstmG;8=|4^+zN8(h@ABxGvzKKKZoKF7)Au#LmT$>MUbsQ%knS)G5ncPMRXNv*?> zb?XqZVg##Bv%i}wGo?-yO4G!}rEywg78>g1+FY{L$+M+Xx4CJQUmQ6)OyNi9S8vm6 zgkBdtTI<&zKP{)jz5Kg#YIYiA)rKRjAJfUhNHFj>DGI9{dELaa{7(Pwov3h1HxC`1 z$>y7?_8wp=(a69JxDz!0tEea}D4^rx+vx2bU0C=CMovGIBlQ2c1#aY(RaL+@sNb^Ln3Fqo%H7*@*YN#H$tLKKmm&3~(iMX3|gRUuA@DPd;`y=tJnfK_ID;m?-* zAhH;az5TOECwDh(L*wp+HM5MejKP9mYD-Ji(SmgdH^>Xt$T4ehRLH9<}deXLP zBC8_uqL;QZpUBRl(db^_XyPubF77C@ zDQD~IW%|p?bTIC$JO%)#Qxx<01hlE{`elDEk%ZQK@nZ8|QzFur$6^WRe9|QPK zGNruOuU~Zq+zxEEv#E|7e_!5D9tumE%x63u4e;*qgL#LF(6Le-^V_93>q-CSq z+jyM@-UZB2e@nGVOe9Ktnm7r3jbefcxk=g>>{~g>hW}X4<8Y+qN7Wrqjwxq zL~mkc(y=(QFwasz2zW4g?b<9?rvwUY+0msU=Q93|z+`FbmZ?r<0;OVUThlL5f`Wjo z)@tyYFG){Nf3#lyRioL-;-xw;l^wIDrR(QcEml}puVrR**A+SX{@;K9NvF~=v$ATN zy=Z7^uCA_ndU&+{5V*R!(hIYqq3egH5k$3GXofr?`aoTp>N!Y{>pzJWLy|<36rvB* zbkV<|gyGT?DOWL!(IGSMH$cG%YQ*s`Bt-N{!Is=lxM>u+rjVylT=PWdqA`{VZzvQ; zl7~b9FCnh#@r6@ni)Y6rEOMlDt!ID>?bGNBt73t2#5-V2h$Zx6>_@MD#XVsgqQF5^ zE~(^ zxsm*X=mFwwKLNl3nT7&sz?2NQG@1AK^K3v06T67fU_JO4q7Q>>UD|ZUj^Af*`ZVNz zX7XZlo{|mGlRJitbRIEbvT|MhVW=jEdx{&+-n8*qv74%vL$G3O_Lv^%Gm7lgprWN6 z6?F2L&d=!GCH|b~ic3AJjBDOY>LZKIR@O~&y?z^wHXrKxK3iD4Cq0gHCCHd#PSJvP zrhI1^ZdY<^vBkHFxvtpUP$v{z_*bRe-BxGh3*5TfM(dN`8^xa%vbkowE&0sG=ab$2L1cJuXQ@*7zW8=5S@I@tX6<)u=u z^KB+ygi$1E5TPetsIG{ug1wB>FhN zZ)?SpEtm6C-$tUba6Zb1ZplqDttT9&e*WG#hMy9*ddZFQ-xts?KeT-3fVsjtio>(g z{!hdoG^rW;!syEA4ZkP|89ryo0*qM}COkbl9K5&~#rk31VA4@x2lyCrFURj5Z*LwQ zpZDLS$b)7Q0$i;NjX5ecTkK?k_K9BGXt`R~7Da@ky|oqCDLyy7V64g&zu+emNR4f6 zZSC!^FD@?5&dvZl>gvi)$c9riY^Qj~Asx==W&q4Wf#AP+CJzi1a2EJ~S>fyuZbKoz z6R>LI&SflM=)fn*HYnHZ5b6zXBlrTd!Q|jx#0U}ih#^*mYzwM~vVEdJ)!zW_{oEKEpVrcJWn;gps+sho95wa8?(=B2^tpPPuZ!J#|Na&L zn8KgcrsFWLw{tpL1bzSUn*QUr{L9=m9I*B&8|fP>gCGfvk;)>=gM&LtplRY|7N%tv zVqA-x)I!eh2G?+NT{SI9GS2MtMTNtNwx|p_>GuBl*+ZrgEJM6r@H{EnieH;~K zBsFzpKjTVD8i5)L!*6;!z`1nmWN4}*Zs?@1X|pwVmR7S~pX%D$yJfySXti_sTToNs zpsuN;`Af?55y{rIq?$szX1%Ops+{IqS~++ z_t(jZMTX3On3yRE33;;?=_?2X$d5%#V-TvpCCKoQ#Pby#+H?TNI&5rgEUf3#(p;pN z3vQo>g=6*VCuD>gZ9>xjq(R?k{PVR)m8?ajnuLJ8F~aqNg?Cb=*g-q^#M=z%>s9o) zHQ3t~wsP>ukQFp>&rZl@$BcUo+wIeQxwKW6`TLSUM_Y&^IMS!&IWT1UF%4b>+*EP* z3s+6tX0_F9K5Q`&mDq6iCos5}n3_U>hX+RbB_$<%&(E?>)V96m`*n#S|mDtA@ z8Hxpi6hiqCdytlw2Qn8&tuI!k78U}r%XaK&g4b4unGb_95t5s1)MJ=%q|2Oe?&)~w z;yG#uaAuIg5BK+h+x4W`yO(E&r$>8h8*f`HPird=7x#LNLv3A?cC$@JN@(aJC1IA| zORte&b!}7CZi94qDYDx&K{+4S=EiJ&LltpDqk*#uN)4aj=~YUD{??xkch~Dhc;8aw zbF<-lFy)+yyUj9^^r#{Qt z=$vNhatwY-8h#_=LO&aGNwfQN#$@pp{B8D6cKcoIWYhY2Ma%MU`*~HeU8~b%l{j~C`t@35^re>2z7pw;tESJXP#^xhrMAhrx4>h2LzsfAL1_G3y(O3l4B z4!ryxu;pcCNlxOhU%{(&OQshLEM0?x;C8gtTTGi>%cwAxqUQKY`>ezL9 z(OWJ(tljmG+4uHD!SiX!09AbFs&C&Bz}bB@|Bx`t1L+{2rl5gRC7#v0=s-?6uw#Ky z1RzmvvR)1g2?3ZT^m_kZ_TvS=P734yqt`Mql(1+7fZC>}Um&>^6%{QloM=CHO@9@U z)@jAu#_nSG!$)ZjnLoi7N)55Og9j$FOvWQ(|DcaR`T)~r3-%jSo&ZM)!Xz|B zU1TMw6>=i9+Fx~!A!|bn;uxSrnqf4}L~D4d=&Kb>ks-?p(heR>2wd!RLa3xJWEeUT zg1=wkke>-o`l>AA`TlnQ6L#Ly#jiaK>&D`17%~{#aTH4K5*UDL0OxxNGC~IjoUXhAuH{=vq88#U? zj;mE=K`xEOB{c>0G)?8?lKIOS%lV3m`LVI)wBL3Wm0S7tBeP3pDZeQ(G3?h>|Ez7O zEzRj^>SZYFDr;!!rf1_|VPQc72jnkRiWtK+kIY(+EeLvWnV%3N-x3AfK$A3YUend; z=4{|lR8TLbzdo}$pPQ_$pr_YmIZv^`fd(UrBTJMvo;;orpy*`T0~uQYFC)pzkv3@D z@Z#sxBYwK6uzMyF8o2XRE)(V#uzRx39P8JQ^Ejp7(LOCaU&yjEY` zI>G*S@i-r!mbYE??L&ST>ATgt)}8Wx-+`YU7$cTHGxFuMqPHmBZpEjm;;dno@p8rD z+0M?+&CSio$jHgbNo_5YzW(-LG?u^73mx0R$o~jfT3TAHWic{tF~Hvq>h(}L-1Z^GUyOglYK8EigaqfOwLd71X&FZdEN>SY?34c zB6T1{Sx}7FvOO6A#83sujz?jrw92mt;o`*$A;JPv(R2xQszh8A3t|Xd`P`8-0e;3$ zvP`kg!%SdTY6w3+K2>1`D5T;R%X;}{2=n~_?g+;)Zo=i|{?+Lr&{x6$1D&S&mKJ>= z0ju3)b(k*C}p=;3HHG59Csqf5extdmh38@aPG=@VcF*l!HwH48M?7@qge>YAJ3J|khU zFAu2wCw63BF6~SLKlh_rH<56&L>|v(8rwqp+DgKzO!~}b?8I*T(u&%`cEYlH+Rkdi z%6fBkA$@BtX>m1ieKBKsGi7^Qoliim)4$x$ti;%0Xo`=wljyWO;jQSf_FG9}Zep2BYyYaeDx6Ayhuv z%?MW##C#D`fIfQI7itmO5gHc7y3k`chz7unjWv}p3+#jSA<{!uLP%ypRxP{BWezZ6 z96E}+!C)h-+}0o$(PXZN9>}aCaZS!o7gVr}I7LA|$rv!4r=F?4HR$*I09zfJfo03@ zi(fE>LK31P1`!`wRS+b4EYM>zYK+YZ)JSWN-28Ezg_8aib?Ssuj*a}AC`>_$|DyEg znGucZ-iiU=%vE&U55dGTB6!f}yt+XWd^|`q=8>MLfG_=cg{TAv9XMk`>M8g>U;qo` ze8M0sFd2fAfL2G|j`mfI9x)Z_+7r4n+H(R`qF&UI+%OJ@EN`x^Zhmg+rk3g^O^+|& z;Xj)+m}->B=Xu`Twt7km{VXHv7K?P&t_A0{4$rDwpavDegBw-j+x)$SHQ!Pbv)Rew zv@5#5aCLE-{{d8|FRwVS8x!O=0$mnx{u5eB{sGSax^6eC+SXrK>Z*ss>tP^4 z`2?HNN~vfY9#&?jadF;+MV7`*4FT~4DJkjfEUh9nsB2fcRXYi2BWmq`dCfvS_YbD9 zzgQ^7BrfoO?5!>~KGrbGeSd!cd#>^Cy1l=zxc;;C_3rQe{tWos@17@v;}7B%F5+_5 zAj2rZhv-DA}+pu@9Zq< zSQBvc*VHhkjhki`)UB#CK*9(QWE`OC{Po;eU0H>x?4>874!FrYVGShZfV3&N_T=K7 zo-x`dqn)pU5Di-Ftu{b1$kcI6ST@8Z^6amX*q!FG$wLf#EE<_dO?pOiK(;3iL=z?B zE8sG1|6>AX$rlI?l@*p#2+rYVpVUc~{0eV^`+h4#7{CRgy0f;EA3zp!8+hGAw8I`M zh%4?QM3o1f6Xi6K98Yb1`@95ojjfA+0^Hi!6v){`72t?)yK%0g8zp$OVCIXONtY7# zh8^q4(q|x$uz3eD`{gl+A_(|L?oGVfqy{4{gH?j+m2H|C^?P>TUcs6=eK&5WXBg(T zMpw7yoKBT!waqDOic^sY{c2ZSMp@oXOWHf$| zRn|;+IUOJLpEqza#%{E;IT-wNFl%-2qVl&Qaxb8?F5hi*3 z)Yg6-_D4}^2grffk6-#okarZd05!R+FA@yZ*P@vZ*)0!;;O1nzg9WGH>dvo zm7=AUXRH}xsF_$*O|7b+FPp`(kJ4>op=qoK%-&1H3Srq;o9^!J`pyF#sd{jT3BOT` zN=$Eb67Qi+qCDpZoVtYiup~-K%o+9Ggf9s#nij$ak4%fM`CKd*c)XhO|3HloF8(At zVun2t{`!~T17if5A4tiI| z-0ypNb+-}-NfY5Vr4ofvQ#in}Gfl!osZN+iO+wTtQUXD1_|S312T7kKfeIjHP|@&^ zneAr+7%&{5OH2+44IKoSzT)E1q6Nj$X$8-(1;3*6jI=d00BRB!4-bGI5wSpcGXH_{ zFN}|mugRC@zk#IT$eo5>9vb|)N@vs?!Uf_egmx?buZS&~=+6!&Rs3K~ek>hTKA&1( z0~Rl2w;09my4If)_^8=K9^w?xUrff~lnS^zNERjeAbhz)OQA9yw_PJWGpnC|%MzPx zsoiy{b=hE~5XK;mVRWEIDm#2cd*8U@6bt=-2~E)Xa3KCu!Ep5yqL0)BZ+-O<6y`Bt z3*-es{lKV|xJXH_VU8n3!N286crrZMfeWaPM-u9O^B)v4M{`DT78d4{M<&ldK9HB{o0@FmlJY&`iqY(yXrZ)kuCe`%;hR5--F#x@ufJ ztIQ;$aJ<&mxZb>!yxQWd^TmYzjV80=;{r^t9@-zN#?H#n$Otj93-L&2Yguq-)^~F) zHJgoM^F@=uobBW}UQYMj=H%@d9MI|^#b1M2$v>IJHEwCpMWf)3e`pPL_$_X8`qC#rvi;2NZ?4blCe{yH*2FW_`!n-FrKn zw>MDt9UXV#VYFsQZ1_AYV}J!!ecV&_QAy0v(FU-(_0yZ|!hxe4XyL7tX~)oUaq1u6 zCV~p8QdD_)J09QK>#No|0n(0krx`F-50fj^?euEO$=RGMmcG0IegdAo661+D^~8Xe zXY_!8ZU1>|N$gwrP1Z&t6v+@kN;KavUwqi%mXac2vX_#0{v=C)x7B(4Ql~sW&w6@l z>D2an*c?sY5&bsA_+^mEu1(*;p*G;0@{oH%2J?G$Tyuj>O%)#Hl@>lNx>21`v0Be7tmZ#pv~hphSe|lkU~ZvWMyTwwzj6FtpGas^_7)Mjk>c)dSDgU&sX{pWDij?ti4L9Vj>4(9HhL!ser2p z5EqNq0Kus8A)^;`T*}q7peH}%Rj4dtN_YBdcH!0Ukxv-Muyl4dM5XM}9}>M0LkBn@ zhy=2QQJ!N>%rdz9j0#&CexUmlpb*y_84UZJc&gg7T_GW;@{H$GI^wH1#e~YWNl}y-?ogu$+1IQ8Ss-U1)PPsbz4dWTk3d9 z>dZvkjqeP+q0%2U?60n-Dtn(|fa)|J^mfBSe#Sz6!a#mXML_-?8}mChRy8JGRbKAo z>9Pu+u;S{R-pX>S5)eI9$XeP>*;HoO7m{JaeniQVo9u zE$I0=zm;GRt3{4}!!59N1waTIeHeD8bF0O|DoJw???R5CkBdrIJ(uqA=97Id$&dw# zHte6GG|;n#AEFYn>!tU7h6*FlL@6pT#u!k?XVgrH;Uz-T_kOk`$lFQ(GDl)1R;T$3CnYE*LUIIgogQFuO zK)AklwsUr5(79n0+V4bZ{thgHjI6b+bRQc-v#a4JDjJE-o70Pp-o!ssnWM8|OJPA` zx_)kBC6Ba={FCI{8@!&!V++filwDklelGPsZbcSmD+(b+yw3k-rJRW~pOwV|yq=%2+}1R6fcNOCrs!y96jex4(?nI2 zOI@Cn|1F==ZXqUNoA7tOc&pca`#XXy4jmtwo1U4W$;Hjh)lpg7sI_-=6b8y0#VJXK zrmwG$f@fS*a=IPNeuUj^Ka}2Q7Cm6pBvFJGslxYXVmO=-J(-E6{(5EOkbO4N53e{U zR$J9{bDmJITDL=w2t`3DNT{d(1dda^^hb^-8P2L$M1PgSy{LLR(@+{olDS$Yal#Ecx zgI$Y-q&#rg*a|x_8u`Uyf-~^$9xBEJ)*^@q*H|(tFQAn!SrWi1*XD)hK|HZwJSc_hYuQkoLliKR%PqU;c& zp@oe3P*K6GLK~sFzL4*S6!>Cv1i?cRQb%y?;5q}L8US4cFi_^_-`w2L(b3J>+|=zv zkgdeW&p11`Bucv-oZSu?{&TKckw(|P^1ANt)%&)Jq zPjCN$C#$}Tx#9nrBM{6ZydLM~RQI=-u8yYEGAkW3e^QmXuHvh$Iob&BC1Mzhsq zzP>+|r4OGDCY?e(9?zP18{m_g%~w8phx_{x*O=pnLoq`VDK64E133?#w+(1TqhX|k zN(PKd6zX*t%*!KQ-U)f#Y;2qu!x@ zo)t${lt8r^_Qs1@^yQILels3%osTDfU;DQ^yOa-X4w(dwiW7EzZ|#Lr5O&%3-8b;~ z`kbsYGN%1k)Y{Hn%dN-Krf|uqTu!!t9hgYISRWvy>LKdzP=53Gq;?0TB+1G_!NX*r zymlr9P|OKc3w~Ji7MMx{lUv)Wsw#SV`bk8{*F1fI44P2u>+8#n2WVHI)<7)4Fm|va zIPyX;(2P-f;UzYbHRxx>`qbKAFd$-ySt6R5ZON!NG@APm2Ne~`z?S+Z{9h13$Pq&< zxDxFO+Cii&4ux!mAmRwy_9134zQx5Lcg0jpfq?9nAcJ6+i35p&Q;-fvJ`|Az1*wvt z>ElAX0tqq}4!Lg2RZ;9jS1?Mh4|}p@uql|?5o+YnE`%i=)06&kxBgP?+iKM@{7taG1rPbEQF<)D;%*h5$PCMOKMFY~F1cm~Zz!=QI zIm%a*N1#5I3=P!>#05X#v9)N0tF4L&rPuT4?9=@|k$T_c+|E|{hOO9M7Wz- z7ni_KWh;}Wp_Q(km7$fDPFGv6)$D5B7nlJs$`=906+QtiZKcLy#oP>RTs(Xdf~&Ic z`LtmMKOTqk=t$`0XMzoFcIE_khos#F<4@|&s@skZH@u8;0p4Y{mKrNF`OyuP)xgp6 zHtNldugnH#SxU19=VVO$x7PWFc6s?`{G6)Xj5z}C6(FMJy3Du}-P;BK@)fcDK+HF) z+RM6Aps9kjyOY1Wnju*c0MotK+}W3oRZ=OJm#-I2-7qkQG1Dm6TGX1FmqjZVZeA)s zJ~sCDbamnkMvcT?U&9GGIkA|aewPKqFFSx98$L4nqv=g#^@!YgkBH^9=rD+bV}!_H zU}5FHf9&lV50@fOg^7!gq}2E9fOI8bq5X$PKv1qU?z779XY0wQD_pb>^WKvsQG+-Q zu9dD>w8yC>Ix@-M&*^4xS-iWARWXzBKTM-ew_;ai+l5EzOTlg)Zx8*P2;;-yd(6ns zB9=gnJ`Z+JpZ^|fVB=xdP#U~0+yC|uHR%v9K~RyZhrPW+-*|vQLsL3CkN=8J-P!I7 zjRuI#sSLVS#>T-Q0+f`L(9q$Sv}!LeFCI92u^z9hVaW9cBRQrr(uxugrSW90W9kFA zoXA;37CR)#Fw!96*I1*dc`YGQF76hf6ZyW1RFL@`Cz%Jx0uki>eZMPV;>iOGZ?`0^ zp+*Ojh&)4>Fh~&Rh22cIn8CFp823OTag21^SzLac!p-DCP(}zk#uGj78;u>_ZIg%v z;77cH{3l&(M1=rR2{D-<1tQa<{~?NktU)wJKY95|{04Jy(4;Na-$>g?hS{^G1-Xbyfd zwxy|Qol99$Rc!w-Aw4tm>r8)tMPA-X-)lxBf7Sa_Q(XL#+HYIh(QT#d7Snm0M+yJI zCTZ{P@4Jc5tam}dO-~;+e}jJ>P8P=&_FCe;9}enIgUXx8)mQHyCd-Lsna1<%^XNbl z!};*r9rQY@mepQE^O#W~Kjpi-9@pmgYDVCF>AO7PIgdx4p~>IMVs2%Ce$#Fvt!!&$ zY^wz<>?-z_VsiN!`I@T96T4|z+E`lZxTqhA zX%$LkN^`93Z*S1zVWes-zvKqcs)c*u5mQPjs-~slCr9NZ3=@p_? zsrKG(eLg+9(5M9g^9oG-W;b6C6&DGMbbo^c8loOSCMKqc*AU=h%&2J;HYXR2mBpZM z*I~2jq^w-B@OXDPo|ByoGNY%bXJ=;zv?&9Xy=94?2!aGVAVqW7b`o|$hTy`W0Vf54 z1!&96Vj@KFi&6vcFkP^42o6Pxfe3Li`()#lYH(i>Tmdm47eZ#`| z-+$4AR!uk%sT`r;M28S3$hcw3h5MAwkO@CaVD?BIPIs8XyC7<)Y8Qg~q}C34DSi zBgM$q;vl7BnF_GXE#5=GP*1w$T5b3udOU+Hz-ugLL}PG6l`-H#4IAL#Sn`9zmwsaE z8|pgz#aNc`;)LT#j_mU>U{2@qQEPP}i^mS;N*f181b0tQqNFN>ge5JE3hP3DE-o)^ zZ7=C^bT4deGQ#BDn&V2OEB|AxcW^gGL~4qOYm%31jE!BqCaAo+rmtBvGbyQ#-NtD3 zm%qQPXmGE=_wae{!8-Ofr-(Lx{x9~~{F#Fiu)EL|;D4FiEPSrM;B_zBe+g_ihRzy# zk1mf|Ix2xGp&Uy#dg-Va7U18wdCl0Jo<_*!-fHm|-d_AuShHHbNOAJGerBEY-T~*$ z3!iz$V)a9nOtoTjb|#^4+1}b_Wp=Kws8rpOmAAtRE_&V*3^|1*uegn$lG6UwNn2Uj z+1uM2Be|i@a1CK?MPq%9q0}F6oIpZ)0`4jD)a0!=L$n^~$NuQ8z`^b0fqo-kjI@Gc z_#-ORkqfVcHeH7zDdG^$(W6z2*cjFm2`#ZdOto?av9GZxA^ReIBfE8?a%EDRggsC= zGNeiYW&kWsi6#lIb&H{yCQ*K)J>d>N3rAWhYn&x|Zh!d~MD(f;u{3I>4lUZdqO*j5 zEFT|<#bf5kBd%JN7CHttUGkU*Trn9Cdq_kSF^*bU>+X5o`Ml--{RwzXlLN!Yy z0mTU82LVfJB5EZAyU4;f{eLcibj!R(D+r26b%wk4seB%#C1X0WZ}1bC2bp%zyr?ky z0}4l0Y=#g5ALaqfuO}2l0gL5`co6&n)j@^?sbKJ|G)bZTEPd3hSHgNs1|*KSVB&^n z_;Dy|F#;k?cJ?qWIQ(7+CYUa)IY}ZSAqXadFA+IVINZ|4fKi-6)=w$RD;O!_<$t#U zV9%JblqaY^H;^OO9#AGacz`W6O~RuuWXifC2~`j409v^-4s%*)2uhJ)_|q8a##&%I zJ`A;}dM7GzKom)G#v#FlAuZP5rnx3OJgaaYjv;N*h?#&M(9*lRtHV&(*)h1$(*5(* zQRAZ1|94>Q?Cd;Go(eCZW7O`^CQN;G@^_t+orz_`;Y7h+U;dY3Z)$2u&;>p&8V9s% z6Q)3$|3y~#u$|72HmB<21LDsIi_rn0-md()hVTvo9sZkxqx@*fck|&2XrBAKc~Ugv zkkPum?B4-b?U(9u?%UmbPp5UgtD_}>R|U;s6RATFOCnGs2PCSxDsmaH}Mo=tP`ax2|jj}3Af*J)n zx=14^Fg-c>tN8aAS(i`qWHWvF*3?9)KH*FE*Z5@j_vfPjcMIXw#-FSW?JWITxm|nO zG-nkW(A?pqaWZ1iKs3a)Ntk5RB$`f1e@UVujHXaA z2l2*fD%Q%Yy=vZEm$&0NpE7RRwu>*mubKUz_T!wNH_b1bmi4^-oF^IS8dj~Egxj88 zeR`}fW+YbeW-T!E#1-tHcp(P@$-qbulq6?jkOQ#SLO~c22tYykb3{aB_n?TfDj{=v z{4^GDisXFK2ngS0p3K{M=peM99=m2I0y@E>6&sON#sBHq=MFg1;W(hMhQ#flL7Wun z8&`=*{|ACv#?y+*;o8Gj^bdVQAd>7NXr&vDbmcbMf@LNu=o>^k;znea94`<<2=Xi< zDY+J8BitaU8!%E<$7#EOFgaK(n#l3si;6ZnW|B%6yy>+U8WdXri6u4=v}`s9NKgiD za{{E;ItfM}Cj0D|>Y#Zd&*D#{BU}geYoOs>@ZMte$cT(~QNnF?{ITnoE*&{H4?K7r zRceSuVPr;3Coy83qb5vQv1ZY7_6j2hK9RrmF(k>@7y0a}8mm)tCCIMySp1*=KsVcI zw)w7)Rb{2oXLB0P2Hh6gTjuh0S-*?G>v`Yq96rl;K8|(W%WwGK?evj$9AB;Tyr1+- zPv!dEyf$dZUuxDH9;REOYY!vIPi8DN7?^eQQnXZdz8@`5+55f?oY^8ztTwtG`O;Eu zci8lur6ey^X8KH*OVX;#XtWzV6fxW8R9yvj&aS%0=(IVl?fpVOp2qF4I-F>8kJatk zn^G)<(y(neB(>9OcqGWi#O|4rHBZd-PhQpr5iZx;=W~B4$ zvK9+xAX0@_&I(eJ43dlbG9{n6)}f87sXKOzf!b1 ziy4dBFyTZCzP;$yAjvdATUYXj>JW~UxDwVnVUhOE!m^Iis;W-rl(;wW>ZiDp>Z_%r z)S&T0Dl^tpC$7ULcAxwN#{b}f=xG(2R0&bIP?^$s4LXV!Z2G|wl+yWAr?%`te;DKE zSDzvy(z`$njv4fsfS^!OMNnFZoB+N)J0cdz7BZ}a12`#Bl}Nx5`viG}^x&esDY$zAd4IWIT7umXg>9-V^ii{`p`)#fB32yt092{o~>|Y`RCk z-L#$o8=b>lEP#8j*D?NkP+=$91lHjiMP!CW43l@k;MuEt``lqgr~-7ACkN{L(W`3G zOp%J*DYVBxC6k^f_$Os@d3nVPo?MQSAxx++sThKf!F*Kmu>0j|r`=~eWWzPK=k(aR zUDllc$4TlZGNbQt)4u&bkCR2f)FfNe_iUyBeEk^D*W=bWTphf|T;4Xv`#moO-fp$g z>}>3{-(1!vhr9V^q#9D(Z9=>0VCh{gX1n&N+4WgQx5;KNDbyH?5zqg*0Ct`dz*D@y z2pqKw&7bf|(-=E!zy8%ZU*q^bZ@SazdZ~MR6Q{&Y}4G3L7W>4r9<5E_OR>y{m{S4sjsn_iflR16f_1`swP-jdU^1L*!^+!+Wmd_ zO5D%$`BR(ZN1UiILp(1|{A+NR2Me0ChcT=@3%-QuM_myqHZxS=n#0D-LbkQF{l$fq z<+X*C&6t^Uqzgsr)Bs?zojqyh%A>2QswycdsfyW^$71ZHp_E0sb z9pX@lY82|Jko}NFVJ~VrJ)19?-`#kxr3sghUiYtjTPQ>- z99gD(l>%RgBJf{{8OIGLqe=t-Of6|FLswzQ!`L3qorz_7Gu$&oW>`4RCGW}Di{xkLcG8s-juNrowEM_7v) z<+=o!Nw<-!r?s~a@PP~q<5Tfa5SCbMjO&G70g*VEwZN`tS6-aHWXnK+3I-CEAVl;4 zoH7QdO0I0a0zoWxwV-8{4zSgzP_0;$YSJp3{d=QNg#rJf6gr`yN}MFw1pnUzuba{H z!@9UYt>NyT=l+$Zfa&AiX!3BA9PW0L|8P``9*^s3tnqQ~%E!a1ELQHSo5}WGviG$f zbA!8Z%kxriBI;)le{Ay~sN<8~3~gx2D}8p$^LEP$bvdm%myL2$boHwAc8l4U3|6s; zbZ)EOK5AOE$%~6PYu62JJN#O+$-OpbbGdA$wQFZck-Ax9iWpqM*;BWaR40!QttvU< zlv`1nE>Y6omZC~28YL*>DQGED`LlnE_{#LkILa`*QU+`ka38dCwk+zr`RuZ$uMxud zdLuYdo?b||gch)5AdFz`NeH5TWdtI(2LF_&B8WOnJ{7PRcwhF1TfIPE$qfz^rOUJ% zIYN-S{R=9)?fdY50E|I%zVy?_?{TU)rIj41Odt^mjIOde&w`j0bv_w91I zZFYw_or#CSzH}xYjxa7nX1y2>1w&r1&k>C=xiB4Fxu%xHz(HMwhGZ-rY;4L67|^e) zt1A!)$>qw*%JQ0;DlWISuCAuGwwlM|%48C)RxK8bksxC*7|dofsI<{&bQG(FAa?`( zM^vxd?M8SXFc)w`7(o=67NdwAMzLAIHymOlH2`y=`xETqO(fC^X&bLFy~tpr1U*Et z(FYX6gSHOn0Dw}B5&TNu0tB=Bj|*YBfL-3XH*`#R@t%fK8%mVI!Q(yNb zMrnP4TZP(!CkpEdTY>y2ilhN(;^b^L%Wj|SK@mw~a3o@`kc$AT1C-!`Ma7~9;xbSY zZ31)IuOB821|5P7lym~$OeV#ao&o4Y^C`FmDhIF|PDt8A2TKIp2s9JyPz>b+(Zt~F z5U;T=0e0hv-|zMLJT8~Rn9OFQQLoo)bvlh!t7cLJ^;)e~ ztT#|}%SLcIFwmgd6v z$+sn$5=&B^fUngv#zvu()bpw(GNDv1lF3CeuFoE=p7#f%+JY%+W0BZr(iGhH*Mt7;mEJhPMXi(8{WKjaR(e3M!OB^>( z?n(?I&V>8|a|IIx$VNI0^mm*IHqF+uF+{*|BJ4z;k@11QBBhAT32vDpvZ0e8PXt>c zAcY;I+v9ZrwNZG)Y|&e+2CL0Tx;A{0Mx!3_e^#4;A!YRV}}+mxUF$a ze``mJE0;316x_L_Et{|o=uT|eG=JB&#WSY%n>BODf_b+tS~y|aZ9|8TXdiiV_mpWP z48khN=u-##OE=d6aA)3ZbRWe0Vq`nM;0 z+R|-JsfJ7}7VFiaA}LK**oXr~2R#`&Yc)#Qrcp*(b0+$5Vc{ z*OX5C3t5lNP`!5ft$+WQ7Y}ZqVw0EGb2x$$j;Nd?ui;D>mU!dBjz4|5_kPb)uv3SVkwly~8x_jE2nsY6!g#iOQJG+{~QCDMAuF#N4rDGnCOD>mIR#ujk zmDSYLak;eu0Z%Fw%Zu@jYPHf}&{-_Zu8caJ&SWw{j|OA|*ZSl%;;kWC+6P1F9sx1n zF*uomE-+9;#R%r`LV^8J`X4Ac#n%!H(S-oneMTDu7MCFX7hS>^0nltDq2qK3cAL~U zATP-&7#xVGKovkCbpYN`pc%Uu6LND1MiYqyg7%Pn4~E(YrrE!eZ9|(_mjL=`-2mQA z!ww)NDG3h_H-go}HI_|qNm>B`8JHtNVo_Ep7K>02G~GY?LFSIuEI5Mg(Ha^W5{U#B zFMhw@<#G|&;VQuEY&L!4dxgiwxZu;wUqLGLA)n8K z&bW$2Ah2PL$z-6d53Dw$*`kMnX*6k}oapshK(@hvd^eR`$&)LX-Llmxy-*`QzJ2!8*Ys0;F+&*>il6kj0dFr7zUpjo@$<3z@FFk#D z@!Z=QMh~)&9NFaeDH;mC{=NB@rbsGjzisN^IdeuWUO0Brgx--Ons2?ObL7pPW5y0# zecz(<7f${B^H=B2oyg~-{ra`tbW@L7CH1)NViAv1QOy;JGoL?q`;(`pKXZ2B+0%=^zVgV|R}Ovl;jU+& znE&dtTOL2UV#A7Y<45G0v*uJ#Ur5@!nj(dUWGL))x*c9$ARLJWqme+=AB-{48o%}L z#;NsNXEOQgen%o1j>UZOsMBkgcQ$(-*}vlVUtf6T%&PT^I~Gn4Y*^9o*pW$B-rsuR ziF+p95_h_+UY|3QO@zX}aKxXFwz1Zf$7HU<0t0mL|X7 zE0am8tE($2DypliQ6xkt|f&i?u#Skj{gO?pB2`PX~1?duOAnr5ZK!3m`^ar+Xz(!R< zXLPSm<7}lKt+81)x&&y(?Zd4_9m9oaEsimy=sln_7X27}oR2QCVVeD!gdGGRL2&{) z!@6KpVVTernuS!wZVDs+Ygs7La0x?!AW*S^O@OxRpmt5f2O!dOB`C+j1WysBDVNJN zH#bA4Cq)dGqaZ&7T@>r^F;I(p1JuGFlF#RnutY6iUqdl<fcx9zkT7_=Hn6Z0yJ#_5wjy=29Jh)-rz00SqSUl;DX@fVczWwCk``PX#y zIk;=yZR2utrnf${b!kImAQrc0bAhJjSbIlu`iz@r&Kfau#;~ztx_Wz(9i538GjBa` zXzL5Fo_pnu=gyuzIdbHn*>}zuKkgQTUZs$W>uM{jDoa&5Engy#$b@FA%486W_#B0p z$-l>28%Lo7Ym$(1d z&(Hqpi=$WG-Tdw4-9LSK^qb3vUpl{W%esjZZ%MV~w0@r^mG?3Ie*kX52r+1Wf=zoD9Cq?l6W6q6aZwvSc@2f{-13K;PKd%Ki*8j>QLT z0FF>^aWZ}-V@Ys|xe6;n>h?93P2mvm{t=P_y!r?TfI?a<&^?p*07VSrf?J}v4m@}) zql)p=VJHl+5X4@o1}^C#D6fUbKnF4Biff!0;FZ<{6t|1Xib()7P#m=g_JC(^N|{bG zd;S8u5yePRiHIJ-jsy^(DUB2Oi-AI543wE5 zW6i1+)7RZQYxRohOBaosJ!8oH8N+sOTJY5I2cLUl`_hHCOq<-bX6@|Gu4Hpdw6Q6A z^QeAz&K^I1!Q@*;ceJ(yZywn;Z~mlh+t)mK?$}GOT{!dP@ohUdEnYP5wy6_y*<=Za z!>y~bnDvzvC2p5ZsaEI>Dx*=VR#eDE9G8hRsM9!qM#IAo4nDMN8&d!|J%3czq`EctB4YPzXjQuY{BIYq>>H6 zKq4ASC*v8tTH|q8LniZx&d%{e2lQ{vX2L#;+F(>Va?#FYDw;?}!V!OQW5z@#nWS!q>mEmtTMi$o$ZlhDZUYpqso zH0rHZGvPI}t+UMriU+?U5E=Eaf#Beec*)stLpXwkHVGOy6Jr&PGO5LQ(ISxuvdpk5 zCG7(3ut_?5oXJ{HgKV2Yj1mY%Rs@y?HijUZkdc}qR3U?bdm&y748{0hQI79YNH~;h zXwc*yBW?>8h`-WB+5JZkfn6k0LtUWZ?ehVPdj$KlZ3cT8LH$RUFox(VSynU)+jb4I z37hbNLi(_x2ZED&TlBW!sl{-IWN@(lqE4`l4CEMkTDTdq5I`%k96(s~m@^>C!N93V@gC$hB#j$i2MZ>d`^HhqWSE^>!{H!7b~qeN zr4mq(kou1ZMSwEgl_a^Kj1}*Zim*Dr1;_+n8*JZ73YW$3J#V;3!$e*4T(Lx(ixbB=N22QFKF`;nvDp1t_k zx$`IY?BBX-?XtOx=G-)Bu+#1+;c)mou2do_E9Gc4Dy2fEl8ZD-fks|#(Q>+*RQD`s zJ-%zq;|C|~-PV84)_!}p4m`Yb_+tkqoO@)(h2wWVdt&xG&#!&<(RGa}ZxyGaic=*l zDR)b&cCVcB=kFi;`on$izr5+amp6ZQ>A(+PocjKYQ(s;_dg-k_%N7l3$msGZYiD~p zpN}(9C1D?4xqtfezXjRRc*yN_rPA3%GV5~s6Y)$wpJyBu{%F7*G-}LdtvwZQY|M4X zB8{OyE)euYqJd~En9jrt4VjkKhMwMz?w(bg5U4YX0wnf=&vA^^zH+~a20j} zI(Rn$4#5##d|c(a+l<-e2X~DDM1?$b4=j*^^I#0fGNFA8EQ|rhjnv>iNKLszoZ5 z%IEV$%Nb|X!(D2yj5C!S({LD;G83OQzpm?K0a5(%Z# z$!mp@iy?y$WKi1=IugdvZnt_ojBpR333W(Nw+{kKFz9!?ogNRfLscN)v)ip^v(e$O z`2%jR&q+J^I-C}#%j)*ntyVK5n_vS3iwV-UR;#vJ?Ix4OU|_0jBg{aj(@7*UUY&u* zRn=71M}nSvR?a;BPC9=+}Ti*x^YW&NLjzxU&}?>+O# zlmlBw9ojbT@qKrmJF@8fktJ_Fci++73)K>C8K+KCtx?v9WgO1t1>-(>v z-Bk=CibNt_uh-}E0T%Ht#9}du#Rd_BX3B=eK1w&iC|E6^761)c!DkRdBpKn=2BZSA z(HQ_ADJrp83^BOZxzRQMKcOTMSl}Rzqksf(kQhAyF^C|cFjD03YadjlRXCuWu#as~ z`sBReSCC6c)mX2PW`L$(=}BWj&q6qj19`@b0FYz7qil@ZANqbGsYwk@OiyV>=qIrqtUS2?R2>u zzPi3ju2FD#b-el- zufrncRm&Z;j#$co$&)#?WljCo{x$phg_r3Sh&dYB+{OQ{} zF1>O8Pv0K+;^Te4`}&a|KHvZP3-?W*6b}dZEv*r6z#fgqg5gjg#6;*bQ!y0Iq_WX) zESz$LlFn$_AC7sw0cSiBN@rpLzbhCEWOB(^GUN-oVsVBeGfy_ksBN^yqRGQ#iY3C> zH71>jCz27L-{ti=qp={;7h75jgKz5B+pi;)jz(jFTt3;`+ndd1^?H4Ic{zu};qiDf znXI@5;t7R(xm*fPZ7}GpRx_TdrC2Z>Ry-K=)5L%-hs+7Eiee?mAeb7_Ow439>Ver2 zb^sX>c1v#ip1w3QC5;R-s-fz6%qG&osgqH^1NOy-j=%U43^{RrYMQ#(^edT)h9iED z*Ab5RTiY6k3?10h+tJ&vv%RA^Ur1+j$;PH!Lt{3bi5J&BDuF;yU0q#QS0@&WWyS5j zR4N6mECAYKF}Yk0s?+OsJ42xW`T&B0X@Dv;SjJtSiavy+0agG9^r{0H@heaR5CdLv zMb3or2|{`K{N;~B5oW?x8Lul+o$${Ff@{E>j-Pdc0$5x z;&@-k{-;!;4^RTii76A%U{2#WxG*`~AS=^Bw7@3pq%a^>1Oy+kbOfvbZuAh}#cF`+ z4pOt!VVu?nvSD@5TeQZOWzc8%Cox?RdxUadkS_qlLq+ZEuSxxN>pW~wH!{l!C<&~)UdOUA2@tq)3PO#=gb;1WqjMv zfzjau5`(%T{riQ30ZCU^aLt-o$4_p%_~Pkjo;$gH*V;8}@1DPK#-N)zZFW76U&H6u zi$nrGpDz&B)p4r?qWa3}GL>3v)bYh!PJ7nAZdv~L-kT5X9CZBP=#`5*tQt-=hf~EV zSCz)8{Yj+qz*;d-tGxVac>xuDo&h&tIST`ybD~ z{nEC9UBQUY6paOvsYoOmV2WHvLd9^MAhW;^#hjj?FBFYLlU`rQ?+Zu5$#5W!tPSkz znoPzSUjkDd`x;!bXCNkXS9e>XA>;KqZFW;48R^%*tGlN?m5vP?KDev94b;1(wV|uK zEt!hy4eGM8veMGh%F0R}k0&lxOqCZm(#7(~WHMNbN*7j6!Jr@RWvkWfayh(Sw};tJ zhRLp?^ayrjY9tc!csy(($zF70flqEB?8io;Fa!bcO1J?D?g?Z=p%D3j0Mn#5;sf+X zGy-{=FplI40(yKPqz3PXB7qK|wQ!i(ixSB-L|x$;#bY8n0X~b>13@qaN1#8{KE+uh znvlR9#(-=Xk!~O?-6p%D9(xr+W`?W+u8Z4bj|Mu%u8D+pa893LA^0X&#IG!y=mW?v z5Dl??eSB`1zQ4t?;a($Yg^-bg1&KK0iU`aAnBrvs{zCSpa1P2z!Pikl8*PR{0qlYX zG{l0Dz?wdwCxqJ2QXs`pnoKOllwN}>2k&_ z1g=C%4n+a7s2?7y4{C|e=fSAL_vrI^yk0l%4)TbjxVxCmW|I-PcWHX8N# zuhVJNYNb*s2XM<|61`C-l`+*#MM9ZSAgkw!_8JnsFCSk0-&cPA;^f;G@B7`A6OSHRTpnjE5st-^sZ2W0WUoYHaeqrowx_eDkWDmXGx2aJ91O)G z@lYVhI2f^W?sZ`V)*Us0bGeK^;Eu&ZsdOxzi6cj*|A6l9p7!?kR^(xIb#-)gbp!%F zi9}Sxq@Ht$UrVLZVmy!1YPCYGwij!o!}QwiR=3-U(hIbMCpkWKxhd!g$RJI3v^uS;zb+=FYA^+MzYmG=Nl zlO{uhOb-IZa-re$g={uU1*oz4GSD1haK8oFgp63@(`l492>F8M9EG*v(x9Rc5dJC4 zCg`U!rzo9F3s{hSGCTy?Y0Zozkjt>B6tU(ZCj)y^ou5e%U=JerTcwIA@6j>&A z$W1&RWiM%IVGAV$d(+?`bRn!2NUwCc99TX(op!t3YAL!OLBz0;jYgwFCJrbYCAI5x z8kJgXFfu`7N~KyPl=13C)m7Zml1hi!e%Bo{&pdYM@zc8&ExdK~sN96H4Fh|;O?lJQ ziCrs~PuaC&<&$R*96P#m!Gha|5ASC*Y50QL+PVsvT*RcF*Von5R0)NAiI^vm3KU9- z$)peqI95Gp{*1!$-BTXhJ@LSUL(UwSaAenrL%T-q-ZE_N?a9S=HEvvyJom_qpFex@ zyALj&*!jS?fn8P^-zcg#3f01rI(d~uQ>&=w)W}K%QKP3VnBBB^`Im1zfAyCSum1AV zzkdJ3vbh7QOE}z0j)kY@b2x4(=hE|=e!9Hxlh?NV@4vjgVa23G+#CuRv)M2cb(e_6 z5>dOymdM6ZDPJUNZ78^g4a-cst$W^_A-7NKH)2S-H6Kkze5q(C8IAcoerEHdOgs_~ zVA>E~XEG_!h)~!UPlTJA^S%8#d;4{^wKui3H}&*(K&fkPZftBU*zMNx@=^|mQ(s>v zlgWfap;*l9(kPe9B@&57qj5SJ&jcJ2h{Ok#cDWpw)wEp^E!Qw5=w%_600plPj0+5ZFhm+|{{E4nkf2FSw z-)D1hh!UhqlMTSv$u;s`YXqfQVVPD~X5{J%uE@rPw}1cs<5&Ov-49;g zdh;NgQN^)JD?_Hbm9zT)c|n0 z$wDj<(gfVRAp<=-w@!ZP`L(ZHT>JQmMf-P5yLEU&L&}i~JF|&sI2dB$k+KPY$W6p0 znT!)%h{Yl|4H?kV+E8f7boaCm9Ms#^-jvBEQt4QGdwZc!aJgK3KEJfMeGHe&t*@`= zvv$!%qN>4Quv(eOdY8)qn+?A-Ih^sU&*!0H$@i()Dll8=)mIubH5HF*Y*2LsUJW_;4*^$fN1e} zl-!bR8VhvBwMbS5(I&`dFA-9y1nv$n4Sn#st1t-93?@1rZLwZ0D|1 z`9;JCg0&GbVl?Wt8lzAs=J9w61rt)DQYnh?EmufPm1VUqr+xX7yY}yWVCS|~+a6ke z_xy=-ZXbB-h;0Av@Q?wy?)Hq+suA&Pl~R$z;ox$)rKKFPSg26QxZGMEzt(8d0qN>OIg*63B0YDuY9R&JM@>Np%_C1+f3`qP&V zUcLI^mAAKTSkbj+WzUnR7XR|?6JNb|__Npde)GZ6_g>!m%kQ4rxNdqZqK!rDsbqwy zSe;3DBc5m>l=Mo+4NINeH}{9n5B|?Tp8ETrPXG1CQ@{WG@cxJA4(%U~`ZW1eBo&J? zQM##kFzjQ)G=h;b8O9NvOhubp3O&6Yon5WDd@7NQG&Sc34(d%NlNO7ms;Y{^;Z#;u zGL-|=YJot25D}CIu@pBVDB?8}rs*oy|8f-l%uucov5L8YmjZ8PEEb`O!JbjUpdT>_ z1c(IFga~W_0p&2+Roe($h=dZRP^t)YVEXks#}DGB;Bf-11GV9Yq=*76 znY~`O^|}+%WHPALN}J7sv>JqzsICVjDCByR(e7}#OeT|BBUh@Va)nsTkYYWDQ&m${ z+rOuM-d$54+_?Psk)01cuyXdy0TV_yO&ZfNs5foW2!z~9wOpc*i0kU=L?V&2sK!c* zNqS0^R3zp}C48kqtW(Q03hwCP+5KC_@7d6La%anov`ltP1)BNuYy{8EibRb5@n=msJ&pT||nqzaLQUsI+mQNe}(}$=2^3Cc0_~R45`)T`kU+?(gvqK-hzWcjNr+@$1*-Ni&|K`e} z7oXqL(c($O?CDh0dmVr|MmOxfBW5IAHTZx%Xc6A<;z1qezfPO zZyuXDwK?b(=M%nkoC$M|#v}0z^U!GqCX?|(A=lQ{(%s$J(b>}3)r#!%bS93l5UC zhnY+(yy6=arFa9p-U!eJxr3(;unx_d9jA=Hf{=o}Qd9}SAAp+_TN29Q_yN9S36J;< z!gq?kz?;Q}TA(37jVuIxk*p3WNH7UF$X3{?79)9FVI;^@`2GHCsWe2c zF&h9eG$#Nkz)hT)N+l525sNVixY=wPc!Y{bu~-CkpNsZC2Br+Y355ZgAnim>N&+~h z$KwK|g4Lob6H0cFW0O=o&=BA_E(DVU1V{WItO7t8`7c<+!T*c(2*w)iKuKi#13`hI z|G*N!EQLY=>~(+@089l^A5k_0n~fpM5qqJLbCL{6G#W+3B=9 zis2%(e8v%QG-xIeMo~%|T$@U>>Wc-WOvO#eP-t5!74!M^Dy2>+U<$~|Hkzg3eIboz2Bs+wvWqjr|973?0_Lr>6@k1+A^kt*y--kBi6S zayXpY+G=jGXsTE&#Q115Dm(>^MrAbWokd@RNkU@nnCLJGupBi{{mfq<~I-y>2V*$Z~S z78Hy=!Ugabss-AiL>0V!kWE-@`J&n%5-ccim;X3p;)-U5+JPQw;IRLL06&c!XN?tu^RZl zAREwzaELznkfdfnEC#`3hh3v&5`Yq99C3TVWi05R008002apfVopUFf&vUFq2792nxjxrc#MM7MN%VQF!RiFbouv*T<5ma3ukw>4mi0t+7}nm&-(>VWd7Hq6^#8Ach1=h}Y}Jeq-=7+U-_*F$&O9%z<<> zC6w(p8gv@q)~%a;>n)uI9bYc35sB*s!a9jmpwTj0$%w^5nM}eos8{j1RR($Wpcd2d z9b=z8KIQGF?>@F={KaEyPw!gv$t(N*@Ws)KXYYFD{PNeH-kfnO6}$?yuv#mr)64i; znLs7wE5yuyrHrqT@)S~@N-of<#5%P^tq>|@e2GXb5!Q-oIYx1%Q(8N`;Cb(^QHA~zPRzzOZz{0|KPiC?D_talN(lzkNDN8R45n@g`<&pG7<{A zV^+!hN&P;5fC5l~h+(*45SUcwFE$ zM1Q@WDZ7Zp5P~w{Lw38J*uV(W1KJlRGcu~6V&lcZJONmP7C@`SnvYh!n2?ydK!5N- z>^_VtOCXgbt)lQA_VY!G2Ss6nv4R)(aZ3WiD6Eix3_t^>OksAUcN3u|ehS3Io|8EL zdX+aOzZ&30!V8)u1O!oKBN}cBsEv~ek!dwR+64>@Qb|b*1@33FSrYDvKBK4;7&7u*26t zKe4ko)MT`S7LZO7iG)xosj;z8DC9s=NKXJ$K$>4VorFX~qB-F*#c>0&iTJZE3O>Wj zkMl`mA+3gX6oa*=6(7!|iraWGh@O)xl`K{`97Gm7^blGuV3%Qh9q%4W`r&=UPtt9$ zwm{?XM#3NEblMR-1JNHTaNzzRWmrvHt!As$Y_nPH#aJ;yaC0%89Y59AWB!!I4a@0Q zfj}UUFg{7KSj^#Y%F4>(@#yT?cbq!$@DpeDoI17T;fGgj+<51fEsGW`7;Cc%YHCZR zGM-i^Q>r9#g;=eTBW=fQG;yoSbh45e<6@8QAOFnpnGY==T5yS~IUE6p)9hCr+Bos! zmp6Rz{@!H^MwfFqlKL{0xJIWE>eV8ZTp$v1`MjEXZWXt>f?Hj|tF038>SQ9mTr7}@ z_);NHr_nOlEv|BEg$7=^naf!zMLm$4q<%2i2eD~QS-+zAM(wjTqcwy5A zuWtG7@`bY*=)K{$Q24X2q}O>5*D3QP*6mpqJA{NRda;-vSQkN{8 zl{R zW#yG6<&`BROdV2Ad09zSWqD0?Wo=DWO?72;RfR$#wis0gjnJeN==jz8TF%U2{_o$s z|NBpl{N=}UfBpSS|M}NTSO4wG|MSb6fBfRi2hVT*`ol+_dHjK7#1IO(Qkk?b;Lqfe z@kAgI2|Enxs9Qg{Epq4hp4Icm&l)qZG2(QY)jp@St*NnJPj4cT@cNv|bfBpv(b8II zZENW1Z67$Or>(s)nTq7{$$tGibGeMoW~r{OwcwCSi;n;^q1eMt#%3)p=ZM+xgfS;J> zv@oZ&CLu4NjnYyG_2>m54hwXnhzlZ~fGW84z|)BcBOaM@xZ$e=Yeq#`U?Nd?+C7K* zNdg6s9ih#5h2eXoZV(!x!+p>efngqxhja{L(=Z-%<75EP2LLWRoRMrBF3s*LzKfRG z7!9`pj^OKP5T&8X159R&7942s8e|g?6MF^kh9w7Nq*6?j8{h_FMYfo(&1SMhV@W@W z$D^27WCk#w0G*`gvY`--;3x5G03zfO9Ar00cnvTm(gD!K`G9XseL`wzOxT|+m&;+s zlZ%yJA!;FBEbWv|C$q)MQ`A*5D&XnJlSHo|A3^=6b}$IAl!1WH>9ix45{qS@&jTj` z^b;78V9*b8?e}{TIs&=VUEIvqUZmI#hYkPj*98+`H`EeDY8wnXg$KCpAw;``R#wr%@@Nt1_oeY%=jjzYmT zo7G}beLc5Ytx^bhLajpNckmusJM6`$?|S0sw3~Z8ib_s>ZCN#kBPro5n&^Gz$k->3 z&G5Oo0x?&w5v$c=nT%J@tFEZzl$3GGDmdjeW!05cHC5GhHMQ4wJ*=szs;;iAsxB`R z@vDWr3aOyhst~yqHB$$AKD&6&@2@=m_n%&W=EU|zGbY@7*Npcr9KZUfcYk{Ck?$^_ zcY;4Ne9cCVnTUl9NSy?U+@FWruzqsRimj?4p^P{RnS7!h z#ip*+9wE|)_a87yl#>9CLi9);0Z+_kv+%}KZB8sqsfY*hWi0C1ES1z z5DkzAB^q{ujjBXHk&sFC|A^ZXWV79XAmGS*Bn^kqpU5o1F>b971k+v6dWBrL7%LzN zK{n2(abV*w#){4a%Z4^fjo^#)T2;cyM^NzOmHP+T0$&> z9|?o$aMZW$z(7ZnQeRl7SOT@ngQ7;_-7~*sFWy7<6>HH@ykcFyEUgTf($fLFrjmT6UDy;>m^ z^7Lwru%cyj zQHtb}`g(3vRb@#vtmJ=Q7$#` zIKv96OXn8<;}0+GUVo=u#`yjuC1p{)WdFU>{`TRCKYV%S*(V;%B`toxJ&{Tl97=`!t@&ik=Z*$_ZLQ4>O}S($8t^l}wzm|94jC}`rk?h$#-5(8=H^C_ zm6n#K#>RrhVk#-&R8>`!mzVPS^@z_Ai5P#Z*=)oPjZi=EEZ|JW3+4BF;Vz~~Axs0% zBTRBA(LivLN656JUKl1rAmC%am1u;$94xYj1R$?ZC@8Zbvh@_|4`X-| z!Fi#219>r1*^o{173fL&3EKsVKfw)%d4Q!E!k)l5sJD2RK#Iv1N~le58dV)3Jp}zM z)_o0O9f0sGh}~!qcY&|Kz#w4~v3-$9sOTUK+U-_^U?YS81zMqv!b1fun+UblYQ_*6)6J&8AKBwryKF>-L*n4kfpiqt{5SCati()~wfvYO8Wl+tJ+%oDJz^4_Z}o;$NRWG;8exKcr_psuQ}vb3(MoL67N zNGrumpL$-6P*g9G3Zyb7E=4TiOQZssTx8K}xHYAGLA6XOmT+suWt^L`^3R`J`LAD} zo;)m8&*7NG61!9?;&3Lmo4$W>{l9$s)X9S@a!HHNXN$&Tu|(X*q?r4&*?caO^*HRY zpf8;W2ZEkLW4@`Q#qPI6Qh{tf(%O_7*sp!ipstSYmWI|myf1BSEsc!@v)Nc$%E%yc zxl}Hfip4^SM5IzF)M}-wxPy$tVKbYJ(5w*HgKaz!Mg^xa(qS;MDIOHliNr~ImB=-M zX+tqulp6^GL9w|6{p4q27dj@X6tN;e4H8lzQUhX0YJmJ22n4_=K}gvs3=|{kN-_dT z)dZkynn?zOh%KQZ&c|`6G}IYV7~nD`%Ee}&^hT5R4VYtVLFfq<*04RaM8Kc0k{}tH z9e_x*m->mG1GsT5w(S8-lj9Mi9SVimNlXOI7;WkU8@@@{`ITh@jDX98o>WB)Xv=1= zZ2f_hZUpe*>zPa{pU)!GJ6SWd_}YN0cTFYCo~^O_?IA~la0aXLGeVK2}~fCz|m+J1R1-LA*~q$=w`N+Vyb3495#fJfOf%4NoejY zmRbg^lXzmYSxhE_UaxgH%{skOt`KRoa;wc?wHZ`uDPK@4;>v_vQB6gu!>ZY_ZS8BX zJh}Cudk!7gvU}Hxo!ghLyKnY{u>*WAeN8#1zPj9^*GNV6dbuR#F+aF^>gBh$Tzuw^ zGmlMt>#Y@+&d(#q*m&W|MIXQS&^I3*?oF92mF42PYJOFDeMPB|TcebUbSkAv zp_ECab=*q6pjIjq$Q2^FLZncN)f$;rr?48d3MtQG)ibpNOG=bAoN0r7fBks-kC(RW zSTo8ZWh%7_Ih>fb^4Qv&|NPGSKYo4o;mvoZV@9vn8i_?SxvVeXPNf-I6ODutkziX> zArTKnV!=XZquOE2wkJ9UGbdSdc?F*Ucn1PTlh%fhHKg75J z-}H(h1__FGAmGCbMbsOF3E}*Bvr?%PV$mQnc#Hpl-GsjY8W0yi3F><|olcL(gJ=_i zX@V7ks(;F|X^R}_FbI>tHaD3}2K1S#nt*J=kWl3fATs$*iNX_=CZY=PEpBlYrPy<} zg@{I@=no`g!eTUzI|5@vz(z0_WJ5W@G{%jMq-0uPA%Ms*8^qtyPmDH(Iv5P5iV816 z7-{K%K9lvL8-yp82>Ugb4GjU)2!O?=t3X3wF&HBFBbo}qXSnq+SrLWe^}5kF;3HuxB2`Epq2s|IQ!bfq3K4|YgIF2chKWe7m2f!h zcDvbmT&UOH(9nR;dRk+Wy8sa*h!4R_0ym@2=Se2x6crA^5xX1^#l|2Y03e^wVz&gi zr=T^Vej8=Yz#EBoI~)!=iurQ*tFu`1FBXd+$j@G^Kte>@V9@#fURyEC#&kWG9r6gm z{;b7-6TMz5m5QOp3Pp?@A(g1ADtSVI?9Mx9J@f3N`wl*E`qYk14=lX@{=4qKfA;9n zt!7ibfX7iQ_*$)+Ut1Y8N_O5m{_S&%-@iEjsS{J*du8LxPc6Ot=KZfdyY$6#3qN}6 z{xn@s%KRn?zPT2`|N$~ z>$h^jtwVp<0SSH#>O&69nTC_SqAvl7W@ zEz5oHcdoGDBi2e)rr`{H&SX7-`g5f`lGmNa2qB-NEr3>|#kt@pUQ7m5HI&d;&p01E@dV}^?V1~`uw_KesRsKg~o0*b>kB^j^hthg} zAJFWYiZbI#iF0>vZfb5$pBe@lT@@7w(i|rB%9a0_CX;fIoe+jEYarEz5<$w_`_ z`;mGpzy!~G`AH!PV{VdJUs#Q=xkM$w2J$!17%IVGn;u90LxYzRVnPTQhP?;ZjRaGZ z&O(V8fZGi>McW}++ZBeR^0Wct8(j-2M$8AVnNt!I9K0*|0yBq-*^|dW5GjKU0(+GS zvJYf`%-Q9ddof~({8*|xgBX0$Vo04is%J)W%+UI#>rBRxKOEGhXLV?pageEVd8$Ylv$LH4?4lNh-cJQ2_i9oTcO-Dj{k5+Q@ zR0-|G{Vphb)pCJ;lVFQ<@Nt2`^U!aQ!7`nY;AE@KV8xJ0coNv;@bb{g#1(KRTr{gF z9bSE=YIc!axWC3QW2`^IFmHNoXGB?K zt=}YWQ7tJ`qxr5F-A7rT$=!WY6kQ4O_P(^i#nJb59z(P|>hbo!sl>hXKMPB75Db_Z zaj+Nib9C1Yr^ZdycEgC@Ja<|p;^J5HR;F&@MV3q&v`x*Dr%O_?X~_WWNd}BrPRy;{ zw5hU3y}sqJCF%}n^NqY;NIeDI9DXW+)?O!CMm}FR6Z4p_-d}E~Nrbmb zm~!y>Sx%bAg2|LPGH5tBSRWc7gXFou>l7__cOr#*izf&F@n`b$>4u{axGp4sBgd`* z0?MiH0LvvTJVt^XsMi=64;Gh}BBN#DxZ-;MKn2>iqUkZga?t-BNiT!%O691%mR+C% z*gOt?kD@<>Yb-a*1eqVyGRGGwkMbpntECYdx%jp*Y-r*U3voOS zcabz0Xz#{~DNS@_wc`}5p*|iduE;b&k40^4N92q&Q;P%JYT4u?Wy->(jqtB5UGAhU zx4aFOGcOm%zEeW5WF1x@6qMB;EVD(a;mSDH!Jh#5qy$b6iA4~!Wyg5Ai$Dz9ZbyF^ zDstw;waJx%WKg?q(TEo<CNPHN<4@L^q_M)?KhtXObdY@%d0 z@?43`#r4plOnIlrwrxL01GB=B0Nta>jk37u-_n+%*@Sv6WC4G>dUa{uJVRzvI_t6j z=%9Bg0P~hL+t7`D$JK3ecia}Ve#_ANL{(9A^!+&qBjc&)rk|ZPBFJ0@A(z{hd11nR zHhH+Y3DAwWt57Ncno@78nC=QzC(TCfHyzO$lop2dqX}tPp#nOe(EJEae2tG;Mbnqa z@PDRw5W8JPE11*?OJt9+(xSgf9jir1!Suswg7>VF8m{5XjUgjNlUl*+!X+hI!q-R8 zM74+Mf>^#WDQv*eZl3S-C;hN2(|#Nbq%~K9^zC})fXuJ!+kOaj1N$ybgU9`{VKoe9 zy~82S030xgK8t>VPecBtldw<5e#ZsWP2OX(a;Z@uLGqM4Oqj}&})Fv0$&c0pv`k_ zSu~;>RWDUcSrkdDmM_VL7JC1w`m3j=VnBfr1%q<_bsKHTWv|s_`c@&OcM?Z5 z!R=tcVIonqS+J|&LhinqPqorWo%(qb4T-Bb<8u@iTPy5y#Z5x={u137@cG(i*xl** zkk(TBx$Xn%4sbjgPTWK`iH$VXNQ)2%m!Kp>8f>zTm@Z_~NxyJAw}_rFLHtLAUMhIm zWKQ^4CB>0nZ?QN3o;Abpah_vm=-YJAQA_-KTC|YY6>uK?gc{)Ta*V1O_jP%vChYrp z?4e1V!`n{3n|zeCrN@Q-3ra1+jFQmSc9iOOq6FLTsqgFmvR)sqzVVddc3}1{%x+AE zMh@<&1O<+~2q$;JyP9db{oNeAnYDMTgl%r;oKY>8sTM=vWUZn zphOD~WuXkBtb>3NOCON$O{ax|AVY(A5the*;m1?D0VD3U7zYzJOEj*Y`D%YE_kMk@ zn0or?>fBd7*>ag#v%K=?@yYX>-ozl%ZM9op{`~CT+3EYZp{E!gmbBQ7m4o`8JWSz^ zm!R9Lr)#0fvI?#kmW-@;I);Hm(8{3njHk80_MI@Qh2NP%`bZ54S^O5RH7Oy80D_$SQAgb`N0JDq7<2Ptv5@j4$Lp$xni z=mccLKf%Z%LCk8SqJgMp>8s7pGp<~?fh%OzkX{^2G)bF>npS_xU0eh@k z6pvF$K_I~gK7~JGL@3~JJg88*9X1hvS-X=UhC`|5w8Itp?L0RsZGz{&UuilDigEFA zS44Suctiw*k)O!ONJtl(9S%>In=?Ms3tKObD<4yq!jBnBhCUatTi4Sbox6+115UURtxFKIPPR&0FO7LJZoLrV0#{jDvWP5k}24E1PI=GVfa>eu>+ z%7a{RB&TWP?AvZfr%}5fuAl6C4h!;pPYUujZ-72j&s(Z+$3^(lhW9{6cfi$1_uB<3 z$aydCbGutf$nl9<=0>#*#oFCS^VqmvSBs&wtykk&C&37iLkxIlMXjLb!K@Z81GyAcG zZ52mq*BK1Kab8m61oO<_N8{xKnf4mY_?(*FwpFa{ObRiI^03@&l0_s#6Z%MmrA+?0 z7Hjdzc;Kv2m*7-MNKEc>*lp<(VzyzOSu2R(h@lV-J43$W7GPVywoKuPrG9j$8wNek zD$Qb!|4d7jJ@*C2^qL85#Gp!74xSa>T)7 zTv0LZ&X~^sX4SO?Dj`YO(&A5{`t2+jG^)|l=htKeE1Qqqj+pGK2(-SHZ5@5T` z>*MWXJyDX@b^jypbx=z9Vax{fmb=n@VaM#Vkmdh&z#MS8P$QI*`%NePlz#*7<9#IH z>qz){W6IF~P8f7OZ3B7@9*WB8_-l**anSho*LF>7^>gUVzge`X4Keni9eu(3BLH^R3rx4 zGGOlae?aCFW{vRwRmn;ibanY{UO)%MSstD+5&_ka4wbJ1kT-kfR*^>$+l|tKslabb%p(MP=nnX4Hj;Rc8ZDfaU!dt3#w!D*82gBr(k6qfPSr_VX@np zw-Yt~fLXzVC)0{X$6Wh8s~dPF$>mCc^=*@9uNCQ=Ba2YZ&InUu65fk2v#|3!g}F-^ zdJ3gk>J9|PdW{C-ZR{lXWEq?tDLTuABEEB9=f4m-MB=HT#jixI{D!P#zGp=m>o|y& z{yc^)QqCZF-b8ufEhHsCDXhO^T)mNgbwR(VB?x6x3xo5?9@2Y4>t)FMo*5{5F85)Mj^;$~cw5nCHEc)Z?-O5Sh+GJl+@9?OQ)nRst@+llZSBeO6d;e~|7^l$ zy1rt+{AZ-PecpT=dUmQkwr;xv{I>5vufv9VcZHReYJLZ*_IAzwV^IUJE7lVeZSGCk ztGk1Xn7I0m=g*1a5i2XGP0OfF|0*AJ{JcCpJ=XyMxW#_6!{h35vtx$utSUD*H{%$D zWwtpNaXePON(eKC>UQbv@MvC9GMK*9917=XF-X z#`fX&PLquP2Ig0LqI*8p6f>Mgp38DG}ZqVjtNEO zIWd(46Afugv=n1%SFW{pBJ}*=z+58>PO23w0&6#a@77g&+yZO^_~pKQEg=IqvJhk~ z*qb{iHtkrZf-b!;WsD|{Oakh25lEHWk);(R-Cp^+ewWBD!HV^66rn2^byN3 z2&z+^uBN&foI#NvW48Q`y-z_bf3B?lS+Xrlq^(oWeF-HW79SpfTM6k?aq0&*BUfe9 z_XcFVX>3YVjgzqD#8bJ$s3`|C^>Gqq%(vxSrPV9U*zOK)cZY|;_pnW{+<*MlK@Ntg zXbaMRB$*iLvr$#`l%3y5K2}sxnx2_ytEJAHQ6=ReAz90mothrR-eA8mAn-q6XA$J) zX6NG*V5y5YJUTj}qCT{+oX5n(q$rw`%!(S@@q6>Q+Gw@|)f9AfiCY2!ectz6w_4TrP*22SVGXNI0{+`_(BL?mr@haMY#cX_^F>kglncD3D41Od-`KA`)( zH$(TYsUEL4VS%T=Jzp0c-LJ5q_M0V8+X1q0=i3G7<*?M>88jkvO&ve|WS6nlK<{!n z*qh2IMX%fa;t}v()FI?M!??2LwcrNoeqjc^{KGZWW3)G$r&coP{QHl`eWyUo{jch@ zfz!~?8Ej@mT#cdsP&r~ekv)f|M#Vw%!{KYtvKUvh&rDqIGw9`}r@OoR=H><%OxM>Z zn&xt2x3G}3W(yPheNIAwBMO}ZJXK_4Kz?Ye3381|6+LQzV~wEy6mwNH1{=qwFM>3@ z_|{646Gdeb3i^l@{JRlUS>LTGxtnsidViR*saHqDN>If@oJ5M7N`Atg&<1jCRzVJ0 zB(0z6=&kuRu9uOEP3zgD^9F^W-l= z_WmK#Ym_KnqWZI0C!A`@8oTPc7Y$u+2d!fd?Eb&vza{IgGeiM=R|`?-o*DQ_EU?IX z;y$5baQS2WDg?i6f(eo(qNY3@S(OAFjgawlbZvCa(bJGp@k2_YCpmD%*Xv>RAd1sT znbb{e$3D}esV{UZtFQG?-e68zVK#~r62+PE5v%g-)#>D>EQrJg;kETZF?4})vKjs+ zGY{U_!Ksca>N3B<9-gVea+ZwP7H!A#p&QmG;aZAS8)d^+H&idh$hbKc$&EynK+xd+dB&hva|EE@^bQV3Ucvt^8%lRSOs_%g;#q# z%#7-eHtg1C)^CoJ0IoB$(CtvqNAyb9<97$ofoQ|KOkBOYe<0tb%G|f&N)!gg3!XN% zCrf~G|Mk3O__ckBy7ii(`L$`8`}NY}JFVIMeA{8~J@VA^a0Bb`(qFw|_*Uc)aO&gX zcMXKimr~*9#jnqkv;fDe(yt?sgWqvM2g&P9z;j<0N$b&a%a+ST$7RPs`_<;>NuJ-4 zDeA_1kW%NvkGmrW{C^E4?PupFjJmn1dF?xL%-wr7EARK+@n8Gv0Y00${$Exd$rJL# zg6`YBlGR&!49u1q6+}y@&n5vsIZhuCMb8St;EM=;aG@)hN~qfeSed{bT)(x^F(l zG1(3wqeb#aqao%G5WN3ga4l(&vLWBXA=t@C1jdtPqX)AP`VtJsarf(I3ai5ii$o0iI>dd zJ3Ley9UV=Ss?e}B)Qgt>4D2fYV4h;U<@53M#ViS8FC^voM{yV(I_x!pey$(+Ea5$6 z3DeD*-xXo?4j^fCtHTRmcjE8cmaG#5(9fXNRIgos7aO;AjxtGrG{I&`94L_#gzrf~(DH<6M>uHsHyGU4$d*eD6v?kWvmcJJ=G5NMO1#toCI z{ZxvyQEYT487CP)jMy0~pKDvhk`@$VMKVy5kCRu7ot{*bpNRoJ$Hbr@AzzXZ6aMSA z8)5#MUvp_(nDHG}+j=Zr>AadT`1*~j|M7k#^vIoim!9@c(gJ%EzS|Dx(6CA#K-dm{QLT;?;YfKFQ~fAj$Jw*UIN{ZoGiwNQC|CIEmj;jmPIi z*Gl(C=0vXh$+ao!!~5y?4*S3eb>1kO^epe zW>X@a`Kaj-^8F+nNq@9z_DhiO7kn-t;awZKXN9cm!^Aov2=R5MID*Ldh`X^i#?;f- z9954UJy{)<5JqW2%_38%Vb)eD$Ld@2Z=sMc~uA|n{2u0}m1 z7pbaO9#yGTI3OwU&*w!%#jr#8FEi!fDurz27*pDyw@_g+4KzQU5 zg3=mjDE%|?=g$aLsU*cBF)<;q4?#T+M{!%ZcDfM}uiRV}GoFWgxo?w|xgV9l)+)yA z`JAM$@j7t%IzE{3e=mO=_x(CJdx`IU@c4RrTM@qB`*NER?)n&J?mV5Y?LLt5@O##6 z>3UoLdarT#+{@dzKj7Z*S%?6A{<5@uwB2kmpV(s54JTxSd2HGHviU*7*ZVWLqy{Dun?6wiqrwm_{y^=*7|YWB zT@<}0)^uLNjqoibBmzUGW^*_C65u}IV9Q{^t<@l7{Oza+M-K{wI*AG;3!72?$pq(u z)n6FEHlf0RgNuV>_Mrz)Cwko{QKz&&R4582l29l@`^}Tuj2ew=l0C4xux*y1Yr&z7 z8HQPmVlwO?{&Ds}=G(qzRM90u+L(7O8^=R22M!L-XcyY}^*p>r>B-RvyQCR-A+;;p zAXSYhHkkbaX-!u;?+yzT89``aGFlkL(Yn>*x0`5FEi;PA7*yftPEuny)k_p+l3Of3 zG-@>R0Qu0cRN!Dp7WFxjiazo(c<;!yOZjmR>`M|t(xP7=WYlSsFduNY!)9_ao0W-1 z5J5l`@XQN?Pqi}H%(p=s_E%aP`65*-kD9aH5#GXf4?w+~mse96Xsb?GurILholM$x zCyX5)S{_lAEU7J+vNvKDOZ1+VpVXgZl<}D})EpAyN$eB=aj%OV3U!%`({fQ^s!w{;{72o;kd*X5*`tcdx$oz9;9zst5G z6yOULRf;o4Tzp_4gfJP%#2e;-F>aY!Q2s=U5*@}$7iQWD)0A0|NtSq7m(9x{gB7BM_@9YCN$yH2jWt%o1v?Y+B~skPx+i*Ot}C{HHOeZ4K1I62w* z!RK;wquf=1`X??98F-M8pRTqVKi=&u^I9INqJlmVm$PP`Qz{Lv&oq0kp_Tlm8%dt_ zE1A7FlHv>+wyLJ$8D}p2hE11+z7kj7--Eu63Ig6n^0uD1JwUI0{Px~6)rLNIE8W*X zsQXa(x_=S&JXw&dywiG z6A<9xY!Kw4r!=kiz=D{L#t+f9U3~0mWMM;^^TW723x-*0p;@E_|Q3mkF z4OGFc#@fx2NbW4ie6r9$VsUS*3ub5FhCb}+K}MIh6AA|jLJpEbe2n}%VTXlr-2E?o z8|Hvl0WJJ^S?W}rGzKf_nl~#;X-cVaD}AE$E)2Lx2}E7&{mHUqEiGQoCeNYpFK))_ zPu8L`76%v4M}cSXUi#}(P`4%LsSLR0o~~?al571p4tnkiEx#Te1V1!$y-zEs4IG!s zL*l#3y5`cEOJ0|8BK+^lM}&PgZF=sedS0L2YQA>#^WNfNd!Cs+{LbH6dY+CzU6)$~ zwJ-CA0%wRMU9XjSAF(8xFT+3_`+Vzu`P*Udd-ZhrTnTIcwGr$a>N@4Z+w8j6I3bpP;h5eo_t0)Va`9(-H1d9qWtrzGPwIZi^`YEBuF ziY(Z@+)eVa>>7J;iC}(^RE$iEW>lN4S$04n?N#mUm6)lr{ByKD^hI9UugYPskYswa<$SZRZje1B=z(`N7{hWZ=mHkDEf12@0~!e$AcKiDEz;*T3K}p-7eB z57zj|KvAZNt>yjnKV{YbK0A`$QMRN3sQOT{;!~-zX1BGYo&#(8Z+7_ixoN)d=WB`x z?<)(SoP?!MH@4S{nJqC0v>Ow#P4iO9{&p5A`Ji zew~NBdM!HoI_UU3ertK3`udzh{`%NX^Z(qO`2dPi;d^02uVdlv=f*3)ThQg(s#5pe zSU}HLt^a*>&u5Fz=cOg+;}jC~+^Z>k*N)nA&|+{~m4sVcB3HgSbUz*YIC)c4ty8UB zo)VYcx;;N4@cKMv8i7(v#J5P7ayO;nX4j=nhYbt+l!yDZ-sbW&JFBduGy^nCsHvz9 zkB)%vRMgaWFUM}e!!+5}S&F5jYV1z$94oe$=?QSxu@96D5=|cLW(#msy^OwqtV?+^ zaU>}`(O+JQk05RCzm2xDrEf&ZBJiF6soxr?CKmS} z{3kFvE2OuJsCi+PbPg*7w!wi4R+%!{a4X{#o`75lsWqg0okLK$M2DDbaq&{Qg6Gbo zy2F3Y*e$w2tt3}SvGZd;F6y|?T(a0QlbC_(0ZZeYg@Y;*d{>%}VI8_go#5YaAC5=Yz6P$z zp*t)GH=2sESy7}mrjs52FOr=LV@ZD1?ed^?&_3;=c@D0 z{lS*e@<=h4=X$YJ|Fb{s^OQZ;r7tPheS0pxhN!2`*R{*BF4ZRO@O16upXb$BN}HuY z!)HIW{%xP|XAXhz+h?uc;U@RTX7iWphZ~U0Bcg6SaJTp!h`0E@{3Gaj&PDw=k^8!S z(G+;A7|GQUT$HXYhQS%XTXL^XVJ=RsD0gpcb!v6me=ZonHT1mSzbV2c(HEYrQosFQ zsj0(+f_$}(a}mGxZ+(3o)DvK2WMyV%W^HZl?Ck97>gw)};}})B(O{c8c7Wq}TD;gl z2zNoSK3=42WFhp;c4DIy;cAm12)o^kl=6`o3hk;(%Rr( z+=3E_0$`P7!d}LK1Lmyxbw2kt>OZD+O0vw&mPs>xQv>rCs-N}70rw((BF4y07ODJS z?R@M=VBGxAf}08SWJ5?nFSlLD@Jv9z1&SJ04AhB7Gt$?4jmFmIa8@oVKgNcF=PFqY z*1kw!i+$Oam?9bWvsf%uSTCkTf~a&{n$?T_r_ zuQ~{-`LN#hPQAmF`F#=w+sL%-iJgX4`cdPR3~H#@jU9+f-!PMo6Rw!Hbp0G-985my+%h8%?(^LsceW!{~?v=qnWwm zsnGu%ik8!bBI&Hm^}ahf87n#1op-KRpFX-hS$uc3_UFsWGGzFn%k(qoh1@L409Jro zn}!MN7b0atW7~_KkRU&|Oxu&~JJ-|83opv^5mv9?8{kr959;zc+TQ+rd1)Jn;Lg2G zHuT!MtMOiDXZE?pWcHi{(!uzZI1)M%ZASYhX9B6z%<8bAT`i{Op7d{4SXA*ExJ(9& z`d(%SzXnn!xKf$5bp>>0s?&~6U&>R$ZfxBPwX*5c77lL3%9FJX=$bO=31HVRmQsKg z1yk2~p<0?jQ~SRPjY=CESd=P~IK{vJy6ynL0ucGw7``I}3*JnOS?nhD@#=+9)Z^gH z*V{9P%L!)4Qvs9ALID<*cT!SP z@MwQgj%+B7{b7Lvr`9MWutF>g4VOFG6E7=*%0JMJjtlJ4~Ir>i`JVKzM}^(Phl)nxO7Z3t`Jv|+driu7HF156zNre4(umLlyotu%|&t$p0m-~s_*J8~0 zuJ`S7Q*_4`UBt?Zb8mi+x)lD^$(riP7MxO>wi`+RVr@JdX2rj9?3D*=7C&nYvde)# zJlIyJR%$fL$z`bi>{cDCt*Ig8?ew1;!fn#Di9M8cRUhqpSXx^0?Op|<67UK@2khd6 zx2M+OskgWLc=36MMmq=N?fYIQDwvo%|0=~!hflgQ_VoxHernyx8STU?X*L4*5CY}=a*JEfq z1X4(u*l}E3T(2x}@xVdH@2kdo4zMf(Xi#l1EPWQ797g&Z9FSmXgJ301q@eSB8`r?7%ug2?@sAEXq_r}z`UDQ7b<9rF~$VxXpwVB%6y&b z-%wIkQT0XoHOce%{_dn%J7JI_e1TO5gn?KN`wffggy4hva;)%HOXwnd-*nz9PNpa4 z31*5dJORU3-sGY}R{=5Jurpi1-C9!qh4|(&@dxjmyWCyc_|;$g-v%i+ZOMN#KoyZP zeCH2+sjgyZ(LqL7g7>WFYdjq?As&Tc2F3?vO|^5HY2~zG74Yg6n5&vCkeSWQ%ox|4 zr*eFUmS;9odl7@}mhnqqg$+JBw6L%&EvL*-nqe?g+accvx(iI4LvQ^HCyV?0o^(vQ zha4Simp?ZFRtLZPeYW4Dw$J0aY^fRnEFEs1R=~!8)HVL|W7NVsgP65^w}X`^ALFL+ z*?cNp`>W$O6eUHlhy;}x4;I$dTrD~|KN%HT(kyjSG9G0sv@>dJCs$GzmP%f%88@vg zvZ}=zwQaegZER8~q;#ki3H9_VHEmS1rHfRe)nv*O6BBuKyX;nKwt$T?z;2;dzLuDH zoL?z#k-Hg^4TG6i&@O_^0E4OuM6u=N%qc2u=<{DIHa~wJ?*OKi9h--e; zV$T%9BUi{o*bTrW*7qTKzKh&3{M|At(EH=j7a%f32(27xm|VXT1SZO-G^(f#=PAqY zigbs2bNwBRDIxQiw}($&bgeW!PlRd|e-gPX?kBzy5l<4Nkl!W6MYLOK8c9km-`s^$ z6DgH>h`pLBjCS~sLJ|fu04L!?o}WUKzbsrP4=*Ug`4zAVHo_7Xy&}&dsJ;;c6(wSj zja?J;jRm2M<8h#)uT`?gvXLsRPgHUceVvk(m9nazkUI)1m3;l;FbLAdM6fSH$jID0 zVYV|aB02JGfQc^fS;HU;kBm_~%ieK@VX}n15eOw*+=etv45`jT zL$*wLf3R|L{P*^Xz;61*GSAx5e_v#*MJ@V59Rm^Dm2YTlF8RM+ElbN%DX9ov*AC!d z17mOjgnP>Th<;)y#HQI4w@EQqtLJ?lQpt02r!vp6Zz-PtHIyF3z}@NNIdOg`wm(rk z40D8znz=lWPo?MC^WqtLsVG8|3nf`|MYh_#evVGv=0t-(VB6?rcIR|w;6XgXIs%nD zp71B5CQi{^ZPvrkkXS$fz#Y`}7-F^}!CU195CASNHXsB7eO@7<@%~=lcPjbQg_}P8 znKTL?7=f|Y^^3<>Z;7ojh9su^^GVyR!@=F|Ba3u?6w$gjjbn1WIooA2z8dj<&loE* zw4k2&Eq~Yqa6VV~hrp~N9foxm1JcEvVS6rui2UUrfyW%gV2MIW5pFqocZxwj znJC(^jXCA{2h8scd%=;%d?I7!AEEe{y+RexVOS-3X>z1Yb|TRz-~wM<5O43t2VrR& zK@^znvG>>HJ0kCu6&MC5MnA_r-XQL0?F0u;kk5?8a%vVz9o^)VjZ8h@*4UJ>hV*`s zOcu6={E?e48o&@w5sUN|mZX0wIE%zCPL1E&Xn_qi{C_Th7z0{hL4#E2T4lr`aE+MV>!%RtYwU$%`RdW4Mq9j;b*bc zb+ial)OlTh{8}IPte57uB8m^?enDVufK|aH@#Y4abikF+)zt<0_NL~d)-1a-+n2H@l|{`I zgZ9!84K#S#U!Unwg)S>%D{BNCUy3xDJDU7X$`4CQmlX}>yN^B3`b}d8q|PGZ7P;b< zx#N~m2^mN>%4`XBcs(7>?d-~z=(xW{$4a`+Yt*ObWfQ{I`gl)+0O0lA?r0Vhg@KTO zAmbN^l)@k>(bAGuinccn-e#e6)!YGC~qP-2PufW*pt=jP~W#sWVR22VgIrN z4DUw90noq1PR?5m(4$uwF$Ra!wCmDxnK+qJ3dwjOtPPnwZN?vN!Xq4;Z^+_PNiPMp zacOLA7n7od70%oB=}eOI%JD)4V&m#y!PA^)qi4j?WPdVI#D`kpge5g~B7Mm;!j0k~ z1gUcCl&foH2WbJX>{&oXM-GKHhH3({+hG3Rc@MQK*cvOlf&Z|s8$&647+8L76@yx~ z6oz(NJ#l2!?w|@3?r(-QZ}M+oMNTlC=ZV8Z_qVD+2T~QUtD2zRN|0sRjHlIdT0l3KMR zweDA^HLF;{H4L;U)H*fWX)MQRLg(TeEN70|_8jF9s$eAF;2cFf>ez6x#g8cUhgAFL zfAS_NfBzQzTLj~;ybfV$N-xiuvOx_~q9isKlR ziFkSFUdgeh{=qT-eEM)V9HZ;MEUJ~+d-A6WwP70}2g&yWjvQQ36bLK^J%72cv zrRUqiyj1hbE{^cqcRkI^8^;uopd$x>X^om&QHo6S6;k{8zLY|@AOO?y7HSyo9w$XI z@uZ2esBrb9sZOi`tj7-Lt(Q@?Lqp>|_B+#KPsQ7#6WV-%swn<*!UCur%AZ{|P+mgz z0JI0VU&^zobM#{zW)2oyT-aNo;^<{c)zH5iMs_Qes;NkRXP@CM0n(77qJcM32^s!FVWNcX_j@d`!A>@eT2@8!VexlP&`tZQ5j<#+MCWcd`_j()l}=yYe*v?{nB}w|jdmQ#F6eB`Puv zIhmB_!_4{4&&@5q99hnQ>{2ZqC9~xDiof0poQy?Q)NL9RraC=&D#81ICqDKq4 z2qZ#6FqK*TnVthC6WR~uo;91l(R(SQBR;Dx8>fzfX!gbg-R%*J@Eq>6KtfDu|LY$_ zSitVMRPcG-d$=xIB+;FyZxKDh8pnA8fxg7jM<_Hp5}_?e%YwE)Wz!Dpdu%qF&+<;z zj!9-EIgSe0xX~};oNNwxDlIBPNbixaFs2-A-4Lt{6mY~OSxpsM24i#ck~u38z;R?* z>^qK{6^4L3T)RO~yi*?=8Y(bSy)?} ze0_d)y}3VKffjlko@(^xSXH~$yo+tssa(-u->|7y^45Tr38u1QK55-$Oj;mbX(5k z&du#ajU~1%npyi>+xmXp-%~olFb&$}8FwRk&!wD_)0-OM*QLxHrKP48rexdV$ipVW z@6WA>}ok{Sr4*%agd zF^aPiG>lX@T5<*p{xo5llsOhScv6l&x-vc$u?_tRzrJ5=f1XC@la;q=S>I>BKFe)@ z7_8UX-U-k+7a`(HxF~mHXh?*cIKV+;x+tvGSmpWPlO*~!zw#p=AE-e*oaQvG*bqsf zvN$5wRjOpw$mndK`X0#Qs7-J>Q#mQ=@GoW=S{Rs^me1Tcq7q_xqUlw3mB~EWn?TA` zLurRN;P%mDIJk&Q)+N{^@Nx}d**y5v+2kNy2%0Haz0_1$fG6b+^DwN}r{_#T_TZib zt-DJ5#<{^oJsmFNaHPHOD?{3w4^W+{_9$euCETv~PZH%V{JDg7Q~K@D1X40f5bAn* zu7D8Ef7R*Y4P5Q@MV41vfi+R z`tScr(TmNkm6nbck2e5%0dSbh^%ibt_B$7bZ%I!HYM9B&&)JHl>={U~OpS%3!5AF) z$3fuv7-W^dDMI#=-Bs-OFHu9BZW2P%Lc{Kk+edk%9Ca#eS|HW^4Tb<#{% zkuY5oD`$mpN1Jr-Pyj>!b2V|`Ou+=*V%D$qcg@y$n$vR%6M$Slk!<@N1F1~9fb zF^0eUFgZJHk&Q_xRde+A99@6n!g@SQO8yU36QfsHsMRIJ+=bvW=EEFbMm?IZ=o^f+=TRD*# z2;mCo1+H(dv;eA}E}#-U|0T!&c)r%`ah3Z&Yjg5nYV;1<| zw@15=55M<+>m9({)tU9?N)IC=5CAp+I)rOJ2sW-(w8#LiEHX{;>0cF6(=VY|5$lNm zfqit9Nd@b6nVc55U6zXYv<*uTGLSK}Y(u!^79!?ZInQ{kfFB=MU@Pwv&YBr3QvSI3 znZ(Gx5!Ytisf;PlV79Q2&t=J*pL*OTkSG$`waqaNK@}O3{7(BILy5q($EnaaaGgdr z&0}COf&hWU<<##F$5SkOZLF?3V9C7)mPrbs^%z1iHxNbnE3-ZlkL8De&9MVmJsMXV z>$_wdtAS-UD!~7GmVYp)Pe0NdX%%Wp@)7a5#t;(cks1tqz$eqyH`HH$k*e!Ib+$&S75o`-hjnhBIp_F zZ1M0>nt3_O^>GJ&0LSp4CpY)51rUFkO3lO(33hd@dt7dyf3E^~xQ&*$=|B}XxlXHX zI;dN`t2vrA$7WB8Gv~tJQpE*L_Y<4Lg3?nmh$f!<9;Un$s55Wi$G4=0s2=PZ2 zHrPhr|3Xv+^2`+aNxS`>%uXkhs|IRyU-oBLAwF0fwwHimexBEtG|X) zBIbDmZ@kQx(tDs1E4Dyc6ybc8Gg>F`H&Xn}v&%PhYjJj?f1_KT#mtOoALx=9Eps*5 z)Pte!&J>`0OT4T?iG~V_yHNb9nwkda=_RrJSR~FLoPV+oMydWQnXzaJI((juvToG& zc;iQNXsn9+?axZDFb~-~BomsIK3ez<)-j_%gfHh70wu5TIr9u$qLufj$taH|#1q!f z1iFmO%=Fyc?95C&5)z{L%ASY_*z#?vYF3uI+MXT<&39`&5iia6xO9NZ4#Z3kD=Q;M z$AExNKPOvTGZPbAPtSy6gs9|~%eSui6D(+!^Yc zFXN8vf*`I6#Y4gV7 zIPs5P%&{AHmeV+O-b1O8`R)-w??fo?0veCsmYktA!IwK_Jb6K8euSJ-+Hj&78_+M> zQS8#lHjfaEguz8&DGbyNwZDz>Qj~6|jhJk4h0!q{ui+4N{`fG&+E4FLk`h3Lmfe!7 zqKQ#1W-*J8=0+Q4Nau#Kmye7{0rzBhIE>K-+I7@3^fe^p+v}_Q6$m8E(+aeMNUVei z9au>SH>-M<~@Wo3;WHJ-TsTI8K6aSU#j>eU&IqX$(kx)zpL5KGIOYS#T& zP7B4W#zJPbjGZ_6s?&c!`wq3MvgvqbI65tc=3$Azi1?aLriqZBS*#}?V+tSrxd2-p z@3!ok!a>g?rfg%Mvut()hW4JA8@VF(TURrIr6qFow{W*5sl6ITfrLT7_pGu?I*3~i z63V!)-|yHT3MvPxdd{x4Det<@ak-bUp2;;xXwFL=GohHeGU1k-$@sj0nN+;kbL zY$3t!Kgea2dwQEn8)eY*55bj#raI^i4q0-KEeQv}&A z^b5qWW`LDkwsitzPDEk1&w$Qwb5hlCZ8lr-no1HHu6e@N$qC4;$?d|O>4w!{fVjoo ztUBT_%j_YD%$!jX6~Z@7k*_52!V^&`*ieEs;}P|X z@Lv# z-z33>Y-v7)A9w|;9wEGVAU3$?^I6#U?CkW^)C7ekkmbqAabTT93eY?;G3L@}bYN`! zk{$N)kQkvSbP~@IF5x0H+?bH1)+2~H?x_h?k4!`&?EaxH$l0`LDN?`&-! zup%oL;;pTgER#p3UY?pZ$^`56$b2kEft6GJ&2fFKDz{n<&O)+OIX=g3fu=w`2sH&K z7XMLOlF7{D)OpVqNXkhj`FxfIK$fzL#e6!QA_#B|kp4h~L0(eZ^Ye4SJr#kFZcrO0 z&YKun-sCtcPoOoVAk;t_d>KYFlqy%NRWlXjg(cD03C0Ezp(=W4@Q%e2mmj&ydo9I< zRcW-LvSF*}n*q2EgOs3_%m>ZEjtPYZ3fMfDNF%~cNQUSMl{38V%RV?#-2nQGeW~+d z)i6Mbnef?=ROF=*pJ*`#oy17FIDsBuaih^_wOa688s}Y(bQ_E_x>bybh4=>EiJ21? zXz~D}cj4+9jRrmvlmlnwm)N_IjbnCDazv^>)vi!Pg5KuzFT+2-`^nv(5%{WRE4F zrYh?jL)$|kLX$gi-~gv+!hIk$Y>`NWA>DqSIX4aA1(a*Gl@K?{cmRK#d0nY2QTb1> zf>jg4@`?t@5e_Dw&vWV)Q0|7BLg8UAUJ7+cu7R_J0oF2n| z8R|YOmFQ3ua@Jvr99C|)0CoerEL5`mC}?t2I*;qt+eHK)he4K{r;zKQXipr^X0vm1 zb2BqDR9mu?&8gNbkYF=H8+t40Lj#HSzzA@MiICDt&5UaK06O5dA#SQPw@ALEY#})U z8Np3}Re~AvDeOgJD9%D$P*hSV#B)3X-3D!q2C!|ms7PFJHevQ70a!~*ORKA^oE9xy zs;f8v{2VG5=AcDA91;hMgO&6Ov*NFUHRsT_+ie(|p}Z5pKx~{;C&l9+5+H7X3%Nw? z88|;VFL!lywcTz@>O=O;Wy)NbQbdUfWl(?vj}sw{B!r-_CwykSC?o<$fzcl{0f{ko zQ)j1NaUi{d{Sn(%tC42nH_!=GGgiCK*$5DGus;60jGcsO?$E1*u7fzv_)$fSzggyN zlScdw>3Y4&4l!!iNGY&296G6~pusxrg9i_;uCBTWsVY;)!=e*TjJJ#G(D)DpFH3j` zaMOYi_a7oayj?E0z=9sQ1})`EG+u@9DL@RC{BWa+4j6#~gO5y*1943WjJ9R40K|y{ z;b>aOrBFuA6ypx*Jg%3zK#n)ryep3pkvs{LDwL^M2@V9CuVCz|7P$*<7qWRp1_6Q9 z;w*c{w7nFednQBDnZd%Ov{G;c%b_+dglu3pOii-PxU{s?Y&Nmg@U$7A3e|Ntgkhf> z(|H{I*}OYfZ4|GWak|Q60pc3G%ud}1l(53Z%)XH_)}9Dk(ITk~ngE7U0)WYcxNp>m z@uH0;TS7afZ@!RMo-VG@&&1GBa@j7x-Dos~QMoF80}vRjag3-9tRozx2hq`eB3_#U z%9u(`Oy47tdcB=z5*eCbCgzd(rK^A}9rMf?C&Jbs@(7vM646rL$J2Cfh}#d+Df+o zIoimJuvF+`u_$?WZgiyhNfbyovw23lH=Y@?^;mX{6i4EHY37~K6&?!f!QX112*C@; zQ#(5rKNt#-9Rjx8%MfZU(uS?mTNByHkO~&)Fpncu4GMc`5s1&|HveRel!yn|rM%CS zh|Wx;Cc{Hb9)I;sX{?R{+-%oGYgx&#rb31rFo|Up)fGQN8PI{L$2d7Cm8_y${&ahM zqm@d@X&k)*{?IzGo+CRF#*F;cI;|RAg{=d5@(k#au#Q!mxT9B6Zx`WF3Ar%5%p5en z2VR`bW*@0PG%h}(oUYa~w6LG*t;1wQtb(G(#wcbR!l98sFwq3U&;eMm5);BIl?rw1 ze8Z#wBYs0Cp{u<0CS00g2N1K5c!f(I7rIGo7J+ja(n|~(tW$ur5H2rs0qxTnnKjBF zt5Aiy;8URt8UdbOel)KN+;C=yK@A_6_&6b0kXHiqpownWx)x-oi=cB1EP*UxM_pS3 zDZnhB7_w|q6EY54<{L6-*=*M1E&)pU7ec{#eKWae2;v@#kck)D%x4ioxveQ58)SvUSEZRVtO5%_d7V*=!aA!(T!kS*QdEfJ;{G&>XOj{$Lb_jG{(p z(g{RBOUVQ1PJ};|d(l!w_OvX7Y)@B%6;O8vx;0$rjeiGD7KE#_CtEdGLx`$XvKokxN?Y
jHm&l3`OjvDZ_{@;8D0CI!P#%Y5K$&bd3uJRT4-|%XU$~xz zorHYK_Q5rv-+cyLuemaPIuf-@gU3z)1^$ZJ10tc_N=FjT*pZqhg4G)Jmr5m8?4hny zdaz0#K2en;e=VAWw&)Mn=rHspT!UmlA7dcQO-RKI6^P&{)-z-foWFLUP_)-}OL3V@w4_N0Uf_g+2D!%mtyn)q7op&BItZ_K!{2 zyg~)I5wC%4gD)Z5AhCO>QZfPS$BXbY43bP=kecvMXa$Rho2fUb z&3Mhag!kePp!q(6FT?Y#@PDBOLLK7u%mNyM`eHNG5xE4yWHH@bW^&UKAhU3wISYf$ zW;2t?EH5v!Xa-)uBn*lXuVjjtJtUaSS_m&fLt+;U*YH;%+l(1{3tf=tgtw@Zp&c<^ zmz{jH!eQXTlenyPVBlf>A8ndP0#+0tEz=pfs`BxJgbZz@&-_(fqqkfj1@>|Lm0N^G zFqFNb&U_3>cj93`sZ_aD%I$ z27?1CV}BDRF+*{qOro z3FPJN4+^SxH7tOvf!DE~MQer(nKjt%)1%YZAjYFrFb8qnTjw?B7_b!@mXS0XQ920VuGON0Ba8za z9$(V9b`oZ6uzYe9EP&96-C$WM-cNt#TsAmJ>`xgYy@EXAV*oXfj?^j|Ae&=b2l4?C zu!Q*OIZ_8Sjx)&R76@-4=7<_K3cqpbBW`(#o$*XG^28aKaxsxjI>KLpaxMmZ!%2ZP zb9gU~L7EH%hq&Bbc!*9AG_`{A0QaR*ab;z>(Wo^V9R&cpS65fr5Fm`=)l4!XSi!NI z4yt&W<^=MRB_MBrlLr04aqxwEMI~DBZR={3xZ`QsT#3D4u~?~2)O(q9=8lJgGKoq9 z&0e=b3yc?b7Ah4Z0>nw#v*53duDc9i|U4lK7<8zCS%}(mr=xP|{IKTKLyTMZ!i`DuD zI<&)#Gy6V^N#tclT+ehH6!Ju-gNyme6FZQNdF$#ED#gtJ8DmqA?YGu~GeO;vRJmMU zU0tOZKCEiM3vs9jVXp)SPoVKHFP9sQ+Ujac(i&!pV^An~ubgXXX(^k{LMwO*eOp*q zNEi=x!epR2A=fsW;Spja?D!QGXDkSij1Vt%m93Dva=(uf#-m6I5+8(SiE}=mC#%c6 zI#^EY?q>Eoq~0|N7kN+%a^EpXEmBTStYFRx4%re>n zRw9jrU7_c)c!&#-*Jw06H%gO1O1NjFL{~{?VUs)#lVPIqKmxIRB7}ReSSQ32&7J{j z3AORpcDoII)BZ6)DlYU-0!>(iDz!8uB{Se|GM3}Qr3Hg#FcD0!=Nw06T0aCM5eB5g zD2m16!oq^07HzR;XkQ|cV*dpzX3*%LUm1v%nluvDYm4=C44uI!Sm#VksNzNP49zd) z*J3dTD9YKHQ*2X9*KaXi#9pmdJCLm$(Uow(dPwy^x6DXni*yK$MCih(y>~F0gh6fy z`cN?QA=PT7(Wtdr4Rgl=1WXneg2%)55IRQ#^YT4bieUYluT;Gd9~Ox7lmwZ~5~h)W z%B?`OJ)qq0wKsKw>4ffSLbY10-EOa~tqIvml4@cCd=0|@D9m>Q-;{sQL!VA-aT2Bg zjV1p;+9duQWnHAMv>%Hos>i3A$aB@1EO08sEY}<86@P-Whu?5xH)GRzQ5O0tA)tG} zH1OSBHi)7+FXJ<7j0iJyy^MmnK>mCVx4LMeAwa0%W&lE-h$hpN`WbFRjR)u*(FZNa z?x|yX4%JvyF$2Ib4IlXxMZ!@rc3*6!(V+l5ln$BYr;-F?=TGvO?$DyI2}$AX&=DvO z&Ju;B;=;Mm_DN1M3w8#jyLyzSGsZanuGe(-y0XUX032uYau# z=lnJ7t@XI-hJRH9oi%3}CxJ*2Aju!@^?N>q^5+}GNSP@m%O*xTi3QOI$E!A|5YReA z;8TGBM(daMUVuYC@G#+;wE{(PNeHl>Y34dSWW&H*P>?qIbVWb_!Ac_!Qg8^Gekve8 zBvg&>X&*#J^-(^o8sT7Lp+$wNV^SzYB~%dd9>3_l4rI#_v|E~0{`|`9#Ia$tC6$Ff z1CdygQKCPgMsehkh2fgMfcdht!1WG1&TK}@uxw?dnq_ld1s*LBL%Qu1?c+}T6L=jj zHAk)j#L;2ITsxXTRKj}4c$ksi>W~zdHKy83Tz|3QKr59_}A;g4h{c^7EQ4%G_ zLcBsbeC(wn)v#G13HE1Nlcx|{FyjcHS?(?)6`6g_+kxm>)RqvxcnTvjLC2TIk=m?X z=3kD$pA_!T?}(H!`*!{U#WPWuY6i03K?eF@_YpNMJDzTyQmF*-&n z@(`9$n9r9g1|Q7kJBf+qtw1ID|F7$qMTWzMF$P4D{xI$@)x!%sG z<+IEptuZ?10RC&eo!&Je1RNLwamdo%gxu(xJyhpV7fjShDvq)vymo03)Q*v{vs@{O zfU=Quw+Px&Kjs%@aF{XJMJyZ63(p0MT{#4i!(Z_qiJv%NyGNp&dUF(vLGkE#_=^mR zpbD=LKl;p&P0UV^6vCD;2UhAzk+8^UOhY$71j1(shtq_DVN0IonP(TS0>qWI9 zmSXr7t>ShDi?-3ME}>L4yaZ%(oDh~@C=@u8meybabW%$;4ad+lT>-S4H;51< z&Ll)YuE7WSmd=(aP*|)-Q^iexl`NY9U`FKBT)@($$nHuem$B=TrASfRiW>PH(}%LL zw&AO6c}mP@&zu;+GnxKF8-XOIP(qAC z6Uz)oTw@4rO8i<{TH=XjqJ;=%1gi;z9914O7l1pl4*Q1a7~S@9LN*Cc{BFHoeNi9;Tnm~VZ(Qy`eAg2cDP;-P4SEE)b%v)I?}Q&fMZ`s?x5Bp%^Ts#Fs_y{B%STi*Uv@dzQ24 z_GWaTOBkjG2(+QbDgeLQbNb9*<=5!5;zhBw4rRzWO`M!3;;_{-VKUt7QxYHaZ6Z4c z$oF=}yX?GwLLds<4l^$xFUcr4a>BPIh!^buXr^S520w`ac!~#OF>68-*Dx<44C6vL z24@PE#`#rIFlwELEHgZ_#TjQdHQUq2LgC*i3Jz626s3>U#bFE#3~?Ap@}$iY5A}&s zN@J@~m8D~32F+OmDAbL>zWD~#OgJ9oC99(Us)9XKzV1;5LoEy87I#bXJ(ZqFjEEsj z7O7zdo+SJ9-d-SHb0wh9rF2;3x)zLdg{cv}(gja|OesogOW)^1V zL8am{(1)~12uWgx9gynE)aXq3ER`9HjqmLcM4VPI@bC!_TYf|nxDDus)Q9HgC}dF# zhu+#%7O5zv#wBaZUXT8$hhd_F=hkX9UKM7ZM7FL3l#=-1Od*PpU#m;Pob4b$+@9-U zN|mQ5I4@?rU^I<;3I#$7#eya{i8ykKLkfigUD~|-$V0=P6Mygxj)!~szC(z*#~gVh z?I=oeuybp2R%Hzl|3S9El8wJ03uXLlhG-5Rl1Y=LQvdGH8(7qttgzO zjG2H2$PIz(|H29xPGl9D!XiKJMH$SqV`%dC5O(R6p3Dd@>tgL2(4Bt%sPZlr?#FeBb<7PW=`7(z~hsmh2rAR8L&w$rsiol{|N?_tH&CDna zn>4)(SLH4X7QrLSC*m_eqFF;e%%zb~B5{f6*lWY?8{Ra=Q3NhC+F_1i5|b#7DJ$}8KhteP%1pPFpYn$*XylT%Vl{6NDooY&=rY><}Jkt6oCFPcD@lhX%kU| zhAg6mAGiyzDb3<8THsH%lUPeo!O#R-7BP^d->bdy)==P@QrHtjq5K^<-)nRRD=;=; z-5coxmw}c{kc0ENP<2^z#nT)DiwT&vai%&0po+p;Yz2j*3+MoNkCIE8!@P9B3n zSllS+xQfVuA@zEdQi1O4+oN(Nr-wF~IT9>5Ub>4|i3SW0(EzcGU!4_7O<@_*V(xV)!J^wiQQQGi2{lF1H{;sq`ox^R@XWl2`tkA2ZH~cr*)%r~&dv zVrY)!S`xr~Nx?#GfflI@bXCb~y;za;0EWhBG9wKwlP8kZO_+LUhko{nBoOdk@_GuH zRU0%1b&7uq*QeJ}u{HjnB=rjPpWKC@lQ03eBo!mvD5hX#cAoYbGSiCW!^bJu(|zrJ z;<;SVwXEoGn>EC5P?8XXc$ST*MNFB}pyzOT`tK-wBK->g%4hwGlck4KwbWsrD2#+1 zGg0ZI5uo}bh%sI%xyuilF!RW8kN{DjB6Sp9VR!!Dfo%9Ai+dPSca12Le&~ga2OXia z8?&A$=1n9tIOo${$ZoNV_r%+=(@9A>i_%k^ltGqdXcT33Ih*2wlQWYBm_ZE5_&?iXG}U-!M8*&tk98)Kz!`XDzlH zOO<(r80qrZQaZUH2EG}x>8dtm)Z(BB4$!D-wc2jCTdfvOi$h#hIl5|>5-rdrAztY8 zF4{4)=SrpIWqi-iP|uM+&2Ijg7^bcwY)2tDePVPCxMD^K>lSX6|1&y#o)dUgUI1SlSKeVb#!8&Ix(F0c7 z345Jv9*O!UNCb%Bnjs)!O>UeVKxmzf9<+(g2u6ez8X>V8@&d9+^9gMVF=T4$0UzAy zpnoE4Hy7!ts_Y(2fOTMUQH21+Spmj~dD;WfNpwh1b}bHPDeDwNxj>dD?L}RfJf=VV z20vtahpil}2U3kk`wWMkCjz4`&_|G+P&Fd`u<|c7IaC&8362wr&a`sIb!j{l*J7v< zCr_3WSi``9FkuuVO|WdSiJpYB50bk5HI$f&|z5Hj5G8==rW3cz~kHh7Tyz!=3% zo)SdnLOIZRv$A@3Lv30PnI+GKF4%`KeP^D7S?EAEaMOk9Xa^VetXNTcmhZwB5hY~g ziGYUxBx@gRSy8zyITFlcJL3qLASRz%ilnu)@9B9_>-cMcfYtl~&O z*~G69FiK9M+@(I(9@n3>{FkynMR|*pun00E+?LaJxkvJbeM#3M&g5`P?(5U zk{FJHi^V?lKTLySESf#l%A^O~TLfeqJ&5=$=q1FMh_MpAV!Vn}I95Y8e@H-^(niz5 zo^OWiu7*dOT|=AVF8}I>kV?`w{19n2rC@0*R4|MB#7f>%+6Z^01L~3 zJq*Eh2D%kyZy7u^AK3ME9wtc)oYfnA3_S5N^%} zn#Cis3N9)lAG&AI5cloOi4mYye_*hpPHQc+>5Mp+j918}h0qgl2qLcy!$TAOIE0XH zC%_1}RD-o-r^dnzsuuu=xJF{x%nSj*Cj$KRvvK=5Zt{U68H==KRAEGw1gCsZqq;KI<7_#b}fKKT@ z#UV(E5gEMFN!U!-atPT%GZDF&<#1-b*AQp(=oAZ&!)b-ercYw*PAH8_WvrW|KWICm zqn3&Ah@N0~PHP9U&2?h)*iZc8sLlZnW&`zaJOHCrgF(PB;>IkoTi4kv(o)w=*D^?X zx8F-Hcoy@7`Z9%Tq&kfrK)3Y)-PamK=~OAdF@dftu^33*1vH#Aw*cp0!wj{$PGR96X_}kH<28WzmC4=1?NAOgKTH8?hY5iTbe^dsa^eW5O_h;FqavLsSg+=Z z3lvcpLWcT{N-%MuKEw(d)lhGKZE?7+D}Kd{;bE03S_twCAL`VH2^>UW2|Q*47_rSt zXM+r(oX!zOuBlV#rg7Rhz2aAWDtC#t+{Kr%VMk}Pm>$8E#;ZP^%9B7tmTV+UUnmNm z$j~$jpU%YTTs6`VJH$9gBqDP?CZ?KU`vx?)JtmrNU}!c=SNT)oCx{2S`7+Dv6w zCvM~6(CEK#thPw2Ju^h?HW+dUq2uv0E@X3uo%h55y;1N{$V@>3k>S)p_8BF>(D2_# z?=)n~e_423S}Mi0Vx8BWSkEh;)i|X9v6@CN7z}f}{K`A4JoK6B-S`y&@gm@+w-bc( zp|+9ARMwygj*hexDO3{fycde_2Y#(zi4#fD879W#rdF**^QDM#L(>S1&IECSAOn%% z9D@k>9zZ{YY$BU5+pF~A%E%RrA6V2f#cnkQX|To{*3Z!&iY()dM|2LK^(59Wni#3q ztBpo5YsojGI-|5T*oQk)6w2AZaujC*~N4&Vxqd zp;sVam}f89p<3Jd_4&qi4Rnl1E9_7NOeo4BCmANtBJWDpM;_ttdSXTjRJ^ae+rxhu^50G zH!;Vw7OoTvQhZPqut3mtl3C?!KwltMz*1N3k5qEC?vh;&gd| zFP=~47=G{-Vt5W|CLg>K!5Y~ZZ4e3J&k~7+Za$|3{SQl7v1E!nQFPKZ`FviuL8~F% z7#qr|31MTQ>kXk<-$)Cl=#cH*>y1J^Zin)ngv)F-^p?Jm< zqB*&EdZHnVXbJD@a-6Y9n3q6r>5l{9L%6_z+%yCg8;w$)LOBZjNRS=&(3WZ37Id*n zH8ckubLbD4HT|DK2`w;EO)Q*i#I9EZmw0zDpG~=F+F&N(LgJMgq4Cls%nbEZ+(Nk(neB4fnx2v$T z&P=q%-;L{+sC+Q+HyzPs!JVRPeuY6pMS*Ye9r*CAviu6gj$hGoW>&~CPtHAh0|YBW zrUX8P{xM#EZdT1uO~c7b%$F?)7A9?|@C)SzT!wX-F+_GCn^_C=DPrgff#pQ9MhQ6P zSDwo)%n{#{3;}k-@56Lc*q}SJoL^c%Lk)nZHf&2ClUTM`}*dHfa{}kqbcwH|o(}>-md!gDm5JZFo zL_<&>)z#b4veHno1(Q$+k^uV$LsWwaxCJ~Zr-;11H{w~v7?jhwL`JEOK(pfor98*jR9>%3QE=h zUyBfcY~a;cI|13Ewg3Tk2-)Hb@Z|C%<=gST&{CWw=)4-j@#6NvvmoRP=7>Vd!^9v@ zH9nNTFcE%mI&Iv0!^`}v>k1cL$!LcwmPQx=nFK9Ji#=>hhyWV8$?&sLj@}L|##J~w z{FO;j^8VHIh`AB}goO~~VNM|=sl5nC9MSwl0cxD}z9{NuXkcD|b=eFT)07j(1o5EF zKZOQ+h`_C94~o z>7UG5N!)Ra86 zh$&VI*}6f;7As9>8AmD?V!hTb4TN0^^v3Bxupv25hv0K>2u7~Q(%WjaVv0Obh=S*1 zmmU4ruoJO}8sPHsCD05fHolP-< zn&it1oOeEW`jYe?)J7|uM3F+@!-#~QN74|6g9Y(KfjBfP?fsD;o56-EijB*)>8kw{ zyLBG?i4MEm7v>G<9s?IiY2QDEe+{R@r+8!HLnr|y&w?4EQ&0>fjEcD4K7=hx-gUjs zivqD_wIcLzw#M~3Ej7nfxFS8B7;#NJY?@ZR|3OLKwSsfS)5c>LN?PtZ)3eYjr)iQVjjvi{45=&WgVe;m_%ZPUtM^BU&kj4 zMsE>IfOt&UBjSU`YGy1UN&uA-8`V5{hJ%xMufZO^+gcy91#rVq|4aB&*t*|xa$bnTo+pZcDzc?xPgzPA~*El z7&jK_AS|aU$PB2^BP@FLsV#||zeQLYa$65cFbIDAr8~I*r>E7>ncEeaw++33)?wQw z_Sr9y9aVs-Sw|+%`ldDKskw>GiFX1MJKfo3ppxg0LSmDf_S zrTkOv1A}| z`FVs4i*8#9WGeGYJp@_#;|;om53e`*3=@^(&W34hsV4y8n6C&KAcD^oBqO-`HzC_5 zOZJ|w5%2Eq*!SSx2Hg=mz#w-jS&4Jk8e}0dZV7@-IVB4LU%q_to|6{=hr{7`JfhYK z2^cjS6RGJVk~|>54^Q*eK&%US44+wQ5*ib_sUc!3I5;jWHo3tdVj@OLq#pWf2Z7zE zr>A^P#vteXA&k0ZpJ(0N;58f;-BqEctE*!@&zP9rxPe{s3jdKIG7JYR1Nf!~b!2yp z*!}(e1+uepsv5;;+B2Mq@1$u)oF>XZBx*bR%^=%FaStePke7{5dbHxiJIE4s`?bUji#0%|QlD%eSKbpDUj|FO2Jc8$3eSB2 zB3y+*btP7!7N9TuB8TyF{7VVhU%<;%JbB`;r5H55GX4S({c^{~m6wwr&ZElwF;=FZ zDZz%mdUCC2_GXs>O0RAiDIgfUcH0-{v#ns1fwGShXv2`;UIVHsI)Xyt%qjSetk7vg zQBMyEor47*ugYOgjaMNkw@6bnw0ek}(aTur;g|+A&sJs>Rc{&`4u=b5=LD!wPIsmq ztB-`jf_RPHglr0x?6(!kS4i!l8z4Ua0Mv@$Y(p#NDwyS%t87-0ZlH5(i;rbv3-s6S zDsFlOo#P}uHX)u0ILsylIic7#WLvJn;yD%G2iXRSp1M!vLxJ-7$X|BKJYkjRGaJ-4 zscaTzQaa+C6=l${nu=yQc_LyudkI5utUVV&gbO}00ILnXP@qY9?qET#DNG(Rjo;Q$9T9Zcp4VXKTJ_;ggyUg*z-;NnXv?U*3y_2hH zWOBWnv{2%P3D@%eG(o*$#slZtN-YCqaZ_ULI?-umSRAgF%(rL za;R*j9?mYIxZ2JK$_sz4BJ1X!k`iV=Ke$y@iidB4az3E>$cH1ei89CoWGw&rJsKY4 zLmpd5n*RW(t3_eLP-p^-&?V!{3L1Gki$$T0R;EqnaHcV%;BL(0<0H4A(`Vbd-GuYt zFYB;$p0>8~lt5-j?5RPpZ4v}F_Y*8DRSCZAoY=hT&VZx_VucS3sIKZf3LT53`tF?g zIW;pU+yN1mk9u6fk~406U4LO6k7=K{?8YUhM!c@vwddG2Qkkq~j~jV*Km<>iPFl$J z89pxIeW%8UJ@|HD?T3h=d>kVoo2^@S354wB&e*9d41i%J*RwnJSH#gGk@0V;a^+~y zI7`rMVhqh2t=Mn@=n=Tht~bOCvbooq+Sq2v&T9S7KmRnR3sTd0;DGGPKp6^G-<(bT za@d#i&2l%d^HR@|N-H@fs9E>)L4vk#f)xi0t0STzDi)aIbJe*u;V|i;8%o~S5{c9a zkR?6>#Np2ANk?@`do5Bpf`Az6*ufFC*=w>$Ggh{haQV!fL5dnoO9m%#jEe~y;uW33 zVK*prSQ++e#5J#AbdsULgwJ1({^(c+K>*ba&-x4K)*vpaCzswlZh%Xg_K-M}NLr-1 zF;T5QsC0#F7oiY9GmjGI4&AtDt>r^{#(c{&%R0&!+hHP031OPybVs5HFXY8>cDG#; z!uRH6_AAko$J7#_{V~}Q#m;DT8X9|NC@Y!ju%Ll#Hmg!wLV$dNqr3oN^pwP(v-OYJ z7-6E~r6HeTKR+XQswujObw`%oks+Yf@pw!RS0Ou9DQp-CAQ%3`U&!`4F(i8HG7qzId2_g&esW9IfT{X&Btaww{@QNTtDk&H1t{pI~r! zmPArq%n!=mO4?CR}zB9QVKLpzQM{S?!$w;yXY?LwQ| zgM^X=l=tXC88FdYcSP}wjc;x}D?>j`dJeq-MZ5~BJrt4i{$VnGVuU>nAv^Kr zwKv?D1Jvm%+iWvMl9O>a^B928^00KDcegbd$Q0Jr*V%Xx581z{1beTCx6YMXuOUd@p)A>J8!^OTbHJG7MTSFzb(PZ>y5_T++`|z5*yzt0 z-LgV0I{6C+KfQxuN#Z2QPkM7RK!H?+mE@pY$HrB*^X|jL!(}g9AT}2%44%89=OBwa zAugIkZSe@(Rum6iVS?rf&{#~)`MblH?{2$i?M_90al%D6Px$fZ9*^sBgRvl6_{*iV z7|o`N52d^%PHyJ4465u-j!o8p)kVV9%t7BPureX^IZc>b$e3YoeZD^Mm-&&jh|K+4 z_wG}Vr}&{SY}H?ShgU?2^<#miDN)TmG`p;Di@|6J*$E1yoW)EX`ZvRcdwjC>{Q2Jp zy)u|yP{SGj;&7z|IZSoo8v=Y%RT#oakq%&DhlI7Tzixx1=+DD&CL#F%HhIC$Vw~HC zZb|dozO4PpKzfw8mgr_!+`;exIGsn{?^74lW+phH5*f!ri(kHc8TAk@%g5xGpJ{AI zNE?RFD-s^vaoviH_g8Dlj4JXulMqi_hBMX<0mJR9g}nF2hig!1Dnb;~IY9sASXnf@ zuCje2CYKE7i_pujxBU6%zyJBqfBfSg|HF>}kVct3crPb$9Hw8{2D{mNnL%pe)E-*5 ztvWgn1mK&6MaqNsrpkaj}VeIe!=*Y?+Gu#DTB9P;S0TlP|L*4(JSO9R)`)w*h(4+=_Pfz>O9( zpfKHLjI1I@K~540BbQaSknOS&aPjw5foy(WZdFYx^#KiAazE1~Yg1wj89JitU ze-}}mtdC}S_6H!Fw&@HU;g3@?v+}i@IblyBlwsr;W(GBf+yr79M=%AxKLN7M-6HI` zrDDyKta?tvkAm!S!$YB82oT+@I?EOm?u)W_g-CE~|mQ>>ze= zRXudjsG6TNM89jnG&j<3AUnS?vaEmq1v=C()dDn&%<12Ro)Ow|QlgW{3)ya)ph`zm z)doFA7GbQ6v6#uvOo+BBM5iN7L)>=EJj+Pup%Wf4w4n)?VBx@<8NWYdXAx#!=wN-P z`-fNAR;dA`R4fTGNFXzqRYlG*>8-uUu{)3E<(>hLtGnoCLCyCoj>jW!Kl-$v6`S|F z$^=*3ra|IPzVf5D^fW;bI3{E1%h=O#0yDL2qLbhqo8#uWP>UfUn>`sUj(>%0uo4qQ z$#HQ6#p}^G`9%Gme3o zz{mx%{XQxfDi*uB={HV!pWChHlqX*?W)DRx?p|`Grc4+D3{RiQW*SfLVUEbFj4@KP zm}o0HZ%@`W$q)mz-dO7e*!(X#8lAa`;J+01Gk2qux zU8I)C_@o|{VAS%Uutspm=K74i=yBo57V(+n2S@n zY)7-9w(xVv60+G>;kjx3w`(~%R<}&Y%ML1&8i=s#ae4xY*zsHe&}D65 z&h*n~34B(bD-|Av%5m2&zbWeV(Dn9XE_hw@vYPYVLf_~9G01j_if1DbrPNFK&GR%3ryT`}F`PVW}YZ9-$ zvxk z3ZR%{A!0@3P&z>1HM>L4&(D~4)a;$sXM~b?rP16_X5r8MMuvbpv3~57yvngK!HP&p zyajnl3{luJUv*n0IfbyItvaGPUr06gE|5J!FnH%CsgKz$#Ob_iXoEYq{@^%@*p3*g^3L!hkRN*YowCkmbbDld(aKIDK zI#Q#bMvp|*;)oS_xwEn{!k~)6A#wd?5St`GHZB6|E@okRv7dYb1jM5pF#~N+=p^xC zJdiOcNY-D@s!h~bO&YJGIjeB#%tO3d<)nMi6sk!-dZivuIkcRTUmn6gclNi2?DRi} zCOUq30MX^@kFB!Flku-%q>6-W9grAD)>Bk6*+Mcivgf_s%SV9O%RU_ZCNSN-d_O>_ zqJ|5YE~3|u4P3IoR(fLfx=yFm!6V-8s}!D31sW4 zhKfkYCW4G0PmX(^6X(4~VgDqjE2j$Avlv1q=MOT_%Oi)tS)5a>d4+xxz&IFTFXKoI zM%=;DobxUkP-yx&F5)t?Z^qvt~(OC*9UsHMzIj{`aq zG@-lDqfBwifpaNReWxFr_6Lv7kIh^jxYl{9Nk7qS7ffUMpeKj6sw}m6V9jYK$6YCI zqCP*LzS{@l2+FD7DbTZM*1Avt$4;5{C2writgE!eP_`O%a;d?SC%MYT83vAQ_bx6< zEGzL^H_UEiJj7w0WH}F0R78olyA6(=^-Ehqw&PN3f8v%;wp@QmET7f$UZM}}fu~Ly zWM6hhI1rS(UCrIA0o^eye-@UjQw_)x8enrHV;h zgdG6g+#|-%{Hr-Ju2iiarmzEG27o5p!0PxVKB_8>%A`}AN(WN-ChdrzO`lDL)U1=E zT5bkX(!RF7@q=Va7U4)0k+0IcrFHpAZ1`Cvp%rGVs)syGEGRfoCqzvispRV7{XM36 z=*=cxus=SY7Gy+{JC;B;rYUd6j(kYXNsqpH)`!?!Y5L=8b`asStEa1+gzV)3^OFUF z16UUV;(*c9pU`~z&?9_(b6k`!0!cP`1YaG{ToFpb*Yi=#*y4$}Q7aq0%27_HJu0H2 zWX6`5iJ?Dbh=w?+-R#%(S7|n&%~xR9VR6eQ!3g>XARBlUxZR2!K?IItU!hN!PI{wX zt0qJ=dpDL4Va<7~T5&moe)R|90-ml!HWYJby6r8`7(n?&(EMj0 z+wsl871K=&ieefQpg)Dk*;zd|&URMd&b&=e#!#ELs1>YzLiF+R@v@gK=%^jl zmmRqCkI@K)`D``vG(Y3xX}50ef5CHwKr<(pe?*q@Cp+v^>0Gj+`uqe{X;o{Qevs|n3&t8)xdcrBKt2Uc3QF+R?MJOQJicq85b!z4S zI)z%->6)fH7OebqMt{^JWD5lh2hGzcw-Cv_hld9ZIk@70tsu-IGhY+B!QfsXTewV! zL3=*r#1i`hAscgA7fPzDcyAx<9#iE8WHSL+LTbneCXGTjXDoXgGDw1*eil&zIxrh@ zJBXy(lTT3ODTT!^FBC?MgF|y8 zU_-WL9v=_JBv+Qem(j!4jfecag9(ZyL;@@L1bs%{ z)g|`nMc&o_vN<%t60>B|XT3MMnMIT@V%8k~_*W-uv&mG$0i4MljIwKHz}Jl|^2}OC z6iKzo-$@vsk!+s&{uj7GI{yMy8S^m$8DVL|2uBSrq4YD|Q`qXxTs2CHQGmz* zkr^Cj6jae8bHKFM;UX9mQCP@Mo!Dg-Wc%K`2;5gV9*;R{>A&$oA&`w%DD>Ot?6PLu zgzU>bL-sWCA%V4Bjz7edB80pm2(HhE_)C3`rG3M14|7B}zGS96&Gm|~X0RAG(H1|E zKQk|{co+c){Vc+<-%04_ej+tzd7HRS(Oytj{#p4-s`I8B8UIuZ-{w_X@C|Y%9H$DY z<1md}=}hsYM>ptN4U>lqbQUD9kfhF{t#dp_)vUi>pN)wJcAIJB(4d@{tIo7%5F(yrRkF#WhUX7JQ5Vi9AL$;Bz`{suU zVGQ$B(q>FXiCC@vRUr*i6?8@3F-pEc)`V&Uqia)jGb4F4=dU6?S+mXl^>LI-rb_th~Dgm{1n~77%Rz8Vb8rl$rWzMXq=2|yC zMKIH3D+H>di;4UdvIS-F+7~E1B_Spj;V12XIsgD507*naR4vLP5EH@OW)Y7p@7#M) zUMo4|^v9?{?1${M=rS<-o^(arL&0b#QQq!6L^)-X!(0QLtBh5#F=8{fb&MvZZM3@q zVVY3q+0R014@Xlcjy14K*v4_05lTWRwyHK)aQ4EUCW@_IzKo$uE9Hs)5G5jPiUKiw zi^DH5=^hXB(L~7RaYMhD=#wg|kR6-aCm+){d>%Q;r~9BAmjXmdyfb0YLt8HzHg5mA zOfGZicWVouEB|SNjGj1BInQxcuh>vxAj}X4$S%lHd2(oIwq!EYb`!1qi)32&6dqn6 zJFxi8#~%{5lFkfHx{%sKF*jGW0hE{XV)TqK6$~YyFC5^E=9IVFWDl(r!;>@f`U(jv z6#iABPGYsB zb#f$TF`1dmY#F;_tqKGc2OV(Wa9FfO0PE1gU#@0M@&joM_cGR}r()<=_7}+B-k8#K28SJgw~yUH#)^ZY|3D;% zMvOz}T@IZ^DqYo#yid%;@hV;$8Tp#iSvIS+)N=^}(zDbMG zMF@`e1Wp}_)Tz_9LcElam{2bGa9y_EWh0&HXgKT%PS0S6F_xZK;M?KLuW4jutRmjFMyPw_h6yOC) zu4>NJC_!)(eAS!georbA>|z|v;J8t81}$fNf=E3@FplF6RrYibWUuBSO0Z~(Is?&> zD`Y1ki&j3CBuBzDDniUHA^{qA;fT3j1F|uaW1KSC)f`3LNaap(cH5w2+qXLFfrras zjhu(H-TzlVi*U$`&=7=Gq!|3tHXf!P+innQ&~6Er-5F%7C$a3T>doR>1WyP~dREfP zAfS^odGk;VHKem9z^Dm1i)8XE-_)Rcaxh9STzZ$PJWMB3o0wG_BR=^9WY6&0_@h5H zr^WFsk_3ldgQ4(k>r`Z|86ss?iCJY4le7Xoq#5kfGM~tZ+KhW@aEZ;HQgv2~F0sLP zZ!=yj9WIv?$X8uxZnZ9Ol7j0O=rV8Gcs~oOAlf&l+@)X~q@>g}nQ8QMnL?t0xJxFrO zu1Q>9STD#HxeBR0EMp$dV2k^WM$_j{?MZ1UyiW8_kcIw#$ToU2!Z=q}Wnhz5Pv#13 zvu+j3Qp~YaV9@iCkga2OQ|u^0=W)!XLy37veR4=!XyG7F$@%?X!)+b%}EKotw@rJv-oF^ zE~{)YdX)gsy+wKc;lWFRvjO7HHDfvc;_~D!FmE`)Pq2-BF!bkXfM>}{Yke_ScGB4U0}hwo@~)`W`&%k z@T4rN7606Ham?AYc)zG0W zqQ=Qq@?BVg+LoD;c$J4qr=FzA+6r%_@*X|aotuY+)ZP|L-}cZmD9msfE0by@_Sj09 zn;k5HnV-(VUbE+#)UyHsKBRInWrP*QY;GuoRCg^rWjAepcH{JdJHYK;3Qw4*JSU!U zN}%=1r1oxb;|L&_7l;%79G z%n*FSDjTD?p#zS`Na%kN=2;PH$bNa1;Mr_7t{lr&9;%^;GN;9Cn{+kzFda)eQxHB) zD1MMS?}@3fh}4;M)iCC`AVo|EO5x7Kw3Re!-}RT~*iGM7m4FDGDl|_wl14Lwr4?b+ znE;$x)tNC-^Wxs+15yszLM-Rw-!z(b-Dh_Tg=aH_KaEO&YoJxB6`FId%6!Oxum?ru zVonrx)dGsK`qZwTAfGxD@eMfg2E&k6p|M+#Ozx?UQ=KwC@p1#QeO_BA-+*j)EeK8i zwRydcr9%h{&F~G1d`)D-&w=dn!MWN|NkadNFawIPZT2exQ~?`)2xOx+og6viS)Gy4 zt0K%@_#uDKPKfJkUhYt!h*IleLJzj!hypVQO8@LoLq(`|KY<1eL2tAbvc;)f4wo~j znZeSE&4o^ub!u4cxM#z|H;^4~;)KXT=50Ok6vqT#m)Hnsu?R{aM-zd?)a5C1tt4d2 z1nk&_NGzuB3E6&8Ln|hjj#Vpf8ya)ldY{wjK}gKKX@`uPnQ1W_`W#e0R*mZDs5r8sz7o^Vo*FB0TkhKn5ZEC1jiPcxx!iuKw!)gufQ#N&zP)6VvLbeO}e5ul~GB)E- zIc6oGWRAU)>KH=|sm=0B$<=|k$tsbRkWjKJyuqyQcxY+a%_U-&9}kQ7?oNyDnF%Xr zB-A|mFY4h&F3n2Md+n;Q2r;^dS)4@^9Pm*J>eD550vw)auYr=}L;Dt=oi%Ob6ydsI{ah1)8IPObYUVg*VQc8dB z@9*7f*7LMmt@L)RYu=jC`O&%@d&IWM^YgQN*+Sw^5s4tHv>q6&oP=F3ueQz26ElD? z>2&gW?lL*h3fBanyrIWQXAYX@-|R)w4CMGXWsF^Z^Lh zS%~G|6i#~99TW;B?DlHKR$^;9>G(c9J-xoZzP!BHkf)X5WUv3jAluz! zW6i#SC=8YvDaGJ$R^dAP3n4p)IcYmmM0GQptkNcdXHn>35oON90jV!V;LB zck0q&(kYyD$|Q{s%UGQLg;TEDUm;a7PBA%oR>&SBfc3l*LIYP4>6>(pBTPeDgQ(l& zkNwL14U(`Rd!vrBr_kfojOH@!70wxPj{pr<{~D9)bJ>YvKSL9OjlV>b4*1t)tgGyq z54Afniq#m@VHy&zQwHYeud-Li$=x?oa3qXjCW=gn)GxETDc@9EGq?Vtxz=rhwwYZ3 zdV%Sy&XhMzDab5Z=uy~`&QnP%Aj(+nDJETpgfK6V)2kUyscj^5gHxk6b!HF{%fAWJ zduT?-!7>vn8unL+EI-TPy2vov>FO$NWD>`HD>Bd0Jl#kiz-9WCbxprOa3%>NZv;$! zG}qKpO#P8?Zpc7UN2NKNSZHIhC)Veb_QAPM9+sGgt9hIc2`M=eDzAEz@A6HKO5_xwKoJSGNm~-c z$6KaZV7b=z7MAa2aFaty!+0Ywd~gm$x`%p`ObNlu|N zkykfX&HVsV$BG!E>VCRDq^m*|`x`>G{Yr(oO3fg+{$-T0h^iDzx**kv=_F_<8knE8 z$~L_#4yB*73fEbbJH2^-LfBE>G`1F~7c`d-d8q08`}-RkBf?_hb?zyPl_fC4#B|X~ zCWT939qLaJiaAJ$9d4fQ|(VuG^;y<&yJR){^ zr_TMBEOpyj5+bJN><%2kE88Y54&IbZg^4@*poWpqV!0<@!u}$eMs+neMn+p7%gLT5 zfTj<2imO2P!4tKWF?q-b`)dT!qNoR6zr4I;5Rw)ID`GD%FYb&Bi+Je7kgIIn&|!$u zFVnS%y+)f^VW5DTszbArCW3Hz1pLfqeK{kA=u0#J(AkF8XD!nefO@bBWsW zX@V91nm0}ooJ#$vA*aU-ed^h!Gu%nfS~-?QWZRKe*t(TdM3zeGDKQUICTUm4MW8>6 zgjRFA*H<$V`t3+IBwz6j0qD1mop{-Nl^$;lu8PUD0<~p`kO4=aS;gB{Nmh39i^#q} zBajGXc$1m5wssP4h(3m{I&b}UpylNn_Dv>1@hEXCAf#*S4`-m*uZVS(1$k-$%!{7oTSv>gd?7LWzF z6L6hZXq(~4FmV=bHlMAsX}JII7<4!@4Kw)}-wZS7$Y%LPlq|^_2jQUouGtP)-+w^%0|Nk_4^L@S8&R4BA{K zk5CKj!cU+#y(&!q1(0n9o8snN5lX^08%oSW1&Sz;jYFHBmb$J!W_Epp1`X_!JU>6$ zk<3xB9s|iw-}0!0@=<1$dvvBuTeQ1JV$Bv!chDSWb026OgwI7 zxGb%n3c&@1mZwlfVY*YSIeS58xqhXyaP%Q(J6e%Q(uvUqHlycWxs{&Cy9(JF&9U%R zET?B27P5V+`glA7**w>HI2?F@B41Vsc9xk7e=T>@h5Kd^>HVE^C5(4=#D zoAgX`$|OCL7veF>5I#OWrVmALL;R|6W`@D7WJ0aY(+Y!XTBOg`Mh<+{)!5ut5_*+Z zbUQUHhAyjVmc#BftFQ<)V2A?P_?w@F^V9o4_Uc+s|BINJPz(Wqqo8EgT)ujWPyo%P zR&zHA)s~+d4Uwdwt@H=J!y$hp(sSsVZ~Dofk> zvVMX7lOTHrsR_GD&*b0BHwnN><0y2F1hFIOp+^}xBG-a+=F){oJvvjZEHH<#^edot zIYp?sh-&EBYVM)S=bwaZ?GD7{#-ksHdU|?D$ToL}hHn^_ToDM#6am3j4;7dZZ;Zu( z@*-Mk*2FfUN)&Dja~8?$pm>y+%TVg)NT4m<&gP>(LN=zk5#>5G<=ti(jc&*bnigqU z#4i1s#Vui!6*Ow;n&~aF3(8vOp)!3)0hfB5On1OEu3!BF^YS*WE~mM50o`_$Gf;m1mPy zErh33>tK6IqS|`6r>#oP3H>pv?6muqegoMHUSBpwvH;$;>Z1`9;8lF`}z6tcs%_$lUuioC#TJE=^`{VBP`|wrg2$1 zYkre2PL+P`ZWAMnZp#}V9b*+nE15<~PO5bS7kEu*oB1QS2(`p8G1Oh@jfeA0IUK_) zSLM1b7Gu}fDg3CDlBwtU`5Cb0HG2BxTH7v&o+^J4e^|;Gc!kjN{{`;F`V>jAcYmE$1t)S(k^Wirc>MMI>0?* zvucEF%~@Xt7X6G!dSa|z+q>aui%As|rdrwd_(fo#`# zp0&h;W;I|j;aJagJL{r6(Mk9;Nyr{i`#%h_XHaf*M&d&tJJT*{Q)kRAJb_OX`tmTu&{$MwA{MDB`0ayVQF4$&f7)=>YLDdh&}f;6*3~pSl%~N_gW?#}bIQ z(`$kqYfgJ9~y*6Zu*w{PE^!*)V8CU7iKRcA0XLTcqyq~7Lw?Lg z&ha+Xv8qZB^^=s?hU^?5A^;*2)osW&P+Ii%Kn|Y{v%E7=H4AvEs~Dz|F+# zT422JvH49x-!Pveu|Ye!)m*-WO5i9jzX!xE>3Obd$wRPdy!5#_ z<)lSu##h=yd24~p2sG$G_EDxXp5@sRFv@4l5d&o65vfO(FTAM$jwKLzBh*lT zDrCEM7I0^gQeY=!&-4^hd+1owP^dM^Wfw6A$s2$++)3!C!<;%t+EUDGz1&x^Bc)LO z=y_WCzXsWsbP>h`zWAjWoDYX=6&B%?qXXrb9zvKWnFiUm{IBLW4~#x0LvF9Kv3`Z@1*5+t!M)2u z-UP}SU69RT;&meI7_S-jZI}~n2@1m*vA8_7ws0=Pf$7nlF6FR|v|{fibTWr?q$`!J z-q8~{mGO#=n&HeKdnP~Qo49`yVI1}o8474OaBE4s2ZFI{!#OvvY*&R> zU!`H#GAX~nD9(Nwb@TH@vVUaw4B3OWGkpUPI}FGCBOEUzweR`jM}J91lr-(;_`t zwYVxjs+BW?Y*YV}2^>qKKujUj%|qjm3O82SLY}6xp~!O6uFZ>>H7uka54|;q!cjno zw980l+!ChqZ1SN^j3P!!I7G&02XQ8SE z1QIB+grQa9HN>a~&dba5`8SGB?+N8+(Zv0PIE_MFAlpy10omt$7>|2gR}K@0+zi-TWWwKqK)R@%<^PIo?+4!l5Sk2 zLcalmaALapD{ti&0c69>2-rdFS{F0If+|9{Y3SJzX9Or7<}-D3jpZ8G2mTVW`F1>y z{fY0nD&?bz>`z>OVI45aJ!|F!AIEl;t&6F2KTY!tK?X(WRLoe@L_-RwYL#&NrL3$9 zClmP^Ih~PEpom%OIFQ&XE2YHYA6E^0A1CEmf@!x19WKI|-%B}b!y?S`^G^5qdmy~8 z_KFZ|ubZsxS(@u`wcuprG6ctvASOsQ)*b4W}7; z*las|JOB6IIF!6G84O++3J^E5#eNmBt*3-H4qZzXv7w(+IdHB&1lF7Nl_j6F9WO$F zQn&=_P_ZI(6~4o5jmD2>2><{K=t)FDRG`OJZh1dEEI-$aE8sGJ;ru3$jq6TUZiw5Z z8S&o=*-Y2efT&d4d08QqNgfh6@p`tfbwTtwkZqv~c?CW2KM=Cj?+yc9){~tCF;`gs zXM~bPsK;&MAA@Y{j>?NuhnZJqSEiG6HS|z{okStEhbk<>M9mJ0gMS}nC(ckrHMdz= z5GkK@wKB*MwXi#Hxm-Wf=3e%J1+1%SVDXnjw*6!Z`BkfI-6+Bk7h$HtcOYvpa@0!$ zhci8ZtVo)NHc3JUW`rwxYa>xcL!SWIs}2aMoW-|o$i`=bkPWkI&_1D|p~P-ox=9En zH&^u7y{YggAv^VFualp2d1drwM7B+OCO_kg(M6=rq>XbrJYI}a7ps+3g;{kyD--$Z zq(}0LD779UrVwiCLW2E&i#|FI!6AixIG(}JV ze;aL0MBDlu8CHUtE|Ag(S073ykz%IcuZ3)JM+6a_vruI!UxWdv?v&We%S&P+Mv=*Y z?5EYA{;$$Aoe8ge$Z30HM2khJUxnzAUqm{&Cjyx~KSzHUWaswCdn;=x>jw+A2nvUu zX6Uk@lCI_+dJl=B_M711m7Xlb0NK7H0~7+ZiPS|m67N1PsI?DxwgK6!_q9`cmX7tm zh5$oaX}RGTd84nNMJP~&=?mXh!Y&52lEa_$h8|$Z^)H9Yzn4g(&{_OiS=K)Mg3RsP zkE7a!v%bnsqrwM^-$W2-1x6x;$L^#R=y84hV;du>S+Bl*`N(%!@Or{8)$sIZ9H#t3#(7*5A`Io8kB!nAB9)Ld%SQ-tzGB;L3r<%iqF zz_&7YJXmtQ{Rko}&0{46(|IU#zLzMdH5T}%1G=02`SRt9=1Pz9MSK)wSHy1~I&w(b z&DG4f`Rxdo$?9>T?Lv~JqIP!@OX{xto0a+bkS)G!uPzlE3H+yH&>O4rJY_7z1vxhf zgQh?DFTaSH!i4Fh^^=D7OLIl!RKzKo%8IFamuyw{iRsW} zcVMEEme6)&M&!aA0LeltTAy@&gHX7Le3)+)R}0^KZ{`Zw{9La92W0yjzNr*i=zK3x zt{4s?_1i-BY*cC_JX9Wz-TWxX=1Z`dg0HWy-@kv??oJ{#6rIKSs~}sndM{MXgw{VKwQFT#d9iC+cTTub33 zwRsb=sb%}S-9g1hg8l1!uG+1R@m}2uWXl?eL-s*n6{!n?No56Kd7#Q7F27z+J!`Z-$BLQb7&rM<12>zUsdT5w6!zumT-k!^buFbOv0v4X~ zMd*LY+i)lGQF>#CqfufWDqn;Sz*l}oC||_)$$w?eL-oT^n`+=F zUmcXMo+4D}<_sDf-y+msM2U@u$ZOrYC}L~~rye-*a3(K5t1RyUX5Ez!d8nQuQYLBC z=7SYrw>Xx&3tzu}6#(z=ug_(l_Da_N--2unh_I2Fk=M!aOXZ#KuG9?M}j6(qlt7VssHRdHE`*(8QmtJ7q>fJw=R?ax^45 zyUG^L{JxU__*0OrUc1MA&(tohH?H|7bs~0CPdSqci4mcMu8%14pc?|&FzFfz z4;_Fa6eyw|s?(nlRmokNr}9!*hgL{6RIExu`66cW*3wQQ)$VNav0{ZaGv#8RU<7LK zkL-ryyHk6(Uo0(m<`8v7s8W8%_@*^-ND`PHjYu zP(lmYqu4COH4+|vth|Y6A;ED8AciVABeK6^j+XvWi5=vW@?u003KWrx);u*@EJG>0 zK_`49ZIgnqa@#}O%2C5Ap;!^6$F{TnD!-E`a~^64j@tfjLiYIU0lrw6Xpq%p!YeQ< z?Nz?bi&zydW};9nsB!!0=}CP1amW^PjRo^k@{>-J^3&I%m7$@KJ<}tfhN+DJ5lZMh zTXaSI=3zzO!;OaN19YZNE=zrWHnnX-o6ta$(VuFrd=XkKd9k1fA)^Q}rLbH5MO5>j zKP(6|X9ih3$;=0Nr)C}IZL;Dd`+E0pG{EjPq*>u5&U zu!#4{^9Y%1ZT6+z6#(=;2D0@`BrReCQWL+VZN3fJ%5Uh$H$n+*tC6UP-#oPAMa&wK z1dc(z5kuaPLl&y502HQ7CF^SP>6QMJ29vdjnY=|?#Husni{Of>zX%0(66J=6HZQDE zpokf?siz1Bs0h`zM5(=bs39b^GV7NLY3S&yrwA4PugL79pe-F@hi*c4K`G(b;1r zuUhQ7F(Q9Ppirn%KOBdIY1VNfDEIgG3e1R|DYem@Q|S+x!Ip@%#6rg9Oxl%c!b$i- zc@Z=p|2ie8pNrpgqiCu(m!;_s!dCcbQA7GX61Fmo=U!h-L zk1sE$uXw+_JiopkUtcdWXE8zS4WYv`0*ksj6DvfsvpP(}H@43Q@D=kBj^yVQSPrN# z<$1e`Q^j}OiLicZ*Z!KE6PZ(Z4Y+T_JU^d4X+Zq_od4tFK_(-`sdKJ6)ayiAcN8`V z)d`sNy*!=2!RDYt@1B?#l)W?gfHh0UGiNGpbyDx{z;JSa~iDq>p_%s2-+@v z2xJ?<8UV-X>FJ5-qy)x8hbKo`ro`9~PR-lN{1C{tW(Gpn-Vl~9TptM#J4S-yFCegZ zkQY$i7>fhtix4TwvC)l%^FGMdvG)>-xmO(CXzm1NND~KXD8fp>Pb<*L{||y}(k~&K z{beCrpy!8cXZ0dKgIPJVdWgKuL6uynRjZP>VG+5~s#{Q{0m%{Br2% zo>Kk}M8HKrf+Bzs5NTeMfTF&5VaNsj@1t))xA}O$PY9qt@1eawnBInd4y*k8!Q<01 zoW=ir{WT2;>NiVraCPU`_9L@IIB)#u%J&^(5940~^IS-A{lU4Cas3tn#&2({m`i%S z_F6f6P4rS7mudzS(~<-plMnv7WEB;yD@RSQmzpl)jpjVkGZuW}kwH&lyZ0|xhczx-wl`&kam!RS zFm;um<=Zo_vqb%L7ZL8if^vL90lCuAJV)fu`|b5c-)JuCfg7)UUmsmpyEr5#b>-;I zo|ToJpz;?FBAEhDsz%4*H{~LXFb^Zq6gmQ6f2fh9^7IlYp^pjpOqC}XS84WiEqBWl@>n0qcY4XXCvnoYF!)WeQMy8ZIEitmmQK5SJ*h}pC zs*JGHkW=Pl${+Uov#H3$g%1OEx_HXVXV{>hcqF%kn6GIrdfg%X>)1*O?qb!N)0EX! z81!utjn#oC-0t#Kq(O80GLFU?6ujv+hV%ZJ?mX-H8{!Z%P6h&);WP+G6~)DWsYxqG z*(Jg*#fn9M4jUBMtp*B%%sD(M%1zIQNJ-TZdlL;5a3IIna0G==x`4kQz0q&3w_&(R z!JU=v__9T7GtP>>&BRzW#1K(W|w zAtBNEEf$le4iB_^^nCoJZty%a#qjC6fuQP71769FL5198)Dp;uvx9h8s2XG1<^tWX zCh3NkU%t_zH&TZJGyao@R-8jsRorgN%&8#ZWFsS-C>`C1;GG$)joD5NpI-eNZaV~pM z&Wtt7Ckk+rv6{S^x1tNugqkuVRaB07Ms`3H)Nru*HiEi6@#@-!9{fv3ziuRVAP#Vv z&!&HhC_-wYKVoxL**I>*Afo5|nN7Xdnio*`+5?ugVQ+qPl_jN_%E0A+5|T>)s!CF^ z{g^nu-<@#;i>iwWmL6ojbTXL=r_o|(QO%H7Tn7oS2gNObes z<~>8`EXHTwErPT&$`toZhnLtm?7iPg@%J#d0T476 zKbsl2amXs<%~nmkd~=n2KSqZ79TDk0-fAbG8`3lr`tihxtRzhx2dL+v7cTlX?^kCF z^)jNScFIo*l})kQBo#k+1Ej*ZM5sb`%*NX@)s0y)@v=3GqpN!7i#|;}I^s;QbsOkH z;jM_KeV{%~9V^IO1pUbU1NA+ir@6%J{`>250&wZnAhBtvd$gCfwsw=HX>A<7brc`+ zg;}Kzku3=_$XXV9@p*w$(l0Szr+UM`>nx(mNtkQDweyD)Pgh`4l{8?HEJ&TiN^ay) zw*zsAgQHzM#Ok%`80Gnya%(KK+ahGUAD*@+WAkZJYm0IQb%)`4iBWBzW$3o%;0R^d zK@7hfJs-F)HblKpcwrnCZ-T&sHvATu;d4}vz09hA*Ocitf4nhf8cgPt>SO7Axulhb zk;XI3>$14ay4}{;IR1_5{tEVe(1jUuJOYvmsE>#0w`5^%`u#We*%Sc+K#j&k^2L}G z@`!JTtLeIHlb6VS(#-}gSaLy>pM9}(dSwp8C)z*t5eVNu!)&AdT|KxOe9KKJj}Sxx z!Y9SiEqFBMn2|nw)_BPN=OFk1O@JF%ElYRBD4=Tvj!)A-yF~$0LmC^Z={1MBsFV^= z`z<$dxIO(XFi71WpT~9B8oR=hR7&aUQWJrnexV+?db$dRef1)dT^MB`A=H^5woVej3nqXRvHtswDFP_PJsB;%K1);hT?M2Hm z`p%RgN)715jA+2iC|F1hmK0S>mI$T6Lp1KwI5cs^E5TEgHL7Re&Ep%L7zYd+o|ych z%Z_#1tH@HF@D)+aU{cjU(Sr3yvxqZ2NY&@%?2ROwP(WGQ&${K*%WCMk)=6>N7^5{a zokz0~E)1y355`R=M!c*MhX#*HD)1m!{TJm)Kwc$Dc`ht5;m@obvsVrHn4o@%2;0}{ zv)KA`k#q z?~kXZ3RBCg4%0_*t#s;k`Y(UT`1^ds%SN*nDWjT-85QX--8x6mGy%c1P34+a(Dw@R zI`V%hL9PEhXX0C4n689cSE5Dzw`>P;#EV|g#lkBgZJOpi)Pw&h#gqPdJ{a>x@Pajd zVK2!1KjuraP;nkfza}yjqJipG#J2w^S^j;_yPl)mfnnL?lm9sANY3|rwtcZu)Zj_%M`nSvOQ)p zrbOU&pukI)*Fxm^bBPQ8 z3PN_#qGwOu0ygdVW|F>Jn-3~Q?tSPKhe@r$*+w7@2ICc=Mi>d$eC7RH&kD>zxXnurB6QoS!yhF zieKzI3V!$|RFH8uJ#GqNkMBuyo>DoKaaX^U`wrh?fTmBAP)1uj{WKEMlYkd+dIr%j zE$s`Rj%3WW@F09o<6IRcJR+hR3%4euY$#}(KrDt5L%QxF) z%*80hsA;FGtYpM$cBi2uhl5@-Y%S6L6*b z*Bt65_}&h!fz&sRWQKtSPn|+fl(a7!ra{|83J^v{ili72hK!qDZfIBaz?6M<^>e!Wh`9ME@?hZCN z+I<`zbT0eBYvc>bOP=zeRHacLyMZ%mW^fb9sHYZZ5AC(a3IM_y2hu4lYmX{<$f!?y z9P&F*urq%&0`@nO*hfTziW<^X19-zH4GlG@w}m-@ zOGZYwq~1P&Y-{-`OV&^Ka-2VMZJSK z^iroRr9V~nzMO|vtSd2H6qHjg=k@mRx82;IUwMgnrSXrieB)@!J4_}UQTk2a2aaFZ zn(-OxS~)7x;~Z!4azO{7KI>L?F+gAHFFrtf4A>~V3Uh^_DRiGeNP#V}?)%_p-Y z!Tzlnx-{ziJS`d+>qYl3_N;*qeuhI1KvK2wX!IQVFNNPK(U{V$+84NLVkQOG>dpg+Hy|o2T9W+gEHomnTn| zCd+X~$$8Q=2m~!r9Y334eC?_5w02dDO9AsZ^Se=(r$z_e^T=SfZ@Y<2} z6L7S%FQu2Lt9DvrpA$~KBFnq0dWp$WbUEn3lm5wd6yAc%ks>#eZs8OZsWsk1F)7@Ux!oX5v+diCU?w_MC@lElv`8X%d9- zGZX6IyUBCn6hAm^1MRYIZ?DYEugbC1Z3-*TT2zL(;U9GIJzgZ)-Pa?$S@M4k8udL= zMv?tQ&k&x1-#q6CG7q7g$}wCu{c0eRbc-S+i(d8g9XGjlE`rnLKF zJ-q_V5bEbJlE8v5#J*jt(tI=F< z8F1SQD19;eH7w{>zAQmSuABc9xH{w1{?s{yr6(18X|t)d841#~ZyEe`5IJT4dMSFC z-~40&g>7#MZVhIn08KZhh-dH`#j>)4j?(5;^~i4Dh(&}jOWe!gkpM_u`)I@MdB1to zCwCM7_)0r6&azle&_x26PW%}X>|;xc2th(jICewIakV4EUqOfe6I7o5!YqkSIR2r^ z99!N2DX3t&A1<-)*>;j@>16F%5JkD&mMs-Iw_nVkY_*#u4FvCYdN~Z$(xji?^C1{! zhAN>5&1N>{%A4vuhpgUAaZr2madFNJxNZ|e@to@~HZUG(TL-vvf?3a@duw=l&( z+fnu3Kz%XSBioYbx(VL7N>h${&5M=4oBaQxl6hN4Ac$6fl~>P=|CmMvQPR-hJXf_5 z!y4FF=d;fh{y-%M^7RO`>7NO0f#vW$!N)2Jpp4)iDS2mq&hD>v+k?7TiR#yx#E z-l46^R`=&4+RFbvLN6aLbSiNDlho(`;!h;LKP99#(!9Ap$EsQ5KSx|PUN`~W{3F3Q_`n)& z97mTA$;+CHNXFOzW3#ao0`&A03{6r0todIC3VS;LSrYIoKUo>YWA1fK8uTM({PEmu zyPc6GXarFdm@&vC1N7J;F-L%03*mnlDEv_T&piXhBU$7WWJEwl2wh#)iMKf58{kgH zbQ-Mjbo^CC5w4(V8wQsk(m!kbmjP3`!T&_AX`2b#{J$!)0eSL4Y9GVv_^7?KB9P#R zr4XtE^s4ANxse~&_#Xp$4>qC!dZTD!9pG1XGHk6UAV5RcG2Kpm+m8q4ti}7Cd^t4s zTU{dU5I`@b7sVR*9N~W$6gd_DXYOiwGVg5l{jV6nXM@ex~5mZi~RhrGDkc?ccazZo|IuDoP^&3=g;XWHu^>`$6 zXuk1}9(wwA81KeBQxC?rE$o^2D(QFdlIA~#-OIRT6??8N>;pj#P&v1>-nVCuLBOFo z;XgJA;E_nE(OmOVwd0aB5>Ml&!*w-m&B1X+zk!{rJI6Z{!mo#(Swocz=ge}}mCgID zcMm|4#Y+R%(r|ZK|!r;Xc#!^$q4<~Ky@(RDS_JwzP zvDH(;&$bDr82^eq5)&xij)vvcVGNLlL;C*_bjq~OZQeu^#y{qHm<1{qxN*X}HX@#a z7U|M9(7_8Ij^Rlsan^8RcQgU3VnjJI)WSf6Ke`jfBN2xH>BZfHzetWb6$Kw|{zNP+ z_VW95fAgYDgoD$l5{m2Tab3^d!?NfUQ2EHXq>!VwaSIWDf%JDb&2iP%&pzdq#PzSk zAxjlnW4rETSGXCY3F%QjR=@%2oZ);C;AU@JF>&4_{$lk8ep$1csl6=eCZ@ty#HE60 ziG=va?rFg=0Z6kWd4uY?Pe<65dOdPg1KTQ6`Dy2kn+F zU0cdnH>~thGstYC7ML;rYMo84JNu3z7gSNPcj5)x4~6@y`{+NMELs;s)@C@7%nj^~ zS>sPWT`6Yz-31ZVR8)-A{5EDlM7(*`J#+S^?Z-%V5*&{`|8;1ymiudT5J?b`pl&({ zM1n|`hkbS&Gb&+I8V3}dMPY#|rBfkO65kPpKXZ;}r>ES8=(d5Q9jm=v?wNTMj(d{C zt@L6|!+|=FkNOmUZ`qE_8~?c<3!ir!6>`h$Gq>Q7+6}F5BxTxv*`!}0lRoC+AQK7MyIa2SCHd$`uRWC`rR9F@Y1AgVFm7`8w+|d{%`oVl7htjFY zSjC}p6w#Y8`VJ*(J7Zeu;Hb)-ReUfvQZN~QNKkhOIDIAWyh-?7cG6KPP*KW7vc@lC zA1n7or;!;X}lbkI~MOrWj>YHnk@ zdDkZEO`ic-%!Wsj_y{f{O%7?Lo9ef|p1kjkNY9`YhG>u=BPHaXKkbx#`HQV5Ni~6T zq?AeAM8;;vYCf=F(UaX7`J=y$V;11K807-{w+D7p2eIpjPB%117Dl%oNLJQaTsdBl zn#N%%nl=q*l&RjodMeqFBESVy!p+VcU&Ur2yi$o3+#Px0J5)l82y&%4hC@bC1GOKRQ=Bq+G9b}}XUH?nq=2C- zNLe%Py-$DdOsW2}e!6FrCb{^t)bmQ<;=Ao`exy^M@`e>X-0(=ZAYL{hBcfI;rYix|SbtX=X zRNh9a-r$`&BG7esb{>%F3964YkqSd;C=qiN^Va#YV05pO;-YYC{>s1gfZUT889Y==dflo(fL| z_Dw>ml6Qef--*+ieX^cQ%()fP zZOe{}s@WH8-YQ12Td#D5A2N3PM%a#b=@+r*9VglvdbxTe?rFJC7dK!q1P>45snx00 zNN5!BBBw!3DUjUx2Sf6FNNoB-ifvOEkNJFiHDg8_+L%@{g%kczhfmu8zMVC`o8Ur=~5xevJ^5l!%2Oy@I5mP!%~QTOc#XQ9xfP+2I`rq zzISpyQfxMn3Fpemy!l0oZW9MK=rIoYI_sG>TGFer#q!7@jJCT=DV+Fwh*&~a_kN$s z<&-ab^pBOa7j#?~C)J+9Xg+UE|Ad1eW)YKDm@waOKV7&YpG<%HZP3xdHi1G!+3LRM zuBeh|r^_@`(RP{&WBbru%w9a{$-=POhV>L{g(0U2MiV|-XLYS3RDdB8nt}yX*J(hP z4{gZ>`Edoe%Oe6z*Hg_Ote#@l6?ePk*=KVkq}^WYv?1X-*pDiOiM_6gJ4>nQuJO7( z$gcf7IxA#d7V#t%e3d$3UAFVBSTjr0H4)ajfG7f7|G@!q<@Ax2ExlKz=S(D_%{ zHRy`g6?%A9X6$U-<^?AblGR!6h;ES&-^V(zAjoH#(JPAcD4~ zzV2KpM!Jg+Yw_cE2q1DmP~&+#S6=g#C%N1$O({q0Hm-n>77}+k<92OYiYh{~EScJR zZL|#BJr9E(eay+$I4RA3$%~eYvoRDjxUzvd^zip@J{>&yHCaHf@?y#(=i#*eOwD`& zjirN-m$Y1Uihpu^YL`AIxtS1jnVH7^siN`p#lqHilr7O)7FcDZE!-Wcb&X z)9Rev#+R{QO-eyY3Abf>)HAj{xB~*U6&0y3N}G*0Llc|RS~E-3dEIY(Iz~|QNmXv# zW;=6XKHF?{i17IGwVilYhV{0X@;SX(y>BcT>2|ssT4lZ2yxF95RhFpg)HTfUYPZOV zf*-NLY#%=n1}dlhhXnv3A%Yg0IEHy&51Hg2j5+0~lpbrsJVksLl$MLnHLfj-AV5!| zH|~M>4GB^v5=&I!Rd!%;;Cr8xr;{Y+d>Y+OX!LRZ#jn|hHSnxhaPv}Em&Ro#-&?}d zcv3`$MKDDeGXTy{_D<-mhDZ{vOtR9}FcVt<$L}l(NWCh@W=ly&X2=rXmwip2I=Z-#qyt zZVIV>xS3@>n9C?G+FQI#=O)ixD32RYx`3`Wa5I{Cf0j8oRE)Z>-?;D@Ju!a1zhY~S z{}Mitkj_lHQq2BSNpyIzN96-vMw4~Q`jqgCkTxuDSg`)q!Yqw0Nz=xp@XAtzoIg~2VH`#j@2iakJWpYRCB~zJT0YYi{L1?bU++aPvjf96{=LTuJi5;N$h99t;6%` zTCvg_QouCWsuNBd{(9wW-0|Ls5XITF?rvQJ;Vn>=szp+0J#f|$qF!rcSZ>BhwVdU| znEI4-%32;Z_KgLj?bFByp42zOlq`LxVEHVE_YL*90VBz<*XVbdgVrfQ1;|H z&4LlE0W>EC>|~vu6Jk_)Uwd_=Aykh!@A4=hag_(zE}MTY=KR9y)Vy>9cgmEdy6AbA z(FdgK^#|7n2AB15H!Q=G3!4lFZY99xe%lI@N0;)WEro03?!4y^96j;xTIzRV<;qU8 z=DOT;&B#N>lcUhBJ&Yg_F<@ux*V$wzVzEx6)K?o^!qARYT~4cwIx9|m6YE4z!8JH! z^@3>Ipc78~no)}dP)lUsQ6#68YY}xEn&0rif-Q1}wdcKS%g8?lBHeh0dI+Lu4G@X1 z{BlY|)tVn=?!IzvCy(E2mLFXiT$EK*z{Y@^GbC?J;m7uwo&Wi_ifs1=JF?}5RC41< zpu*K({Yj}o*l}s38I^(dLOQCvLM~ZDCi%tPB-7Dwvw&J`BHG0VM9Hxx-27VA*t-^i zF-^_63!jt*(JlA5sa@&yhN;B4{Y{Fz%8E>Hc!?vrO8<;>VCy+Hjf!@X4X3QoL4v#M zinUrVPhPRfD2}ZY->QilPfh7m-hdPoED;XWB=%ra2G`!X4 z*NQSxSu1=!?XP{d!IkRj@0Bh6mtd2g(B)^2msh-8WNtBZFy9OFC4y z5~XJS_aQJTobtN-tQC#zI4T?9?vHg+L-`NB)fvWqh-<3yb1BQZfNcNfZu8 z@dom}l#XSZhOowbnvM*TcE6JBY;jp!Z8G1AAgVAlf4|kc1iqo0>xxULP?0TH38S)K zaZ?_%tFB-Iyue398+Mkd7V*s!uMzIeFKvVMx&0UZUEV=Q0G{YM7DLdTm6;Fq;c$Cy zCDgr#0U2dxJ@w)`st$nxZq6ED%fdjtO1&0UM8&Y%mMp_e$wlhSwA;9!DBS6jb5l<< z2@S+ew;2jwMlZGAH6%@^rvPFHImZ^c<=Dzvl9se0oInCp-hiXA6(WeGfwIR3=H#G= zD05?r@z&(IA`OElmIz}DKc@ulgt~5S0kIanWrPu98y#c1X|H%7JSnw`7aAc2r-nI3 z@op~}vrWBKt~c~(;*V1{@007Rdiza~hg|l-;PkYYZUHI@0co=y;$JZJ&J{<+sFAK5 z5jIT*>XBW2$~{r`l0wA#RT*}$kc%^8nZ^|5(yvDN1{I!6&K-={ZE9;<9gYA+n|Kpe z<}oFr_Y-LTKLap>8FN}xk z<&lGG_HDJr_rZPb{a99d)F9sc_8YTA=NC$&td7faZd8-Q#-hH(8oWykz(JfIdr2&_ z27j^rTj6uN%~l$DTTN02n@L(pMG+Rc!MonGZ((X2rP2Bv$Awh7OokYBg6ZV)N8I zbyJAPG9HmEOHYb2PTZP~3huOij{fxDG_;DI2n$sg9K^|Zc71gr|@D@_&{Xk z&{Z&^s5O8E7X8V7N7oXs>ul5T;_mC-$v<-*htl)2J26jqn_~kp&V}A2;~P>@1hv-i zDQ8R(!`xtQB`n1SL4ebpwxX4rD7f{rH-?X8@6}0Ns4@VMyO5$NTBAkf`y05m$XIwR zG5hf3vSI4ROMNr_h0#VEZvW;_d?Ewi`H?EjVlQQOKW`@BqQKr%;iHjba=b26_ zEGPT^E3P6DC6JlO(lp(?a5@4DQBOvyOud@hz*LCT5stRuosna1L3Zu2o59Ke&Lxf8 zJ@cC3fq*&PzBOd4) z>qL+rcDdB(7QNi}B?uLzVbXY|z#@90DZEU0nN4tFHAgqtr`eOcl#k<}Y|rg@9=WhB z>e#W~IPv{xW0s6_Myd4QBCpFk(&EeT?hOg$v+C1rguKfY*l((uBL=Qtf!PCVS}`hW zc_hj0yc80O^V3YHM)b}oHRR{|ZD*^XwCf&keq7k{M|c-&Q8TLu&{d8JbYPOFCJh=a zA8+!{JoO!#>iqf3_jtnW#dmDqfX*%ZN15kc!7MyD7lVx=Ss>{;?jQm}Qux%|$0FLl zii0*06yZbzRk7TAh8V{OegMN}?9xna%u?O+#uB09Z1@N6^fnW-Mxb#8dw4v46KSWn zgaI!kJmRd8L!k2#FHu;h)1qt~tf>wH8YJs9@fIY{_8L~D{A{mz#nrOM-I2ocvM>u9 zN!Coag?ac*5xr+y9C}{bz7X|x=leK~kQ>?TN|J3cqUcWW73lcP6C(+S;gS6kJh|mS ziC&i8^|QCMwFDS!ELE<*16>Rb#KK5i)u=P2Gw$ibu4VbO@TYB<&EtWFohd5lR6P%S zbjT*N#8rd(&P7xzIY;{-{&s$qGiA!-hpvg=CUAu@m9|b4P3W=59hUU_y&dq|#?^E# zkjMc6ARq{G#iA1qYpV(jytNF~WozDzNR|K8l){y0A=X``I_DwW_m)Cp4qu-l3TP$N ziU0Tdz}vsCxBPv5JWpzCJ0Fs@uP=->#$(OUC`1Ufs!V;s8zi!}pA62zi?y@2zVBN| zM5ORE82x(vS;@TAxR~xc6Ff^DMMFo~u6=FB!zgxCLAZ}y6h43meB1x{Ew6InM)V87 zTHFoe9UFYiIX~H%ZBK_oXso`7&s_QzFT}dX)`YtGjpz{y3l&pBHV}YCT7Y)mL#IUK zr)}8e#>U_^aX#j6Z|^|^jfb^B*-UP}ua!BfywkfTd5Lo)AF{NkpYcR7PIz?T37YGl zwitfUAhkHT_^6(FV(z8*^)!K->+w2AUhZq@S#e|#P&li2Qz5{$8G0z%xt4Nt=9NU9 zZW)dv477X>$b$-*OCG|$G(os>c1z2hb&MZzVE#y!r%$#F4r$Ms^ngN3NoLGZ;sFJ~~v%w6%fLe;p`WzGlF!o7&WIT0M z&u&tib~d{MGxtcUYn~94CN2^mOQJrW;UC=)p%Z^g0`#)lB=hYu2hk?69s3`D{3nLr zASb)w^btmVMnE%lS={~VX@SHbP(Lb~3Z=lYJ9Wap+-mf$fYIhBL91cBd6xVh?~wl$-UOAyYcENX*`M7 zW+>nM`NJ4R+#Y<26(aZZtYMK@fkE3n_BAOrjXZEtpkNTy3=8grN+!h=D~pc0Ugl{e zg?zZq)BMCs8ZoUKty9tLi%7%6LK6BK?{esEp=*aRfpDrO-*{EkVffd_egH%mY;uoO z7&V5+nR5ur0QMO4h+NKC?kgPSPjY_$Z(r-ui1JAUEWV^^h+ zy9nk{0llRKnu)xQLj?_qeoMQ4mm6cH<ezf!K@ogBF$myO2MmXk6$PV#UC3K&%(YynI2i41;>GN8S)BNL3k%0_ESWLd z`2@8gN5nC2Ky|b2*D^yCO#F2ZJm|MNl?x(iaUox8J%yVmE4>bnco|{wz{!F>gUU@@ zdzLY;6{PWD#qcmH;HM5wEgNZG#*~FG-J@#-n=^?i4k#00MF_Lk1N92$$4nC{SAZROujI~fO&5qp^ z;C*A;G{e^0)+&ExE#daN2{=rRrL6n#xLy6ea>?40%AJAXBe4LDut{nN+;rin>!07@ z)c&t!Z-D==f3+QT{=T(0kg^;DV%EivH!FVsJX}#r_%~KwU!SaBtpxn@`0VbmIY|HD z?PGkP!4IluKT{sbQn0s{P@dYzBGVn4y!-0j=nh%7VC^uj?WjFj3NEPkY#M%0qo&R} zF+1E)kaE!-@{P{A>Od23_a$0HYCi=4Tj_yIR&pEPCPL3MepclOZ!v||o5;u+-;%^6 z1EW9twOu+QzFZRi_t#k~_p-a_hW=-x&jaq)seNY@gCrhyRUx4oSayKQP@l#7n&-~r zJg8Mwu(IJj>vwKma+vvguv3RtBZ-))<|P5N{lhlDEHX)e4U5~G56*62V$vU)F%~ai zqaEzSFlT)aqbr||ozYP5lGo#TzsiJ}cP2?6$FsiudhOq}OHd)BKEgfd z-nC+}y#68lGaiD9h9$6`=h5q57N0BegLR6dUTdx=@zsO>*^s_o z>d9TK#j(rKx0V^H0Q&OBZS1@o(@RKJD1aEvJ?@iYR{Q-{mUA|yfl8$oV_6&$fCM#V z1y<5artY!SG@?{dk$D+u`f2*Yr`V*cw?_7*P@{a&Q&+5_^KVfli7V(A=*Q^@vydi2 zoEi-(P3}a>{<6K4wFMR0-@6ntiBxX3YrF25X3C?VygQ8LvazcR>A2|1<5a7jdgC8E z4k>71?h!;v^gd1~ZDm|PtK8`&AWMr7p&vuYn0T3(TVfaX+mHg|>0rOa^ac%V*F~Tt zZ4uyEWsFkyBsof2hb4~PYOHCfV?CV1ZYkBqHmdLspats?2S6AY2bczAm1KA_Mq)P+ z@RMMF6o%J~$4UIQ)jeO2lc*0)j&FPY`@B@*#NS3G#Kx)f?w4qB9dp#m@5^S-8P@(9 zB_|c63-#A)_+VH>w-|whWnE?gk8^I`_;x{;`snkPUss~4bQ3}nhcFG2iYX-`L3tm)(ofeSE*?62u4gSIZ;ndICQ58WRa=Lnf__8AHwicT3J)50_uUaq6oSm3)e(7cnH@ z*Q=IBTF2}Cah`a3Kc26^&j2HPxNPo9$>6QV>Sh2!v=ko6gMq!R47)S&Il#atYC@C; z0HfT%D;~p$Ad}zsqpRV~!oF>|$%d)D_D`RVK58uvG&V&xMbM5*<^Iu&7%YWq&?I#J~V}d5YF$QMTMwCzCki6|PJ@FJR>Nm!d zianoP678uI@{Q6@B*Glm<+MZ;61cp&>B;C)V3lhD2)`js4xvAydoBxy1Uf;Sj%D z%sbknq0dp1r@yjybJVCItV8T>6#`@2v+$A4Pf2#kr;-We{Hj9oXHFrtbM_;cNss_- z_l@F)2y<2qNc`{PwO~zyIS;@?rm*j1o!(rZyeCvrxMP=u09zG|o1dir)RHK;%1GL) zH@RK>6NmYYYFjLE<$Mp#1it?7Mw|O89|}&@k{q_a4&O;O&3ChNkyE?%Bif7o4bPgBns(DqZnF!qp81g{j!Zl$p25*qXDu zhBX?8av|T#b_SG~oPx{7!*QtLZCQs#5E=FBWjob?%E~#e z(uM&L5NJ>lZ%GAz@=(8rNAqqGWlXGirvwufrva0+!0n%Cz@^o8!hOg0Vtr3PfMrkj z)a&hpAQ0=6O2@qR2)4w>+}>mhpgv(rp6x5m`A7rIfdbHik&Y+N%Fue_!YiIRnkm?&@d(eeT&s*5zn47Jk;&-1gjgLFyASp}cX;i~_)G=4kh- z>^; zxmqPRmJpElwajbEsBfwwV%ap@-RU)37^i-oKC7x>KA4B!?)kL6z%;Bqdn}>GMdJyUce1_@BD>c{8Xn@pt&H)hs5RHcpX$d zAl&!Syk@@Sdv@d!J7|H#Ekg>l$OvcNGb_xcg~okri?~XUn^%RbNWHAsIWBfa3PaJN z?e^`t^G(j>qPxEty5VhSCHKD3W6=OIZ%e7bSds5nk@Uh_>xVAv1`$4l!MEoKgq_t$ zq{LJ{X)2dX_D6-!85!Yu!(qArFau3J58()~ev2cKr@H!tGNzT^v<~`F5g+fM8_+|-4yr}hai%-p*JpfN!HeZ)a2f8&S$)hqtK91(&!V?CT*$DgFy+Yz+8dXX7 zDj5pAwR4qb;RYu609+JEra2Yr<;X@5rziU*t0!Px13)z`p{TOkjC>m2;Bemvyl3c!;Za$4za z8E+&$>Tk1tx|BIe;`d41E8efwu@<+#Iic z0TN>%HumEQ{d2t@cMy?7Qh+Pt0NQbn?7IN=I943D3436H772jgvJX$~@}Ip-dpmP> z1B`lMP4LAxU0~_uLs%ST^AvK5*jl+C+L^a=BqN)CVM?AgWcZ_7=?niZ6dH1Fx9fFv%o$pvI^oM_e3}zayw0%P;zJ?BAtYs;QUS z;8?sm5l66V9P{4*8GzwTD6%&-TYRpmJwsbnIQNoPe7Zb!?;k*-UA|nDs6zQtNWxJ^ zz{AB{@N5^<55AT~FEQdKD^NQ;jknOC)tzg2%=0U@f z;ND{@4e%u&c>W8<@aNYIN~X1Q(F)`DjO8b+D_K7}l%GtOJ}rz7#ITg--|pyNpWs*i zgETHz{^q!}?DU)uQ(JrH!p8_1M{`2B$7)QcDd2~UdhZ*c4Ya*L^&#N<)vvX)8~P?Q zh|Z^J(c_Yq<)f?Cn&J9(L(a1#DvWw@Fc%U0zfmBDr;H-bv6lG?`PY(S#nyZ3z>uDp zAb^Oi&{@#}Y5*Ddipi9>R2HFgO9j|1-Z+!ZzaAQBg6xdFmy`==^I7_X?Qs;8#{B+)C>`^fcJBkwy?C z%Aqqv{nlM=4E!w!pJ#8OB1rt`TK>1d-5U6_5T~D$`fP4xUO}F8tn$ab9i|FN>2^p1 zOhc^_nDQ7>yS{;w?P<;l;1Pa#z&7E@pi7Tm&~~(TubE?;p!E6r=41ueY~)c4QdH2J zFW|u2kdx0p?C`h=BwVE*UHK&Ldpy`c_N{g5q`bk+?s$9a#~za+psK-9bg~Hb`}x6D zz5*&jKbv6H8D?g^RXex8>rVUYg=Lu?*`D*(rtHNVNZ#(tqCd$GAB1x(0>Uw%TT1Ohmc<{wVLR74#!k`$UbFkWzg9GLudvyIF8W(J&W?#Cgw0&XBRh^FOsr$GfKJ`Bs?zTh&Zt#4G% z3%&pc$nS%_s!cc55%4Yr@uZZ2`vR7VQLonC|kSdVTkz`R3y9z#KR;9k~c zv5~f3>Xwv;XD1(kEqE$pmRD@AYq>2%L`wiZpbEM;M*)T;`$~Wz3(QcU(w+`RoZ<0H zs}MZv*q6VQYVY4t=#0|ptazFRU8Mn+#Rlr-Mbxo%5O zcY`3^jUe42-5f#$M3L_9Zjf$}E&)M8X^`%&Z=HMJ=Z)_de-3-?y<)BzV~n|(VgNJ+ zph11MVByi!EK#q&Ut7_hpwSzq<;oWV;wvcN_t8hq%jlM@JwJ?ULL?kxoZ+-ZG+N5z zqw25=Kwc7%!J(s#%ZEQKz3032&%eF$Xnp?1Wa28C3Hlg4HqM}~LmbtYu%Ox?&iO`! zc~;(=?nO2Mm`4fl^qsb641Vo~mgsdy69c}oId!ZFM8(97fnAZ{e<+t-J74q~e9Y@K zMGyW%wT@8kQ|PA0NNzgNdNY}x1Pi7G?zNH^>x2zt!w z!^o5{(3$3>tnP_qR2tsknSl#Rpr-JJElA>ouDZ8S^x!-JoZPC+>Nl!v;#K0&c)E&i zvR^O=TQcI8aPkw5@IU|Ar$8se9y2JPAh4%QN}Q*M=NE(0+hCDuSd`JIzCPXJZ(DtKUwOVRDlCLp5b}~8aJUW9&Cx#|9)JSry6twb3dJ_nF6`i zE<$CPpl*~wL-Cz%CORer($a5c9tS0bPpMuKhinPF&hwN`0__1J234>h^BVVNsB$^n-Fr3Ri(#N9jLK znEF&wC6rKceNI7+QjQ1PD#B(#|F69Ur^0$%R~PAhzpa`U3hcrMZTvTZ)8H`;4)5mh zyB80(W}14gFH_F}u%5^qT5tOA$YFOR?eb;~N|RxkxXuqbf{W%e~oPq2Zm!-)G*OyJXF-oy&_**Ie`} zt&n5Sbktv3E9AAfF%iN>SF8OKBH&TNGDZJ?pGSt4R)}hEPB{e#$s=L$@3+ZXT?I47 zx9ie3V|Nx0v=cWUmzI^Yjd#4jQ${fS+gd(?v={2i1Lw61|G)3X9=5-N9>DebkI{3i z5X&Cwr341sSLCXY&Sl6nJ-A036$G={otTC7r&}YwA1eO!?|Qog2X{tIfo%Bx_$=*Y znl0>&?Pk_1+)s*$gG_V-ZyB+o=2A#Wi#$qXI$qmjB(1|pl?>sm918rb%OV&jiwaBU zSv|k;!#pY?+n{g|I~|)9CX1?l)w^%ya)msP1=K^};VuKkBn!rw#6h^#XIU!#;r3&Y zhEv4`r#;u*2PU|?c)h-ZY^Gu+q4?4ip;ytN>~|@X z57pgG=m?3gyU5O7)S1_OW_iY`XZjN!RDhMB2slw5B2#u_@e7ut7IC)yVfZ4%x&-8?eEC$rvA?@m%r+Y9lPF zjxMez)+ZRAD7RfRk27v1E|ji#Be?bv*WuW`BC&*_Me^z2jXZ#l07^+WC@YU0pB%vQ zSC>Jj<43$x2(9x~Aj+|7^0kXE+C_{~J)aT>+=YO#e#po=cJBW0Aj}X5E#F2{W^ofNqo%wp@Lh9Lmh{F91; z9Jb?8DCz`^$^U=H9L$;YOCO;ViSJ!Lh&{!vtk57|z@icQqL^eMx0vjAsK5}71XuQ2 zykWzF1YCCNy{bWOhlYx!6e=d7SbR}FRobXYIw*XRpSvb=Ch4B%fcHAyt;;vxXG^4N#yMYpAuy1chnq=90fZUxXDvo ziluTl!Q6oCK`g7Om?g2FLjd3n{2`TtqpGa_$Xtn#kNFWsBjwmr{H8ANRTcXJ>;=fh z_M>l;lmGndYLo+L8P#M68`Q@0NWia{VbY|~(=py~!L+Kgs15l-Lu2rTFi?Ij0tPF@ zO|-U3W3q_e3-`z6ApX*MOz7&e@;xPc=!i6ofVgo6%AibFEe5!QNd)H&Ft zkT1R1D>;*jNud+r+1@URIzR0*Za=EHfeX^)>Nzn$2JA_Qi^BOmc#_!xQ{bcx90m8l z9^6X!CiE9!lwFdP#VTlLBuIk!L0u7G2$-uYqP-`B=fx9Num0t^@@wLt&gGDX)p3Ar zh_Va6i#Kgd0j{DA>cG1@DnpQr>aGNi#2!ottpT#r3sy|Yz_8b<UFO2|_r(7~HJ z*-VAN8tp^fAxu@>9(Nee)irhmF9yXTQ7x@+4kUUaN15UAI;Kj~$BjHQEZdtqZk$FN z)s9M=9Tk8(V@wNuGrsFL_V7T~=pAt1=3vnjnlM*b4M;=5)P>K4jaQZK35GsQBG&=u zlwCjM93;6uQ>nwZXKr!ZGhKz)$ifA=Q-a;TwDN)jdhvQd9Yth@SF3`7txnE_aKiX> z>f~n!SF)FJj+^)h_F>NT=U%;K>bUi>ShdYarXSUJ#Lk)|?F!h=tUtfLO@1%mEkU3FgPsy=!tgxc?ty220M{CSTJ4t=Y6`@Z(@tFw< z_FtKfsh*(EAS^_5CQ|qf!WTkH{v~dISM`w$}a!!qX4q5;1^w1 z;H&_7K`U<2UM?FZ;LYCThaRb>e6$NY?52hO0@UiE1I1sCY_$jLWzqOSgMydY)gSj@ z4tw7G`-^Mn{0H9NNAz2H(J5Jcf6JIPbNrGi&go!MqzM7~3>Y|n=%JkQpKtSI-;4WL z^}j#4Nef~0iXlB~Eq9dEsOuM#I#42d20fhO5PxYilt6g%I@5}HEcU(VT--`YIG7^7 zKo|(czDKKo*ds_7{Jkq7IYyuZzA*F*#TyQbgO3Ghe!#z94*|Z;N*L$wSf>j#M_I7J z?1g>UpR5o*U487#k~doHTEZg6z$X0spZ8bArrv}OCX-q(Rs#i2gdBx&KKUd%Id9G4 zMGfS=8acZmC7Nw;n78ozLV;WF-Dm2Br3ZJ(r6Q#|GL8*hGqz0%%l{~z%=h&9_K3v~ z382nd{&pu+jv6(*Jo_ifqNNofsig&K7B}$A(s6^$w5cpWu>n&uW>aS6!5{0EhN*@; zT1PCm2_AtPPWasU^?&UZ?tv&=xfWjiCWg<1e*h8Zqg~x$3kLlq-gWub-9uu&%KzA`EQ3F$*vakWSJ>=dG(W_7SLJIOyfZy9dfey3YaqRM zI_o@@EsDPfa{(%MZ$E8_XzpJ4{HOrL1OeWQ9KTFHPW>;*^gmb#D72*Nd|s@W>*Y&8 zCXoWg-y>KD#y)LT{wN}!83yS*Ahmrz8NrBR*tAt$rx+L}EMcV4e>xCN9GG}ZS(7pEf6q>gKSI_-bH z|DrD9>Rj7_~&PrRYf!K;ly}2myQWBiNa$f*NnyZ6!cn2Mx7YJXGq+7i%WWl%!C! zO(P6-^1{d6CEIyMW(?^>IIiyV18@IHX3%ZK048maI4STGh@SR8X^4rV%~-+cHWZ`f zvp9WBzusbAT_EQ)*#&qr04zDfqQ$(VnMB#`eY1h~qQcvx4lvN*FTxSfOvR14;avXa zom*>#BZ4~`1{%zNo9_Y3*J8LUX(|=Cq5t=d+Oaec4@e&1*Z=6+{e_qR#T&}y`}-zzRK{4E&=%!pfU%lsgWR&(Jv-c*l6zZH3rQpn8NOjym$VQ5Z)KZ4&2I&AY%pv zAOkWmrVcGTw-3cWNU4(>4z2NRs}$ie7s=7V37>Y!>0Jhb6zv5<#!WjZN4ib@!G#n{ zKd#UxjsllKsC1nc)LN#oJlmDbA(4j^<9Ak#_t7dstXu1aJ(DdxH8tXs%DwB9>@j;K zAY0-BxtOBu8V#%B3*M8GQX<%TFt9?A=!7RF^8ZQhIW({rV}-DaL#%COPM;Gw7~bcO z!d$G5jl_;kW|HMC3B%8jcWTqU=rR8(%LT+5o_+ries!l5Z2N9*RiotZG>7igJ9b^_ zQf-ydYpa1zEj@3`^b|Zb6I(Y9}{Zr&!JxT>}$xB z2&%QJ6EaQMpW!0!Vp{a!;9Kl#%ZS9*1PiI;vErlpMu!nRu2E&(WFDYPF|gik1RJLz zswsS2qt5gkd*v-=CJfO3fX|jl_!HtMOh(6gNzQT# zkMzv1$oo#Sl$XGdErkcQH;5zwKx)5bode?7~#eXVBQSFp)d$rmiW*n&tc!_4w)@gcf7F3PhF{$6E zKc7N_?LnK7>8_1Z_=!W1&Ze7u`->}ulm79Au4A3`qPA_rbUSf698cryP&}c!#7pVu`MqEi zc)`caEWBt;^clCu(#Qq#9i%T{3arv&*W+WIUJlrK34$a|0pgTs@92W5me#nyU}-6w zLRe7C28&Vqpw%tPZrw=#KS?GRS6~pU>XRqr&qh1BVy?|nRhn5o_t+OXX?Lfr!)3z> zC=WTy%QZ!=^9W~<2c0JpBnOgiE4Rq4@BTJmg!?SL6?hVwd@AMg?=nKO6vJ)JC0Hsq zgF0_H1t!wOmDq+gfy7PWTaP^Lo^K>YD}!h_x+V(xIdaU;NG&0=MDZo%vF(9V8a8C5 zR_}Lvg+-jD>HAf3MJ?YmN_(aMvl#{$X;%d!=Z@X{5ww3zXnDRRDFy!$%+T|VpWIrsMzJA+APYa}c|-m4RBrsA z-W#Y43(Bk#8a4~gZ&J<(L*Gu}s7e?dI}9|JfXku&f}fds73GJ5c@X@vu8YBIM3?_F zyUg}B%-lAQO?@-6;@@RYcXjjG`v^cr?t?^7=F%x*F&6osWp1UzW^(UL{re&26NWPJ z{ujc9`5*U^QM&fLvHzWcvp!R676kl+SesdDE{jyeXk8XKe72h-^+I5o{8O`DK0Rc<)dVw$ zZ8}@@LK0P{iXC{K*8jCU)?Rf4G}%;Tgfyfjc&0bl(e1|bzktGt*D$>k)vjjKS+nSk z2Y!jTvc-+zg>2L1F7>^fVJ%ILbosG?IjbAw{2OXThw3(&2ss?XJeJV}gS~ zkI#(FX>n9K?xn?#Wty>r8G-gT0<{d z`9&}xB}Ab5_U}?hhQjb*rM`T2FU8SmVhv9|f*iNnO<~zoPh9_~qRU+C$h!X! z{|!gNT{}{hYM>LidQ7aRlybqBOuI);R|EH%W5U8Yftg2>WyV30paz?PJKrNbCBf4uGGSlNbDLH$W}PNOYR_ zY)r%R&p)8<;PUF0H1UGtiM_=>Lfub3d``H*d6Frv@b`K0?1Myqm3*>O_74hUK&6C9 z|M@323g-Rs7u{CyWqlKh38mter4|piI|U@m6LwqNxUAz#K5H(`=a1P&0SI%(lvp7< zGxV{uQlBqAOe@&QO6uCbzVgK|tb_ z>V2E#1dTy@b8z2-Kk}Vi6g4yhVTGMTxjM4Rx$wxIqh>4jOCU=m;jXlQ>>Vy9G^SDT z!3zDO8uK)D$LweLwB;vU-VG8882&iiiTR>ca|#WXLN9;q@u8GAI5=!FSw+7l&<@(T zm!t(^kgFnh{>>S`qRwJGiuc7$(A%P`kq~#m+P`fLW-5H{QI~eX?5QC@2Yez zVw1i;{)J)C(v$oKxaoi8nzZ-Et$VG{y8o^*$c|A%(p-<;hGTrQ@2yQhnktt{+#D6} zvHGKVh+Jy;Q~^9OeuPLDIyUQ;N(QvLZ+;K{-LHX~qpAXB9n3`zHHHJqemW3o+s>RH z)*5euQOq?r__@dUTS$i_o9N?_1JU<5PAQAk_POmg>Vp>Wx0@_k-Wttpdkdy-d9VLq z6COAI*>5Dw`@y>i`?7+mW(960Y-jMoN2^SEm(#g>@5Bpx5=#4}D=>H$*{cSD|yug8PL6oz+;x+u1n->Si#o~cu)> zadVZm)y#nXCsccc4OB{7Wn6CgyQUD9A%Ue(3%mm*4QEy$3xJyCJq6&&z2DYZv30Rw zTUA&rMonj+HX4a7R}>_ZpJ_94o=A4uUorAj*4eXNP+pDE6URRYxBjEcgNnWAg`m@Ue_}Q?(c)+QhPTNP3A}@L(KKPruU8;X7!RW;8VLcaCM* zTP<$B3y!->8%59edaC`jhEpE^;NtYkIagWB08#z7$e_jjBpZm1_)T_uU9U$S31JWM zM=gPhw#lY_OFhwR<@^2c+d*mEI7>o-)pdeb#`J58PCj~B-W=l#oDCuX=Un#2SOmlC zJ=FRJsJn$8Pj*oG=PDZJp>1s3^5w8U)=;i4e6$OWc&0&a*yR%Ie_Q>sGge8n|7sU) z0{6rhCR>zKUGzPrg{EK!M%jn3sFw zgtx5PCg6$k^7T6f+jNq2In;qxa^!aOtl4Z%RzPwS;uDR9U?~|$TygK&P^$F?inXM%S~gw`+dptxMJp2|5{E_xmYeT|L!)r$-t0`eJ+{Yiu)U1&KYY1G zWHYxmI!|=5O091myvp6#Brd>9A^P4#!A04RWQ!`D@a^nByHb?IV-z8Pda7C1Pf>Ap zo#)C_`IW^Y$V@EN5XIy&0JTvO++xBPa`toj=Rrlu7jxWBRVTi099-@FtUJXfx|odm9bp^kd~ zwUO%}!9?9H8kJZ?U<77C@9E7UaH^6cXWW%k(B1nmjp!PrjTG9vZzQp6z+0!# zhTaQ%1#4mcsB^RJ4F^#3s>bRK&9skXNKqU4E+yCs|6WN*fPyZrdHx+ zcGxFj`wt1leLxd#tQZsbQ(zj}sFMcPU%5^mKHxQ(7Q3}vm|!g7UFYB?k~`}_l?-3v zheLzom;99mpNd2cj)5fRh`~M6+9%Q4I>aicFK`#ATw?Fv$tWC0*$RwHvA$Hzi$(0U z5v04aMk%_p%S(lZ7T{<<<-W8!%vR^0v%)sW3+csTD$#E6P3ep}N7EmbyVrF4v(3oq{id@; zq4r2uXXSH(AsXOBXT#N2uSEthjslIX3UQPU#Yuf9A{NQI=&e%nwA?YK2xR;sDa(hYtg52bfmdMJtj*P5j-uA`n=Ml zK&)?FT9_0$=*d!&?HH~{bmk}ewET1z;BuTKQ^vfS@$PiheB)8|l3F4UNZPy-hrq>! zp}p8v`6D6Aqa?XJrkZ*%B4MkiyR&)^PdAGE!bXYyxauP_MMJaxDtXcpp;s{|8;_oh znxqM*4kAt90X4YP-BKtApIpZ@EbQ>YVrz8 zjXkZ$LWXMO`&z5c!`OE8PfSuIJlCJsu1hfjd+;E;ax;E9O^)-@l92n0q6BxH1(K~C zd2iwA45L=XBSsxL{ShUGxn$Gs%OxcfF|^&|h4_V{HCU%tP^nPG;W4Z$Rv`-{%8nAHo>CR0Wr+pe96lufI6Xul(nWx+{$x{i9v z-pR^kc--rJEZb{YemL}eqjvvz)p^u%c-8qNBKGR(ChKW_^eXx^;C>)rWA z#MKINBHstV5h+jN_6t2Vk8dvS)tke);jK!>^(Rw}@~EPt*f z$HdV>gVbd}`HYun(mlg3RlcWBQRm?M>JW+lVvH7|ZMwr zG&y46RziHyj`}H&y@dC>C3s1cb+jzRA_lZtGS$B{sYIuKwdRJb<#W~(Jw5nyJ-WRn zVVPTa^DHK}Vt|HRT6cKTIm5$z`Ka*>@2#y&jOJ#UCNH~LGkzRRs3y)`%#y;EhTeC* zBA<_Pz1nGH!~Q5DAVW|IG$O%1?Hr;KX`BX~5Inv41Cw@y@9ny@SzUKq8kV^+ts5NW z960Po8$u;FWt%WJ`O^`B9~0TExo zgJ63uqtX`b`k%qgH8(djPgJe-vzrYr%FnrkB3F5ECAQrKuf=-`-UF@=fWl#C8`_i_ zrr!?I7ccEm^O=qqm2xj6Wj%g+Uc)9zQ&8GP-9O-Oeo%|H%qZc~CuI3Hx9@I}7XM$B zM68V7S>JNRyHOIi{pUuB&UAm@!Ek+LZ2hVc%ej*P>rJIC{>xh-)JXzvuihaf1-J5f zDso(47l1?<+K?Kh-xl+=S;xw?uU@0CfZP6bh|}R!JS^aeT_OPtFmw6vsbSX0CT^X|puI<75-#->QpxVVl70h>3k_WD?-9Rz zfJ4*;n$8J@mxQ~$?~Ctc+m*J1{H~uD5 zFeB8RQ-!SaFbQI7oYD#TjHird$nOsAFssQCzoaJ-ul8(x{?&Bjh1H0RrlDAUn!^Ef zR>dZwR{+9Ivd9l55A+p_lg3?g@|k?JdyZP5_xt;Qp9z5cAs&X@)A@PQvOePs_MwIF z%z9(Lo#wWD5hTK+yd7MuG5t68&-Uh6kBRRfOzbL~&EQF=gFcr$z{&Awlf+7JY27bs zm7Z!1J7Q0#zR&`&x6N*stvs!T0-t+$<^qnz+~f_56PKgco&orUh@5y zS*}wmx`!>wO1srA3H%w#9Y!oMgG?bY1(?iqtAejkoczX6`q+_TF`lL8`f|RkoT*uOx*)gQ&s-(NTZv(9Fk8Z$>I+3%#iw(R#j5 zS|v;yw0NAjysqzdDGZ=jb?m0<3G}!XAv}}~rj&aI*btezEN^`owhMn=0EJGUsgZjO z-KSHPRz4=&E$H&oc6UD4d;=8R=HkM%i{J$6uYYXN8pxcze5@o7@>0fQYxb}D>GO3z zKQ7-F*`qW>ThjkwKsVSl6Z>8`W2@(%nF`=h5g8cgxf7;wi|cXD&#^UdLI&*&*N zQp-%sz@Y7;ekA|6(OT!sIoIg@Yyx#2Q7-3I&q$L!F8wuEyW}0d9sg^p4q80o)lcNG zH5oV8exf$pxuhkUw{C)rQ|kubwF^GyR<|CHPkwP82&FC5#7udqPJW|p&Ssu1+KzpJ z)+fep-g>0fDiG8a96j{)3>gMeooeW4UbVwloT9cp@AYl}jj{Z0uOvHj3~KDaH8Y3W z&UK<9B0P>xs&g|7f?-wC!Vkq74`p|!&balo4C%Sv4>~GrE8BgOM#aK4QKD{=%$EdFWPnU`D;1OhUtR zoZfjG{>p+uN$eZygP}<)|7NlHZQo@E`M;|f2fng@QbH-UfgVp|wOLNi;1kIZPKt~z zeS_PTs?~vzGm3eCqq#cnC$DURr3Ey&rJSA_`W4L1wP1f4h9Mc40{Fic?O+Q7(YzEk z?>)cHcSHP1NIo^H$gBd)YtIol``h4`%Vz1b;dbyAJ^kZ0RP5HFjd z%cXJ9X7qrXEQ7qDCGexGG?-50SweQ%nYr5i6h)9_;r>>SiN=?skI zmtNSXgiJ5e%ttnU8qPXuke}U2u=)Zj@VPJaKsMl=u%rwlQN0JUKU>%<@9l{DDRz6= zmW&~Ki0?$<5+T;(e0zBmzXl4>Hbm2jci%vlho?UAVg#A&qj2b{^2<$36&06`xZ6Ps zHos*jBm0{w>AD%>IDbf<3{vx=99!&jriY6$vD%0t0Vm-LJ2X z@1~8!C2v^{Rl%u#iVeRfvu!D9<~fdcHSXlaG7Ul$Jw!|&bZAx)D~`fSDfR;?tlZ&! zWt5q)*TmVP!qa;~4;eBT?_VnKni=|Rb9_oo&j-y*bx~;nN$@0pJ$_M;tAuVrO!rQJ3uOiDL=*qPAo$&3uEZwYzc z=;vQ2+h;eRcb47DLO*kKH;-S0m+R{y<1z1k$|jLg(AXoad1D2oIASEpMeJHPjHTDD z7qH&+q!Rz#s5ox5_wY3SYpD#-e57BTo65u^HEJ)^-OhbSeI)_T+P7j~ENh~J=w)m? zo50jP_K~}pHVv}#ayeEzhj<;ot(4`i+4*!9g0Ow2i`8Dz)QR{4@Ejfxys(O+@FpZu z6kn!mpvylGNY&X?aTkccJ@#=^!*A8wjWy<^*!{%$xM`^z7jx>da2U}r3T=ogHegD+ z#1y?Azn`rM1$Z2E*?Ht7T}9`ci{YZlmlY5QE^5S5Rw}dl4k5CECa5<6*6)}Woq83c zjdINj89$xMsWV3!=~}MJ-|V_{y%F2vo+~)O?F8Rt zL;XciLuN;{^zOQyF7v2PkU>sJT}oeP7e1X#6Djx9@ArIe6}d6@=K0obiXV{_Z703Hu5=h=cJ5*S5!ejl<$Ia0+3+W+`eG3{c*Rr%mTjMxAE^u zpecd>8+W%annCA!A$}lbfT$QKE((x6@E1d2u9#!^tr%+L{^jR%oFW%4Qk2;mhdYJF zZw{S3$o!rcGwfB|6k|bNWmpY;&P5@=;~#hUECt%?X?*dUJovj_q|M(G+3S!A-q+h! zie*4byn$Oa%i$aB=ii~l6Add$jfoQ+9C7HvbJ)$vd4gLXAgRE5?7-TI+9i)ft4V>JAOgkb1|Ifq&SOWjICQUS-7+hINSYY|h2i#{ZQ*u?2BTX9 z8Tmswx1#${tELhjr=~sAx3t+_-JtdgZDWWSJD{MO37!>d-a zvST*AdYQNoSI}rFPt{>D@yhLt6-T<{ikV>G-LX19r@3u9=ZFgTB2lOJXYRNjiRF<^ z$)*GcAc%50s2=t_&gmrq0{@|8_SGU{?Zd|_9VR)WudZ7Pap@Ne`V8hcLL$~ai+byV zTtgbQV{-ZlT~Ag=`rpWgYRVswPEbxzkl@j7aSR-dXY3|l)!ABW&*cAtsd~*-{LJzp zKU~d(PuX;;KFOr_I-!}_GecCJ0Ut+w$xk%8B)Y(LzU5$&<%3Oa6P--)iQ|@@VyX^G z6XFB|7iF1GHvV)&Wf+>2DKi0AeUqCG|Lh8moYJ%qX^A# z(h!x0K&@II(6-P=HHI zROm#+*sB=LY&;VtJ4})uyw15Sy>^BIMr6}cB-I5JpZ8~%+psdQSrharc*pMg0p>^E zfS&)skdISN=pjMjqD+JdAyIWbLGH4N6b$He-Stg=-rnNcOE`Co^TEY{&&ELTy60raE}Lc195F+s z<9ob+m8Gu=9PCi>!o22TRp?k(Gt|g)hh05l=++lrE$D0{8pkKyCo$1sDoQ{CWf3A@ zi{=sX;~+QfwH&_6bn`XGS@@ts{~ot;yf1NO8e9BA{B!Pq_Xrr2g|H)!n&ExE+V6aL z({kEzouypVFi)(=J20=}ado%Q8GYVGY3R{)cHx6lkK0djF%-!(tnirj?oDnNW3fsu zqn#q%m&sxkD^&R=K|K8rDv~fisb5@l|042U?+L1X@Xrc)2)vS#`u)DKw3KR}zUpqT zLbz+yrMbSMqKjwrD|qN5@&9_Lc%Epucu3q3756S)zigj;lTwvTy^Xhs|I zr)^U)@Mm{zpFZ!dtWu>5R>KWPCgN7AOK)Gr1;scd>-)k^aa3zQ=;PXS`?+)PV&O8h zFRh%)QP#Qodh@b()k!de%EjrqXO%v7fvr~bDLwifNHN|Uv269?80-9P`NZK1aU!PW zT&8xWyNiiw@A;LmG@Hh#hI1J=0x58IkLv0!p4dfW{cbFPP~B5xKALGswR`5%zHu>j z+oambGz_rT9C9g{P_5afV(2(sSE$;j<|bXe>^k#NJIzeNsbd zCbrIu+uEbd30v56F8{6UO?xrc>;i+-?38Tsj!=b#Ji-E!d&@K<`(cNAV~fnnWGL=$ zSb2o6Cq(e1;iN0$nGvyK+VRWTTOUl(c6-s>gvo9k(7cc3F-R1}0&iEw$(l2cPrQz) z$g>^@FNloJaIdtSxMY6(v26ozt$b>BasJwWz`8hkEn2Y>RCqcjntz(f^f)lXf}f)f%Uo#X#LMbPCi?>~jO7wqIJ6TJH9}-?r;xnUNSJ<$w7iEhY z3p9l&-VS}K@odd77Yi=ID)jr1)j)YC0D6rIv+q(XnCmu`GU@r@P}csDiLE%Hug>DN z{a`n|ewB_i?G#3uT~@m5#GgK4)$y94oGc2tVTtO&zf+79GlryJ^U|B#q^>pYrEyCQ z%k{u*|M~F#Hx2T0Gl}JwjQegzIW;XZ_+@HYKc5?X?q)E!ag?vbwE^pL%=POjcC!hQ zk(MY`^@cXry;@o| z?UQ5zal`Q_q){?M*C`fiu*qm~UIjvhRU4ffNu2F&<_9y#8!9cYdNTk?aF$TI26U~u zF8h#oaqp%{$v1EB(9Qg!2l_IsLy%2H8OVY(qJ07k!QTwM)rH!60iq(&iS0P@gSD?X z(vXEN#VEdA_;RWl`aye|p6xRtr9gQ7Y3}06*iF!ub6_17*J$or`rRsNsj$dOehm*x zKph-5%qz}UL9r*Cucjk%MAd~hke?EEsWw^TIF@*`D1XP8SZdn&IoO!r{tT(v^lMxU zx-wgs%7R&UkAEX!yvVT|S4NcsP?pU!R|#A%FDMs}l{ELmp1&u&h=~)Fe}P#G=UM)P z@Inn6!;5N%qBxZRdZE6?k=e0k0K^gz;n zbKSQL>lV6&L@JQ{`f;bWrH6fKh@T>1Z+QCR0YS=*uQ1u+`7^9rX~trMHm zK(}&;EC?_|E#PH9N3NG6dUidCbALKj3k9k0#4Mpcr4u5BlB!=PPZ>+k!`-w}_)CU!Uao1B7% z%JIwTBRiiJGC$pND}hA7kMAW=uM)!EhY-q$|4i{tP^=-puv^Px8tgM5 zQLvmrMqH4CG|9+Z?xe58ka)^MaD6YYcYnRzB`Hz7HzfB%e|>P1AX=Gm8{ua3+GLdj z1z4(JL-s0Sj_HBO?0SxvX|=3E8z<2>nI@>Ik(ql={BDKMEM;gK2EWTh&h1$&AAdGZ zzSi)$NVpJHyZ#*Ot`2_Q^|)zn?!@#7ikDH%`qr5&zl#@eAdz6^6EcNVJV6NPqL=)H zuz8}vId&rqVSx>oi-~-W_xUsQRXYmNg=j9QbV`oFYUIY5uOUs0Vfm!3V>Cpu=!W41 zHZwAC7Be!rCac}hH+}X_Uz*3XFzTfP9P+?~B82X&4ZB+tQJ{%XJAhqewC$6&iawalZOm!4Cp;|T59 zf6c|5|Cj-M^1?KYWtxkoK2Mp=vtOA6(BUT53e~dIs>?o*(%OAXnGVB7owNOoLHI|Y zv_v?c`lPIgUw>UU(hU9@p4`Pwf7jMh`JNw;T>@16DYnqFPGiiTPP~LOlz(MyJoyS{ zR3{YG?MaQfjeK~&bow;K*viz=AX80l^aBLFdiZ%l%}b7T(`$G*?7ML&nm(K!GSBk2 z$I_;XCm4kF{P!EA!}T4ut_gd)#e2RFenVE5=IJzcE(B6QD~F_oNi^YqwX|rD#LP|I zsTrnQISj{1I3A|p*st9L0VZ_)ME0@}ZeX3`VLAcxPXn5^>2_S)d|_oAATtKoylG?g zjkq;uWAl)IX08*%0DMm>)m8IXVhBCqqSU;c{Z8!BP8=@qLE~y;Rd9!jlbbH6oXHJ+ zFr^wvOrQ9_ow|<^_Qn*tMqxI7_AE^Qk59nuog-6@^Y-3`($UDA!DG}6)~Al=>FC5%g6QAm2D{!(=dT?tdRwRxc!yyS8GMR*p=cn2!NIdElMp6hGS5-5NW<_ zlRVAPjOh!k=yqLuQ-1{NrAA1Z4{NVAxv;YhT3}YF;0$n%qQ$Tp``q?yf7yCXdf|W{4yweXI#_$J_xP{IB&iAv0`(eQ^ zv=A~ds!^kbkKAAGT67qZAgwt=1bU4a?B33@dw=<7*-|Ngf8J56ox6^6$JdBPe7);c zB_(*X(Vt7@?b6hR^q7Fv14gL6KZ2}y^!{;6%$Dq$KSP$%F`{?fE{;jEa0AV^^1*4K z63q06kJv^NY%A|Uq<8#+LCWa%dBlNOr^=8BrX?H_*axEmE2_zdkKX*Pk0LtIn8m0Y zz&+A7-?nJIbAb{pgq8Dqk=hkXa1M8|$ZfE|XW6U$FMNxY8D_ank3C_wmF0+Xzu$AMW5wwV%k_y*_I7 z3>X2)m2AlicW~{Ic@wQDPr*7Phd0Yyj8U%6eLswr{L-)WO_f)lL6qV^u99LVD9MOF zV^ZwwEBl_1$Wu3}Pf3Y6_RC(^9dOK?xTbWy1u9I?JW->vAdK5174%P*>%+|&T+-D6 z(y`CDka*}j^Hk59)5k!;J|F(^%c%F-q}b`#MeFH0=bqv>?*wc=P_?4E8yJO^#DS?4 z`7QGK^<}8<#A6(dxJpg)`Djv(4P)j{MR>JWeiYqkeIWwNqWY7RWH%GxYoY{KQelt6 zMbV=k$~wCv`L(-#p1QdoP12$)Z+BAxx)xC{q#DDZ4`Vq!Nz1&X;8+z!9m_mcww*2$cb=HOi zxU}v1MZMN;93KYGgxZf`dCo?!9hPwx=n^Fxs^Qp3f&|bYG$u&(6L2g=QM_p&h+@wi zxtU@7LKtr228^RwNzwHA1^0w7x*%nWnKrnSZ?cWJP}#`f;)*FgAxRf#QnT#kzSzC) z1BDmK5%9sQ@#a68!$k-ROnn!hQH$;Lo^zEuc_EeNtXunYC{W<_J&B+lV;HC3yNK&{ zM#<*oD~~ZP`S_`Qj^J_p`Hk0?Wb6Q$aT7EVFCuf5!`W1 zfr?`|Ng1+DLmF@pYy>@Nigaw23hWgQx~zMJ{1y!eWj(mN97D|GJsa=#SYdvM{w*gJ zp*)bc$Er?uIs}ws?tuJIAS3SCZ9bU4Hn05gK@0BYVB3|qdh+W2eHUC_nFF47B*42K<9IvV0aK%FjmU!usi$BHlv&pPOzCjYHC6%In9 zRn&_D(o4vEZe~<`X&sGauO_C>Y|>QOLnZ$c*k`GjCW+7-*_ul4&>^cmBk!c4?&>CQ z4orDLxp<)5c~D@q?2lHn*Y&iCAh0mkKt3MHUXo^tPS=<643YidDk0~MvIY8iM zYdDL)TBxRfw;x1IJO~y%8WjB~2Nd9S*|hJUse1jNYC=mDhh{#ArX<9;k*o{)=Zk#l z^QX;e|2z`rOSc@TdytVdiiT=n8d*oe2$;amzjricuIaIwup=?pYjRvsHX9(IF(lj7o zn{1h1F_h=K?3qKDMB_qcH;Iw~+=Zw>Eo3gAF2ru6fo9P2Sr4v_*ji7H+=tiqY!7uQ zlCKun-)m*70pDb%Q#|zKE07O9^0A0c>P7BEUc?b&hi**=+6lV+x2%PR<5E@Te7Io6 zb$(eGK?RXk+i;CHklvf$lQqy**h5B?x_Mm}uDIwm;7w0|s?C`xie7sizA}WPgMgSt zK>IpKlgpPIbB#D|pc>p>gs+!!PU4&D(7XspHh}{D{ozft*fqLkb*AT?Y2wA|(P%_# zaV8Xmk7Kg1l|U$9(xuu}@D|h@+Cvj(w3gDqf|yJ%FpKJ4-*xP?mj9#6FwNqnP)dO* z>%uqj*l)`&!b-XljpBf32$sp&^LI^XxGE2cT(poyTrv|4yI*fYAuQ4L?n1Buy3qJ+ z$HH-5H9MsJMh-y#WfpHeqqg&T@D`&jo=>z;^b@h*P~X34BvPlUi`mZz@fL8Y@73Lc?;-$pu`*vQ$``wNAW7wwr zc#HLWMsRePpicbDTLkg!9Gbt19yF!}oF^pYCzlUgJ2w3M(!FG z*@L^Xaq{jT`C6;ENxwO$RS$UFUKNtEHXTdV;R@-Iz!jlS6pgA0ASB2rlqH;eU`SRM zTERpUu)ycvXZ5`kzstdQ+CUE^JukqDQ^>@MryHg~KlwPJWt~V$kntq_yx=5V3#SvG zb=W!Z8Hj;lfG1f$bS^ECl#QeEGc1ZW|8*+1Loevn(@-&1DJG=H1$TpN&M*(Gh#z#G zRW=~cZ!Dq4QWp|}X3%o+afnKfGmi}1q37p-!{OQ9@Cl9%7NX7oW~+MmAHinz3tPI$=G(peGJ6#RQ$t+yVz=C!CqV+bF$Vo*B&BEl+ z1wvh|QfBNCE!)8_G<6h6^KQ1ibL^N8Kb5d7$Xj9%DW=eFpuoU$A729R(GEkhj$e)Q zo&zTV>Gj>p4iE5#EFXdoS-^*M97itx@?o})v{y_!L%?oYNLe^2dBcQAp9C&LeN_uG zSKa)yRc?E%Jzk|!LG1?U@?_xB3APl?w|`VwrmCQJN@CwBw)ds%^X1cOi2P>hzeobefUG1Vv=bQ#qH_OL6KASoScWZo` zeK!-kAW;rTa=U(t`(U;o`i9MkR^-LIv7%^&%mmdHIupYH{=03!Cr}Q|=4>%d<#?e_ zASE>)Vf6HV!cX6v51a!`^2&hgUzQL}Vf~NrDBj70QE0X&Om#>g+JG=|?nXq;!j|v; zr8{@V)%~M&z0e@=mn98udbgbu!+%6ETqtX{^lM%OMj99AE&Il9$_-Y0n;bq^2=*Lc zdssg$+UL$FZdt#L?=!{^NSZJ1_{lk$6rXtVor?#-8p?H1f3+In;L^HS&LQSd()tKa z=N7yhYLB158!>^cn z&=oHz-x-W>egZ38W$f7uG!TF5-25iG7r4Wgk3r6bM)&9>Y_XD(5`Ttufs}z0p`ROX z?v-XnU6%rKB#nUH6=#=p9X$0lq2W-qK(;WhIjciP`s?U+heKq>QBxDLvxv6TPUi0r zvuA}T!HY(d2AMa0TuN<7jI#m#u8*Y(7o*q!Ew4Ww3x- zk&8I*`+s_5{fK+)c9Y}2lyGT7eifcc2*HuD&Mq^x{4}!d(8w{KWw9Xu&O|$R7AjNE zJbdQC$oq@}aH1`Sy+`7%L6Tb8?cc4&;2Y|UZCrq^NZzueZQWcVQH*f(3?KGbf=M*^ zmal;i&T5$ny&l5*p$DJq<)^o5A)Nm2psf)TKtj#lGKX8q4(~h!Jg`9cRuXKNImQhr zL{|WgR+h5NeE427L>tXXTkVFb+1C|I|aq<|Cq*iEI4%k*kk);+@{a!o`$a06uwP|G2cHrgZ_KW zy~YCz$xAfiUEn{;$mbV$TA?eKZL&(OK_do6*YC?6);+ACzjog|4dVo!MTbC%fNOHP z9s@aVa)I#1{$(dcT4Ntbd;eD8ymdb>+1xDAxBb#xBw#N+0L=>Cy?V{J@JNTt zAlwIrGIO+f(b_CeY)uFftC3r)U=&03p98>1a0*8eoHq;8U*E%6^n6mT8B)Kxg!@Q< z65N%u09!IOCj-w$DS6OZL~S=8!$up^zYi+J#=ky~nJCm2>zCcUG4(!T;~U$_u?C zK@EiY5%nmh;CN*i-ekilr=QJy<~r4EMUXE^<*R4PdJ2!QFF|HwFZ^gZ-dBhY*{^$3 zYURU;)f=D&jL>yqxVqanm3>C7Vfu>bVO;k;WEc85<2fKf!!HBVIfS(~Jud>aNVTBa@#4sT08avgO;@Nfgx@zAN?#fuogROU;< zMCb>2Z(A)JmSo_p;8xB;M$(Grs>RlRKdUm)GrpOU=uy@`31Kocg2+!UHXJqJiA?lA zGA#7et!6McjCpmT)FqVtd=0E_bLj0;E68;Awb)PuL-%Xn{%L_3t#9n<^ZFG_9XQBj zrS_jPJ_r`E0b_=y&Id_!HWy^}E#f2V-|CLbKKvj0Ex&n3u=KK*r_Czwq)P0sZOlZN z_{pjP51BR_|0AnI716(%Q>X#0m(_QgzEcL@YsV!M9-Ut~H{QQ*{=*CK7WZC5*)EwG z^m;6)UF?+5ckI?|iM{N>^{?XO^_vDLZt~_2z5T>gCF1bciwD>*mmGKrJvQe=4Gj6` zsl?7Z(Po$+iTXU`Q-SFLpE>f*6FN^m;CYJq#sj-nPx^zuMm$E8@h2{VSs5Vlb)Y2j zpt`*EJObQ?w7UODP1OL!&$%C~f(1t?dBvXl$X~csKxEPgGujPxD#RLh^G%2Pwju7e`QX z*kuB;%}?fw|2f65|Bu>e^Opv%Em51$c9Tx)B3q8Nb;jdE;xxZL0u4R@e=IF2iA8)r z=)$_#$!t^j?_vg7S@NGvkV}J1Z$Vb8->LkP-0hnqbW_ugA0|0ER_edEhJou4Se=I- zfK(MrTRaFa$nw+8U*kZ3`cM+Bmq?}bb zc9S9zxxe)U7Zhr0ei~#HPvqo*OOJp?TUMY>xv9i>83VqUrgBOTvSW*-mfdd?cmV)! z2&`6RnV9lKl`5YcmDarLcgi1tR1=q1`Q58}5BQO%Yty!!rTnTxbStKBJ^4KEn{_IP z!lS#5mYA&1Yv}np6x$QGTWjOrW4shx#T2&weAi%{3)BN%!biq_bORWyvZKrWi$fa$ z>_Ta%_>CK~L?`wK_~eHBjJ77c@TT(LCu1r5U6^_|-F*WC8Y;h`n2xSJK1Eyyx#}() zI(JbFP3yGU8%Vzz*uPZF2d$AKnm&38I}rP`j!H#qpZ&eK*T(0^_ev#$EVZkMP>v5? zD8VnYm9=Ts@nTN&!&IIOm0ff1uowZD4T{hn^^8?$_LI(b;xORlOvYh%7#C&8!CCz}lB zBqhFgzl@ucqsM`Mpx%*{PB`taO59E- z0^(=3_aiUutcOruMV7tjst(8-xx5R`2g4w*lCVrUnA}ueHN~7%JW~^kQq4xVdeP#h zWDQWtPoz<`B_9vmF%(ogF&*@2RPa-h?To5dm>TB~nO-zh0ZhVFcnHXOJ4d{C1HF`=r4@L*M2I zg2=a<#?$m%jpR&?UmNBR7egUHafX#71dsVGvOXapBiLshGX zNx*l~JjugsOD+@wsMh4u-4nPo!KmjBDE=P<)I<^s`X!m1M^4MSzigG6v#Gp(3trrrf4}fTPcAE6 zWnhc>I=D$nYouF~@^tCmuXblde&ayWIs#b$vrl?E^kn0{FSBU&0bf>*A)ZaEwY#G zYKn%IK6t)7#-wA^5cekBagh?l^|pl3y*YWGlkW!+47K34G7hZhioE(`8-B>k=o^f; zvi*pu1U8^|2>p~N6HqO|73AjFp*2cj=F&o5H%*%}s52zaEB*KW868Q3(2Vx^X$dsN z-C`O$uMrLBCCv(F6eZ&@Fv{Q)e`2~k+&Go7%~_q*3wg~=waitj3I%#%Tf7{MR_lC( zqA9p|XY8rr7*{kwr{;tJeuNi+eZVStc4odUwY0z==g}R*yDYP*IPY+1C(P&Xu}NY z^&GcG^`9AZDNHfLtIK7NCqvBU)7v1|l2n(IS5no`_UTHs7vu!6(E|iKAHFht$)A>+ za9M73)8iLuR2xVyv6%_(Z5S!PV0&UgPju0!iXFhwwSL5NZg)u0NmJ=UqvD?E;poyI zMC{^KY^2cRKav%hZHbyMJb>G{TJXk||v z9!?ku&^B%^wNS1Qpighewd*cQ(PBm*En9Omer8roH69Iop*maX#PPVSH8;P}=fLnO z+kBnB2=%DBdbXP#m!E`C7lnF*n$eMpd;N=n=Wc8cCV;H`wc1JcI~ANxw|JIGw4Y9_ z{AS4P5*_LaeoF=q^GBG1vhWmE>U9eG^3Kemb6`P~l-$=yN1w!l@`V6P!vXqL`@3!% zJ1gdi_CQvp8-|MU5F4Syv~ZQZhSl%LX#A}^j&BMfJb%REZcefj@)Xj-H22>lhP^Uw zax41WGRpei&|u(ZBSp6YCB zYB5q+<#o3jJ>6{GE@fPvL;XUEMSSM)FYOBJCsT1qtPzoP4kZiuW+XLoh?xUwzrQ1Hk!f=J zj1dlZVuJ zp&+-c{sPa`0*K34@}H#VFR8k7l%UlEuT@HMXC0za$dZ0m6){CUB`_6#lH;7wW59~Q zyPx~s9Q3OAZ8ZbQ0!5+Y15B~pKq?L*v7$Kjn38M@7N$*;^e?K36BUnvd}K3$w-Hgz z-Da!ykILN{`H$WAz%Xq%zY^)CP?SP`*Wf5U_PP_pDN?2>ri0o|D9iktXZnH1bQWKz zB}}e~!CJ>kH*3kT;!)QsCgxOwTcbDq1^dt2gpqk`d#*1Gu#B>STR96ZPIKJk?A$Qp zRwHTl0h5%*!{H6l1ZmW;es$He$JgXD@b2R`QFrWdlD%<>wY7fCFb&sR7_L#wW@{}) zHW{@^YJ^yG?!R|y(~wA|(!8t1yhg=qRc~>3%Xqw`PNx(~5S>lgW(4E8= zz#kbZ{8M`?9`&KKTQ2kse;`FsFII27+bMg>l4*9L>;iO`c#*2uKw(GNF-(SqD6fZB zYPvooUDbTY*Ppx8PutR0S%d~pWF8saxbf;!v$chA8{Klwb2xZs;9z;S2~p=KBnJiV zy`(qfo<`*UEn#NG(13a#rItt6A^qi}V4sdfLQZV-%xRognpK`zB%3StERL)f&~&2l zrQ2$P$>HKL7?jAop?ybbH=UU}rY zKl%JpK(K2vWS0FC%=uR2kOZf@hAKX!b89PUPsBDdR-gcy9|mH-tDN>3Ep%3Usa$9z z1#4Z39<>}^qtPDOHj+uofxe*Lfkb*A1T{4?)HvbwWBT+ybg68il2OLpttaU$8&8a0 zHeG|&@j)#4S|_=V4A(m6BTda2!xLPP_F8Ia9ZeoE_BNjmD`t+otDtKU#5St@+8CEJ ztGjseh5OOSb*w}DZQ*jY3xt&nt-+9qw?S{JVnt=&7tUK|7}8tpc|1yw9mqKo1mUBZ zTeitwuRi$c#U@nsHBvk?!Xq^R1W{4B+Ew%?ducEA${KEPNi)AGKTyh&pnFgvRIT-3 zN1w8}ELcMs*lY9-fnxe>)HM=J|G>F(r%pyONSBErd&sil9(SM(zqfy*L2G83%~Y_A zq1!rPMI}fzQ9Jq-W1+r$9{|@?!Ho(>PR+RZ(5|8?7>B;|jhV7b7Zg!IhM|_!T}6>= zXp|fXvA9=I*Dnaxmdx4Q^@UP0hzS}W^~|996_-Vi^=+wRoB%EKUB$?wtrt0upI}Pa z64FINI<1#UXRP(B_ol?}ZNTA}s`hG0U>zL}KQZI?YJOWco$=UHY%H!<&GovhUZq*& zcW3(9MhmEOSZ_*zm~dlp^QR_Snl987eyI8ce>Jxsps6`Ys8I`uTI4cs(PTsg-yVaD zQ0QkB?rJ~V&~oXIT7ua$h)U z_rj8lL>gya9Xs|OR;l=8Xs}SoPxc;D1~B6xtNRxnR1~<<_rL3o4+99QkbTk8dzH)Dwnd`nS2-O`oZis-z0-tTIC;#i+3vw7zGwcDEpd%TlW5_d5MQCOQF;cUbh*^zbgq08@NpLkz$s zwww)4O)c+OA>U{+)R{J#4YnN5qW`#3dJRe56dQUSS=*RMsJo-h&6%-<+Pmw#CDSOg zx4zCJ6+v54@mi4q^rwz{PpNYS!%KC^AXQY;sLS%cWR|onSWO4TU^? z`)aPqlffp_D(1!qp|1kJjA$es$;g|Ub9}MZ%tgIA^S2ygZJVB|S~nUEQVVXMi6bm@ z(PMpiJhi;DgmnSi(9=5qli_V^QjNSf%6rAGLXCmd?{3`~e+mz5pf|@x$N}R7Fnv1R zOloVpa%UvAq18$3op+(~Z_sGoDmv-t(G5c+|K~4Q(wK9QsVafS=G!sKC zSbiY3jw0Hb-29TEP<&(IP+ajk4y&kCD&#=5ekk7>XT3MCCYY6Oq6t}k(yYKyR|xz(3PhPv4SXE;h%VX4w?8uE z2HT~aCcYFF*sEO`!?LSfFYJza{=h)3sbQ4t`i?ZRsYK*6)%zx3 z^ofB1S#>>TZ+MO{|8s5dFP_ayNE?b-%KLMCAV_aWjpo}a&AiM^7`-mKo?{H$yKO1W z=6A+bU%Ky{e97t3l$!W}qr3LoyoUp(LYg9Sho`7sWu!$kS4ryjI{{@*7z4tE2sI;q z#<;kbzlYZvQNbbB*W`8+FI##mQmxQ_giF`ZxqAxQ3-dYllhusiGWQ;kHCk@D_h(s`yrWdB@Nyh3Aj|-aBm9bk+u273i7NLCi-_Zm@ za{~3~YVVtbk>13>yg^`4x}ZS(<0GM%o;`jOjYhKdK}!u_InnnKz1y3?#cemMtBjT0k_egm+L7esixAaXL|*)9}*K67aL=|=y4-Qd@yxVk7XvZ-kaD& z=;}%fx!gLJ$4SG)0ynRGX~Li$G{`&TG0~auiB)k+cygeM%~Dr}&CsKtsa%XN^u?Es zD3jEZGw(JxjZ9i%Z;G{3R}eLG`!%MTfxUY2mAKaetT8ZI`_tGTf-LgP z9{cSLXap#UFgW;@&WX;vgaH-J=25KoeaR>l3Ym^&kknj|*}?(GQ{-Eel^b@vgfH3Y zsS${nopEZ7In3+lp|`QCX*J6PxU5#%^d!En{?Qzv?)O&a2o@7_FQ_v0n-qIBKvUqR z{C@WBrClwvM_@O=ih0W=^!16QchUSxg4rH#pcwh8pZ9234RE3XI=SUW$WxaXGT|!D zs}?%AUu&-EtTLeqRT623K&C0?z!kCx1@pFLQ=d$!j$Ql4zI(Ho37Ol*pr4AF;3^8nL`+ox>J@nQayp;7d> zAaH9D(Rh+lp3+^!P8Xylv=s+9p6-vFQ&|4^9*y#(%pY4vp?gcyEZ&&5Y*KW9vJ!&? zLJyO9(duUqXP7*pILM;uh_~%+l@-HR&PV!y<5goIl6wO?ebsXQh)?nQ3#GTfiInv1 z%H)i}c9Upgu`vg54uqmpo#u;(c{RMr>E2%!52?J0cjZvm)$R})_Qc!bmI&STbySMH z%QM854ee5;8(Eo~x^zcY%&F|=t4emDdD{|A@+UFTs#SQib@_OfapjI<|M0nSeDHp~ z>*&1MEQBvxa2da~brME=$doXfU-83nLW!TPXx{&*F6wnhS}<`Bd-ZTi_*rdx=v4Yk ztXJur-u}YRhvXT$@A32OY1}ho1CGoon0n}f~+ zAg*Rz+D~qB_%DAW=w=cDvwU{(E}yEpCU8E@U_pu`{bF8Kh_cE{f^t)j$;cZtlM1~= z_Q5@y7B!*t2f=3uRbssRn3UfB#=1wu+|$nCAJ16 zZy4T9iTvJlm78D#4iz&~^0P_8xMw`N0~ydi{I?w(W<}1bmX9fyl7Qp9illaD>; z14bdtLxc#3k=gK5li7i8(_`t#3oKiU8;-Kw_f}Y%V3V1r75PfaMhylW08S>I-lSKK z1|rPLsi?$RIj_zr$6pIOldTY=xCB7K_G-Zu4gvsllnPzGoMpf^wCwVefxqYl0(h#_-sD2e4*&* zTR&BIoa%rbkP!ilYl*Qe#pU~#-lj_~b*wO$=lR=)K#-XZXs^@f0r%kPRKoaiJIV|o zyW3#fvp59KbN`N1>#eK?zQ{8{hi$XLy6R-&HYh-8WT8y+eoM%0^R9jCsHa7tnw46D;~V1nFI zA{>yIRMxTrxp1oR6i3*==a{YzfZ~`fkRnvMspwQqX(c$4?E4dl zjTf#D!elWGzVQFBH%O=A{-760cB4<$=F{%%opfW%nJ0iBKZX}7$C1Zs7?UU0phn6P z=8`kV0ikQiWbPYqh243fcmDQ$oSnO=z-!%$Yd^X|1iVZA;eND}YX|7yqJ9eRl`kJV zlc3;ANp_EIUGX+kt6od~DjK*PEO~1=0PCxFW0tn7kac=`>uE6S&y4rddduvE8Sv6~ zq*YDw__85&u|rE7{MesgHX%u&QwzxT*7Ni9rTbW>@7q zne$t#p09y_6u9>27^x<^A6Z8ZVPUb#_w7W9If?INWzYZwnX-?sAK98gs2U?fvm1}j zzY>9TMdv;}uzVTB5-x1)z^K(j`Cg6wHpt7|j7Z=a;~V}W4E1Byr*nq4Y{VB0s&oyv zt=%JtSr5&><-jyAjTowf(344$Y_Z!l(dB#ltC$XKGwE#9AiK4Q8wCBOf!W7jZ+J1n zDk44UKTNo`(*3Y$5&T$DWv&5{NG2e9{`TmJl!RQ$Xq;D?)~N2x#iC`<662eJFq zH9nXJ4V+`9X0jKE0b)JBV!xr@X_kgTXm% zi@gwb*1<)VQKY=F2e1f)*Ahkdp00Dltn1O9Gwp=*)y~A)1>lRuu7o=Uv;KK}%cJi|!*At}ft%OH#Fd7}uF9P4nEB`@rC z4S${t!m^kX*laW6nj5r%gsopC`tmE&G_eKp|rwcV$Whb zyZ5OG0@1C8Zu(LZWN+~3@)OJ;NG#VlMP=62m%4%yzDZuDyPW1Q4aMD@{$g%$YrFmq zGHUUH7KUW~zTU^)n`2&ojGJDTd02q&1>4LmfY?UFBpoZF9I{W^H zc*~Y^V{_9gY%7w;r`2BPzQ!V&;4_p`e1M0FiraF$eWOy$-O34#ylv6~?G@Rt)8c3? zrU6${4jgl8`^x0}1+Z%$^tXVlZXPd9;BgJoE7;aLzpd$bG+nQ8lueU z*@#Sj>yam3y&`9L1_SL6i~2Q$rix664hHr!i-$st{Hs4t%YRjs(kzvN@9J8_MtgU?71qTiVm6f>f)lzJ)tPZX zL02}u-}UqAH_gMjLuZR+?PErdMy|>_8UDr}@y&lcH28MO$lE@3T&J*s$q6x1 z6}>wKf2{g)wvde>NooU{0lMcv34dK|6Z|wpnO{FAvohsULc5yCGPK;MeYo(Jz8Xxb zLA0lqLOlsu~|XKAli5zdl7zCPj?ww<_29nN}<-QzSQylB(|sKaBB0Y z34|`WqLzv=`7+CWMTMh~iYBO;gQnNuvl9uZ;RK*RR_6u{0!LUb)}vXXW4*-D`l`vw zA3{fq@%&!mHy}QL+BcTYtxA3M2b*H|Q*hIR!$SC_b(oFoZ8zGZYs_7dN_K2TA!7HU z7#ZI+K))_BjI=DjNq>`Q<$^c6I()V(sSe`p=8sf&jGeWoWBIC*iq=m#zt-wW)>@rw zF?ysH6z{w9l8xSPUeQTOxwS2PbYBkCr}Q`s2DzJP~>Y4t`=0|hMtZQZ)rd}-Tafi7ag8G`z#k~DSJ^*;RLmm z455ioxz@}=&GIoBBgRZbHq1VtvC*(kNm7ut18GdQ@_ilVz3YF>kq-_nV=VW3gPgtd zr+d!nkwi9mZ7=4MEIRch*SCLT-+q$K(O2gkX7T^9esf%w{W7vegQBU&==3pJ z`W5`fV+g`jvZx}Ie3h1=d15p<5n$xeduY!Dtd~5;?B4I(bau+8OVfrNJRZm{=^JdT zxR+Re`X{9cTy>n)vl<>Gd4BRJ)vng8ugZk00n(lGZClSSk@Qu!F2!5ESE_I;O8v2W z+2ez~A7B;Rf0F&k`z{#R;c+%)G$e}j^;1W)hbT>tlV8UHB_p;FdPIDvJ7?LL%A1)b zLj))F0+1(sm}p?yK7KLSD@-GEB{j*2tK($lsnf+ig<0@wLL$?yY9LI95qK=>XlIQ^ z``kG#r*XCrrG|QdmGb)V2!b_MopF#8S_F8*eK(b*xsrAqf?|2C&uFVcUR+H~YrLvI zC7j~me}Ph!^OB&PjTw(9^S~}i-;L(q-dG?3P_YX-3Y_uB z;7d=w4)KEG*A4d#YakNvd8L7TaV7qn(Ai)u5-f#RIT$|D@7sx`FAVtP;;_d8v#v=%1RXUIyZR z$}PCKZG5k#Iri5p+-~IulDj$T^r73nYdt+#3&d8lihhZxd$N%9X>55noW+xG5kCGG z9bWT#Zt*9qwR^jjZO3LXh>Kqg z!5#7_1585~LNBtCo>j%VUn91swMfb>g z?sW?Ig*^Y}y6scf@59Z~TYcxZj%9=Ne!uc&_XEEu*i^uk738^CS*4X{Xj?L-Q{<)kb{V0d}`NsO#_<^86Js$;}lwb>7RV@ z2Hxmx(P`ntu5&ZFs=JvSQ$)Rx7Kc9v2(w6)a+S{&!GFdmSCT`ui&yGJK5>yDcd{|5 zIgM^RG}&?(heveif07b9cdX&twa_8rb3ki3!o&VWZ+7|3GkIIgs)quJK`8G#IQEZK z9~)&l7C*VPE%UeJ)lK50F@kcL-a}ef|8f6e(EMm!-xc*;hjvP zGHS1qQszx+(l=-5G-IQ-_j^YXrW64%AOC%|eH^VF9=9=*q|bW+S&o`VFlkGh(W9V% z@AMtx$3t`4mXQ>R$(8;Q>AG37Q!tRv><8f=d`-OrgvCUyT?3^O`X(nSTeoUgci#ox zSBfnp&{>#&Y$)G{NP7s@Fm8N?%>OlQzKDwMfB(yB9r{|9ZaC2XYDnN2yk%KSTa~;> z&V7n}TjJg95Q_5AMfa)l@lU9#2Fu?Mk^Jz`SMZjEn*w4XmlM){9cU=a$#_i`S%T1F z-`D$sp|<9FqK4A7|8!h{5^|?>aSP3HW$&%0sdI|n9pmG0r@g-Gqe?#=0wv}4WobNGYeg> zFfzCKZy?b;#FCD(rQ+ViAd8gcKYxC%JV?M9umTtbPeT1qdqCtEAi1bnsAeAgcQC;( zVjd8iUoB(~`FB$SP&hCTHa-XLTF)jM|EH6_Br$IQThA=XJHP)vs?-7%(A8TG{X4$T z^V1gv+<6BvsRIA$64>Vqpn}AY>?Z%ydp$TKF%YBeEH0Dvp8?T>qr(9e4AQ@@83L31 zZ}Y03xd(XiD8~N#C@~yVu$dUCVe;Ru&OTFjyivsbcN0DLeozE31=tVv(6RofEF`}J z(5rrwVtBUyKH3B{9j1-OhKYFpGoSxI7&d<8m64}^he$QBJs3qz#&B}mFr2S&z0~}` zr0kzTZ6|`;Ab_7D8!Q@iA29Do)MR`%-Gb?>6oq=lTZzRsTqGxG%P)3;|GH)N--UC+ zwH|*l`8Uk)C3@wN;SV?@I{U#o6DT7m?HVGJdjY62NI+Sj?nIX+EWn=UdXuE>TP)0&w!9Mqg9J;-2PnQ*K51Wk5iwrmW{C{rc z`X0_U!!xgseg1gJ8**P}4=sD&(^Hwx$2#glgE+oZSEG$XXP(Sa&!N{KAtewJCy&5@ z2nckZQ@zb!H&p!TdU1WcY3~Q|*VzvwZGjokC8ecFDyH{cdCw@fym$$NyCCcVY8(@w zRqh|l2^<@ftISf*Z;|qu=H=+}-)G7t2owiUB^2!BmW^A5jcnIkKys2*(@QZC8e=^a zJLb_D>?y9?8xP07M#)q5MQ;A%%@htU&}t%k&im*?<5o&cx);|1pbRo8pRv-O7m|MuQ{OY9Lu zY;9wdh}bboYj4`BtrWG@7Gl(>mDokm8nvs$Y^hdNRTZtRR;|+S@&0^%zdyc@$JbvG zM{>@6&VAq4>l)9i>UHvlcO5uy%&l$yh5(}o;8zu)xo<-;tRcX-DttIVaY;rB05B{q z-^ZtdM2D9#lFU>zK*mWa4-&o_C#rU*zLC(-%KbCaMgpwVbOFO+eIo|jW0 z$09N+YUpF`ScV?==^pDKL8wxF{n`Lr#qGy)3K6P1NAf#)00ja5=PnCLGx#kK=Z!f5 zZp&i~mZ9iDflc)*lA$I)_2Nv;w2S*dD9(U_bW+NOcAYcM1&P3oKar&2(S#H0#jL9( zk9EOr;DH|JVn8*)>xG@8FpRwdH;KizKx{?hvTxB%np$&`7L8F97iYs0+P+&hP_1_l+!o1Yn1enR1-V{NYpq*9wQ0y)DTFYIu8_ z6*pqvHpeK z?~d34Tf%t!-^#;L;E6achofc^j?W<3XIp@g?UOh$$+ufr>BoC(fdc)vOaKrI^%5Q3 zLx7>o>*h-Gbj*P}wA=ow@Gss{+Z!GTZ0XP{zI>ltBkcVkjr_rStjKUD`fe9V#&1IynS!-Zk1U{*TcwaMPRI#Y-cEkzYAZ(uHs~k-~K!NU;>0y z?klQ#Eh&jf z+FJjrv{IG$GoS)Kb(qh5HM2-NB7Imm921~?KUVr!yq|o%#>Eb;{a!BzeqI4dY4=TH zfegnmix4rbYunATrH`pz;FqoRE^sQ@ePxKkGq)AiV>h0n1pt~b2fomWzM4_X zHSaVo_ZY`9M4o6?{4KQLQ-O{?s3RTiR@-9a@>3W>+2~-iv3LLQX(}TPhMMW};&{>N z&TnytWuLa}M-h>iryd%@)_EmuUOX&fRb(gI>y1bWYtAq4W zLWeZe)cwET636#PLc69YSZdxZMG>>i0hnyN*_jkG?#|4-I%89#W8ebLmoig<_Gr;W zPS=G)z;K@jwH-VLbt--C(1 z@sC^XYXs7?$AC35-AfDZ?>9ifs!d3rPz77r*!(kOZeY?|H6?yg4gGyj;=Qb;GzfW zfXaC^U&e5}m$?Ten*S}gS(Qrmbf}&&pMIb}S<3*I5otZ@plcmWTL)Er4S3|6Z=NNQ zTwSibzjW$MPQrbbK1NM=n9M^-XXY{xGYqUoNui*&d9yG_RzKouuC(=Dq)FnrrScSS zuIFUHY}7Vlm$beuByu|cn-F-5>RcA!9`cONb04R!QSZ~Me#0d>%q0eTP`$}h2bP?n z{7NFsJsn_C;Yt>RdU1=|ASi3JmA(N7%dE6`PtLhmY3w#~PC!XSP}iDD=szB@z|m%X z&;*HOT7%GHE?fr2MIl-!PqK9_y3ZcIb8OTnjjg#D#re1I_g^Jz9Y00?bj}}`WkEI) z-QBBhEWQftyRVb}w-LImTn+=zeD=xmIDO>(Y)}p3H1bcWf6lX`)Ag#775bT(24pG@ zZn(_b=&x@q+`%xruoA^k+@LRR0|y$YVr?YNkL zgZswaq}8M1H0cz6zZ=@4ON;&rwv`KTz3 z7H!V_C=2~jNly3eqx#9k3MYEy^j> z>t*w3KlKK`wu`%H&0$zkm1+H2%_#pb6R@TkCD)pLMxQAP?C3`H5xrLf0?PpKq0(z5 zFt4cjHb8fziY6unuu%*${!v>vxc~P=KDFP37n#D@^*yj_?F82uy@p0fGF&|0r5!FV z#S2HPCHS=2R8x7noyMlQyE>zmH}j31EsIcsenho}6{_hIcE+uuJ%nw7zykz}pdQRFi^W}wNOW?+ zz1hkarqALNHe;n;FAljYu`f*_gVEhhtnrhHKBQ^l$T<7rHB%+$oC}YNx`*6rG86pK zQf?z?yY>qK;_TBB-$EKKZUQu%CU1&keP^ip4-g}!rpMthMm}K=s);T+KHnB`92_X1 zVl{u#iI#ZS&X0W(y84R6W+9Z2g6Z$K3`;)HL7Hq-%$$a(p(D$PZs7IrC#(Juj^5`K z6{?9kT#%4Q*FK79B1V1`r82C7tKLPBeRU5FQmG7l>a<=V=yUVI zi@m_!781y(cuWHK5jSsmK69`Yuld<`c@K zCf;3>cEuo;I~RWDL#gwThSBDbF`k4k7opdc+uB^?He2O`0}76GszNsBt4so zwbv)i_-C!~tuaZ)y-vY#gyO-wM`h{{2lem&5}6qNKo@tewFNH8R(n&qV=0O;t#&h*Qr3XITuUl7QQBRnGmNpNy8I zc;Q@(72pfHzA)aNxy{ot=k-5I4#b=v)@q#q2ZXakV$K~fZ`S{~)}UmcV){lYOQL@Q z8Ff@eZrN1zcuZmO|4Mfj;<@a{#-FR-{lW%mnLG!xleMLKa@cV1i3LqjH63op&6bbV z`UlVXZLLqvSop8= zF?1EmRxb!mP9G@4V@v-NkWu)9dxbO6%ks|tPO@uQ#G z`iz;@^5qufW&cp1d!Pyv>LHNZ*r<7UKygF;@%aI3+uPEQW4WrO6ldBo8<~dcPv%Gb zZsv{Y@D;cA5@ieP9tsc)oa+|xNcn+6RMul*Bo zsirkuHUJ@+4t0N8F6pEJ;18kFrYi^z5sBmt$w3CLH@F)>-d0S=51>%>!IMV4rE{(6 z0o5a?;6wPDene350)9pnGA^_^{!I0+-U>n6WWD%8zyb9{B1>aQ+9fp!OZ(v@T4&J> zb}BEq$m|fGY{PRD9a@YR>)kHx*)8Ma`z}`AFNlb!tu24)D6(43SlAV)yhdxZ zPg?wT5OVJ_!qRl$3n?PvlYLA|lSVf<=#Q=6V?dzw*@@&tuQvZe_YkzEsxwIR;Aaba zQQooYBRNXfQ8JQFBVI!5ZZMnC9${wii5GrGkKGi<9w_u(JaZZ=q~XVO;56gWHt&?i zzN^-Zjp&Xv6k;|T!L?{PgzKi7m2>S$NZ?{rXyDdwM*UVhyT0lBxpmkk2I zEP#g$2l{j$fij_CwB$@e&X%?NVIF^-2&VzDNgRI|EXxfnx_hM> zhgtef8cN*|>C$}N*78uSP_)C~C=pgn*~Lkh2aj{R1BdBfQ14~stSvvetu8(B_b z0VSmX(qKi_FO7k|Q%*_fTBJ(ppoA!^|?I^6e0`==pdRYv2zRU@gJnOYQV&H zT*?p2#}qbVCkCSUuQkstu>_~fHwyt|nT>hD(C1@Mn$2~`r)bF&lbInuN{L;;J}-Yf zy#6U@L2=@8UXU`Y)P8u}A}B@_5Xf>DzYgXsZ&|Ud^S7x1$u70E?ffzgW(D90#QnGn zw84-sDwe#^4@+VcCEgX@!auJ?3<%I7y!KQ()+Y<0tO?rU!_Wi7z^A49kNdle!biya zeas%ePqqoQmYG^HODW}a3e$3N{YP3T$!bb~l{4wY6lvvcg!bVUCKZ6xK~iR*jV+Mk zdtG4ZTAAsy@@oS=$^}Mw{Umj@LL~``K!*kL%=I=-<&BnZSaE;FVS>o(>kTKF=u%Fi zF+V#Q73SAdipU58@;x#5+Fy@+VonoXXzYzAn>TX251qHHs*&lNTil{Q_U&wj47R17 zeH)oHz>i!Kgf_9`0*iQT`;>VSbP`PI7Nbd+GEkR&v$j`8%c?sg9YjuF`jYG3?=>=Q z61wb8E_cMnfGSYoTUQGt^F;YU?A>XSBuW()3Qj^ zZ9Y_MKl3M&lZa6mns6^;C!5GE?bk!)>JDvyKb$))=2v?CmK}sgTZ3On!#(l``NE>X zYZ!wO0nG%bD2T%fx%l0J%CkSiJlb{;Rh(YO2M00$>y(t&JU6F_U-RAQWI%g32Pd8}IDLS3 za1V!nJ39Fz*U(&O-K5_2)tayQL=UG!8;qwJ567yQwK1UG<#* zypobrhj>vqdv+OS_{CK8=xBc!5)K!cXd28Bi>nc~sR~p@KH9#m;lfZ^+@(=AY@*7(9NZXGu=wGN6XtxE5ZFzxBmE$w7ZkvQ*wt z)#9ngm!sN)h|>lC2b#7jQ{No@x(S;Teu^}-6*0=05wAAuH1vXS&d?A2qBk{gU2!>W zW*^s$z=_h>TPbs}-pKlhMhmtrN_^%;#@QHjj8+~3pb{!TdIX2Nv~a3(Q<)tb=*v)< za|+;F4$1%C@e1s1-awh#VIV{0J) z;v#aHiakU@f*Lq2*J7Agm4SY>nZ#Ow=)h-*3fECv#+O;6+{VH6@|%7s(ja)2zk zN&hxTb2n&oTX3`|h%4l-Uo^oGw}n_qrA6HH1!`DAJYQp*>0xwF(USWE4sFh>?xt9K z4tl1{^_o1)PGOX)7nLGZTqnpdfomNS0iJAb?r?A_Yc#uUpbN`H6T6;m#{+p=jfNh- zCAz_7Mn6)eduIr6 zhPG4LWz+3Z|yuA?BCD z=aV=@05@W3G-*}1fw(TyD^!osfIvbG4Wl;d&41bLSgBPF*JtN6r! zvpQk2++;b2Og8+l_t3WthtTP}hew=e%R`CWL_T&j!R}O=McsU&NbwO(6D`UVbBHch z)VKett*5T!92JM~Ol$z8iNwSMYWFdE;mCHVW<%Jumn*zXf-!C(_!s%GJ=Qk+)LR#>8=$*X{p#EFr3>4T(Jw(wJ1;z{ zj}Q?FLLR4NBzL`5+^haKPOPIDxFW~~@JF@c?ItbfG9mvPw*;7YqiM7Tx%Xx~M(`~> z^RB`UX;UTlB~rFpoK8%4ZO&fJ{!+O6--VRe94I`xPcNxZy88A7VYCiLpK>z_540rl zb5lstx)QyH=&4r?BHiHAS>K#K!~#pDkKMA8r!04?0^*x^LW!>$uQ}>`b=wtHVUVx| z6PQg8^45u&{?|+ZT9cUITkhKk?J>t;Qe2?Bl_|)=J@L>5JRNIE{Jcr)HR-6Xij0ux z$@s3W4~!wCQU(B_^XrUBN|@^nKP!2vnV2EZ6E?@?tJO>}u>fAm`V^I?CIrnGh^H4;BtvbxyP zXX4#w(JC3I73PYUx^-Z4b}wW#P{zF3ti&yMY_$H$I)B?RE4?GN5`~!s@K`|SxQF~g z1tEprgTnGXW};~|wWvrM%933z=Rj*5d`2R^J!Ai5vNOcBYgsGW>;Yi< zVYM1F8ox!`6*|fT{}YRnkGOBtB#>rfyTca>Zg)tMuJ>uJH+iZC?xmF7FL%$-%W>?F z<`8BvKK0el(~5OJj=?YLM>y67f<3$HR{S64;*|4yZsF?1n`K{Uy|^S)&KkURP10H@ zQdcGUyKccdS#Lq}tKYrKBC3Dj7G|pYom8^dI-*iVMA^SxL|^m0zP@A(bqof^d2WO+ zxDfjR)(a~3eo1?yp4Aw?m4!n{4pwKpK?%uSJN|Vb845NP#gT=Y5r6&{+54c4x3=5= zeH#F;bK#|={;(y0SF~2+|T<44ij(%KH!amaCpbHs)oDcQqmuB zaO*kZ(eSEa7fZ|G<*6yoY5t$uB}>gyR=5S2~r zNeRxjf2YL3qVMGjtsnBYk&qB;2lScSoTM3mw`!ZOX;It1|I7vY5zv2I&xl_{`LfLc z@KfHFRI&jeWe`&>Fn#-HygW?KR<+ppq^996+GCZ<{qnzj1s!KPm+8w7>lT(d2b}(@ z&%i|8NXA0utK3>tgu>9^dy0Z>1DAE6$wevshVcD_SQtfG{Qe6XF@9qq_Kgi~(aY6ECpoB&F{U(a^_au@Z5EoE2AOe^WQ(X*UGq->FIk#@(Ok-5Lfoe@ zHwJwY0M`5JL;31!?wEs9TY!%~yT#dlE#GM2Xv|wP#~Rw0Vo@s@y*{;T%7d^~F~A@r zM5v(oS&O@E*Txd;S#nFq0!T?)p{uUMx94k^7i6=DZ{DKuIafx6Oiq)E{#_Xh?_HFz zQVa9*UA3nt``Q;}Ml5&y_4ee&vVU;e&5-oGdXV0Ho@1Pa3LKy$}YPh zqX?8r0WzPZ?>3C6BLqNb4&44Eu@jSbfUvNT?VHX>4bS2uGJz^|2_Pwfd7(*qN4G_n zW9#Ehpfs#0j4AWTNN^m{p081-(qJBxLt2@8FaRkj!ve`(EGndj7 zIj4vOdK^S+7cIsELup)TGQf%()1}<1xtQ^Ajy{)pzH;YnA;#k=tZSG?J)~cFrAd^;8$Q5{ z>kpTykC%t$N5nT`-jdl#SRpqH^DalXriEuXRC-sf-n{#z;G3Icldz=AJ2`pxskL`f zA}|uR17991ZM6Jhv5mU`cD7*k$-rO)6)Sw z<~sqMqe3RxTdwV2$a!5E$C~(ly}zY>?Hqo+R#MOld{hf0Spdd+r-*0s$=Ov4y5BpK zUg0RBtR}Ke9siG{yPp7JcVYEP=>XD;SEcVy!O@-#Ra+hk>#IWSxRgvvpX&>TJhu#T zIcqVr816axb zAhVUVkeoRizA5~|Kl{`D`7eJKFCBlc`V&7NbZr^rUIO~bx4m6Sl#-WOwQ``QlvY=m+NFwvx`0msX^W%fo5xv?`$v~a8IQ!|Mg!i!w_1c~dxW;| zw~!j-mmy^5x@smb^N13+oN&a(O*L55TXGK(D@9Q95VD;q_YfN56Gpkg+ z2BJ@?SCC6oi3g|XcQQeQ7ab@el#yJ0@?2B~`22zXHBm}BD(cCz_mYy782>;gm=1*= zXQdNSk`vU6NjhWZNz=>|sIHn1JwElRSl_hxR*!wIoIa5OJ+aL{H|Dym9NCsI!eOK} zx3CN*iNEV!DzJe8bw=b)G{DBQYk)@jexjrx#8l|RWqSY zGno8wEOKssw83F+q=zwbL{iW#X-hHZTX_axdC2%f7&)>7qg@Kwqyxb6lx8HNq{rvQ z!vU`PPD2u^+Nwcl+Ls?5h9qY4-E)jeHpId6%djG;w_S4_tvewvNOYsnYVwHXF>>p( zxP@8K!m>aut047;zT*RJcwM65Zek8VvoqXktuQ23l1^yl09CZV`1i%=xjvY#uDncf zr5ot5fu{uScAQm!;Lv(zx&ZJz%4Cm&7xW#32mTlG8T zQ9pONXiu)Vi}yygV}s~| za(JuOAEWEKF(35TDCJjURUT0dCnvPxcBkmPKIa3rqd8TgN*?<5q_Ysi&UI)qcmXw3j`*pH129`J9dF z8s2-b&&FzNvI|S9KCrHdLXgZ*@>PA`Q8{HDxJSZLw|PWU^g*KPGKHB!9T2X9?S>RksF1KT$7Et{LSXF|*ikr$**F)2N%dl&N3}|6yQ*VAP z=Ub+&L2v}|rG?(^PHDj2SC5;5P1_V14ZWK7JqD-8XO0K!g6cj061UK=vA=J86#Qqd zM6&aRMJ!kzCck*(r5yPdPP)i4ipiDW!~W5}nh&QNKD-_>%$oLpW&wIFF9iF!w3mTi zoJJDJGGK6{kIO;aW50zl1sjlMS;BH|<+AOg)D#gNv76pZ>kLdI^Ga?Uac1;I*0^C| z{;JTPRg~9|UM}3}IKCp#Q(!yKvUpi#t>W)9iDqF=J9l~v=zOVNo(xqRD{LCKwPj+< z{DJn9i9`@(y>&25j{djI@RSS{-A_CpSrieu5J-AtJ6JdsMmwu>PZH*edKJ7Ut>z5)uJPCU17T4h5)exKINgB{3Q)UN%}Igv>}GVs4K-n&|k z3oh?WH-Rh)-JO4JcZQXT;-GXy$BP9qVx(Ln%(GMBE4>m-i}cYlH)X|%Nyw-Sqk*_o zVCz}<%vMORI_1byBH-OuR9%la3#9Kv6ufScoX=Iu%f5QIp|4U!tl;AY>#9ZS)$deH zYaC5yfya94SFb^uASuVAB!4MH)PH{rq_vLdJQwEw??4a}yXy0@8y~KDxb+YLKl-}H KIt|*6G5-f@_XUjr diff --git a/lib/DFRobot_BMM350/resources/images/cal_pic1.jpg b/lib/DFRobot_BMM350/resources/images/cal_pic1.jpg deleted file mode 100644 index c47206f5e777ebd49486f171031962450ce1f521..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 33222 zcmeFYS6EZuw>BCD1f};5(v>Pm5kXKC5D*cN8XzhnC5F&zAS%+EfPjLKAH9RrP(mVI zKtyUJl#o!QlK?_!;qc$*Jo}typPT*deer!4du7e5HP>8oWR5xJJKizI+3&M?0GqLa zkpbYsg$saZ=Rd&NG~hmf=HkVF-RBqW`Ax?_M@LIbcZHt*5(Co}CML!!jEu}I9Bj-i z>@19oY&>l2oLt=8+)S*zd^}uy99-O7{~F{1&G|dDbeHMqE^{$6GIRYeUuWL{>oV#@a}ahgA;7x(5;d7F~QAfZ>=!EG@@lDzrC=iTKiJiL7T0#ed4 z*RIQ|s;O(-(!72Dfxdy^LnC9$r&iWBws!W;FI`@_y19G!`uPV01_g&iypN2Ej){#+ zP5YRhk@@L!R(?TYQE^FWS$SQ3Lt_)NxuvzUtGlPS?|c8i=-BwgB=+|djzC;kTw4CK zvbsjz+1>lQe?U1r`j=c605t!%SpP2Be~^p)T&|0>v^2Ez|B~y%#lZ7M!%j;lrhJLx zo;m$<-pqRh?! z_eCns05JPA06A{8wCI^8f^uKx43L*>bp}8yz$rbV|Nmb3T`fP(0G<50r%WL=r)2OM zp!eDt;Jpg`i0?1xn20?CB-ohh^DurHJ`qbh1N`bMKLg--FefjP|HIgRN$yJIVF`08^{qp3qBthV%7P|bTWn$1KF%aNWzEi zgsK18QfR+&goqB84k}j?1Uhy3!pp%SRTET1nE~ij_PXliN8p2`%47Z32hL*ZDsOxY zZI=AdaFQytDy#0}g$S{t+3B zvfleu>$JMh4mXf*0a*sJl|GNzKeyn>Hk%PLT@b;(8$r{ZPu$Roq?WPYzky(p@N9p& zy?jA%UZ|up-@IL*d^IUTq*D)VbCdtNfy!3e@o2zqKo2ivh&f} zZv#9X+Trt#HBTGCen{z6MNb3?a-hC}0Hv&}+WbW8knzc{;jf3IsXSw&gH(3L8s@dY zv~Re|6xAY^ChO1nJR6LCZ48m5PD7~z3FdF%Lx_gtL_hd@QQBg1O;qkd7gfF``fhxW zhW+u(TB_ssx=+QqQ+a)v61`7#ar{l`udMo?lu^l!{&j~f#=2kpw&60aN&%0R^4rb; z-=1P*YEG2*O}Te-i;nHq)N!IQC%&%pE*Od_;nV`6e$air!ud(MSXzH`+q=Q<*QHQC zTXcz?Ew;1ogaC6X< zkr3DjX>39t=yS|z1>0YfWO4DgL|<)wHt zKl0^1Tsm}?dlwx|9t4svHIhPhyXP)bzlkVkEr-e8(ds_n)MjJW+`8{LUC7=iA8CNU z_L-Y6%6f+GRmo;@a8b~oZ&@0#ClbX$o}&C~*PTmNZA2tQNon?d%IT15#k~xqnXHD} zH%Psv-n`I^S5@;g{gaNz9;Qm@2hFCo3Q2yzhW*)MX3u?ekg7N}MZ_ zLMAmHKNQ&s_}D`mI4bXb{Y5~2>4m3WfN$K(N70)V#CTnnHMCqbL3jE@s)&LH(GM$N zVt9`Y+$T4tC4T`Mn-dpY-7^2=s_=h$R=(}__#_r8#d`*L>oZMGb*d~Wxfv>rorRAo zAZ$iJx7HAi6WBLP5YqOGXEK6ZeGd`*~J40qF0BL2Ce z^X$iM&^X3D4E_z7D>kYfIv=k<-_4WDiy}WxXGyPaJk2fQE?*9X-`UJ_Th<#{4EAgT zc{#tkt||GYRgQWYxohND^=lMTTD5lqftt+PZBTddD>Vod>#+$X*_Le9)vnbO4nUI7 z*<_l>&F#Oos{HXt2Z^4G4#65vPIHwxRUiG}m;7+C`Ib!bby8s8HV+uXhH*U}Qt4NP zM;{GGs+qpnAG9RvPb?C|ZyctY%4clsqGY>^53~lG9);cmr!J)>G&E7IEkgDwqRShV z{qcWnlGx)Zm|@p2yG(Y4V+& zin(}SsL%DfcBFRqOo0s4kpx~)iq%mJitcfyvaR3Y?ZmMlOIK(tv+dkHtG5(fmA8|A z10&gQhz1ui@u_S+qe+pTZLK(|0^^b04ZC-7_D8VoP+;qUQ-vw3V}1)FRz#_lB>JxL zj!$3LQDz*pD&2b8aP)T6bbfshfN!W zZ6Y3xfbLK<_7T_`m=Wm++v`NzM9N5BXjl1TK2ihuJB&1AkD_ZVD8^_tr=X zP(Ai8Xjdr~)1aG-^8M#Th%B8(h)=#u;q4K*Jt|QuZvS=2@(cHAZcxhYjanFgg9Q*7o3;r#6xk?u7fmTN~Hqt0(V7j_{E&f=GU zWO5kr4}5)auU^IF>&+@SnDGoC1QuoW+l~&uEO3&m{HsQ-c?s)(zo__&LUG*n7cEn? z8w|nxHw7?1%at4Bs~W~zoDRTSZ72EEZ9U7!+Jj)30~|hVWY3iQ58`6DLUN+WMS+c0 z6E}gJ#?!gS-8;b%4x1DK`&O(_v2!=ZVzKrq6y*)Wa^(cc=qL5_)k@Z(!y>KhyP4((gVM>Xqq zNN#?yQ0*s=vY&g0ihhV-&=@E%j2>7V#yT|8-TD=b?-$SelqhG8=z zDhUB865qTjmS=!Tq|mSZyG#VW(4ePuX(sf5RiTLBto z^8Au%jlruna94N|T7d-ba@6P&NXW!+Qf0ts4XhuSb<^?TwBD+_S1-}MSB`1SCSLtMk-%?H#I`R$t@@I`cft)tw_515SI(j*SiHO@Tx% zUJ-6oJK3eWr7$Rb*r*X()DmGip(Ou2<67R$a;ZXDhbaHM3`?V%y?Rdr;| zZO83j$O2?KbsfJ0ZEVy@$wx!UC7Z4lF!@mw9I~KGGi^(0>k<$MN*a4K>feN_pV+X! z$Ej+g1mP@m8LPIWjR|S&`t5`_|w?5jxjopt)y;b-i zi}CHE{^F0^*AL#So-UFygnC;J)-*#rVI-Gk_#|cgn2>0r$u;>23|E zCG8nHFUaAeZ-RzJ<8%oZj}7;;IO6xMbzQ_)fYG}G_dNrjbFpH-TpDiqEg4&h_tCA(fWO4R7Ftlnt)fUXE{tB8N$M z$BYAKkI7vmaq|p7|Lf>y9H|YC6YS0vn8el#tg*MF&qa6GtL%VIn~Pm$UGO6I8!=UvmeM)Bp1*489*Of8NozW&<<4`u2cpDDDQ zW_)=?GEwqczeFzA?YtMr%Dxv;e65=HFzAsE5G*RIrK zJ;yp)KnX6>_m*9^hsGA5+QuF|Qz<&li&AE+BlR=Y*QwJmaV*H_pH`^>XX!i9n&T+i zESt_6PLC(<`vSXQaZ^36X1L=skqVGZcCq`sY4^^qjjNWclhljL`4E;x^MyGDr-{0GlGRyrH zIlc73Mt=02px2dep0{)~$NhEVbQ}EOOuUZc4Wd`vs6xr0iOdJ6)PY^|EO18LoM=P0 zwe5?0v`KT81)44v0b7@>7Uwf@HclBnn3-yglACZ>!}V}r*j69f+(`pWI1QYqOHTB! z2(#%%>yQ!xQXJfMxYC9v8iPFFK9~2JHIXop_u=Gcybg)>W-3*75T{OP;D+O1&q>pE zUrGBZ#AzraXlsnQ3Jc(%0a!X@8^WE+1&w0r`R01VgIGC zwt*14SVM(dS~It-Z<&K0*oXg`lO#b1D08&2Z)SMA~B6}d)|7oywH9jsLbYyXA7MPC?Az?QK z7lt`tDkMxiCjnB`Mky0(9i4}>J%m(l3h?Bbb=Q?^z-TI4sWOozd#o4W;8)unZpM)O zugLYHxXFXvff%0G+Vl%%boLbMW1A64tl#Gi|C&v9N$-cTs=PGcx~|*)#3|N{Y|4_gpSoz~s4J*OQ62WmN86EP;zS83T^3bV2KS@wB(!+YU{}i8 zfeEoj&_l(2ziC9DJ!{#p8C-L%p#{sBr@W;q8;aWsGdtGmx($Da1H~QK{~eBY zAyxI3*4pESAOgeQ-cs8i&8FV7q*hc);X|$^a0G1M@-gZPsG;cCKqdE}C5{ONif(0r zNMd!()HE;vTeb(`-ihwUCuhxJ2z|e*A)eaI3m9g~ahJVk?ek)fWNj7PEa;nas^FUx z)vsoZDj&#s-&6R5`j61{_C13?@$X&E07$OAOr`VViC^io;aYy&B`$M)!2fFVJ_GQg z1#Dq2DBv23mPK>c&uJ^Iho`@v7`hB=# z)eaXv15{y6M3uqtdYSml9)W}S22-1d@!bJbZIK(lHn$eDH?VBNDuVnF&m2oX{Rx+@ zf6}1ey{6=V)))qzt8?p4y5z|+)(9zbbWElE9vIF%%fHKwkC7G{N*9XymoI}Rsc_l2{KAiiBk z@OM<6HG8L`%AryqW!-U9427+Plw|+R;DjiANpbjIRG6gcmzanO%!GFZI?4V*O8|!oDEA3NB{8~nf5uLv2%n|KRrOJIX+yjk$|#<- zIq%DyeL@el8~PQ8QZPl~14otnB5D~*G$)D_ux}Z~_@HY)K!mwA>E4}*PByFtZ*lMC zf<&)4G5zQ7e)N35i?JFp>bcdt7kFZYAQZPMD1hZIH%cj%<0DMN<^EKiFT-W54sB4h z)j6b>{_2qtpfF!y5+A0wd|mVhUOHnxZhzqwUuA;epQ&$ui73}DcZ%ASJ8 zeTqAwLYE;Z-gMGG2V|5>sDV9(m|V^Bg0S@|_DjK3(>w!v_nsIX`@~HQwN_WmHc;JX z!-lulL&do)-W4|))udU&qi4s;mhl(Sf*x=tKPb1oM;gw-sGL$_jlHVw`GbeCq9jWV zGSKW*Nps-?t6m5;R&q4?PGbEN>zr9VSEzY?BR zZ!rH}Mt{lA*IADTx#%lBY;HUQ6pHoxN+Yb#_2fK=RCIG09*?LSj?s}kc}T{_%Ksf? zzPfhX^PQj3ZzH*mQg>wP?DgCmTzsGElm?E!+Ri_FWyXENNQorF&9Nu<7L+Iks-||@ zf@Kuv`=bq^tJ{#t&~bCMnFAGI=bCPy0K=p-t}SUjy3Q#Q)Q(Pd`yM|GZ`3&$esKIxc!g7RxM z!O$gf^C+p~>p_^#BWTApX@uT*UnEScl;Z021~d$CgKGb?i^EL){{CI!wM6B!R2~1C z%F-(7)54a%+o52ZX+RXFq zdc7;)jGI4?l4|MR$L)I=xshTv`={7bCWC#KK9tj(w8P);<+$$qlSE@(Q4wa7o_}kE z9p-S;_W~vFc9nT}h&%Rjz$Wb8$|2q566axEGb_b~hhJLTPqv8op&hBC%RP3A)4{+j zywrJ|j*zT)S`^N`2I5DvdxZ0jddfSuWf4bLfF5ns9@tk0!<+UqTy*a(V)m7vJY)*; zjP9D=x2L=<59;a;$#U0aJz*zIIrHis^CU5)pAm~nUO&B>cDVgCBBmzT^ZLYojnS~V@ySH{=xS+1ld_gCm*_8gOC zPm9nz>$Q_o5rv7K ziAw5A^$!MOaq?YCfJK+^L-~oVJ?o#QgE`v))W1@PMpWSxgzVDd>Pz$=9?V`k<-j!~ zd{~rG4f;Nphb)p^>0mcATuMP$Pv(Pp1FfRgR+kciK4mQ2Z=PKM?8#Jl+lbabZmfU- zDD@=jwsmbCh8*5l*j~HA+D2IMrueka*qsJLXBD<5 zV%ON%MtQ}w+LGU9?V)8(5shMjB@8;E_A?#j*HcZ$RI|LAKoW~x%nLH!W|{c7gWIxW zb?*LW08QPWkA^dMz}x1@OI*Rcn>3`Z?r@zpihpGg=vXn#tkX#{8K{1{eLUmqtbxLx z$h4nH*Nru{BUop@-s%$uza`sj^b>Oe_rocD^KQ^RzljqUqRHlqPIu|d4f1`p9~Suo zoeCZA@@Qqh{?xn!UTu|i-g26SQg-lXfQPY=*`9qQVF-G99U&PsyszDI9tYp;%j!*; zhewI1neh%}_Lm2(eK!fqbNpn@&twdd=6!M!E89KHA{Zop|7941_QfN3$1=$(VRBR6 zo`3ZDC!nGGWvIje^OD|MafjU|wJQaYd;l9){RjC)rlX;1(9~9t4_pUX$AG+C9`9c> zZ1xks1g>91Fj0HaSI4xiNHXSalY4*1U=oCBVWpni{`D=6#>*XnzqKFqYREp`(E+)4 z7Sl^I+Oux7Ex_rT5{Zty7Qd>sLH|(toUjUh$8E8r=b*uCd|Af@RWGkk_-J4i5wrAU zHL;S#aN?si>gSfp@EJflHSHK@GN#96VHAL*8h^2w#}7LWr^8&26)9tVXm(0`#hOMd z9j059XI((2Fe?nTE3EPpZtKnexvD)`#q8iM&z&iY9jBZ)hh_E}e>4lkQx)TrJh) z_tLS=_$}kh4EmHe!F?6xrfx*6$@Fp|g8Gq43g2=6izEy}Po;$DyTi1IvfwO{+IdG4 zqn4%yyZmvKQgv-p(>QnMMmkg?%I;aJN(sPVg%Bh5m@f$5tu&=!MLD8sPQtwWK#c3H z)VJV&fVL~XIwfF%X{WF{%`K@6KBnU$+wq>I(x=uJe)sQ$8R{F#9@jwS&H!EQ`>VeK zPjvzUL2*v)W*H~E$2ZoRa5>Z>-8bP}C$~Ps?gSR~(7)YVSqwcMjM-P+nZ5H-WxD$f z+t)r6@>9=jQ>j+Leh67Loc}aOUIH^}u}$deJo=Kb)8O-QOsYZp!dKqYg|e>T;3vWK zaYrI?ZPes5zy(N6ui1{hq-g{4Vg}U>{R|9@8=;L%W>hCr=beXMm2(R=anVsrlu!c1 zV8FY2+DvOLBq!(Nph8tWPF4IC-zTC?x@(#k%eWvFRJM|@vspDdyqq(3cqer%OzpYU zQ0QSz+AQp-eIKh2Riy}%#w;nW;03ovqfHqIv?nB^?KMRBlO!+4CH=5-*h7EyWeBGo zo?VAOC|5Mj9@LGwU{*9pWbo@9QM<$IkP8gGV=*|i>wJ3RJ@Ctf^D{qi;KPlSk8eM8 zVXqY-70?4lAyR{fZUgwNGk|*&)$5xe<9|0*@Q+4O z*GoW-4l4n*_iyFi^A>xU>)Il>WF+1hb?Z}k^q*Vy@QtB`DYVpYaEhBQt2P}0sLOcn z7a>WQ$Svuhe=;@<&OgE;KW~ZF?~=)AyLjo6-lEdv-qYsdmJqv|_H)R5i5ikU7f#mZHXjPP zR6qg~mAbci?J3E9mO)_S=3gkS(v>6AjJLtwzT8W*8(<-`NPb zqhE=WEf4>zrij8H-b{lZS)Ku+jmk=ni@$^bNk&SiQsH+5F@tEu)6B+G5MlV+ka(Cz zr;|DqFeO!8Mu2jf%B~7zpS}kkcAC`>?sm`DLEpY*nGx%#c7jf65MR|2%;KM{1)|xa zt;l9Eer9Z|)>$y@W%t+eSu@$1qTdJdt6B}}%9WvL=SLf&F6P$DGfS2gfrqmuyK!@; zO~2B)3i$kt@p5X18s`p0%Fds7-B;&^2HAa1wEKl5#pY9T*X@77%<{g~4+XjlZ$_4+ zOSKOMdn-p7xO0XuPuuGJNQ@HwuUV4`)u&bJXMiYFFo*-GyDrI#-oLS~`mVRGkL{a5;5^eOKn5M7 z-ScoChY9K7A@yJ$k*KXy1yd%&-W+@%$5B03h(o2c;2<25TUcB6X-AuCQh~v3qC# z&=G^(xu?(dT0^Y# z6n&l~ZBB)J)oPU++}6=`YdQm5@yysE!nETqsiQ-5gU5%PxWz0<$KAoEWJ zT8J`BXse0T;Uo{o{xy~B2ynVu+tik*1~I->V3;8$^HD18SpdzQw_--$s&YljO`A6k zK{YRe(~vp1!}HjD)*Y6(oijj;Zi8V2Rn!AbTi-gd*Pqsdd?5!cDD4t5@_Z4tDF?)ZD^*Wbtsm|~%d7L)8$S9aSi{0DV6=X*(-E}Jb z`nPP~O6|ZY3xfSRStT{T_ST>+LVHtW9U=0V%kkXky7blvLI93T``oPng%X<;pMjqo@*EUXG|2<<=U{hB9cG zSRVE`eElmv+IXrq9ae3e>hZ@?-y5gft+WY^%ata%?!(hh<4bJUL?OHNf5M8Yd0!1- z6!GAREYe687SU=0i1!7O&h5n)DTF_aqle#aaq;*k=V_z?Q&_CMJd*#Y1CSAKae(VXyPHz>My6 zLweor(q@&y)+6zi&KFO_Tr8GNDUV7I>r;LQ1rnnpV4z9|_uH)TehN@4WWu0YQcl@@ zZ*4aQy3g$K7c$IKwUX^E^Q@W63?V1&daJ^BxR*q3pBBIr2vD{a0haW#6{;jw>Eu4- zpE>u8kOq+Z*vX`e`^(tC8@~rGSn#GL#BFR*r6_t`Jzf;2^&WdEWNa}`Vx(yNIk0a= zrR})_YSHJ0CRgZ{CX1zz%^l=ngu9k5Xl(Dcu^cOv6Ty52IOiVS;hp!2;I3gc8=|j| zUx%CFV8e3#_%;#O&pWSw26`uu&uNS8E_){X%2q^-U)Ak9QZK^vx3*uz*vTW-e)N0_ zetv%R1l*ifLrAv4L1Unxqu;anbueY(ENd^$Vl7vA((g3%QNT;!tje0!CleMvdOZU} z@2tt9Yt3y&cCo7aSFYt3KL2mohySj9`TxBC1Z1c^X~RBktgz*zZd)YREWzI8jAmhx z4Uv7>l9udU;_6FK`prA9u_;BWA^u7F3rf(DY8{7Z2GZ!$+Jp>GPadrd6nW-54lP~N z_l{!d3rR$IZ{wS4PO^0qbeiBtc66a(K5)*L$Ocj+5{uSE5SAjp#H;;8GG&;Tm&kG$ zqM~fmO;mQ@_;6iXjF^tfwkn+hrT5MS1g_*ByP+SbRU&phVC_1YWy!JVI}~>*)Iyh& zQ1keSS8D48#-iCK$UhDNz|S==k2)Lh5%$aR^9s;;Y%B`m4=JDofTDPAho@9|)X4`} zA55`ohl5X2OeDpWGc48;E_uft9HK?R0Y|=T94D{IFl+X1*U%E=ulFW=g7F!*11>In z+3V3TBJtGLtOjIdd?sUhT9a}DIffy@?w2CvZyI#TuB?}^4cwz;^SW1K^@5|s6>KMc zx_RirLlwrs-*Omxo^Df`2e(?G)VX7-*RMI&D^oBYMoAN}f2cf5`UD)nQBY%Au6r+9bu!_IQR_UerO($I> zeLl>_F==TJpX4Mr&VeJE7~v)rE}3(UG);-WX!XXeeS25(AxO=H1ARx~6?$^m^e_dhSM14HMhL*Mcga8>^P;Hcl2JMrSe zk7RK`n^&-euEt3K`6Y*&s7R%vwrMd%WzD4R`yweaC#Gfc?@p7qyoSo1!SCTi4Ny_n z$cy4UyIfIfd+M3q#o%x`MCVc9rb0Q0l0~1Y*#HJ2Sd4-N`w+_Z++P*1%x}?pM`W$* z60C!=sqwsta1!hNGr$t$*0HwG-^A+H-Pbs9kUh@5_z3^tR)2+mJtzcoxQ8TqfiBc= zKB4pzM6FsTwi-&qHG`@hEhex1X|8?f$EmIS-PT|$;_*y*kI+Q}mfpVm zHt_#AJ0GHuhn2tNXzSE&*s;Vd!xW#RaCVbD%#YmH{Pv=k-TBw*RlNu#Eh2gVcH2wCyv7#zP1&*H-2*Ybm_Zjzy>bK z>yk3)!I}=^_+Dt04(<%FP!d<^>Cd0o{!v5OO}YI?p2?>L`p0zB9`(&fIR?{Px~TjnWAOmA&>`}wtZotDl3SL(a*d$uU>8Q@Kb=ovunJmK{` ze+GIa@1%B)wC}K<0n!`ht{ba=O!GXTwC(#VN(@HP<+f{|+|hu6;4Yx(KNl2gEmvat&GFz z8DQ>|w#J*@xZe0x!+3D1Qp-H)<+bc0(3hJ`$Gp+v4dkfCQnw@4P2tM*5cC&YCtLTi zpa3HAcg1U{it5;)wBVA~n+{@QjW%!DDy|w)?0DiwwrVOWJw&{y&r+b1Zr#E9<=P8t zDK!Rb-TSsUnOb8Z)UZ^T>L{6$Q8m?9p5VAKy0rFLyTTKT#?8K_dOn^Dw_ghXDWZYs z4T(;EltKYnMNM1A$i$<>UO%gwocc%4#AR_-{;urJ%ML!}3^@HzNAE1PQi`vjZY)|1 zziw1IbI;XnPV#oxSG(U|ZS&OkNuI%%X~3S6r8s)cRsSkqQ_@_vVnM|kPpcDx-CSyR zW02{g-MebX7#jI+EWwg2e~H+~RSyWl!l{ja-KC1-YaTRA2^gB5;OC}7;;MLx+|^Ed z5(1y}he8ER)at%7r4(c^{Al^kWKJ@3OiYTZ#7dZY+M4Tgy*ZDT0{(Y5S;qC+=Puqp zBmJ^nf)6dEW;Wk`xwaKF|8(zZzj{`Dy+BXFy#c+q=_%-)>t`LbeN?SOz z+{sNuXw*+@$O5E8T`;YUn=|QGd37Yt zC|6P}ADUhob{g|nVp5y!iTej6PLOU-z5KMUVwcA%>S^^uU4Lx@kt%*mlxE@K^vAM> za$^;X^p@OAcLiazWKG`CEu`ea=&IYkPXw~+W5EtkNT-n~$_+Cin{`Y>e7g@Ov;IU; zB|UWbS}HG!fqEK`HK5(P$xVtL<%4E z*A=VaUjeb~N^=?x6(6V{(lUdKKO8+A zcIWaS2vpwFb5Y4FWeekmoF;sVkp;G0fcFr|tU(H%Oy5go_(jzS5?SvRh>oeMY%mo$8n#D8O->&DWSlN; zY}4ES)x&=!W~=6_%9i$*i?=J_7YDM;rnbU4VHV^5nkaoRG5*wZ-I7E=jVmcE+Qbiu zpBU7>iFtP`g-e#8mufWEUYBik&QZe*OHbG+Z%g}$jsn8;=3~`Rl=fsYSn$zZ#?yR3 zg+I-bwS2vR?Zn%^Z{JL4xsJBZo=ja%^~EB$c2@X+lqhV{=H;N7f zrp%&`swS$_3)h`!&T$Ns!9CD?){X+SnLypxH+}*6C7CKkoSBhyb$^=ce&Kgp*Cw|~ zukIBkZD;od1qBohIn$Wb7w_rPK7qPZ;xWf(V(0l%-zMF0TflEn{JXgedj|bAtIv-$ z!{il38p&1#R*smEC*G6hP=o0|?pnD1HpNf}-p)*gDwm>tn~`A03a44WmE-OAw^6xQ zPYX_<<;L+`$hj+|p~3vH3B{ubwwu#ge@zhaA`JE9IEwK?uajs*kLN&qo>BQ-WY6dO zrEEO-)WREli$Z%f5+qf7#2eUs?EDwNv%B25jbYrfbl9`Ok19v zE?DJ45I+xukHB}HVqDJv$3jwPfHBCd-x;8RHBk*g>*mDKJOb6}Q9FoN4O1bY3e&<+ z2S!3=(e#2JQ&Qe(v4Nu~Wg-~zVDtQ^Go@y*W%+DG+bNHZ}MJSy5A@MOg5Dt$vH=fAmZcY!_QNY1-=MW z4{p;t&i3UE?z<&VajRy7Bl)h!D$6I~Z+SMa04l4TJABsR%rM9KSSmZr%v7%X2z4~E zII`v>#M!5cHSrnb*I3e{e*%#0gZczl4hx?sw~=S@iGi@&l#YCNr<;j3P9u9cz%J!! zr|-4FChC9MgPkE2eBzqiqJvM?25dFTxZjkImX=lAIY)1#68)lriAI5Vr+tWwUz&%* z&+}Z*qjNJt>D$`ThsT42(PA*Q32olz&Na3kyrNvH6{foPZzHCjIWk&x%SrV=DIe2Y zRZerq$2vddv(rlko))S>z=VU1l7+UmFza;-?D^s{|3u(^#&YeLEWLLB9&2UQqO?;A z*aO&nUV}4Lq4cyLsNo|-IT}YQ-K^(?%#a=;LO*j{>3_s~SezOwf0Xa}xv(tG{-&Hh zA4sX_=Ac{+0@+dSkXgGYEo^giw!-X>yN1*@9%T#tur$|~`uOETfu>qtj4fzC*gR34 zAU8Z$+>()~6rX=!Ke|0P(as}0@MYmT{z2PTRp9O_4m-Lj5)5HNT!Pt=>`<-+K^Dw( zSKG!K-2HBOD!7uSPa~JymOlQl*q4dB&OOt^`m;>>Tln@z3Yd5hr6Wn5#515JoPz$` z&w#x6V^cfU;Py9&(fxLCt4CDgVH%Vc zBAj9PI5P1T}l(pgeA)z!rM3;RBMpB>UOcKC?j}9P(j}u3)vsvF&tC7 z=ES2BHE_+Jm6hS;@gu$K+TZ*+9&^2f$PGK})fn7rRsAC)!*Bd_O~3!?JExtpm-*AP z1KLAs<MM*RBODt^DyE@)WqxPP?WtF@Qg|cGGykVrsN_@#KXzIjB;x2jYj@_8-I}L z;*nx0X7Y(kmjq`xyb1$!`6MQER4G1Ph7(i{*yAzr+VQHtwu*jXz`Mw1BZ6e_xyR_v zapQ4N$GneR`nZnJEcnPQmO!TO(v8;Mvta=G4;vi4g-hFWSnxSVx?S~St*@WXeuxhBeRn4WW zfJn6>WP$`QX|**h0GU5`1^f4$4@2F*`=2Uq{LdCa{+Ii`JNl_$FhCrA_ULBs$Sr!> z3MP?IFOQcv(;g2s@Oo{35buKF8?=l^Ytv_f5}zAda$GfYDhyKW)Ti~$H{q*A(07SD zDhxlt>8DjNXbtSvY3>P-sKn$UV}yM@IsjmL)%mgb;cUCbk`wNu6>+hH}oD+9PEkxJT{HDKUpr-RYS zxg$?k8L45!vt!51;>xczqcB!{c{6ys4d!2gtid$vYc(k9Et@owYUB#l$U(3C` zhjcfNi4BzPg;RaVGaZ_&$phdoqR|uWtclGp0rgvSb?TKCUta*u0LI#1gzl3D37N^^ zOfxVQ@(t2^s&wi!;WYWZT05(0d%ejzW6b4r7lSNYLb}Gy-fzYXhkW$>eUm?vtZs8W z@$yOgW4sE?QVAbwTjgu0DQ|-zANOgu5J!^+*0FPu*;|Le!?NH4U@xdqVLvaF6a}YU zv2WbZCW6?8iama5tJgXL`K!!_Uug&asgEC%~bc@%J>LJXb|;A}JCJHLSoO(H@JSz++3` zIYAH^wr~f0Zxs4WWvV9-qHV%qq@7|YVIaV^c!PFpx*6~YXVx(+5+v7iSg7 zE}#r{W1;_a1;5VJ$nq>v*=T-e=*^a*CvoVb{j%(t@fRA)&Lx!u_g?c6lTEo68R-I< zu$n;;mw_*i+Y=n=`f^nb$C%)ns*gaY_}W#0IYxA~Mn{`| z@$suh8vX~U9K#o6rg94T|vm4e)_Y9RfIK#MsH5geWGlcA9ckfQUP6S$N5 zz`>B@Th?$W_D9y`Re{5q%=UWgsBE=C2`6`VJ9eQd=%3@K25PT+cTALZ zocJA(9F(#BPovtR-o%pV&N(SEOCmv!6NFWbsWPqpa!i|)Ak~~?_sF|W>rlD>&9|_P z(w~#smSjZFoJbvM>+^g+jPbkxCrLz3<50s~?yuf?Zqa%%JsHoKfMPHO2)0hq74*9xOki?*Os+ zi*mqVUVKmngjF?S72jcyd?Tqm=^h_ zHC8Q0a&m;iAhWnzAc$UfU6P>}iS?bIb%OI%H{@!O>CjpH zwv>QdstYf^U86Hm%WLkC@a~@KpMTpE#2+cIJLz!kr>v|p)(;nl>CCN~J5>s;9s9WW zrLb|#>^MN<1iGv3ygxu`UqHOCB2gDQID20E#v8!CN zK89+b{o>O+f6SF2n~u~IZA_G=|L4j^lSHFDqb7GBNBfRQ8@l_(SnoFvZ&{@Y%_nUy zXmqvP^x`?GY#uzV9{813#R|B3^{}Kz?LEaDZN~IhbY0qU%}>lUwO?X~TMakb$pXXk zeX)CC#+?c#-8@G>lMCFG`+OOGzAaw6EU)6}+L>YVc_3AA$vlA!vP`e6eoFG~zU9R1 zD+3LFT$q1|`Ief2aaqsHl|albqHE#dn8cczaLW}|f$%W_!-y^Irz8rn8!a}1x~2y{ zT2A3EYaBy7OBs2OWFNeqq;3e8*1W;T+MX_;BThLeSv^`EL1_^XY?Nb*c++H?w&<=D zAaNA;=#XjKS6kNJvD#Wyeo=zspJ#|1>aCM2wFOHrw*?(MWN6)jZ(n;92%jBfSGEpv*=lO0~|5tPG8PsGSy?;ir z10uZ_1w=YXQwX3^Bhq_~igY1#A_Sr+9i#~e2t4!-QbSGXNS7|51OkHe1StVR-23<6 zce^t?yDxTjXOeeexchy+*SW6G(Jc2W8Yt?$6D~Ti9xcPASL%6RP(Pik`1g%g6ZvK9 zijYZh*em=t8<`HT%iDXVACc1|Z>8D5osqfy(h@u+y~s4rdG#TGn>VQY7UXghT{P}S z$Xyap6SYK;`K6u)cZL^E~-E$rul~ zf4!&tGC2h(eJ!Mb5>ha%FpHVx*zJ?^&#Hh`XCY6cYl<7uVc~=L{89W8>LeK@CR|@% zioPmYe-D%njwD9uO>C__ZrVRbL{wM z6h{d9#qV@2trUK+O?jn}vf31XTXS6GK+$dapxDmH16SfmG+VozOB}m@32FX$lh#9wsL`Z_C(&9XVcvnS`GhOv=tx3PsO|rg!J4 z=#D-#EWmOsMT3b<(ADviXq0BOut1B*;kXoId|oua=c?kjLW$o%85vT4C>6GIJz z*TnzRpvwPyzc+w#hSfI7$8g$4&JQqbyh0#aYvvz~yvPxOeV=HpQT9@0t7y9^`9ac; zE)uJfQVDl@{tu*=Bo5Wn`LpVG)pX*%=FrMuT)x-RlWnL#NC#T-q71A?^y&Bi2jV=u zcs}3t^U0FVRtCbqBn|BvX02%ol^4%;e4eVGqUZhYY-lx_qzDVk*x^x4uWS?a;&>Y5 znWw+7m-r0QB4sJxtce@@(5EAU8*gP7kPp+iOYL*t}h8T$>+|j@C5jH8V*6)xnJuKE#n60KpY{2mw
a#ZTa|QtC*0p4Y<^hn zz(XKO!93N~$}S9f4o0Yx!b-l*<0(0K>cbc-pDd#x!|20)2Peh@Vs7k{Q0A^$?GWhK zj5AgD=(4HY$Ryo)2xJRrI4et5RoV@(J*Z@SzPDIemWtZlJ3E@@)d38Wl4K5`e+gNJ zlJDI1? zPUi=g%eUZ_uxlg*-C2qhDZ;X8++D8SO^v|v!7IOThgz}ITVq}j&f-IScZM1GgZ)&Q>%aJRmjwS!kM=hVij$EF-V9>t|Soalx zgW6XEr>xX{DxxokRG*Co;KlMU;)jTCB=hlh>6 z^V384qU8rVZ<}m9s$yNu2}4jVi*gHfhwz?X5BC+f?^QJ6k(!W=sjjouvKM(#zVYO9 zDU540v2TwV+#%Il6TO}v)i(|NTj#8`od(z`f_(fBBm>cuMrUee0=+%{8P%0E3N3P6 zfFMa>^oNpNn=L~a$Two}VVL)0o%=Vq?Sk(f6@G)i?%u&Or@t1lcHBMx%H`fCGv*5L zP~;ntv}CVUBn?TdeymnIKJ{G4dvn5J1aj)-k$Ao40U-@0ZXEmG2PI$Ah ze6kQ}b`?o7wel;9tL!AyQg(fJZ!@chukO;HdKW-C63RYy4E!osZz-MbZ7OYhu`4L* zIx~)L`O`2NR5iyHteZ%!>zu0I3?GaiS%t5Q)68Es_c%en=n$1S{I zLxk^%%db>ERrxQSjn0%Or9Zl7)$?y`NR2`OdF-@ew|o|r9UJ*bPr?S{FhqbsTcHx| zt;`o+RcLENL+DBD5Oyp=!6ESM@`j7(T-I>k zIkVmL=u@dY%3rwq`*dc;lbCQmX(%nJZUuP*zTc_Z5Fe@X!1@;^x=kU#%cTH{lVY{f zi2l`c2Ag9``YATiirOQtx3)CynY^p+rK8(CLv`{-ZI`(;&emFx#Ryyk>K`m>Fe$f! zrOb%I70X%v>oi(EHqyhyiFgH6_BfIeYxo6F*HC!aPA;osbve{Gm$&&ZY`z#)Qx6S8 zUOK`>Quqj_m`>b{qVhbKW5tx73Ha-dC&WcrywoS**B$fdWs^%Oo#53f!1M_v0ljDS z%urKhfua;aWx=Sn3# zp!x7knDetI(gDM`u!WYo$bdDpKiz}vQ&?P6H@$r4f+BP>sp9(gr9MA|fD;NbyoQOj zX_Bby{axis!xPHJ>e}m7rc9JJMI`GV=n&wo{8diw&7nbGCMor!ZxB-UJI8M7l)_uw zn%+8m>^i>2hFzkPIV~vRV`k%2^O>c}KoMD&fyQ}tI1gKLk0P+c*9Quof~A*itVpkW zd%x+e(DuClPsPZC=63+If!>YlynG~TJ%Vb_7!#QAAvN-0!lz z`SzM`t6u%aHe)-zL8Y$Hy7;c`N_$nT58O%b-H^1Sqx|>*WG^tsXQ^Gjz6W2UI~w+U zB1sR6a&p3MDBmx>F*?)IWT?Tso_UqY@X7ygzOUdz`m;yM0@kDeqY2-k#$-lF#iqCG zoi-(lhwogxE?r5&NWYf4f%Qpj)sWrUyB-eLUsjDIUoC+kSJG9ONZx1K!;(G)lbZR6TjLnV>8(-QQWwx&*J4WEw*fx{!?Opm?j~m7S5mueSM&-1_jYq({oP zMX}CR{jn7|nZPs21ECbF{zx|r71G)40;q zU#1Jpqf$Kqay9nLbdhJaJE+tUK~k{GJ284|h}ZQGRYqFT%1b5=;iXBX?Tyt>n^xK7 zwhm3&OwF2YEB|1AJT{)r7PKcA_Xave7ZH`Sa9!K_3@>a8XI_#5MC`OJUd6nSQ{LdO z(wE()3#Eupv>AKh-9&L=$07X93r;iQ6rLApNqgt>MI713qu0FORlDWo%xni(TRWiK z8*iJ8Nlb$|iE1{J9`zSmz1dV#ViNhz9^xKt^nPN-{4@_0h+zW;sYRsBV#+>dNW>c|WGQRtB(fkkMdjUk`+W z523Dm_9_Rzdn5*zv|oD&-jt&_PE5;OSG$Fz&zo)2*`vRogIQ){|4M-}8XP?a4$AgYyCd_;lm zzdUlaH7C;@K)uFD0V^kAZG5pAtl{;+%p5bKEVhbWqMq)nxZhp=4^A0}lU)xv=Rt2~ zJn9JcD<_d;nIgE489_3m6Ji6a1@*r@JTKBVp zAxWBWZZR32gItEv+Wore^v!C)h2=nFU7yl^{Dt2)r_U>OKVy`L>dcbtQN2}23iwYv z=OaSWmt|&a2=ZM!Uta9I%6&!sK@Gb}3oB@K*uMT7{U2Y0Bis<-0{p?HhPkjpUjF;M zwR(beR}7bzX09m{%~g;uh~{-+UbK7TUQg2VAAs3J4N&Oc|9}0JIr;~>vuVdPzUSu- zGp-vyEO($)KF;+_czQsJlqq8)N;ZearQ2Y}Pe=TI#{k#8t+SQ8F^E_O zxrH8@x`!p)5Wd^G@c7+bPRRK^1ms3xWNqY%CY+U?0SS^Z{ReWNl0ks#!=%?o@cMLG z97)&K6$`6CBh;3f%DO-xxG6(g6Op>`uL>~GXQK65Houq@uMCKC#AT3#gfYE6r zUahdA*VhAz=8NJ7n{A!X5@c za&Ny&u^y`s(I%5ey0vXN>G!yjNj99aCn{_$^P^Ad``FE>%hCe^=|*}YcDfe}sMGTy z-SfO}R>|=h(BR#J@oiN4aSh*PNC$IbF{%H_bhVhfnBR!}!PeQ(`SS_tpr*B;7@LxF zb=TWgVlA|*qJM9{W8T0p?;Y`Sh776P$E2OBby=n6t~{>3|A9Y#SKec$Nb5tY^DnBC z{I^9<#N#SMRbG+=m&X`f(F&yN#V%-->3VbIr~B){W}HgwFf*3y;lef*ht_9hg$W+; ztik&?#pZhpE(%J~IpkOzW$yI!4)*wY-ZsS(dLDoy1^?AR$k?A7ljaQoZ~-rktKxC7 zLzSE2dVA3pMU1cy*t4bt8Yetx9F}XsmwYXq?(+@5g8zK?>A|VjKC%uP-)4@-kzUke z==-Z&SvchL68|g-&XSe9@@!ojlllaB-ZFH89;%~q%b+MJ zDf7I)n00E$o)%4#TeuY>RRJU4Cp6=X$6>G!K0fr&-D;fNnn|nH!;+v+?T00{efV^VBLAcQkzK@}_AvT*<@^uv#)xF4>_PiWj7rl z$=1Ug$ua$Rpi+keXHD{-vvf*jvqz@7fW8Fpl)|Jg2Z)8bsK7NED!#a{|DLp)$GJ&9 zD+96x(SaI+ltf*ezAj2tQ>3W4{Fn20E&1Fa*ejZ3EsrFd!J2X%{!gE!EMn_qL`t?G zAaA$7Ir#Wpz;Lo09~z=cqP8Sv2kchD`#BQQn(5 z_~S5cTr~JDZ%p2dR+#wM@ofRmnMR^V&wou8+o8?8d?v zb;HG7!1A8?Re4mBHkHS1?~%M1_rgU<>-zfBfp_~wq3x(i%?t67pnsrc$sv!8%}VCe z({i#GX_H`%pY26PP$U588fnG?&4D8gX-$jQiw02@+N#&SjpM)cDUyx%sBqv$MEqB| za~#$OZv(yg5A=rC0jv|J)8De2k`}pfeie1*`;flf{}dkoc$>}mkBf#6cG1Rs)aVQH zIxDhk87Jy;XoP&w_mFIog5l)#bG0hWj(46lKk>A{mfvHqdSmfZM#_{kib^ouM*v9f}&?}e@J!j5h*Tb$NF1{t`$-doUiripmw^yM&t z-Bzk&C{p7pd_({B0@u1h+k|h{oy}C^c~|#hO@VA%4J@Ou0?l*$Vr7r(B?HKaV?ncn zP_g*_pD&!qQ$;gM>bL3)X{akM$Qy!OtHe>RQX2Bwu=?DjoIYe-7ksFb15AtGHScyQ z+vL#8Th{a_L@{VkH=5Y{TpbWme*Rf&Ooij37>2mHjA3^RoQ*@6SHLs13BK5!>`MS) zQM*1^Qy4FS_GNr}wat6Jj<$kHPis&;X0T!G#QU35TfnJpYd}N8Ztk6nHTwq_<<{#H z=DR_gOQZdBJ@0P{flRsS>?Xnb1y)-v^7$_1E&vH$M83l1I45Y<<9C96;`qh z@st?f{YP*H;j}s=Nv|bfClF&vLI&i|IUjKPr#{}<(~Z4#mqGH2nah30+n?m0j(sJw zk*3RCa_A`65RYnR$dDCfNy?pkJhzS+K!bcU>nHpV6f#4w?&rYT3P|rQ?eq8eG|HLT z_RBeD#w=}yFv5nMaeBwNXZC`Eeht+J?t-M&5GB`;Po~z3Mq|1`CatZZ(|biM$J?^e z;V#-@^bbQEyJ|W%ZUu|3<=jHNC1tIakAcX_ZS7NScgul`yzUA`qKQD9+}}SOQN9bW zdRdE(d26(A6K}pqowxHfuX?Ca^>YY_7#z_{H@7uuLCPuLngGNcC;wE`&&|N#`fd8} z&3-Z=EBQ$;sWfdFWFO$RKE^*xGWSGJxF9kCoid}Yt|dSXwwMfcfB?4yu!CuO@oL+Z zIwp1FyBu4TJ!($VH$ZkihU1#!t$Z)OH+3Q(77~=E%oLB)%Un6)!m{&S0)mTLG=ki& zY#m@*|MRsp;mUpE@RF1L3VkQ=q=Aj_?3pt5)K4KF7rNf zD_<1>qIvhWxMbIv?mrOOFq=B3M?ausizRPE=6h|6#V+2qtR`LrLaiOJqN$Qh5?qBc zk)HyqO`sqmB|nATCbjI1P-cs4t#zGCJ!1!QL<|JuxJo>$6s~%G%hpTQyQO;w$fgu% zBE73k<90R9=`1@!0})JcT8)Ty2OH+ilMRSDQDnJQ&d4L?Dez4^?AB9QvE9(Eo1EvI z2H^shEUGIwFVE5R!H*GKxNay`2QL`|R$hj3TW;}45t)HBV1th16qqF&)TYZY`J(CT zU3u*L8lyL%@|HAX-b9r-sV33zG}$laX+>2-2Z5E$4c{RLMYx<5%uy>kO=V_QZdaz8 zLwBaU!c{&)FWoi!%?WCL8<0ees;n1vKr{=59J%xv2xI;e;~#R$_=s~=`-#Q zjAgsKWxb)`PoRmS`}>B*@THTXXo!M!xHr2e%G!{tFrkMicMeT2=)2u4KWM9>mAt4&Q#j5w*SY1U}s&#pF%RkVX z6HB3gb_^hg-#0{_dmUymA6)PH2a4xWx+rMKiJ)-T&rWt+LsIMGm4i$O7Y*&by$j<@ z124bNQ#Y-De()l(t*74O*RKz0NzPW}H>6yAdG!?%JJ`lo*PA!eD(9nI4#S*FYVVPf zwGO+78U9gW+-kIwM*JhA&?h~@`bjaqcF0f7oPd&p8HTAZ0OVb}?Ho!{3-4=)FHr2I}TMqOV5y>h)+KI z{IsO|b?EQx;o1SAM0XYrsap~wWoq1=^E4`7iPu^kR)Vh^&G-q2HD(oCLjrtce6{n9 zMse@2ObwK1WwnbVyH+8CHl@rvZTA1U+6hd7m0YS^PCfginQGoA`F!CW)$I;&9dVp`kslBypa_c22`$K*vc4I=h&@{2<@Sc z=TM%T#=<=+#Kn_l_RpnH^;~8(wKT+u@>(*Qu@V|GvTsy!qc+fCtm^=B{Th@v#*)H~`%&3qM2U!%U4=gP z+{QwpzAa%GRkPVxJHV3e?gB35dW9EVmrT9YdhPVRgn&)Ch97YfulWIqhlSUW3jI{? zAiKJ12;o_)+DZtI)_SVlU-R+{!ew`ivPt+Q#WkVbb zr!cx&#dmL0SE^ZuJ9EGff8A@s=txQhm+3rmP_aRYvi#+OB@BbGIA8KVP&H-pghE3y zUcLSk&9}`XL3}dfo5g{h?9HYN5{GpsK~LRU)<@a+6rNn3Q0GT+eto<6VDskErbk7) z#{^Wg)pm1TzS3>C{IC%i;4**8>ugHhj(qWbx-hw*HoFq%+sTL>!{@j*^Ju)EhzitwUEt}ngJx_IcCT_5)5 zc=t_aMB_{Q1ZfAp+tFkFXfS~{l5$6_3Vx;=D9PxYfv&4Sx?(M{bG-ucQZFLoXj|G0 zH1{^dYzZNbh+6@W$I5^ln*!vjR8v}`YzL*b{(%N1|A9Q9O2;ZiWgHUiMewAarA>~w zqEbh}Bq}cl#Sz|g&aZ2_gW3yK6%~r11w0xE(`6WzzkhcX_bGt38t~7a@y0aBP99me z8+V&wp%J#l^{FeGUmQYdpU%jzQ48d0FUq8eX#^p6pa4Hs4|dK0*7yf1ju}LoRU_s8 z+F%Nj1qTEGTg1W?#^TqBmFV)KBtD|A-F!viQ(F*>_@wZ-j(CYI;@cX>(7VIXdvtRr zRg?PG@MNy3r~2Thd!e89#3$gztJOWQ@N7O(`tl910a&NZ+RcuA!k3qx6x#Po|Bavh z?;n#|Zxb}6BJ&k#qaiQZzBAJ!h`N3*lIBAW|3Jx-;ztrXsYWs93hu{{dR#F6cr(_)bas~zAYejL&$Z9}vY=7-fXZcTJ#)f6ep*bqF#M#Js ze06Aus9T88w4Cm9)epM(pn0ay!3PqHH2MO(;^?){5LLK;Lg#npP(;cW)+ru+AI|!e zB)7U4)HeaIo$U`S{G3xxdgIcVFlP~`q0=!#$Mo83O}o|+={|>z`mJpR~aF_qSZlMJtGkkRer~<%FL^WGd=J^wsC0ic9;e(vpW({TU*L zc>dE5sO?T##$u7EyQKJ)V13iJiO-qtv_&ai%&`HUnGX}A8smCzWJ6H5;b7W0)m3Pm z5Xt^r#C5D^1^IkwQ6H?n=`vc@(S`S+e^$c}{chY!7P@l&TfC$S;kU-B?) zt*6#Mdm)cRvN)1YHGqt+GI%f8(DbdJjywk7pwicR@R;&=F~?5Aty z15jFE%{qm6GU1yOg?>bod=IunRxP?jbX%dqUaD|Ur6g&6kZp(Xu?L4gEOJX{&k``c zIk=jC5$db7$lsv?2DtyOR=<#3Zi!bhpXZ)Ev>UAEJ9rhpoPB0~fwea9F`tsROU5qX<+SgjT4Rek*ZR&;y4PW!C4VBBDV zba`K>thCa)8ivy|Sr1so_=}(VXaYyjBc=q0r6BL zMNL<{?}#?B`Jgii{ag?7KIJ%O40f z0buSFhj92W2U~6kO~IX~*ROCiLs>({mV}4_ak9K0d1>nDm~G&^+LIL4O*{T6IbDgF z89Zh8H?*$TBgZw`Vm0o?+npt2X(f>8=*x)J_}+G_e)XCuN8&^04Bp5F7&Sbz7f08o zd@Z+R#K-kdBkKOBwuij+0H@OPS04rkcvxR2(5d6|6|QcaXzGa{TWwbR*=K+IR$7XY zZ12y&`4`VKnfF;?cIAT0<`H)ZOCO2+#xpx@PaR5J6^lP31eZ5Gj)d{`zEQ7rmEHH$ z8D$3Z%;55+nq8Wj~7$t=Qtw zs48{xDR&uST>7Qv8LwRS<7Vstn^M9fBXdu7(CVW~j?;i+kDq?kw3KO8-W|U&dR=^Z zN(13sqs+GRiUNcBtL6vyE$I1|+NwW7j1pH7{Y3B;_Rk5bv|yOEBG|20OtMZ}k-1F@ykQJZT#of_0y!zf_R0NO2o^CwT)*ccJFzl|$h zrN~@lRw4qt%B{B0VB(i0hUsb}z(vue9|RNs^xKjqx^g*DZMrL2jJ}@b>==zm@FVXbV9gXJX0S(%z*u4ck zx0#YM-O|TLNP_tqZfT(Qx4|FGvg&y7527~m4S<(-p>R#Um2G!|jvu*;+Ms6-$LQzu zK~rK*t?9p;)WxaQ37D@x?2{CXnno?vZsS&Ry4saiQqWa|EsoEv72D=OZpw7lFN!~C zXtVK?5yeW2qf9e0Ix+8FS*!#^s6OvY@U+9`!6Z3tA^c(^VEb<_31I21`1ePpNyV%I;Eg)P{0x_$YX2XaH@BV{by*F89i!f-X@M zP^I^h;Thq{RnBRSvj&qAOre6IHh1W#_C;?;aHeP<0VAL?4F6OD;~@MZ0)~H2FHr(; z`zj9cl$+;-O*9jHwNs&GEcz&@nqvqi(TZO*H`b~2*#D6t5N7r6o^ZqSt5idq-`18t zPp$^+l&|Q2rd%dehaJV4_i#uNdZ*j>Qp*1*47nrSWrb_F-#i$+{djaC^b%XOV_xR8 zbx}OfXqn$*7{|>5OIzGNxF28LLCd(x+c6X$mVIyfsJT8U)7skdNWEEe%JG0l!IH;3 zE~UURN=I7Hdr_wQ?nO4@FdpErD1$TTSII$=X-xykQ;%$r zw1II<%CL|YOoj`EHrLWp3vk8&lrvfM>N@Zzp$Nnyz{sz(5+6Zur3lyXuuc7*u7@&O zY)Q{=v#>G@zDej;RA;)ZCtX*Y(?)e2NKRfMlVDzi5Lm>-R<=+E=SVOZFhYc`8hm!Q zHb$EXK)hrVAEK^bxxy`T62o{n!Zhi!2+KdOgbf7$fGy$1i0zbfOnbHlK7KB!6D>m; z2qtn`1Z$ocVhBBGhL(w?H!Lz1gTrGfH`ifGkv|e>{Kw?h?3jQ}bwYp%RjB25b@)8~ zeifQ_3O`jZN^5QN89&jHA0gFC|6W9Wr^G^nZ3p_*C#R~Ukk_l2Tb$xf0g$0hI!n4L zn6xWj$UmNc9{D=(KW6T9 zgVs7mR18)3fT8$BB`xBUNK%f*_m;-!N!t_?fjV7EJoCgiD4|ZO!&Sf@PGup86aR^;JT~uvjqE~J=YjjBOZ)>bRYWG%@oBQR|F9NR$JjXtP z=#z6^=7l$B!mI&L88q2#U2v};HFX{kp9N2N)Ru8`t-6H9=9OJF17ZMx^5+fDP36Aa z-@__@pjH^gI4BYRfIrEJ-ceexd$7~;yZ5jzt%UFjfuCzD1@8@FhJhMbE?+%hgFi5 z{4P&A@jNQWD7`S=(dE~=1er1}QTx7g$DCebX zIQiUW{|+zCXcHVV+moi?KWQ5i9<}m@Ub(s9v!w9gsaHp|bknOLnILW^pidRTf?7kb zDU{XyCBuSF+Hp&xlKB0uEXh^LkDT2tmA{X(IF_t%oxw$5H!pWD*h5{WsCE9_?*CTC zzr?PYiK&8o4U5TIjm^^yL7Q#C?%a(v0ZJXUGe}vNZHX z>hs6<|29z0C7b;@+#wK;Mhd19=hN$Oky@XnT)#;cU!`M)a~ghph9d0#rhJquPA{|S z_`s(?tz2JoI{v=XF^;~&pR;k7YJ$wWY|GkVM>E+b`rllZlG@~MSYaFe^YcVdAEGND z^|3&+Qj|b)at1E1N_X&N8v|%;<|nmAzZ+VR9sld(J}sb(94Ejdy0M>ISL0dX6aC$F z5T62P%Dv`>Z0v+%9Nv;c9R=Cr=1)>LYf3f#n*@PnlsY48(;|F@4})Zhyip!x_Pi~( z^39N2%}pqGiNO`NHtQSjZDhS3FC~IUI1-v{?tR$(VvvXQ#e!{f;X!@+>)T5_6CRaG6UR{D*Dea}tz-0l>bLKuFgGrjUj1av+PIp8lYpEc`GfmH(>ZfX@OXXs5og(=x~HB(G;@O2%+wtT)AEHmh8$}41& z+{Nn6Os_wlQstwFuJdC*qC&JP5K^_10F-FS5B0X@&n6Csl=ZvQQeRa+i;1uA8y{in zy~Rjx`Ha76wdU0I>~(Z$(7}3YD@6f=3qT&+m9S{4Y9xyTOj7Op|l1 zum-nwKaZkjOUJ4Gs+Sp}F){rP_cf8q3%kEAVL`WY-DVyX2eeWeFdOB2M+;(=9+@F5 zHU!*>&vJ)S)4PbJ()bZe#o#`(cPb~)x-DI;M zBy_eYlPOa_-NP$~F@%AH#ACV^?K?QyjOPDvq0hQ=h34db=v2&K{z!*hZ(}{@2aci zhzwC~EOaGfR;_NvW0zwI%g!fND-}J* zWBk2(U%)Zpi%s(y*SY?$x~}7xl_6%LQ%q*J9mi~1j}>qD$l~|f$vus3{RV9mqjqN2 zl-LBM!Dd&)Q|qU%acfJOY4zv{rt%0Atl{9q6R)3=fhx?ji%51+t%HX9BI#XPrWCMs zwifVW1EMcPV4TUV^@l*X$xHt0gVdtTpztd+HC!A^cP~=Gym;$)4qIE>ZF(pv)4YBb zz3A>+qhAP}f0EFtoLT0;{*3DH{*}}#%z|#eN=l#4pw!bA-GUd&mLiMGTPf8+7v!;h zryQ~(Nv@c5y+;ujCE-^I?OhU^;SXQhx0}tT@^r^vA4J88GzlRRNZ4Si&d_F zAOO5Mug|gMddGE1iI{@>bVRGE{CvAhX32V_cyMb|C}kbuF{^Xamv*gU<=XSIGDO1; zlc|tn#^yf|-Rbt0zGf?6;|{S3boQYr-eePw@n)acQr~I!r7Lk zwXICwJn8+FD&D~}uAz&m-mcF6ZTk-domtX~!|e1IxX!4E@!TguqY%(?c+AtxZli6h z`qU^Nr&l81;gvH>*arrw?!SlM4x0wB+yY^Vk{xu^q?V1Y_;R`3X-tG~`636Wnn;DY z{H)m~Oe*shTUMl$LD5Z>Ux#JF^%-vYfKmY1e|7d>+ie?JSCe>w*8&1y;+=DC-Yi3? zwog&`NUMOb_38E&XFT2f7OVejCDS+>M!?nJRsCL zE2^Iau(%_GO48c>T);!+=@M_)O%3b86-@Sgmy+~_D)O>$>lBY!q|#l>5NO!$iS5Nk z!X_~PDy%*y0(<>qE@pcE#W+G6YzPw_p-&EFY6oDh4Jw*FEpc(Tp%Tnetx zhsDG^t{*2K<{PU`ta(Q0FXH!SIraJHZ*f+d3c||j3b{Hi=WM^=% z?cz}RKaf1|!3`6OF47KljmCNbUk@WGxfhFz@)d5AQ)w^PaYdQ6AfnaOJQA#XFC&I+ zY9j086@cTrFpH*wBYPCbJ~Sw0jzEM6!C~t;FKcwzEbW^ct>4i!KhwEl@YE<@`6-uq z!MNIUNbe5NrvxNtqx1P2XiH)78C=AvWRg~_Gp@Eete$%8s=h%CUJq51GWGG}y`;@&XVIJ5KF)Wa?nH8_J>ND7{S?06$- zLO5M=Zh^(Hw-c2Ydo!U+TY~$xR{9UO)^*aanVPuMiC$&<0eX`>(Az{}{?7&;kJqf9 z4NPbu?q$LXx10sz-$<*`B$U2?J6L0Bk<=UhWZ73GPQwvj$Yb8v7p*6m4htghBgc$~ zukReK`8ZMCsNeApJu+5>br<5FNjF31T0frmrPF16AdIQ^gosJywtiXy5IZRsrAdvlIMTZ)@VFh>Y;d9CF!x)oiqT z(}glBv2Kw*bZ^9Snfb*YR(hN)PEsu<3uN|`7r34k&SX|@B?BVzTw33?@WFR$F82>C zUt8X4MQbOn^?_{jAMZPt+U?<{cPTo1w&54Mz&MzHpplFH=H;}1pqh<{>V1S`ai5Cx z$0x+>qO+VxgaYkR%daiKyxgOoxS_@=@(Fg|Vs19V5oDiB)Zf`Ca;4mFpKW`L&!HzP zPRVhrD9aeDFeS}A+Fy=!j~IsRuHO`JwPdge)n-}+P=qrjg$@opF$WEm>y?FH_vXEU zO*Ic7ZTSE)V(`j7HHl%YGs7e03J+UD4aeI+ABWX*m60$`FTq-wq@Ls?h(HDqTDV0S zNzG;q@7Dd;kCtm8RHf6*oH>O%P4QVPJ<4KdP$qVuSZ{Jjo9LuF8ion5nDYN}&eO>z zV{u4TX#0G_VyI;5Lc2T#qjI6o5^-$t(>GYDlX?Zi2v6<`-1t;)K~{DGq#|G(U-RVn zZXZ47P?gi#( zIO&apm2SsZ!9M~Cl!$fdD_7{IKDk8+8Q9Y(bi2imMSY2 zoM;E_18)iR#Yxaf@Z2ip@1foaYK|5tS2>;LBdH%$x~Z~y=R diff --git a/lib/DFRobot_BMM350/resources/images/cal_pic2.jpg b/lib/DFRobot_BMM350/resources/images/cal_pic2.jpg deleted file mode 100644 index 0c427f041a44b94357a3fb7ed2ff012ceac2b912..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 11813 zcmch72UJtrw)Un=2c-xI5vkIpgFqCdiHIoDi&CVCsI*X{C|y8MKtVbPNH3v7lp@l5 zuL&JQ5^8{ym-GMkoWptN-tq3c;~#&>8e>ng*V^k_YpyxJIp-!!5EcNYn_9YB00{{R z@PPOS5T*eQfQ*#%w=eNSPW)1wp`aiqr=X#tqC7)KLq|tTLrY7~aF&Ulfti7pmWhpt z`5X%?D=Qr%`*}8&^JiIDS$-RYgpAmSoPwHyf|`Y%mY(H*{ULk>n9l&)z#JLLC4iKf zgp8Sl&<212fP{iL+utVqj}HkcagLN!XQ*jti8sKQ08$b%GE#D~-)2p`JCOK0K+a5Y zmiNka%5#PfsV+TZk$xGMd4^BD{2S}tK@`7??ek!28aDRx9Gn7zLc*6tWaZ=)6qS@U zZfI(0>*(IRXLR4##MI2(&fejXqm#3Xho_gf55(8+)$5SZu<(e;_;>FU5|ciBOwP*A z$^D#{U+|@(vIL^y-*7P#agmaflaW*XhKq#MhuFxN$tifRP@cVRNcHg9xl7V7&#sO%F7n{A;LXiFm>5+1Yf51l$Y+yX}>L&jS46>%mCX8ec>FB#c}6#FL@j_}YPj$r-rxTf<4qr#BZ~S+^U_ zBrZMIoaK}J9Z~GhI%s41M*={DhEFLV>4KQhVZl|i+Q=HLh(4_$Y$UgK)Mvf?Xjk(9 zDkwfaa5I(v?be<1i={06ltF{$BXg{%+0^ZqD!RyduI4DV!Xh&#w(2psUBu)Nhl53T zIH~NMMg7;J9bw~{>|h5YHwB#6N%f|CPpN&C6#+oNOB*~U2|&d%ekaHgEByO{m&$>w zKF1ZhBpatAz;u{*-w&13A{fKP`{F1XuS6+v56Cplpv0bVNZHwfRuH!*<(=_;>E~eS zZ@_1&Bw1aj$mh66+_Ps6e%bCUgLcPwFAO0VFH$`?x|cvk4ih8*rSfpufjT~%Zy{dW z9hW3|_-+@B_;Y<-OkV1rXh?=M3t{gJ$hD&d_Bbua(kETBFnV`JkTu%nG1`pcxmA(W zaUaY19H~xfi&jnIwwjX2CQ*X01ijWMOr)$2T5aT6N z04cqX$_;J$Qeo{}Eq+#?NzjhFw;le$Eb;E8YO@P&C$FAUZtV5PvdyuKt9U@4@zfy; zRqwSQDBlio$jwjPRf}+V#;H}IEcUF@-B$O$@!QG-tDg!1gP$^|4br8fo88veI*pK{ z*wP&s0T2)5{1xl|``Z4Y%w<7b0s7ULXtr|ZL6`x(E2rG*1dN-@+*Gr-DpWRsT1rps zcIk!iu1-D%9e(LD?gRrFcK%!NKNJT1k6jbJ8)^A7s87)5pXg_S=7k>BPyf7=(g%OV zkI=uZm2obMN7=zM>A!15@lD~Chd+@H1mGXbYWVxsnZGyeX`O8A{u@S^aQ4Tr%7`A# z1)KyZ+{F5dMcwVZXSwY;jaoN$ZWwm+fB9;6wdUs6)QPVbd{piR_3_a7Uw&LF)HEXY zsCwK@u)4PHT7`C@Rqp730IMmhC#iG}D@UhYD0ePvvazu>GV|Crf`uP|;{SmBP7AD@JfbB%Lx*irR8+YSY<%g)m^PPO1w;sggDJ@>8i4J12 zz+|^Sha_pEOT$&@i!CQ5QUg5@>tYi&*WUD={gGt6o8i>trsZ&kdB;6!Qk} zB6E@*1c&Ptxn&NX4mK*dXJ{heoRFkes#}9@Dqs)6lxI#B_baQ()oUm%e5N*d3|GD_ z!MC~Sq*6T8#IR@6Ek^blO6gsa6B5QU7q8kdx%h1!cP~t zn)eLKjm~7U$ABk!KW{xqy!;5+7)e{o9$YXY+n%X)_a;#<3KS`1SDpnXpg!1x#9q$xpxT8(5VSfLKxJ@d~`F7Q}?* z)YohGY33ckS|Py{a~pc+NBIWkMl(lfgm3tsU7-%vVItqXv@?@`r|qYHL4f%I)^qg8 zd~-GE)jG~?djH6xAPLDhMLOOxKGj=@ac$$_t3VBDsc0g(*~Tc!hts>v?0cTiP%lk# ziM=V~Z@(Xm?N9g;bO~3WqKfGCFs*cFge2V=uJYf!N{e$hsEBb@bZCg=5PudC(0L;i zDT^C)44mM2`Vxt`c88KBc3T920zWAEs=%&V}tpyf2{c=$+ zl{_v*`9dL)1M#(Hy2yHJ{23<`9%<-V*j$$6v`ti-))oFBlPSL8-r&#jj@>&kNSRdZ zua53puNJIdlABvXT}G^Ax6fK*(xis+`aQf3(ywq)p%sP6%(#!-@RTC=SD3pTp-D^0R{t`K2LHon4}A}6W!{7RZi7Z4Tn2JkPgkSXy>={n zaR%xXOlp5ifJ9Vg_?qfaYX1-T<(C!glu1zl824$`%v1RQ7Io|hl*I^QljgU9;b-S5>M0p9+MhcB$()lLIbVEy}?Z11S;k% ztOY(9KVECrjyKk^e*nFHd{uVOVp`^mDAOH_iKMiY7MGQE&AMZ90LpgVmoE z=J^S>5qxLLez5TCoy_@ zn^!koFAF7J?N#5r`?l|E9RE&L2_Zj6SB zNG@H+n$)z>1p8UKPU#nBI^Uc|c$Ci#7vD;fE;sacPFD=Dz~uxO2z|A1ZWQw2i9j>+ zHYAw}P72|B@O_HST{`lJ73P+Zq=Z@%vKUp94roRjX&PbNVljB?i#-% zW0qr}Qj{P0R%O#ecm^FBf8IV?58ET(Jh=~_gtsWKWTV+|_*r+K#X{jCFQtngp`H;u zEd!Ky`5d_vo@$&Qh-)_-BLI)w*v--2*~J8)MHflS6{u}eHZJKIr9os)?A~tFA#++a zG6@7g`sMuW8;t758c7lJJLVwb_l@hvVi>EK*xpoNEjo?bZyEw9T_d! z;youC)plC~rZ2a5W>lhiWcx`z+}+te0Ka0X9xE22%lzG-d;-flP~;}I_4;sF!xhQZ ze^#Um{q~Su{Hc9(^KDxKaPu8mDQ%+43ZIX@8XUz3$Lk+Tro~sh(>o@v`ib6g0}mLy zwYsp)yrw3sMqT~RYOJWrzsclgh-B4zB97PcBc0)#?|?`!|K+D;I(MY*OURq}+MTG+ zT24C44`8pNjVqC6o*!UtdOAY{pz_dpP{+*HnLi$FD|qih2w#jY$R)n3(eYkuI>}>C zM*0mk&ZKrV{!y&>v(Mc*=1w)c-oh@gMp^9Tbj8C8}$kx?{1GaUS^ASbB2^}UYcTSu4za>!V)hDiUjNO zIkc?^#ujBsQF9)GEBiwnhW2OWXSaVomUE}oL{Revd#UNaw|!dlW}|n70OT~Ab(4kg zJ1V_v2a%|Nk=?WEI~%+AY8vZ@J#osSQD$*GgGD9$wbixZ?-dgq-q!TiF$~Z!*UEUW z&!ZZ!ZmymUKI@L3@#%rt$91@_S@#v~gFYDAQjH_&YZ^x*n#&3jqso52y1IGjSMrEl zL(faWNbJ|X1=3u5FH$A4pKckYQSgO~bZRVX=|-{_Znu#$a3(n*smx}*HzjsI zIV74acm8R+V@3eJxF4?(fMbq=4O;NNJ^`=-5daNY0E`W4Cjgf7N5uwrPF-K4U@`n# zV=^TG9SLxpht0BOf4c$aELIJrKL>mGxwUYf|6pvuY{rVqbSd6He8Flcd`URt2Q}~c z1<#V?QxjfNlZG%XA{|>#;0)8Z#nVQ8@HZr=L{MBI_e<5WAW~pzfihj9N*jX%MT^`FEa^SvUb_Lm|6{&6IJ!Gh7E{& zaiw#bWAY4#iiP4=hA3(({mcQXHEh(WT7HP?M1)%y- zdZSbg75fS{&k$gW?kg4Z^PJ;GGfqCqN|nfAe`dhK{MFVepg81=`rLygrK{dhRzG@L z`__CzO%~vEGh%~oq~Pnp_)r(W;C|da=(sik80ZBU2>_@ZIry^8mRF1BKwNQ+rr|CI1Ob;JP627@91 zoIs(b`DqzkDFIzg!mEJ4zYrNThW{bO{yA<2-6jaLQ$qksT(JeiGXnJmfoT8ZKtYVZ;9FZfQJ2tc}jKb9kS!|WbE=_bN`YQ!;Rs0BtS_{)0DXlgslO&hwj&D~jm>_wJ z9j{dQpcK*V2bqP|dM-)xj;NJr|Ds0Y?Q{ue%}>%F;!x8Z2Vqmwx>FMp#n8>;LEJY- ze@+762HM^BB>*p;69BYqU=_5#X%$b>O#s@)0{g!c05bDAh{Oyga>^V1PI*mws<5B_ zV3f|gE7DMlKX16tscEk&^g*8A5{}LFM-4>r+)nSn>x>;ZZ z@RXRSyo{$;tKPSfD?CXovXb0A@?k#(Ikr0X=&+Fhd{u&Ck_!+vZ}3#;dPt}hRoih; zfg@svGB?m&!tG)gyHGy?FkYZ=Yd;?%($&U#(O>}-8FT@Yg!`P#-M&5L*?CvATh-uJ z{cuT!M8jY*?T5v8c9J3|-ql>>TZ#%)UUfp#+Srph=)wg!Rv&a4zTC*5*2{wK(~B^8 zFh~H@4%0DIk_6zKl|G9T=ck%e{gp+l5)C9Dmp3a=B(uMXn~DDFn2+7eD-w6dYp{X# zTc9`^5y0UTm&?l+BLJfcI8P{!Zs`0eBlZ`A#?4)d^=rj1;O~oTx)K1MG6GNwPSE?C zk-HG`&s8hMj@ZeV0POcd6BMC8Ol}f&bBh3E*?)fBFFq7-BZv;Gj|rC}01S|r0}zW# zxy#g}(#$ml^CF)!Vq06iji0BKIH{r$io4akW+cXnPs^OtMBXi|#x`G^g`~GM3%c5{ zY)H8(2jyn1nJ9NFM~Omsh8{Xx=%ssG#ZQlkeii)YDI)MVQtw8SQqaw@qczyhuFsQR zxCNE~berU*$JcboV9C)`QM{?Wd1vx3D1euL&t`???IX7U47UN%{|oHJ)=Yer4Ps%-@G=Huus0W zgl&O@LP(pdvOWd&!V&O=X|3Z-eWgOR;+j?H5HWh$F`%E`P~*X5qhrnA>5SyT5>@3b z3@R3&Kb_ew7CzNYX=1w3z+c*r#T3ZXXR`^}lZIXfMXS20ypcc{{# zEkm{a2SNuL&=#-M^oiz&JH&voe>}AYuj+sFp)W|k*|F0~5SG5>Pq%-ff&gp?Ik0JeK4g(S{rTMYc4az^iKiMKTu7pdkQ{i41b}kjNUoa)2@WpudWyS%05tc+EJwuIhe! zV=t%l#hRB{z?HimNsn=Z>vKhe*G&JvtZ}|qvGsWCvFbrVpm1#SPKd~h;tnl*2d+&#rYgi<$e?r8KxZ7^m(=>N{9y?`G1*%0!CDG1m-XM@d;vd@zw37cP>e; z3aQ`X!Kpe*LUeVT7I=P4?gE^0-eMB+s(p$f%=f7+)AWYp# zzJGt}`dx(;b&tq=sJ9xy9+{>Xy>{hr)RPoMpccKOVQrbWdU>2k+ai>1_Kq zD{@z3bj%(@9j1$kndqw864?e!NzjF9h(sT9nZxu}=vtk_)SM-GF9VAVbLIIXqf{5O zoBD1(hpu=%n{8i)%U1=rYLLkES)V*>8=1*pYJ8ZR!{6oc%<1i%Vrrtb2J+lA`s%FB z3G#_EWo&a=qjqnVFRK=2mog7EvtT+};cQ#5Xa;}!bFJgg+tuJ=%2m77U+k((S?OPw z$v&;U4BAE{%R3O$z5wHs0%wb3JiKpwGFx_feUNCNRy`wyv*ND*&dC1*2L2y7tot%j zcXTh3bPB;VPI)UL4PjZdNT+Uh7V32;hAQ4B%m?w*rCZ1Z#!9}5^ha_q&Y-a(=ecp` zz!kYK{vvk^TqhL{$QnTWvb#9I5Y_cNIrO^0@)BjJ&bN3HPNWJURU6oP?#p?r($_ij7-NN7V(85Cf0? zPy&E*Cl1n1Bm;jNGL^;SAw1p&bCv)sX(XM)5|#Ta(Gv3eI$|Yk0O-Ij0*?JH$AtET zwk)HlaExkP1mIf}oB*&}ClqXW`$?pD<-4#yH8nNAF+5{s`GYU={0N()k1c6F5U=}{ zv`CcdPM5}I4suV~fAJvq|M@|AniqbD$h6!>092qTb^_4JLyWclJ0Q^CP>&Z3YRhvS z2@rsnlK2}+&%pg4ECm7B(N6puA}jfX!imjlW*g_4>f@02*;i(!x+=aePQHKZT3jkq zQTa*_(}e8y*BP6mjh57hCklUOE#a}4n7idU(@B0U?S#Taobzo;uyebOaq7Na#V-Rn z7mwf+eckCBqgCz=KfUf#q#u7KI>1;0keQs8QAq%d=J$!avL|Dy?ezbUP2KMexJ3Zo zQWAB@jxve>Orzp)5L-lS1DVmQFd1dzh&(NAT+!3-ZS4T>W5o@xju|Z|hd0tkRa9 zSy@N+>2}1>CESKyjRkY>zzv-j9>D9IL$7U$^3F$LBIg!V59&+p#G?5RmFE3SAF10* z{+Ry;gl&RAcp-2b&PE577iE(QuvV+(8bPpoDgn8zdYwtvg3(ehm zSaEW1YOg#C zo?6~wGYhx)8wv==z>iRMTq@Rakuic;F(UwMkm5Z>6O)ifmBV|kW^bqS#d12u;%h$G z(0o%D>`9mvR7i{ISRe*7dvMlXWRxU1#(TJ}vS(a+Q_5LNU@5+$qAFTSe>t)txNVi8 zwXP&qcSy{WTY27KSgd$&lh$jJzBosZ#ZWTq%M0LuG}D=-e)x33km8BOVChO!lH#4!yzxA2UdTxRj zkVHebDwJ=Y3T6#X8`%<#A`l)-%<`4EW5@FHPhDp)#Ej!r9}tNt37q-#22b!(o1*8Mg^Mf@x*Q5q54U*{Q%(P(t|&7u>J^!E1%0`LR2!P*8q{xYz2r(UC z^X4@=d+kdzH6|nrd%dbQT~`4u*YG-d*m&qy)pY)jbkW%1l@4L!Z&U5w)nnfj71;!z z92gFtloNo95GPTqCTNr7t`hif2&4UOJOMP+nGF<95Bn@Ai);#>^{${tWy?Hn*-gxkk0DyPlUv7^#ctN|d@UH$&m}hL_ zzB?u6m%%y6qD_i9I_J3L9a5iCmFKEnL%x_`wUl#r!1|*%50iz&JsPFr>_nDt${(me zBR#Eb+VFxy-(e5YA}2_Sq_(Sig|8#z3=tzkizDMd;#i;MHR`!7RU2`<3Uyqze|V6~ z`YcHdA-U{~9Tz>aNwP7%k+5FtV+>D7KH7#F#R_3|Kig;oE-pekEby7{K?eKIKzK_;|A8l+&mo*;KO&Bk!$pzeQM5n(H>j?9d+h^CJ~m#!+{{56SuLf4AIqozV^YPp+_$|zKEBIeoy%eehk z#=Z>Ff1#C5z#sLsw2VJ5UnpPwBd(78(|o_65zhKcQ=g9n zQW>DK@yx{_{7Yjnh9MncZghvz9m{79#*r35QQY8`*#B`3O%#pBMQNc8!dfq5o;K-%9|JNA^z(dnAKX#NUd*zZjSAju^wyn~W!~j*P1Qk|j3O z49Gt5!%wL3;@!HJ-M+7S4+}Q7$`O|*(XYTPX+;I>Z#eC zome-254Am!&+~O-snBy}Qn+*jI&&-Yv(BQR%=3Pg zZ!vv5k4>LpyfM8_%n@V9=lozShIju`&pAzS{>?hhzZFFW5PdfV3tFfpmG;{lV-ynn zQXC5nRK@mwHkHp*OO?G+^uSW5MylXJoxhh;1W7mFgQEwrC55|;c$$-<&+tWXnA-U= zU-A8DQG@!C&+!k#d1wpH%F<|=*19VExCn4Oy?tA;JV7;;TKB5&_Q-J%XN%Y)*PHLx U>pF~)>7vephx&3mj)cko0vFWIUH||9 diff --git a/lib/DFRobot_BMM350/resources/images/cal_pic3.jpg b/lib/DFRobot_BMM350/resources/images/cal_pic3.jpg deleted file mode 100644 index 5cbc8ab913feab4cbc4b4d352998e993a6ad6979..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 154473 zcmeFZ2Ut^Gw=Nn4L@Cliy3(aeSGpoi1O(|VC?bRqBGN*Qfb=FHAVrFFX;P!KNSEG0 zLI>$Bp#})y=HKW4zwg^;?|x zI}sCc1Fp~#5z`V~wgb2T03uStX#Y0gzrTpC5XN|w?Amp53POWg8o(7IV&W?##D5z# zp|wBZIDmwfly?7IJot%mJCJQSczkuK! zA!!*|xqJ8J)gGy9XliLcer9BBVrph?VfWJhm4hS5$<5uv(+lS96Z|eDG%P$KG9mFp zQgX`2)U?mJdHDr}Ma5sLs%vWN5Z}Jnx3;x+bawsh?im>!8=si`HHBJSTK>JVy0*Tt ziP=9mJUTwXo}T@UE+PQ&{~+rR%Kj(1XbE&(At50qA^RI$L|42Bg_xFv^tQxRx(5bi z&t2)cB?GT9JdDq&Y`M-OWr${c@n)EuiC21&5A!$D{)Mvt9AQEKOO*XV*q?Nv0F=Z; zgvBGK1*ibd+K#)Bvmc5@5#cC#gV4tM_|V^2HSVpF>7 zWVjKvXcQ^9BRaYx)xN=dLM3KluOasI>VB#=MfZK)JH(sRTrhfFY(%zfO0lq5H`5Yo zRnfbyy4+KT< zQ${CarIHNeQDuZk*TMw(J)i2|AE5J=4fA@v`t{w1lNTu-M)e~&>q5}L2+ZxtI4(ve zmGNO{kX)+ib9>=cse3~0FKq5M7`>73vuMKFpR4*Ak2M;U+4L`HraJGG<-3Xa_>b4c zfqYk5xSl#h?A-tvgZIm4NB4uH~R_buP@{p(p_8rhR~FQS zOYb(~jhx;mOc_3m>63Nei^;r?0e0wNHla zZgmw=ea|IMXbA2Y^E`kZwPnMKRyocJs}ZLHp(bijg%SDS^%rSFRv#fKvzOrR1Wuhn z-rG|jpxrN;ZeC=|gkk*q>tV{&*hgi4+R(+~+G3d(2vM2#r;3uApx^8T=i$RAKcgGp zbKNXEub4tE?#%dDiGH5x02ls3ZA5_}U*^=HULa=)66Sc`9C03lr0LhZBvQoh`>1u~ z+JIDp$4Du?+2bY~4j<_JPdS^874J6}yAr?E_v1e7{ASN6Q_oqu1aQ^t==;V?m z|Em-Y9LfjnOvx7S3j4oBvOKE%=xj6A9zWB%J2KPy!~31a!@|^!=KEOP#li4NrUS6S zrsZNp_Va=*xip`dNA2_sTTqb~?pyCZNX87lm8-Lb2H_d>Z>leWEg_nZ$7xhKq(8kl z?i_*hJyc(_Xp?*(J4T+>sBy|@g!=+`;O@N}cCLkudRiB3(1`WiC~%VZEcVK6E7)v3 zc-oZNn@EJ%H-0uizADN0=5@|Eg{@9bz)-*~%u80LPuVbdD{3;zLm#0xVKOI}VfJep z<)7-nELHn9O*koGf0nA+@~UC~xAGC;VfdmU*4n*EK|iu{X@W|gtw>~U1iy5>Y+~_o zpP|uv`AW*yi-3175X^I()XjIDG$fVKI9nU!NX*@YA{2+Y*^*na#xM`L#fOm#` z#f7hzcD&y)u{M3g#fTTirazpJ>33?=MDKh`wA`>@s`SX$mQJ~%0ZuKbO}KCE$`V5# z@WaqhO?KqdT39m&%&Rp;)|6E*l_R>&2R5=G(Xa?<+nWx0tquKH*-NLV-TxF*(aJ>$ zy95~3j?3JWp|G}?qjyeAjwqP}nZBZ%j@FmSt5oP}SiRO~#Hl(c^S~`=60bA^qhBfr zTu|8_$J|KgJ@zr4`_9qv8)1Tw(%h$r=ZKr)iLYk+;9K}^*Pm9IGf0(oog3%bBsMx zl)5P1F=#D$AoR0YV}<;2gk(<9T)>F@A~w-&p;w=BBgIXJaiuA=7+f@8n}ZCR%7^iN zgUCQ8!J6E1Nzx-cVyw5+-W}=^FJuMdWEjAp!dZPuC+(8-e$8j~O%2H#-1`aIVggAk ziO%p_rZ2JqfSZh*sc7+*G?f_Bj^ug|)YcsjSO4pY#tjLm>uWc}cq6Cs@3y}@U~g_` z`?!1GmP+sQ&_4AQoXSba^ilC#7^8QHs6Mi>JRU>Nt7@Y}Iwhd^HOxiV z=0e37jf&q)Yntcb2Lp(PYluFpeb!d~P!C?;0Q(nNTbG(R_sl)?u9A3U81Yq1u_>E> zNW!E>KS-Ho2-5d@3TX2fT6V*4`DX z84Ii@2e?yNWE`hn4)S~tE9p#2{AD?1K7;JrQLx$;`pj$izPb|nF=VD~{erp8$1CjR zSeAa>xq_1^1n%xt?VVWlr5e}1e4D}6)^+6jCx?Z?cQXAl&V{49Wvx!8tc|7?0r?&d zUZi6yeIx2_l*J;xxGu_~#mALakfl!{Zc(EFirCzaIJ-P7_{Xs+r?6Q?-netEzekzK zHfmxWC9mnmQPY3l+c?^xN7X>vjqQb$TnjRM6sLtvT2j)Jf`js{VV0^$#7M=D@=UJ=eDQ(R}=#zKQyoO=-BI#}}{hETGR&yj$?lx%Xr&u@2n>vxPL_sxsa)Kr~iDUrTEGs{b(} zE?FEq_BwiWi9ck?+P4EpjgwfiezV-E%ohvMF&(*8|1I8bqJlfdLYtnbdG`9@$isIFcttPoqzTRrN0+YGXkbf_z2YPS58ktji%{ViGFwojr3 zLZvz-SYS+i?^a5O{4=1nuD>FyN_1_E@~=VRRK9rIpdFrvyM6t&8s-s-iPrjo${dbB zs+#j@r5kLumRq^LUdlN|R=}B=0XwaeZl(4Ft+kg1*)v__kyinXvO;S*>I}wojQXY{ zBDEL%Cpu$gFPcUxY<oUX7T>?TNmw@Y{CpaPT9j@&xtQlL@jBFgR(aBXl(x#c49xA;_JOoLz3$Icno$l(#f_$aiiMj<4hM+Qg`?{ua5 z&S@W(Z?Gr3y_M|KR?_BwKP^UJ&~__)Z_0W1X%;&7TnxA;unKQ&v^7(JO1|91^~|m7X78P?z#woM*6aMC6Ac!qQ~7Q5 z2pNIe&G9cPk5LYTfJjhvNf1HfvDy5DxhbCKygE(hCWbx3w@q4$#@^Iht1PH=UvxJm z+CNT+shGr5pQ<#8qLh07F}rcw-{Fl}sh0rq1KEoLY4AIAAFD&CqHY=3;xJ`mc)iYZ zNVGq{BmIl@gV!T{@fyR)D)--aPAh9dFnb6z@zO*S#z7zR%q#t~SD2*a_Ur?ti#9pEy@mE~ZcZ3~a2zGQikOMqSN*sBnV zOMs&;i2c<)+&jT-KHiH7;oH{f;waOHy1wmMG~A8jwQypUca2K^V29^ydW*XrR1dGh z7N~-LhmY62{2EQvKu$Hgc@77nl^%@fqwbxjRZL?AuoHO~{I^ zL&;0P-+K}KhrEUueQi_iz5nRr51FeK%uNlej!5|j zw`%?&4o(J|Qq&Ig;{TR^#y-cs;vC=y{?YVL$thN6?^DWng8a90U>JG-qwl>`_&yzK7J4{ZC@4h@@6f!7LqPH@9z zsL?ajeB#|^7C%7*){3XL29pvl<9}mhe%r?;;)|7~OkFyF$JzDcqP9Kxm!dLP-cm-G zi&>WH`4g3cah1Iss})9F#J7k>-NhKW4%23?`iA<1`_j6PoIICU7|1@TiJ18XCrwMS zQ?dsRK7Eb9g_Eep3{>WBCEEy$qV(!dmW+4tZSy#3v8D?kdWl!EJLl#~LMy9uxy-f$Q4vsPy7xhvu}S;a!KU zYeb&zv+sUIeS4epuxJb|@YXqiYaW{n=5RUN9kd*KIj&M&!AeZ^VMGGdm=It3(G$|H zwHE}i&W%KS=;z+rL5Tkl)exwZ;bY@OyOqDL8Zm@e=2Z%>jhA;l!D0k=XC1B9#63`st z_Ted+=06(6)wB_2?iv1!alk;8gA4VXU@#Y70{qF9|K6SHeRaSelPdTp6EXaE-~WTr z{(DaTh3)>EPyYWUI}eV3?yJ(V(_J_F6&*``uR;XFU$_M4#F>sYvV4Z6t+n{*g%qHi zwb9iMB$TpeZ^n`Dw`6@tZ zL7BXhiY!ZlWz8M@h1pHt!RfYry_A(!ZPH?lQ>kWMO**m@M870AD=t76@Rq6O*!hW) zLwtRzJfg!FNxJzIYsf*?u0q$SV{eP7kFF=J&ER|_vi-GN;@h`S6-j+jyjBEn=T0R< zQK_}>aV5GuiMIahaHHmusHD;rY6h!KdFupk*?Q+Vq0~IOZnjYU+r5t%dgJP&jazq| z=C9Cg8HO2+D7q~TQf}$m)_dj@Z;Yb)#R};fDSDqbUfs0 zFsxK_G$(gDoi;0bAX%XTx}eY=_2_LfZL{GYnb%=;?{$#LleC(f23ncG{sBhV?E!hnS)Wa3R0A8!j<=uUesUqW zs4(dga7;)y)lIL0H{gt)k(dw7Ov8S1OVl)K1=6zhnMmp>lY!1x5ieD$ht=cLec5gwy=gDtBy-3$^=c0wNwC5R!(B( z8lRxvmj7^)IjF5cg~njoo{a9*Lg~TBnWCe$6V|}$J95Bowin@zCmXE>o zVj&(>H7AK`UT^A#bZHTpW_i!<*b7xbt;6md@UMw)kLS#Q(%!MAgeyKM0a|aM0y67M zM=jetT$~-!e09R3X*#1spmNsvW*UJXR!+>JQ|J0)&N2*>ID;i>`c1D%R=*LavnUJA z*OgONWqmZtwuC$wVJacn)_TQ|V=v+NGn%OP^zY!a2&1V)9W8t%W{)gw=6>!lV z2(&p&6MYF-dZMftW~MEz1Z?vui1QTLt0}X-E!Dci`uLqpV?z68H#d#JbTJtTt+nYi z4}KeYvO)+BRvqeJH(zJn3-_?}7VwREvnpJYloa^rWzaoURlqGsjCQwT;&kM6={ejc zpT@sRWw-Yd5CFv8!91zHDxCFUA=L1ik`Gsz_EXDCK-u?8KzZ;bK-EH3**uvhzxse3 z@I_mo;=y70v!#k~7n~Bhy3?XFMGCbk?-}Fm1(8zE5;F>!VgpCB)7-emGf^KEcT_ij zG;|4Ar!rEsTx@`{z)a1D#9t;0E13*{Su(GXL?+zU5YoEEF46gbWg9HiV^}EI=J}~f z7j&;P&#JEe`$1Vs7o4FNE$h#)sTFXSuV-CiR;JX!y-Mvk{D@0{JcKkyjs!sO?h<^j z!`Uie9OckD7|eB}QFr-UMFpGr&~^p%$T6?7F2X*6(d#yUCR6I*z?|`y#|z>!Z13fA z1b#p%3S%LDmUY`(vS(yCo-eDx+Pe9w>*e-tX7S~k-0R6Oedg+xxQ;qck+~4h9c`*zxxer! zJAYUKcN%c+lynYyY|dm!;P}R=XT~Jx9Y&)J5O{3-<4K(iNsZD zMM!k6H`~tjhE4NVoU3nGXhzFeQ#DF0>7-lp7*>zeioT(MQ6=R~Y7?tkN?o@$o6*SY zV*7AkjPY@`cSRRiJ2l2nz3q!V51Eu+XffQ2D_b(estp&7ltk^1;+89{qI zrw}O(mhNkJbG&C&j-9H8rTgiq*gBi<4A)Xo&Zre^)|I`OWSV%!DE`t!$0X9sOCy@H zvN1cGTkrdTT-EAM#nIL!AmI|=>+8AdIbC?PaS2F-yIW?V95nA_w-vxlJ6LyXOS*~} zhn+=jnN6zAy4k&6>)EGrYigu~&KVrzVyBnqnWD~3uxigL@#9TZ6OAg1-)n^9Xs5vS zwN;u>e|tdO4mCTNM=xLT_vy90tHuPMu`&kG+B?s%X*CwH+xJh}OB251C zWbNkOpV*EnE-gw@lhg<3O|n4C|hju>QWZM(9K^X zv53JXgI(=^|KtsCue9V<4=#E!qOtvpC<*{b*T)J;XEAD*nPW%WCyKpAm@Vo)QK0zh zO57MgH@~Gb;a|FJF<4HJMX=fS*nWLg)?Yq9IaB7lS5}rkGH7Eue|F(Ht$QR6<67!K z#2wB0bm^h-2-4&zZ@0o3r<2!h93?Yt{9Tc^S5tYHDLL$>qKj=8vbXV5TqlIUEm9oM z7_%@>@(as3X%y6I8S%_uY`4~2w@sKa*_$%9B!o*);O!gNv9xs|(>As}d$=VSyYpKP z^LW~NdgLsCgv&YZyy_A#pF)W9EC1Q062p(+o%lBiE!qLU++1LK;fZf(_f`Bq zX2x#O-s%Q0#k}oaaEr{$Cgc*0kVnHRhZ3svV+7vdCA!^mD=8-Y=fVNuXf@&J{L%0w z;804H(|k!+za6iHttf^`J;KNg1|5E)(5)GRdT>ahP`>Bi%WXVjdF3Q@7+i&Z^tE>m z^z{&_mNi#&08tc=FEXT+_!?a%Q8gmzE;2uxJ6>hb2ic`9@hIjSr{>mbv#s!It`xLrRIix~Oy_ ztD57My=4TlI`DTY{eh2IuU7EYOvH)hIX>4b*QaY$NqoeW;9PC? zD^t@J!`%o3P6qE=duG#VjEGEtN3({+=9j}Fh+&%w*8J1@_0vxC7(MmZLo>o$*b|lJ z#20Z#4Qw2`CKs6j3i=)k(6D-Fcny#~bixj-0A<_^5~yu%Fplr@mSTIW6{%Xm`#7$8 z#gj6m=@yP|XfP@V!;CtjuIng^@wPkQ+3#D{#Sfq~`nLBqwjC5s2b3*Z(fZrd`B>Sl zwi1CzoNmQBp4}lub6Cc_EG9o=yR`YW!~^z(yXJi4eDULcZM7O>C{LX#9G(8!bp8oF zB=2k*Gl@oBKzzZ~B5;tkoBom9ga84oU_FKZq&s_i4*9LsMo? zfdTc73VGwmvP%F*W3BJafNR*5=g$`^u7NU{hZNl~+$*^I4y8IgN*O6=i@vOH3H#uv za69k3X@Oog1$s7ifKht=;EwTP10y|1o-9J~nQa;+r@*)75y)-YY0yYb@9Iy1WPzDX zwcQA#-ixsp?4s$wsj9XImBY8u$mm9cMT$=fkLu7kM7>e+8|@;C>7ZK&6H6$wlY$Ki zUdNd8PL|FgS^5R8P|>nlu%$+GRn3^66!kmQwF1i9)lq}Lep;JHXAvCb7gMbn4);;H zdWNpMJJ{(J^y%JjT7zK~@qxd4$_m)pYp;Ut;pB%nK5|9AMo4o$SxOA?{B#udmJ>{{O-4;I`$rsqui^%ScQb|1SY<-8)B^`fOAYJGnLSNBCYzg8-gYZ#bz>xYS*35#msQC z+|Xn-99d{fwx{#l=iDGzd3LPhOYNL^wY>PR_Vzrtg5-k~#y+6xqAfRrB8$IlPRQR# z^(fl(N}dJLIwhe%O>Om1n3KI3{?Sh)Bh zo3)+(_ep8&a`M5G&<)PjDRz5St-zVU2D+=h2EVVCF&JBG8dZ;oPAuVfDFj)~7U^al zR~9E|UT1yzUQVj2h(p_!jQ_1D0a`*pH2tF(g_%}<8{2hXuYjzKiQ2`Q@6Z`bw#R+r zkta@~szht8f$eg#DclXT^see(iFs=wRFGI=Mu;oa+ z58k^xIakYuzy60Hs0ZHoV))i)`1*^&B5{>*@e6nT3(BV?|C+o0)ka7^{Ks(rG3@`_ zZ=%1j*e1oFF7C4-5~e?biNakr`~=XBc#HBa4E0p=^hILf4A4KlZyz@=B#ub+0to7W3cA(P=R4f(bg6%1I zcsA%D7l%)e>(1Pqx1Y1^7mC$gh;NMJ**3jwST6Dc*kOZ9D!AM7)KN7M2XinjocTDQ z5TfXIWq?(B>h`O66UprynBfiYiYFCHi7ja>SzY%UjUAXi$p(7l@F&9f>S5)Ov^)99 zvXK(>B016NTH>5Tl5*}94~v0Up#IQHK%hbZlPFGa8gwd*m-{!0=fA9Q3L`tc-^=qG z9o}cS1Z?+aof4ulanzV>@*3lcKdZUtl52Qx_;MT0@k$vZ_|F=?j}Uap1Y!yCA67t# zy2W4XD%E1}wG_OfO6OalVH4yZwYWd~{f{mKV{RvON{A65u*jt>#wez-*eLWan1FE+ z$poga%ql>{gKJ!SZ5LiHEHfUe9NQ1#2<}Q(7u%=7oJ8T-a2E9#U}P=z4OkC^XR*Ab zblME|s?%C2GAhbcXh*ca)1Z#3DkhhF4b)$7?&1$B7bq38UTCM+jf>7AzqX2&yP~Dth?E!L-Vvez<4Ea zT}fCkQrI5eX$bdEo2(y~M%}jAX_^MUd(phZ`6=^^XKjxRXMj;5;FDlN^PQ|#tTs)H z^Wmc#QoOX9)E`y8imjPA=GND1{kndfWd8g7dryL~KXgem#?OGdothFW(CQ^G7FXm{ zXPTB#Ux#!M{VmMc@G$gd*>W1)zLb?PljPgTuoXxfM`0MA2J6u3IWd9adMB;RI)_@` zd97af>%kRum89RNUuacL_aow7uRWj6a5cnsExH6_==DO|Is%wS6m_3deunLMq~CK{ z(gxg;FAaR_OecB2MY-np=*oUAZng}LwDgN?n#BauuZ z!R`YL#|bkb^09EU`d~fB5rwF_w@{s8arz9a+|sAhvw$yhJt25Kp-X^`nV-bc4#S3z zbLX-aHU?Jzq3*ommc(X<;2q}k4--LF~`}6q5Bv< zzBVd4x9x5J1l}x+{4E&by-?J7S6Cg-;+Wu_-YAnVm&!3Fp01_0zH6oZCM?#(lqkdf zjpUR}#`2(c%kC-i=9K@y-l(oK==y%Q@__g*a@hf@0Mz+)I?=Vv6@%x(26R&CZMD{q z*ua=h+I_58b!#?{ua4X_XYv9~@7zVEF%K98i)084?r#vJVXr-gtd*6)Gr^G=FE_sZ zYLfZMXpMHcT~Ifj=(+`X%kgW>-C0*&j0=DyFhapUOBKtrK=AQ9N;^KoxY|&P79$_V zM%tbr0-+yve`avU-Syi$sXj>`8=DirDlNvbsTFiAiIc7S99r19RO;&M2dzM;i6zLM zeZ`fWxDNRkkGtgMO#<7@RVI|bD2dtW3JMmEVn&2lYMR9To&8cua6k+qLVAw|Hn#-1 zvem{6yk3UW!c&daY?SYquf%#vH2CN7th7+hJ)Pwo`@!RVh@|&>fytx7Fh4`%@C+k| z)M4GMvyP~;yb&9xdo{5ek$s7ur*cb!?sZ27JgvKSN>&B*V?f6ir1{vu1lmqOh33ki zURH0^?TSLIWff^x0<@--4WmMMf+X}N11Mqo9h}^wjSot(;t$4;cI0fU#>H#4yvxfx zCEWM(?M2eflG(Ic?z4}}RyeNLp4#YESPFnu4344J%>mn{Jv(w9<%Ln3^Q?^lnF1K& z*-yx@9h~@Lznj*`>S%?ifP6@wSEacW{`3`XJ4R-T=j0994=a8-xokfp4EcKVUF>rw zlub$zm8Nwjk#f$BQ<0txMB;T@Km5)mz~gHj_0L_20dP~w4-5BIYYZ!&>mW$X+p>!m9ni@k`C_43pIyfeI z$SB)#WW*P>L6-nZq|tmI)41~ue4|hP*eivX%kfk zX}lMv81_(PE}B-QQ~MfI=))u1u@b`q z77g$zd}F|S%-34)LCUW(uO&!c0tD)@`iq)jjU;EmFo)JOl`zYvDFclV{vNhxZUQQb znPzO$tBM(!`ejCA1b<4!6r+WaISIrm`7Wv2@tA!Z75&}VXKx|3#wfo3;b9}%$S%7e zZS7s!u*KFIA~VIN`Q*KlQHp;fvaq5cZP$&9tYsc7HLR`A}l!_?gwAFEY!hYR+Dze-X=Zd+zI$a(Axtb{c=+ zaIEatbl&%E(RP{Qgl#GrorSxt)-sO{apXdW2WM?lZ%@O&I=~4iTF!GnB=W$2zG={6 z;10@a_7Xttwu{nPTYu(+K|s6a&hfoFg~dx}avc?s^*d{Uhu3R95w}?!SMrypoUnd) zxbZ?qE?gvnv}`-F^t?x!e||5+gO$MWZ!f!{VIb%KVG*Q$bUbJ_`vhpD?y?IoE8^-Bnn;P-m(!Mm6;`< z@0g=w@;tWi8x{$$Urpz(d2(X-CC5Y|$#l&Q`DP8`FH_=2iw;08#;COUWD%IE23igktSMoQ za)pjQ#&s3NK=6d&oVEx1NKfGNN8jE)DiWP{FCCDRj|m2ej^mWE`bDs3mKe=&8E`Me zu07!P_gJ0u2Au~Wx(DRmo@m}z+Bayu==y$FYpt!Y8G9wAWb?Ime5= zn^rcFv-n8}%7A4vm~^%usX4Dn*GZTYG!H%SI3MMH(qZmbO+k7Iup(12wDjXe&t^r7 z`I(cwt1(kFcH>G?{>~9i;V)z>HjzQKefP^+6b-6<|5_=FvIK%oa6NE?>UV9IXCkdhwWlsA2*P zWN!rL>SGiv)3ryK+nPy7bDL7M)V*aWrhxjEiPR{PAi;PtJzsE}UFDPbNmk}@7p6yHS+e!fz1PtN+EY6- z+!=X7YQ&v-ZRO`v28Vlq8%a%?gME{hxbj&fb+2B5^hlVH4?&s;F!_pkm+;d#J?uHg zR2_X>A{U7hE%>D`G0Hu1B%D-RiwM=3&aX4gWb@ZMnqv^*rGrNGp?=C{Ww^shk&E1M z$067X=u(WsqlqIe=_V@0iyN&vg2U9)H+kCl+P5nX=ub{f)B@9v{Mi<~g8l9pEUiLj zWh0iA*L#u3cd$8nk<#yR{?gRadDimv{;uc`d;R!di0*DbCG5s>lS|iPW>bX~OwXUI z^TZ9*oeN^BF59WjlR{=xH*QzGg$$;0eQ35hIPaQDIq4#7NNbq47!bNV*3X1{|7yMS z^YhnnF0+{dayuxkPS;rB4_JkBS*+IrKGD{>hJzJK-|%o>9h0m!{(@m({uBaS-raQ)20sg2VJe=(aMroB{WY<3aYFirULsK zc6HC9a@2j@9?=w0`uXh_o!9&FT2&%>3EXkLohq=a`ufaWSy5*K!HSwiU_9MOPBS7* zH|t5-wxxxd#POG~5X|rP;RnvcQo$WTFv_)@;Eu4)4}{VkS5m!-pl`M^=|Q3HDyl_56qVyzc7c zefdVAJhzGt%T~ld-wCi%*-LJ?|cO9UFtmU0Mriw3G{x=Ad|j z;V=HYUb$sao=X+d)Ku2fE3z3L;ZdSG@w0@8N_i_jnfLP!`6WOTr1WZ06L=Zd7llem*#@=l!`ZAfdnS!quz=sN6@d+Bdcm|);BsA#Pe`zzwOP$#hHn z@bN*w;DMhy})il=Q5i#ewv60Q^OkI4Z;mGd>x&!4H*8$ zM+o+9hD*+;#M;>Kk!O z)PzV6Q<*fC2V-ddmj_UVR=HQ|F~1}pRPO(SI>*iN)<=*d~}}*Vi1m&o5Zc@=eyCvu`)b>2D7{hFaiJQLl^8R~?ot+e1TW1f)dK})_9>-n;T*^g@J zQysm&!l#b4IEc&1xMZX%;pqp3A4j@r{eK2td(jSHSi4uD zFriGm$@*!s-7@|nX$_m$&dOf~;Y~;6$?Ci$|LMto7wjEL^v!QMsk=*M0XUURFm2(q zr~|_wQGJcN$vr=!pH1iY zORuaRj_zFo-qwwrta|~en(u?MSX^*2B`_6h^wE5%__jEILuE1sXc7yX1LPPAyd)2L zw)#7vKnvb92wIpA$J1k@NXPID7>$@E7=)MBN;}tyX0}vJvw zoqFfSz@wGLFeLSzxeLfE7TBm(lRjWr+=&je?jQ7d~=IXBnYUC(A_ToCv3Ly-gDgdTuM{_94~ zAPG(n>jo`_`L=8=LUh_rCQrO3BX7mG}D?SQJy>rnjZX)6jx}Lp&!8( z0fVOXq>c3fDR8KA7T4RX*7v%ek9GOFUn#psM$`zqbWaZ@hIF{~4<=yd=Hqyg$GbqW znV!{>l+?m`^lBV_8m@wFV4bH7P{Kk@(Wb!_e)<^d7D;fX-~+yQ@{n!M%9)0{KyH$R zC5_bK!4Dn!V$?lhD;zNd!xKpi3b-{U%{It_4H&f=-AUU&(8)3i6f4U%I$$;D7XMCj zo6_v)m!$b z#r0?2ZEv;i2asN*LUD2!jtUt;?y*BKB;cf7Hmx*Md>jRo_vVW?+AwDd-*m8-472UY zJGK2jJ!&`rQ3Lnx>RO^FP0Gg`=M}|ryrK5kGB}4c>SSLDz9`<2Mdb%Z>t;pz2^Xou z3ufq|=^XQ5yf^vp_#te|i40Be6NQy|$`BxhR}{I*aY|T+e5@TXPLG*YZ_7+z)Ftne z*e$XR^ZDDJ~%)3T1&uc{vLy#q+5$?kGgm$ zY{V<$q99=QgpZR#th(t&RY4EzuZA{YCR;MOz7Frc8WV@+jW2tbmP*I)9~d+zNZ-<0 z9hti$U>p;!De{)*s|l)|+;o$}8T{AF#SsuyqfPVpD}?>9eS$OR{Gp#RA^x6+&D?9h zb0g}DlXh;4g2iByI7_Nu#OJAIG82;7#MbYD3s5aHYICP33#+x&DO$!RK8N zLE?0|2%(8WUnGu{06K{%I#h{LroqU?)B>+T@*qd!klf6Yq}6s)@1 zX(!tBz|iO_$t2pVQ~Wyipk3~aGp5K&x7fT@EZR%nzyFKXbc&!rU4q%T*z*~Q)mH2K z!1PtC{Iaq!&J?6B-j`W<^b(+V0>@Gi+;nD(==0nA@V`#Y@Nw3e zSHmUXhdCUZwkeo>1Ng62P_!q-=w+JZjCeXlwm>dZXk4$(gWW;m{ z*m8ky5$<3eVk#^Wy#!3m5Db6^1cnj?{573e^jA((WkWgOU>$@2g_Oyc^1lTPBmz|W z#=rdaru_eHzgxyG0n2B=wo~$fKLHvR@>w{z4i>UX!G#ReKDW-q*1|*}U@6_=GsDE+so^;dxwqsb-@KG|K zce$^j_Jnu(uo_v=V6ju8lhUoyR138%@!4n^bo$&3!A4=!p2aPugeX2+gmZ#D@gDEw zm|mSf41_>eOdkkNh@s|xRvRiCGL}6?q}F`@6?GVyQKa}rfwis-Zt34X57miMXE40^ zXQuJrP1*ft(sUpf_{u!KnQ%|haEbPxnYiRNyfuOER=F-%YlzltxX0!fO}k2b^A%~RUuE89D#^Jw0@_kTGtsO zL{VEj6sMbQHf3r3YaPKFvYRE^IH_lwHZsMRDU&2%PVC&8B+TE1qHZ>LSdSopx(UeO zEFJH8%h-M-Av=XwDaV_P%=2s!f{^0M{8l=}PMmaO5I?zPE-p1+{uB?VR@cH9j_tY4 zRgUin$q!`CAMLLyEm|e9Twj2O&xyooHe)iAiszhcC@}m{i%qi6h^3sE(3>Xvvra3f zJkGz)OSjBK{HuG9=KV4TI;HG8D|zal=c;~I_+5cj*3gnzp1$%xZpt2^u4J?H6aMei#L z6t#KyioH9t`JUUe&!hP~_iNVF%YcM!;k`%2*(KmeoA8_^l`S7?B!04@$?S7v-R`afV^0Dh zg%__$QG|O6q@JGzS(K;BZXh zy$O91=@2{H+Zp$}d7)HQglOP8v2qaNCrNN%{LqAEIC7P+7Xbw>0qWYSj6xLfBZSJ) z5PY5D+1Otd)Z4#igU9}=p0cTSr0|L_aPZU;W78*ul;BMy*Q(R_U!U{wzwNi}CLD7i zzK9EPuz`O8o~>t{-7MqK$E)PyRNj|v4Ib$bc3yhI&dWfg^x#jKC@lIDuQ5b&NO*_| z;~*B0av3GI zR%H&%)r26yY|DANK|5bB51#O4L?mNn5`{vQP@*6SLP51(tYqABT%n@fvmV@iF{=Ta zJT}7`FV8wnnvLPEFYfI)*7A-EAfq&E4)$JJB~g9Q$DYB^ z5^()Q&W%*k+JS6{b57E-m#ECoNR3DB&RP<=l)&Hj93$_Y@kF#{68YCH(*5?Y)DVe7Ch>P>KkMAiYafs#29IAYDLu zCnB8?klsP*Eg&EuARxUHr3C36q>0iyBsA%vg#aPG&pzMmbM|kaecp54nKK_V{E$=c-47 zm9FkcGSS)&Ijw^ANVayjN3 z8oa`j!Z&TFnUP2EpxTqF{N?R&KkK3n2Uj|VPwq-A%`)`6f1)UMo}SQ4_+;01c82R% zWl%0x){r)TRuIQW`k&g||4s?{|9Cg--~Qm4Lx62SfqOe8tKg1@+h1O3D*yj~0r9+-E$N(r?hr2b$KED_^P(+IR_Z=$WPt{!FY*5> zi^%=l2&|JQuujCdxAk~`NpC;@WeM@zobry==+>~KW);oPtuJi%;fO3&RBPlZ7S*d}Ny8B=cPo zdTx`OY3$yUitgpCj?yp=clv-?jhaM`JNL}Xd9rpZ0`|)Q8zYA&|IK;)56qx{JFoG> z%K>`9X-D)iP0qjbcIv(5F}MsAPO%R5Kj-flQz8!uRxp)Fwy?8@c8zi@Kgp-C=_8|? zgCXC)nm?hR*X2z4{VA{2hMn2g=hUmvKF@6zcgt5b7W)cgi9C#505BzOR8p*%rLei? z0vp-Ru?|aar4t$?P<`UB_m0c6HKl|j`Ig#oe!JZo@;dn}Fpp@E(eKAqcUG%Ua}}dc zBp_X@9WHeGy8P9xP8D7Glv$Nbr5az2RrV~vqz~xVqEJ7I z16?-u^O;Cfcy8LfrK#2Z_|Ql{ihu-5dZgczM_Do{c{YCSO|^lc5;>9V5TluTLS+c2SFP{Q|(T~Ci7G=rJ-GI9p?9fL{JUqVREdP zz-N;UrVW+XQbYVsuu{sXx-k!4%bB zTH^n{|9h=e+f=KwVkRdsab=R(yq>r1#?%td7n`>@Qb?oC$8T49hG7j?rZ%Ad2Oq3| zdG!5b*a`a&g5N3rKXL{0ivQt=Y8s0Rkmx|lN8z}~WrTeprI_%SU(&~a9Pek^G^Qv& z+)Sw$;3Ij3xBm9Yu0GGCdE8`K(Y&6I3SHM>!ZaX|G4It7n;vI-(YoMLYe7Q3A0Lhm zoa$uKv#iCt6p_Im(FOBdB}t3gZ6$w@q_!GTYKr+cGV&T&3IlHgb& znMlqVAuc?}ZwWVtN@`%j%XXxAN)b$Xx0Xv9-Rz-YJe^aXcY=b}Cj>4N`~uJ+joDWL zX8|i=I8IDzPwu_+V7jhLD;OfjdHQlj?d#Nm*^r-2m`UC>`&{L7cOj$4r1%@}S`ROT zhO_uCtt3x3>q1(aTYM*83tgDQ;h~{|<3KR2*QuQ`^7fIZ@#-MOs6adimLH*fQtjs( zmZ0s$L?!R%Xw)}M@|}2I$^9&6pn4!9rH0p84FMxp-nB{=%z_y^pfa+>+jMB;!4KTI zVHmxT^$>-`Q-)tpwXF=wlC7Q8OJ@v+FU(7WtF@5~ zaI*u2k3R*zTkHw8_;j_U8Nsjq;1TS#9@@b)7d)1l^1vM}mO;(@-ixQB=E#h&Q*tHc zFHpSK(5msj>G!EM^~#T|>!K=)1GWpIBW&m6SgwNwsTD8$}4>Im;Z5X#ZzssHkp zm47jD3I&yZ`I`04W-R?TL6C8bx2lIfV96b zMm`B~&Jp*Z{NJPYU&~RQza9>F|5%Xz6Z9cjKZZGqKf>8p8(RK7Ej0M&`1pT$9n|m# zkB||wfs}vy2Mix=6d+`Nag2Yn9d`DF$DT7=s~pKZ>qD zF;@q&_`Q&yKDwJfQaCc+G6$+Wl}kL5j6W47oK+1*vVgUJRu#Qh%#g}i^f{`Jpt>vi zp7d^&`wZTt;kEqBhN&t+Se2`FYi$$MK5TRO+0if)p5at9S2MdNX0Bh$4pCZ#>AZ~S+-e=nJP+u>v`gB z&NPq!O2KH|PB(Qcv|&dPCTJ!o%o}=qO)9}17+(kqi{J7+a;E?wpUKeXiLHT6b54`}djF&U=2#=oIz|77CP%UkY>Qu2H;Y zdGos~`eo03a}QYhAG|JQ9G4bq2CaVdXorb@pa>EG}98Ha22} z^hbM*i!Kb?PP?<9t3r$-MjW2%eCWtr@%FnDdGy+xU-j*eBd$1_Nr{^jO1q#6P~BEn zUL>eKZx6D{b}z`}r`I*aYXLm6+Z;JOzi2jZZe>}ZGUK?-vCtpc;R70ei9axO3*|IM zndp%p7p56lnOC*;W=`jJcN94Jb*U8e_}g$=eOB94%1*VLSkM{p18)K{;2@hT#U06J zyH;ODaX3^gVCigLW7)#>yS3Vq$}dq(#=A9dY!W?042*XPLjr>MudCYc1<|)m2T7tl z5%w9@h~MG0&gW8t5M;|>BytHPIUVN)X59D zz9yG2#LI?`_L%doo}uciDwUa=Pv?IJ&RAI*lMtXV{!5kZ9n!uscSJgmh&bGTc)CbO z*cMVB(*0@}Np%&h{Jr1Ms0vo5Hm(n`{qIh)e}4aetpIx$YKP2}F}8NMt8${nF{mB+ zmRdN84Eu{>SHyfdHuN43y|MN@Zj^tt(4oxY$|B&`4RX%Cag@=&LPK$9r@7VL%w)-A zZqBSly z-$%_FZvMUCgfq4@UEOZc1bSddXA3@Mp)NcCVy0DS=vfPKMdR7Vx!dmV>f@4})x3B{ z-+gifARJ$&L*eqpmktWtysPCcTQUXr60BcE+nDh6awg=Ix5nB!k=O}n1rm3+NxqzF z1yn@zyG9vCzQ*(6+h&l4buFf@QZs3l2!5Mbpc_L*JW@L_`9OTzOP6N&-252p)i@eH zjdKM^w0Xg80#(4$KleZz^Uc!6ufEZ%xAEnd#ZKa6$~)1r7RcWjk%A03JT@FPEn96y&?5z=XUycx&BIk z@U(#VXG#~(a8D`){gtza3i_F58|=I3X!rR*W#qtR9UOykq&(IZ$0fDvxo zfcU>-q)V0R%p(qH+n8hhGuD%UIz4iDmEw{$Nb(O}cwi__C<$ZHjt599wt7M_l0eOZ z+@1VgJQ{^l4_yU{{bV*F-itK=Q}4j39gqFK2h)Zr4-2i+yu7(Y-YXC=-*w#V3FYcQ0pId_^ncvr1oS_+hj!f4FDrw> zSd!4=`@^v~KLG9q(B>4GIvkzwTlwGqs1+Rf{vSL{vpm8Ba}yVxM-F^qdF2mYJWRhJ z(M9qYc(5BFY>WpoG*=!&3P|n$#kw?;Q}hPt#O{qQLn}<3r}N_&_FSoK$)un|YGVyP z-dn8fbzwbg67jOFV6x`K$Pm{#BAF8c^lPf+;^)V2b)I+{)BmdU>k`{ru9i)^5{l3; zEH~44sw^%5`??;MkN*W5`X})EO-|Q8l+}O9Z`(>j2NFO@C*sZ(+kdYb|5In>pF1r# z;?~T#;6g;Z)UCEk7eI@cG|k3bDxsaK+R&)IZ8 zy!ipi)sWZg8SGnGse3tL>~FRrcvxH$oMtf=6~gN$-Jfx6>KE9T#o7|ctl|Kl5P#sx zWzvP$Wbj%sY)Ev1D_~}mcpm`M2;ALQQ}=t7 zGR}xp_Y-w%rgA3B4}QLHLwL-E3QLxE^p?`TC{9C47lU)b{tALjg=OFEJeYi~h&gYv z3I=T}rFdD763@8p3~ZaKMtSsJ1xeV&piN?AIjRK(y$-$d#HZ3GEWLk)>>3Y&;HAA| z5msEkgyrsHhBcawLK;IU@(9y21RiS^F9EwtC9THR#r(VP`rR6z$IA&RgsIT$NO`bj zAW}G92+%=y7={~uFlqRaTDGha>&u(=)od0egMQd-Ik0uT7#Sb_0ox0ZKC)JNJLp?I zk+QNvf~Wg7R_&AfRO^Ikud@*A&$`s{;a`4`utuEK#C_XFKB}mpbiO*MZdzY`VoaX8 zHPLxQ0K3IC5k9UBB5j8XvP>uL%)oIIt1t|&0UJI0WEGAX`?9|2$STu=>O}F#HN~rx zc9wln1*PM|g+Ek+xAydPlh*b5J_B&d{s6R}_OQ7bD@??)+@uWPHgo%O+A?o$8{#Bh zRi{jxwsGiddUJTwKi68XvTm5*kWI+X6FEZL&i=J2o!(7PQt0Pm4Q6FS=FtKF=@yQp z@5uFJ4b*eUgkkHoUjU)dk>u4?wCBG_8qF4~yW6U=Yq=r>o*2G*Q#G8DZ|MKVFLo-W z2l;TW{>+?pg>rq?qB){2D4Sta`%_^6LqE~3SP(wst(%1!Wno~bu zc;QlP>XV#6!xbXFIo+d5EEM2%(G0$1gQPncViMzeY#uwORdcPi_%syl7c|1O2UhY> zS`<(m4F-$?*rE=J-d8$zoOPX(sxAT&e)W&{aJM>AQ7_u2D_@DyDqAEy#v}M-oEqAt zhLbW6@{q%y45BOqdu|6XUlvjANE(GbaFgkAru@tl|E1S1hOa6=gWVx1Dad&39V^WK z7uoZ>8$IjyazE}TSzWbNy3QaAM~ep>xEC6#Tx?A=v2g?CH)oQ@qvQL7tsbGlX{Q(a z$AF~_iyRB0V?O|sR6S}KZbv)@o3`~9w?~zh2 z&dIt^=ITtDyL(@4W-oaW?@hiULJg8Oi|Y+wbOh|4>E1cW(T~drdX}3MpH5$j*S{$q z|3XSQnQMB#IDJWQX*Q?#)7@|LvZQNt-EI_EPmB}HkFJk$QM~|sw@RPMG(lfwXqU@_ z)8i&rOd>v^`b!2=b>iK!@dg%2Ff1Q?m}&FrglUwgd}w*UYVRym{yWakE0k^QbzF_k z&4yskt9wB%lUU&^B|jl#|C{(qXLPf`m+uEuj;`D$MPwB!dv3-S>%>rXVpsl^F)XE| zY=~&+M)e=OrL^79T6rwhA3OyNDRP&B(Qm>sydTF^7scQrKsC~5Q(|Q!%$NS!m4WF7 zuU(QW>E6nhfsNK$A!m0Zr_xZRgZu$;L}YnnrT)C4?gxLffD@jE)24GlYF&_Gh#XCi zpZQwGTNwya8cM8q zclNaEL>px}y&vOVby0k6aFNiGP1?9QxRz?AB1s3Lcv4|-kpaRG|NbQU-p;h0wZ4u_ zzgRZEpy9H~*GgmQ@Fy<9u^{ej>__*%=<)yOljy-`vVYZ2peg(pfZto*f9NaxRR@YU zc(fG@7$%UQGAbIpLgIe%0J`1|@fjTd(uL5Xgrhv0`@5rp zf-vj2=l+(E>i8AKg&7z9?_XgfK_vpL7+vOx8+|ua(fx>Q*Ip;p98X62-SIhk5#f<0&BH)>%mJ@Y92u*a-1{A`8767w3@eGG14aHBbM+=8y&rs42;R>m#o zs?KK{eYJ?rCC4NoL7He9hZ5d#uaFKvn2A#=eyT!`9IFVf&H|~7`oSo+}H0m z1I(?m_t{=FenllVBE;Gz4oaH*jSe)8!VrayHn$%WyhAR!r{OQS^B;8F(eHcnJDxbs zE9a(C`jSo9{8-OS?NTSF;Z2_l_GtTnTiti_L#|xA=j-A^Kv$mEf+d$1x6R~tYk|BU zmXY<;Ei#Xl9TST@Wbq3*(O@JWh=P?wF>p1X7+p?3wW9q-P!Q3ZELCd<-yo5HQo(jR z)Co#4uzU*ugc{cCP{PrtP|JGEVFOfyD=yF{kwNgla+a@ev*_r3M2aMSieHUX~-7j*Zl@iS_RKW$nS%p#4oeGr%HUnxa~|nGSe6*c!p>FJmT%5U^G{Sv5}7z zlLjmGh0bqjTWUiD*S|`+_~hy>_dx{UDa0=h-YHREJdgc0?REJ5Q{x5*L$emz)xlrx zRKUFdW720c6hmHYcV2w#K4TQnUw8!WoL7zB`!r6lk03Zio=h@{ice+BnrJ;Ja_Df@Eh@OA=W@Pa_{0*1g z%%t(C6kGQp4VD}D&ZAT_FHi>^NOO`_!?GTt!iptQZ}a#M?`c|7NJ^-xeCdULeYI)5 zcj8)2(#{HyaRI1>Et1mAX_;}R)o8*m+dPmoJJaQK*R-Z6N}Ut_NrAtlOY|LYTBcl3 zRfsjI_KXiefxh;6)-iT40}@Qn-raz;j2$tKL%_6U zeJq|KTI*cm4mZ`b@g18O#LJ7Yx+wdOQn2x*LwvoU%D{7>=HjW6VzRF$)CAvh(qiHr z^|be1-ONo}J(sUNk8^F6F6*AT{2Wm`=9A_voYfj;=0@a;Ens%wDMk!${z`jtoH$yJqCa9NU=$J1#cDb!rwdA zC{^*b7o1aWpX)e=X%@#OJXm5t`Gilj^Yzh)B#BwLfz#;hGf(pNPX6XO0_zFA6{I}* zYNCNHhA~1{t{6EyM|Wj-CV|h}08Zq3SxXeX*L15QO!l41{0SRzkT(!%R-)x8S_J`x zaJQ~=WdT-xT)a(jb6=2!SN*lO!IE6D1KJBz2jA{q!~=b>%xk^uUqPsbL1e&^39nE- z?64c#2WsodE-J198IG zdx(X@dp9W=r+%aoWMn2(sste;af&gxg)^>d~D z*h>CFWE#u$bv?JfV80ST&RIc27;BaPjs^T{LyW&S?lEq-+xM?@!SdwZD-=P}sLj&A zd`pli6r?xll0BG{FH);SEz0luqE#fLJM38k5#Nu}0}YHZ?)K9wN=zmCZTq+!dywp> z6-?ucx+L|yo|94LhrZ4{$8mFE-K^z`RR*gK%vDyNA>Hd|pf0av9N&zqz!C z6~^~X=to%Yof&TjqE{xdOGnYYn&uQNI<%j7!!;Tc@7oF~`hVnO7_>87x$5De4|{gI z=|V*qQ;3u+_OqQl3vE#Mzz`w#%>|yVQU#!-0&Z`xqkKA6^Jo@&)(**bLRh9!XudVn zPw&~)XBG-{YEUWb4L6zGOt3R&jyt{f?Uf>`E;UtlD&@}RZi+kfDtX@YT4%JOF7cM0 z6tma*%+|M|H~CMxy3rcAkZ3gT9UFJk8rB*<`ZSuSnkn0o)Mw|}PV<-iAlsF6`6PLJ zH|A|1^Q*wxPP^1VWFGrhEG%rpiIztCr%l#5aC%RoZnDQc7^YbE?}UEtw?pv@2JCd= zGe?wdr-Hyvq4fY%Dv1bW;qPhZn<^RysX{oelxJ9FRke;owo+;8zyGSTGOK_rOuQim zziyL8zrKEl0}RsG$n<+NByjAgU|g!#JojV>+mzvFfQgz2Y7klM6IJCD*r_T*h_Y@N zE?qY0odJ@Zp2$*}A|j16G2ACA`2%dFjtNmzSo`UGAC3$&E4D@k_?PLVmpk;o(B zJ7U=Cd)wJt6S1a##%kYM6Ol`y?&$KbF3B(Y)Gi9rH_|++UYHU@SexZhg{~&aQwhpI z#8^p=Xu~W0v;*OZLtCcJDWt<{GVu3IX=)m9hUex5i>5hD!^*-NxU`@f*I8KnD>1*< z5W3E0$=Q&Z4RKt)`@^gQoZ3%ze_MGJ&#iYhM#)132T!rXz>jD(A18HG3Ox)mb%0r6 zoW5>sH_N8|3}jMkw~n>;e)#6fWK-4RfE}8zYdqPjoqpqk|L5g4ipW9KEKYD>3hfuu zRaWgRdnG75eK_drqceq*2w*N8*?lR91iRz++9U#=){A z9AcK=bM@JE9?J}*eQnugo1H-LcI!lf$Z9w-TAn;GJAc15-D$UrNg;bh#R2z^YY#Un ztvP4k^1I<>GOV0kI(7d`RsJd34m67-VwjNf(j-#ZtP zLQ0g=79+=Q_&M}mCcKRII~31hT|Tgl5q*>(6Vv;^!6so%K*tjl@dvMdpgZZdpAI_q zXe(Nd+1Xk~xOhj$iOl#|vwhhX&*B+FswbDH|JOqDOdSDl8FIk>q6O`QGiRGLK^GyBavxAjGS-taJ zBNuQstD?&a@~E0vuvF$#65%H+g5JA$N1^yKs^91R8`a&FsE*Z)4ubl_NSp5Yw|n{2|2(`_~*joG$UBRJBB~>_2!;Iv6f=17fRwI)q>`M`K?4 ziFGRq_cf^8S75tVR7~`V$q$s7v8rQtZAZrYT`GUQP9&$+@#GXPbjIee>_|n&oQ};c z!s>_6uu)D%ptSl*6>MwvDg&UT9U?jsqVYDEUUvhX-*RuOBBMkd)F^R@9VUTO^szNtfqe8s7vG4Y%xJ_QPZN9TPp* zp^a|Vac7dl{NGtMX?8W+zFDrt4sK;mGw<8lMsp@L1w?yy4A;C~De*sK4|}A*J`;m| zavd2$5X5^V!+IaJ(o=a$JU+N&c@wvZ1Z++YYHDhqH&Us6{azJkq>MlF=`P9GI&oNs z6U3p%Y$SxEVX8R1x7;6nRHe3XkTBqL{9|sJEzr&QyUTkIK#ND(8_I~qN057aS%Uim zSTidbo(ns8hB6M5(kB#-T5NJZ5Me-vH{m_?CLZdsp$Ty?WBvrI1SV{`pJ&dHYYKST zq$B0(_Fpf&jMtWdw~c#DShA%yTLzl(wda+Y?M&0oOiMmmHnr%lQ}A?S_uGKJ<=g22 zoNn0@Z;8KdgPf^$)+6VgM+s>*L+gbHs!7pa7;niq@9!loPQ2#)r1bdYzFtFn$r)Xg zHM2{ZW6Jt(M;pw$v3~=xIZ)}vg;qOO+&^u9=EqGR>~Pgi7PR=#q7Ow2V+o|Kv?`ME zTLR(Z`eA-MYY%kG$_>(r&^WkU(#@XC8oTiFkJb;Kj+X}3&nWxau87ty59Ynn1x3-V z!0F=Jc`>+^J{;fVdPf_)MbgKIMCQx_Gt?80j_tF!q8O-$da(yG$l~TNFUK()Q`dg>OgBl_+JE!VnM6hT1Jw0 z8b*~ZA%xYhMO{nKiX`iDdPi2sJ zO`0q=Mw5G9VDMIqh9LQ9_w$KJ_DT_c(Fd;#zP#)VQ;;eKK0e<;bPsNPxP8w{ z+xMO(64b}yGw~c_iFc&kk`Hew)CvuDM+oA32b(#K-(t80zY;@0hSjbXm3uxKdl2#D zk8< zw}fClxgXksd(YXVv;>F6jN^83(%&$R$V2kq@)UCHN~Mmz0hVZ(e5{NlT2`U-(J(a$ zfsTNuQe)7MvE%gX`7-_#=g*irq@^#~7gf>-5r^j>$L=nf{Dy_nv|}KpS=*43rbLNF zInc5c|Ayxm3B;!#HOsEUV^*LsEy($uZ3!40HmtdOJfnHN)%*)2yM#$a5~U&X;#t}1 zk3RXDbws4O?guGXIz1Zo7A%6>L!iuZFF3s4AZ(9^2uYfGrDK!&0pIvmWA|e0QxrNT z_kPoi_&#C7sN!Ka8cq?q(VLEl0J-vmS+|AoU$0^-4Cy?HO!c(4y&93(*r%4)L{rrv zjaWtybgE6K;6aT8qBK?j3j(UEp3AgImc zxM6TT@f$oOM~fNg|AL7}^Z|kO#r#=b(rF-6L+f$XJ~CP@$0iOb*5J3M&Ul|0#&D9Q z%B>qNJVFKwxX#!O3`U1mM+^JRES+9;@WXyy62)Ci0MCC{#=$9Y&5gmtFGZ7uqMPw7 zH!+vN`~l<2%ZPXzPp)wpd+Uc+`nN_rI4Jl;hOR!c&ODz9GAG_AufT*F%|L|fNyI4j znV3kmo|wnmpbP0mq@`PHA>RcU?!Ns7RpUSid7K;}iob zwZF@K%g)>`2!ZVHZ*cKXEwOoDMJHK?p;-)FuY^&uLXlrb-?W*nGwuAGO6G&O$K7S% zc;63irQBWz?}TEMTI~S#`&j%Ryu*F~fBxRELv5_zXAsaLf8`^;?olNuR#nrnza5&n z0Z7lH{f2?&GjNv`D8QLd2D%*)(*2-Q8B7Nb>zId)w+u~`3C+ho9p{+zUMPPRnV5K##Cw@l|;H#Zi@^Hez^MJ56oQ}N~kg% zS1UG5ku)+gQhhn3Kyc%sz>B3lz%=gd05%Hs)4VBkRS(cQMgH^6Rk8P%0azn{3xFxk z*8tV@y4l(7t@itV%L545yR$JGXLk#o(rwxlD;=7GN{#Q~TB08jKB`q@6?on)+RMBRWYhs4udh@yLvEtcc2V@4Hw6y%o*CXuQSYqr z>&?sd(T9?-qb>i+lfomKeEOfWEI?S@GV?3#WgK{P$C9awTF>e2jE?i4*`_)rOSgdnd*liZr4h2%Z(GMTiwE5PVvtl9vx%Enysp^#&!$5o9aG zT^XT9XQDWoCWIiL+7jv-M*5B3oov*794&_w0eoq{1uIu!+OqLaGm4UgP*ZmVZQ@jw<^XGXDq1|h%uzNrgq0gw1wwrM&SL`F z>v3~y%SFUmIS7VyYS3~pPZ{o`&G5J`S+71#dSIFj2IwNv{E*Zd(ueHF3SCtYH-tnB z0)eA@D|;mgojT=?)4 z-kZsssl9JfS>knzSZwvNr z?%vib5Hp@k^*rzXQY$~g@FUH&%aL0=K;Xc*y_`9_R%8)Y{gO2Lt@#tSO!O@ta~+jp zBwjif9tpeg)auvdUOh;gP0Pa8?@)Pn$veh_M@OZ%0@E5wsV}m$wuxslErlAJr|OU} z%)^eoKv)pu*J(%0GC_kRP6)M;J-@u|?goZx^gd1|AZ>9<;c@z?Lgy7`gdfl4xRTv$ zytj6AqL;S6iqTm!u#GYuZ2DRA%JOUf_#<+T2Lg(B%kFHwuE@{)z&4vhivEqUsl>zy zO6+KX6l$B23u~v(0@--FQL!}ms$`}H2TRS$%7(=5`hCHqiivcLi=QW}?p5Z#8L?5i zr|s2LGj#x4USesko*uz@VEN0e9HpiXGHVueY|3V}(I<0O&wmXQRP;(oJt8zUxvPK| zb_@2V9uv(y-$NWtkjs`EEL%T(A-09I#~$0L(<-sQ>@sZssrkJ?ocOprj#Ht;+by3W7cF&v7ecWqU7#3vGAK&NJr5=twq#7{j_?HL~+nw9aOtTmG@C2&X!5n z@CMt+@K|iDyX&TDLV^m3O$zvu;Akd(ubs`0vsdonq)o1+ywXICxb(;U4`S8SkHr%2 zKF0fc`whuW**>53`YlG$QZp%D?@)P+%?9>GAEMHp-o@3@P%1TA;KHzG4J^BK7|6d= z)EHnYL%M2t6HyxRH`+N!GhF4T*Z1eNaHG|I)D}>V6*JJ- zF4{@mHEO)$V<+>D09eMVxA$ybw z(bO^_wl}qTg(YM|>;`@-VYIbn_UDly#`Py)j_ON`E3-I^x@X+fs3@z-ozE@c#HT#4%5 z9IA$th@Xd@7y8Ka{lGQ(IMCf{w}Uf(`$iR0uThb%jRyGFboS@Ij|+x0Mo81CMC)!W z_(EZC>OVYMNBV=PmWGb45JWZLK8iZhh{$GOz`RsN}&bbRj>N z`6k6#^mfn--E>r3PKbETCaO`vU+4X`eDAqapV+@oNbkQPqr&ussLX@3$ClG{~^ zBK|&l-?-CoXGhTqUZ7|k12Co;DX7B2t1_{6;_7;Ehlc1G9{%uSF1|9t%#VKyYY50d zA45jJnOhvPIdQ?FZW1wdzgdm4wQ1b&y+qIP^(rugrv1)iP;ih98>Kur6vJx-MG6va zZeI1h0aWCUOWV!QrL`N$t4Gj>lnGK{vxeVh^BdJ~RH&xB3-kywG*&UN^X2w|HI}aY zyvU=hWhRvAkFrtjrshGAl*tENHu9UT+^!3@%rGkQkUvhoPV`CBYLxhggoq^%-^jdMo=nK64Yg5$m(5846X}15(0Rb0$VEZ3I;MD25^X^?S!oyzF)e!+t7!`czwNhuOod47k{>hWgEQb40pHq?50GK&?oh^ z*edth_#(7RPU#6^F)Eh`F3sN$Ujr*TS?=YvR>3MmDK!0aqpy5%3yevfYsTO^r+9Wgk!=y~$_S3~ua*no@Szz9k;xBpIJmQ_K;F3B|q-Cf{Cimo7?AjxN zN(OfV_pY`G=Xg%Ql|WSVs~|KkM<~)a&M-}Nc%gLZGM8Isfj?1MpxIBYd4I`ZUVSOJ zdLQ!CXBWIa%K8hZ&pEw(tk}pyO!kha%wg9?mLs&T?IF&)rpKque zMl;u-hINi!%WZK-TH2UT!Lrs&rd)-D+-j0(AIqeQid8o}dr9BIjE6Ud=MHL;hu`Ty z3X|eSK$K@7QYSbgyb@BRb_g!-VV>TcV7F`;xKF|}>?s=Ysw?iT?#b7V8$r^D@2v_I zvvVdozW%}9QVL*eu(RE_ER|POPdW!3UO&To$dx?c-1DeZ+es0u!#%Se(0V_#j8+PM4m=os6QmQ{ zhddDgef^Z3a_;)6=wM;W6x?XFGmirrWLv%*r0J^m!bslzhc*_s`YzopKsH8W2 zimvaBssA;=>`A{2dW@hLT>^Du zrr;@*GCzosDQ3x~`Ox&7h-U08PHZhle8r%Z_R_Lr)z_aTR#{`Y(KgA1b)MJb~b zw&IQB=7;rnMei^V);Z6*$Wv&hRKZ3{d52OojrNun+J|f6HS@~rjeFT@b@q#^gVZtE zMHv2G$^d7X`!Ce4|9gs7Bh|PdQ804LiyWKPR)yQfvv=89 zPZ9Y6lLwFTx;5FD7k9>2cFh(w1KpgM?<#l|ut)_uWjVqGliycpvwTQ@)fJ(3`~5B1 zDeCI#f%P|8Y~6zL>L|c-IJ?@|VEQmfjhnHisZ5Lm{kv81Zm2ia^K8!B73GX&3n?T5 zX6cP6jp>UZNr@yRB(OW6J+c%a>UC8*5lwAn{frn9Dek4}?X1^@2Yu;;4H<~u+@{ur zxNT!Bg}WMl&(mSq`bTjO<&$GqJBYV)@lZ9Hh<(RhRl zspej~21`plHZhoYD7Y~54x?+i6OzTI+iW93-(0oQQDtEa?C*2&{?WH6g9oOZF8hlN z_(sfI9EX6BBz9gPOBP;O?R2T(gf=pwl{n9ge~~h7l+M)R?d@XWW+%vbu(I*_m5S%m zf?tMKOSVZI|NC(#su;I-Dy*6xQ(lRvP#mnQeE+`1qCm5mcPHfOPVS?bR(Zg#N-Idd z2vgAw(do&EFS{-P$8gRrxaL3Ro!f9MR=>eN^oW_3@R@CkFle+o1l@WtT^I;(4$OnE zg*U*zy#oH9mbxQGj?8SQ**D5&9IIY~G1f<2=TGd5L+|g84x5W`$mj{6hVNDSyFVWB zCudCK|M5nAEJ-RV16ge?h!u5nUtJh#X7wO?@+ZcFjhAE349ji0SxB8xh zgqvR+UA<9Y7E~=LW!fGVvVS-Zs4!->yy4pm)rml$&ZV3PB1Aw$d*+|(&}NrD`=ZGG z{`>l!su6#CUVw#>q6IO|@&m8g!QyaYyEuX`6K0xPoI2(i)7Ybp;Ws>whh1YE^Mp6Z zuD*V&wRr#@-+}%3a48!~+abp9(Rim43%g86=gQ@cdv40<&G)_M{=1!9Fz)dV`+Z@J zugw0^~FT0+50%ApNi)a|Sd8Tje_Y6v5;8_#Lg6KV>$@xPe+RxMhng53m;zo-@J z9SnTA$u*OLeTvzt@awTcUAKQlh@)_+$V!q1`8!rZh3MEC_9Pofb3|{RLs~%^*DctC z&Nn7B_{Gjkf17W!x=^$2&4*S8Yyki(xeX6oK8jdvvQ>+xn5VJ2Cd1nk5?Y4ww|zV7 zZ2X3R(n9Csiv_^9n&eeV!P8h@e!FmQPYl&iDAO=9-_w`2lqc;vIcDiOm@dn9nP~BF zF<^^+--048MAn&=?TF{gG>%4dh443HT1jfvZc^FDn)~1KhNM5kkK;zE6_GbNGhZgO zPkDTNJckXMg2^a5sz&6;cg^S4c_Q|O%~K6H{9)E7#$NDc70yQgSLx!(wm!VpkKfJ_ zrD&oqDnlL?wN%q~Hwt1KFQjqg5?8LHu!s&qS2;@4Stod|+>u06zR5zipBU7L{E?!F z=cZ_v9reh?pujjw-$yvo(<;--aP=_O>ggnocM!pL7o*fOAN0m4Z(h>)k}cMLlDuYX zj=)2e8`@6RV$UBXqd3=ZELUl;;3W44Z}ShHEAR!LB9HHcP>|vs?xBBr}!Ir^*otQ zzK9$iG#EzXL^tnRAXFtjcFPG;zO+4Yq1Vp^HjJ~+;xT2F06pyI8k~ayp2t+)9r3wO zP+RX@&sw0y-SY&{^6KlA=vGmfy6j}Rh)|vk+{}BOF|uG7FB1z-o}%CX;ChU{PF2?G zfTgwLmL!^eltFGSIO5W^xylwSv?@p*6J4dLxh=biGVV9AQs->^~mBkY*+N660rqn0(ndq|%QBtJ!LKvEoUeT1LcM9*XA$|6lL z+9WgGu%WN8BUh-kw|OK2Vn9GYdEKP!m{T0O>vOm}eqDc>QQc7!YkJ`n=<9OAHc#9= zUm7RJ0GI`rv^RK{I%nBeT`G$3uk?Za$&R13Ta&bvfX%?IPY7CRf&WO-sjg4B#~ zrU&W5^)G&t9e=&E5CTf0+v9ss&COrb!qvW>u?7yGTDe^6nB=Fh0Cqxk(zQFl0Z>eA z;www)GCHW5`O%kIRnjC>rMal%&MCH_}ntRvpH|I!0xc|v}zUwGgmtHIFg??UdE z_{!9O{WtVB6}Fxb=9+-4woDq)fx&_0^SA6iJe-Ab6n@Z~B@BCvmqPP3+&K;p7b51C z*c^cls94%bUDT{>%q&y)yq}_(A>3M5XIn>i5zp%R1AKcIxxWMcDb{#A3UQ$7dtH6s z8p68i5ks-WYV#e#Y&W>073j9l*Fh#Hh7CDFw}GALqW86?dL_=S=yU9&4Ra+Q2y^j1 z2tt-9{vssy(MAg#_5`t9e-IB%`h!O;2D|B}eM}m7k92t_APqMo6Kras=K#ZphPTbG+jR-r!2Xpj;*;ueU(bI0Fy12T%}QSEJ0&H zmJ&=DvV|qTPLR7BGA2oTj-y0Dzs(?{o+P%FOIxncn#@ZivnoCp;4b-<2ISDVr;;99FQ&N?x05F?)DA*M=c5QXLMNFoBeblEIJWBU|*Sl z;7MR?uvt|CM~YfsLH}M;mmSr2e3^Hg@6Hp0)^H@2S0Wgg5hfFSk+lu+utET7| zP`B5jiy*b?n?+y9#~8VEI4OD4dk1d{oeF~dLuNYa2s8E_Pz7wnmf#syrra4|5_tXO z{YLXhQ(dlvSPp^W$pNu&{K=?!k7s;KelGle>Uw1tO&y$_KTdYMFk$KPBwFKM<68fR zz4r=h>TS2ZQK}RXqzFinE)b9|MWP^GM0yEDKzftjLJ*bSq&ESP-g_^RE=`00kx&x^ z=_E)AE$=t~`(W+&Ti3q!{>nOB2RTVjW|HTc^LfTS#&3W(n{*b7T#$_`hd#KhE3=GC zt=6Xe6F|=zjbwsW2knM0N*{tL;2ww3`Bd2a+|mVnujZa_+4E*Zo!eSIf4D^|)%Wqu zyOJ;PDb0C$c@vrtAf{}F5s{oNgPLNJJd##J~hbDR)!*p9c1a~OWK zmX}l9UNPjyTnBU7n+(P)i4P|_M@G1~9Q=4#)myo%-doi*dwF*)U?`U}(VFs@mTmjg z$N3ah?CmfgVB%DqXcDVR{n&n$&E4&$+ASmA@C|q??VdJT47IM(7&2amSL?PZb59%} z%sA~2xZ^RtILYz*ubrH2(Obbk-k+sn3FFvt^hyFY6@3jTDd82kS zbY`@{=tYXmAAd?&g(kb4^FQkW`}<|k2l%=gJO?KwP{_CBgjM02T%IolG5${B%i?w6 z{#3uf3r#8WvWX{}Je;r5rBT(s3zE`V1PoJgqT}L0D|Yg7AW-PGn&POrEb7Qv!4hP- z@EtZDhSg5GMVJC+zKCHfZXD;82uOe6O^%}E_WK_z!*4ZZNfj5M3(Olwqg)ThU-u5{ zeo+#+a=`1jdsPB7(UEBPB6q8aUoJA#0u=QY74gN0L7Bb|PB};A%CQBa$eP1&_`T+W zMEGr~Lndb-(ACk;a*4VUca6q$Jl0De4jZXU+rSGg zKlG#8tU&G%Xk>|yiPjnBiHbmOGitf>Pp7KfQ+oZ5W0>PU(V5$FK# z{GjJfrXnysQ7ajx*PeU^B={c*IDyd*HfdjYNE~bYt=W~>@MWidxc)!`gRbWJ7Pf1l zMg3XdOLDVfL}`1xVylTz{0{rQ&oyhJ%jHAqK6 z&BM8Td1X?n`s@Ci+LguS764D$bhw8ug3WSL5%}?CgE{*^*=87p3e7BsfR2P~bCT^S z2<2|ZXm1q3m@iHCbjo9Ftg9$@guvn|@9;?^XOpBmK`VQ1l$+pP{paqUK`F^jF^DPXY2myu2Y*?=W^?-cIkN`eEOi+(C9C_S;PH&!_PLk zW0a<3ZqwIA@U^sm5z#A(t&i3c=oSVrt5hxq78a_unR;eAMHOjT`&mm<*=cIunO+TL z6&)CzYoC{0-Tm8t1U0=bzoKO-3HH5~ebG&rGd6yGX2LY)!Tnxxqw{yO%T$-s(cHJ! z8^o{ysOR+;Mb1lbAPi}MGg^=Fv_EodUVNJ5=l_gtj7K7&{2r6T12scOAECCN_OncE zw9@8U08|c0l_h--9G9uc`}5c(+y0hN>U)U7kIC|$fYz$q(d8`|!@otVo zDo$9t9kFQ8lz8+5^TRJ=#iBCXmj0dL=-o%^dOy+OZ+!i){jRgG>;S$xxY2sxi6qA1 zkl005*zdP9^CL~rFIpd|-OhU-zEdP>j32N7^)UNBu`Afs{S$1MMSTwD%y<^6hw+Hz0K;SOAutyNARdOZP&rIh(p?q)?9!#@t-Urn z!ZJJC)bt)gTU(>v9EzeIS)pr#dpiig98E6$(7!kK8ae*`ug$w*qdIL-jN%h5sa*Hb zXMZ(^q|)9Xj4e=$+3uwy+hp)dy(@D3J776S@5-0vV%(W71dF>^BeRgKZ{Bo+C@r$@ zd~N+>d>+Z;^jX8sp6Jpu5-R)^FRao!4OJ-m4^^ivw0ZKuwfF>+kfr7G)?5s6! z)BI9635@;AEsr`){Oq27n%tq>r>Q^oR)hTBcXr__QV5;V=)Bf4 zDko|-gIGi=k?AqJ~qThChyDB zU-^3(zq)cso=3E?@6W39|J__}W)oXc{|Bg=Up#_~0moZ)xWi$beC9qg228)jaeH3T1YN+W;tFae+;7Y|-(Oil zQCP{%Nb$=o-?1r3Pmi4Evk<6*0lhZ5G%9__UP>V4LZ#moWfaLGW`or^&1TJ&8<$ud zSByW<771~n+e=vgRI1@L_Ib0xPyE)fMMK=h-MO>g}MGi6d>^IUgY$jNTarvfbC5{b=R5yayvwwb6X z8a!`ngRZC)l)LQm>F%$XSD4w;i1xMDGMQ0$$h2*FM#64D#j(a6?lpk{=#h`j?6!*m z$>q*D>@_WekhCKAWFG1cWBbR7kvxTU!*vV0r&S%-pFL85Yw({pMl6@N^|rJdhq(Tx zgu>;BAA(p!#?T+^qkpgrgf3o+z?NZr_zoOofIu_9Hse`1uYaW5Z2t80uenB*$WB3M zhQ=Jv(a4Q@!zM{#&%fAvo%aGqZm;t$&g^!a-iHjFmwK7EdQr|+sxcrkMXL817N-wp zEKiJ$d!q&`F8!~b<7(lRuI3~0EmaRa7na?m67(@+GqdUaB6>V)LhrioH`$2{#n_zz zQUCYh+Z<$g&b3h8!A{Hl!$BQa?Z^{fIlBE`goi^09TXA7EtRO}aa8%W;Tl6E!zs~A zciqenkT%5@iHByKmD?B)4^y8#{VMkA! zx09ar7OM}*I6?jH{DSda-(H8!aEq|L>6PObz1NXkR zHGS4^QD`kW^!4^mf!6ipYODGqw}!%=z}Zjk`A(rmFu!N6e&Jws&9YBn%VJ=2!pEv3 zB!PyX?2a$tQTmN@)HbDU89eFVzvvLP+B8GnJ=FNwt^#IO4Hp2 zcI5yHujqV6MS6)JZ8_nQz>s`koj#W%p~j-}2KtQ^KbUV~E-DEem#nNaCkPp7=#dV; zV88mGrLxyxFkRZ^eZn!F$<=DU|=szC*N8@OmOrog5}4ssYyh7TEji#G?#Vp7@$^_;$##Lhzf0n6H7q>WxV?jfH}ac|L^>DaGnotFduBTLUjF zYGDJSyKP{8G{HOUR_?7hD}0#&-1d*e%~2(pXJr=e4JyEeJ_fQ$kPyaHpF=wDj7L? zvY6YFakA`QBegI8=T%3h?Ll$|mDBG}U&TZ&{cBBl-#E+{;%Eng9mA929p^zwkvf%D zr6so{MnqoTh##rH`yh0T(U5-V-7C$Taa*f8%*!D#kCnD1psB0wpS)j6$8VVIb$%J{ za4_1Bt%gbyA+_L9Els0s*o-{PKHO}5^OjTVXnwX=&yJa1F-1u58#S|IXvvl0tn~=T z6C7DdIaSa}7U;N#|Bo(o%FgaS@1H-)RbnXqc33>cQPbzw(l90bgYJj2(ctDfrWv*k zKqWcO9h%M9uQy)ZBNJ;rFEO(aNN+EsO@K?Q`&>Q^lxL^andg!xRFzp5Cox=rBTjTw z#>G1{>1{}xvUt_0Ywj1aYt?hzc`KD>9^#5GIdjG7Sznh0uEOvj5J7ey2D;1bHc(d<@4dhQ+-R1_$}It)*DM zmkXnV%FRG^Yt$=OEL^F4*qcxk?kBn5-4^aWRMYDXPtfW#9e_+JG9D})WoW-hj0mOjJ~N(MOxj0W2<|GW?Qn|5Bz$<%-Z2O5C;d|f1CH|CI zxc$9aa2~UHJ&q&Eu5vrz(+;cq@huPnhZzj4c z1XnoT6Qtd&r}_Zs1bKSrf5$}rH*)L0!^LNhZz#JHYqzHtXX-R(sL447GNgq5cvyf< z0L<0LlnuaF1`b1%Ghg3HhM`%3jm{RM9pF{oCNPBcO9P(hpF$&msTXl2tQAW%2{@u% z)q%1Iqa*@x8D0;tG|dBQ=hG_AD{@_IjgTO*EP<|ulMrqU#@{YLt6%Y$gRgH^hhf>l z{mtcHs8{i7&0!a$rodE3J}iRs|9Az`wUs%)qm~ki;2Q?^jnh|jp zY)-K}dznZu?|hn_jPzGC(qJ?FOv(#A2VXJR4dnP&Frbp&w~U8Ttw6GUueBcTZ*=5^ zzv|mRi-;%Qq&}~P8J)vCGylE_tmqYhn4+wghS&!?<6M|om%oYmDYV;rN*H9=v}f@C z{-e}lGK|wfJ9!!-^^y!DN3(*aTz4e zwN6@~V~P!SPI!H(suuEBV5~Z$R!A%a@V=+d_$TR4?aLOM1twt*+SX~K%z^Yq3BE|L zW3~+8HyFFJ(~mKs|4t=*FQ3`jbXdjnhMA?>T#9uWcrEp2^lqM0%2I2!>o&t4zEM zOeNUg(CrNXrt%fK3!u0G-u}6F~5}Nkz?S!1TTJs!Pk)z$t?wXf^K~RjUVQadSc*G#=@y}XCNzQ1#<~Uu1pCF2Dt#xxvlefO{ z18bAk&By`v_(kP3$DT`V*h=OqrIMJ75;69mpj2Hc!6T{MYWLH)(4^F-;%RltA?|cG z_Gb=?O>_}d9oJQ-kn68|a3?s?XvMwP^*FLz!In8U?sQY(bW(?e0A@PPzwWEw-z0l4 z%5vuXlRgfsFKHX3fSTZn`d7H*X`_$#`2fa=(mr5A(sZ}AkZvG?U5XHdKMB*)6Sy|b9s_cWrWjHxUV ziZ2e5gq}~=9_R7tKaaJZ0eWyru&Y-LN#D$M2kXdoCGoN&sOR*~cZY)Oo>VmoYqh4V z#S5m``?bg4Z8TnHdql;NGC0Df`%7)CrWP^3e3d<_!dEw7+LAM;pHH4WEX_S@kqQ@X z^w3+ZY;r+50zM6rZ*x#t+HVR;G|n^K`9cWK{J(=DDtkH33m@r+P16^D_b0Ep%Z112 zwM&LZSxdnN!x~Aa_R7#bel1}PoOc702DzsXyQ861+SYuWbSedT*uOg2Y#tjx%*6jA z`>HmwEaKz#bi9!HZUc5me%Jyq-58eYXB0mI5skF-72=n`IRt-YK_5A zDC+pEtui{-$1%^^waR{4T8IoV&AH1>G|n3jJd&f{_Vp^~3*$ykiRQ0pE~%{p1^QW6 ziq@0vZY%L{JW8e?vP;#oxz!rT6|JG=9{w>rK$L_kGuU;`ujpT?H)?5iEY0iuIX*PGX z#JQ`n38!UOZ}3lu_>l4r4~}qA{sQxa`69arKa`|!v;g*FEuVvHRm&rPw9U zIhD{B(Q7W$Bz;HoZR}uxx>l1TQh<(9${7(aQt7!7!ucT8{$BNn#PGTh#$xAn?bqYx zw4ko8;{C=h6J*mA7CzLKC;5CJEgl zBgFZj)?+Ql^aFc5uBPjwZ9AVzJ;^7QhSbefb^C{;&ARd;6xz97RS+m;!8 zQhXC>(D~YOqctKuMcX36GR2c^Jx4~AA@$GfI0v2lbgJ=w-CAfQRl+uo8l7QWbnCA| zuj5#4daAe9_HpMtil-dUbLs2~JU!%dOu}oqu*fL)1Ex)OdTs3xc#F&{x$X|}>X}jQ zvMKH~!k#Oo5H~D!yP!?1FG2T3TQ>(toCU{(jDIwgY#e-e7^foLnXRVQ4Q&ALqC#0J6brc!wic{ncTD7 z;1l)T#Q$4teei$8)>Gu{UQ>3~qto6~@Vuunt(&aF3(7{ftVUTkne^#^2bB2Z2CZ*@ z0RU+iwV6`ftNNX7k$f$@!cB~mJ?n19Z;YR{ADB+M0xG76q8}!S*=0q7sZ)CdI27*T zvc;bIwIvzof}VTb#EW8^6uS(Q8}Fx+5(isDD)!OZ3(L|tfzs8?yeVM0n_!cK>#{=K z)k@@~Dzs!$wKP3L`MNeXwtE&X*ey7R52IJ8@pjl%<2h*H=@fb!qHbXc7uK= zBcFK&^1VYMNZT>U8(Mx8{`Y|s)1EhF?XAbQk?nO0x8yeTW9_vU;_i9a2KV`P@;a%nzyz77DtnLK(C&{U@@ z(5L&Wgkf2IoNvl?>-XpRuI5>fQ$0leb!pgIt`)^~5sY7bz3Cr2Bx+-6zQ~Lz#4+|_ zh4<*YD$FKpxPj{vlPcYNTL%Y$ZqE9EKDL4g7zdWDY^~idl_6*@|56hdA zifwnAJtnyfmpX1;w!eGTpvKI68hqV;ES9MBs1-Xo9|s(w2o+((<7L&dr8xdK#?Cz6 z+$wA&$^%?gL`xr&0YKOREIcW3wJK0|zl)tkIar#lEMzOk%U!8T?WA)FmlRo0FZ<0i z;=-(@3GY|z+B8ZnZebmmLszLIsa716^;zQiglWc|YL}Nv7DC}z=KV?Bq8?U##L{z( zki=dPL0}7XQ83+Clr4NJQe7%JKm+&=83Ii_WnLr_S$=uPl9zk18dcB+AE=Ar-~uY1 zpMVGDgXY9|5Nn;iEg#0ret%D38_)jb@tT3X_@7fqVRhMGH zCAcmk9;LGyTicBn&3Kc=0zy-4aXemlV~G$>n9;DKpv@M@jUTjewRtmJ$DY@AOlVd@ zMjk;g#iq8DOE}DHd{k%gCNEugTTvln7d+d#cz*b>^_?pNtZb~*C4M7w0LGcWvZ&sf zB5QNc?^Dm0EF4#iF+FpJYWgz;tsAFLV4j2t&Q?-*-xKnFr91Nu2r)$pZl@cFYQ?yo z`v*6)t6z(3X*l}#rRSJ<|M(_+y^3AMoPAURp{$nh24*^XB6)W0@dLc{gJuB_oHmT! zR!c?>-<~H*DPy(I>VBdnUUF->HW7Jv?*ACS8ub^-WC!7l9S}t1!lk7JUIJP0xe~{R z!o6>DJ$ANBfeeO{Fbv^|%f;lwYt%Ql39Ok09Uarhc3J4=Sd(#ZYR`;ZsSsaQ;lS9z z(q_kMjFMOrvf8G%zM-vQ_Cc)RO%$|BoaCVc$vUsMS9o&%A8-I+-WsdrS`f=gCmnVl zDuDwfCWX~nu}x~LA>;d(bRPud2iDTP@#-1l{wQB=IpgC1_ckyR9fmQPxS z3qqwEq9DyOCW3Th7$;(Ix?tZj$0o{K!Yg&twsEU+Wkt6ZjAPGT9d`!ToR}!Zm^_8Lx6HqI+>TLIK_?DBov1Fh8&ojy>yR(mt$ z#w*v;brt0C)ZOj3F2OQI&Q;D$2S;@xj%J0au8i)r#UCO`?sHJ^w1ml8(a!-G!bRVF ze-KHxa`#50*Y_vUYc87uyqz- zezdaR1FCdAxg9H5*9^}7&s5j{LaIjxn9+$KIw$?4)3~eHbc^0xlV&LG!m!b*ySkQf zy^~oe`JL9=*Qp0>it&DFhA)M@yh63&KU+>8O}#$>Dfc7L%VU9JgFo8_#Hg10YRuHX zPBNq}Q3V!4Ae`cQVpPqdJ3pKF=_I~&Zt5~^ch+p-!`HH|6l!Ez)@kWYcUk?vbXrWl zY3&ke(|m#|OQre-vgd%b`!w7n6YaQ&jh!1E^C)f$xk7m&4129SHnko;d*;@9S=|#5 zCi^=m9u>L|-)B~;cN1NGp-U0O>5@q1gwpf39;1n8Ui`82hjHlY9_|&s2uBHUT6pVm zGN~9N1b-{SmkrRTc7j9mliYcR|MF&XOoA~ z^VQQT$Y*8lx|BGYk!U4$=yNPQ4r)hD5Q&k}QPIr#+ecvS${fwt+~16*(m-v#G0`x4 z5ixe4`eU-cL&MiSOc@VCC*4{JG%?S8g{{t!jghAK()@QVgRY#VxH&vEpg{2!$2$FO zFOHeTcXj20rL`Slod>;VV%HC^Q32h}1+r)91xuOZs%KpVB06M+0)uFrCxLE1w3}N| zmErxwR;D$|N`G5_A$O`i$lCc^j!xFmz#i#oT3?N;Cv9MoKHf_yi7d0yx&BHSmoSTP zSkc%-G{@v^rk7ceg_lM$y^xt#?|k+2t!gNbDsM`_Ikb)mapGm!<~rTAh&xAVf-_~; zx)0fVx{Wh%&q!RU#RZ=ykOB5VBJ$UynyQRCtH!)3(;T{&DqBjj$ZqK}bu^8(c1wb^ zj=XlR>+lYgYolPnU-MzkHTPA=;2_OPTK>wXr znxf-aO|d>efqdok|JaP3|K;Bpnr0kNdgqVf#Q67r2aNSxl(^gK^DX6n*res4?d(|T zI=rcf#5;Tny5(ciI&3$7mDf6a?aZAu86R0Mtyo+Ac+nPpOiS;|$#|k2vaj^xuloG) zI7mT%+CIbUewCLeA#z&yCW+IQwHHmtx}5bhT-d%W0AeKyoa!gA;h2&tx0&;~GEk`H z0}l~q`@xCI`g5?$-%Zq!S`A;f_h3m!D&>Z+%gn}Z2z1p}tSD3U!t-B5G#z^kCXrX7 z*F~P)2GCXxek=e?-K{!gv{ZrmID9d{A6|K!Vn z%m>FZC;9odYS+w*(gM2@$f%vC;-t;npB9ZRlM{ONOC5$L5{wG1L^UmZeoVbHI#2+N z$8YcwR5r7F0LioiMD43f~{F>w~-kCLT|q#>>wD{Sj<`LhGQcO5{OgyZsLzy zOW|1_GYo9&Za~+>I#}YjrzV)CMeJrETovbEgbvjo#*7;vJna#OdcUOJ>fCMAppHx9 zlBgd`x&8QuT4=xk0Q4gv(9Rx*h76p!7VesxOp$Js-M0RmN%Lueq(Wb&5&Mkf&(;(w z?vx6j-+5Yv(|wjdJg$n&+9hz$v_PsWtT}e4D*_Hg&G>VsYn`2Wj{{bA7OiJ{1@Y#8PV<3P z@D{H>f*$ReYXNrg1q(O}XK{0fkkP$r!jz)k`zylE`jk$@LVvYQKm*lzW)SAuWT5RV z*s8+Or)`izrRr8bC%(lFUBlk3OCn|~ zR@U}DR9)L|g}05F$WxWunr!pWd4Cvd6Ram`r3&-k>MDtTWLK0n z>s6g%S`TSqc0FCSmi74)hUXLLucOC9&`B{+Ka6llf(-bcwu|pLTb8oI!na0-PI7<$ zG30FqiMnz6c9F)1b=sels-g|RbPpTI~o7Cs3H|u*^|FVK*ZoMjw>7cM5Yhcl* zm?B~AD0gA%)QOlpIhm00H=dS4EG=p9Bnr;b|Ck6gBBIw^yI~#6A#mNS7=}p*KD3&@ zQmNjOzwUGRXu4uyrtau*8SsqcS>&(LSdk;`d*QZ|8Feaj(UF!fAAOYTPR5-p=|-=M zxI>Kv?o^mhj+xBuWxkBF^jwhK&H{w1gj27;xL~N&Y*b_~5`GE3WK=?)TAm;EBL2Aj zm4Ws;rnUu4Zme(AP3s72HU4ZKez9e#LfMV(FjQ9zazQ{ z2g4L#%RsrGaU3>Gy?)L_vj^GDSsGYih+J=ZA9O&|FP}BTtVd5X-SpW{8?OdfbJiH1;y-UcmR8uOXvY$|*ZHwv6qj@0E%7=QQ7qSmm9!7I=&`l6d_ zHovVk7pN{~Nqm-TI6ChYGpOwQJD7BR!?b+3ma<;q2-ue%%6I%U==2Z{T2H zjw?B&6o})GUQ;5w3lfsQDb9-{N}gil*1Em*{=w67=24ozENmRPSUVLga_;tJAs(5%~VQ+ljvao%6 z`;DGO10DVZ1Wg8n>f`IrKqIU|f3M&i>;YA%0tCm#|MN92!oWa36=SSf#sxSAfx1~NsZrtK|VVin3x9P`rE>8uG&}z6KVH}Qq zMWa2yNk30Zzhm_P=MY|LP8H;~F-!Bi6;Vzq5dUN8=HjQ?W6mCu48bpW-60SarY!;{ z9{2%$77rB*z;JQ^_9GWDrqr^~vdhqa_94y=kJ#>7oAz2&WuA!>*h+f3YeAdT}c7AxST7A zrcfU1ZtR~JsI)(3CCJvy19)FLO(S(tr0`9meT12%b!5CvubCZKAkdmXv5qrdH*bv^ z#M<6 zS!eJBaC|oXwWxX{O}RnxYgYq(m%<~xv2yEAUDuLUlS2A=kGqvEmfc{kNh5mw>p}wp zY3Wp#-HRniTu*oRkGlh4QpJbpu=l5{R9y9vfyz(Vo6Tx|MZf6`Uwco3FQRqxfr0H3G zM8Lam6yrDH!PA!XCASu{twxemIAi<&Ua}@CE-oAdW$x49{yw|@Okf|y|!YU9b?_xX!M&Ptxlpalsyl5?Df4MI4 ztBL>iIZy(UXk?n8fm!S|mG z1y?^UhFh7}4{CK=nE&3X4*7NerLMMc-OC=iP-nQeiw?vc)Y8^7cQRds_C#^6oA%;{ z&iW_szG%hP4HQIOr2mL3#{2gze06+p602R2bu}}|L+(DABHJc1$ul|_SZ0JhSwnb8 zX*>H~MuXBFo!|T=*2y>X`A)tucD#Osy6%PB*F}R#2oizt5odd^+Ca|1;PfA@of`>F zS#IW-bsxyG9XFF1zoD^R>r=yu<(|6(P!O6kx>pYC(1Qsj@6YKiL+4R4=jzXcYS{N{ z(y3t%*7qD#)7g_X?R9=URdwJLP8b)OuX|Y5afzhD%@c#hwrw1#1ZxvV+qy!RPrBwW z@{@4ns`ykdtWW=n{A^*8&d&qsuDZP%vYmyR7B+;JySqr+DfV1@6UCUgpg3q-82j#v zxWIlLp3gWNbFF24AD?SJ&(qXsb2}Rxd0^oG#UUxH)_(c#0Bc2tl=ZpOi)`XC%hg+3 z+c@IWFUaEpT0F=6WiqvZGk^QC5n;bhXMmfWjm!2-mbreqj*fSGOtgK)4@@ttr z+rjdD(&4{|K(wit&-3XbWMbq7tUHEPV>9u#g&^BQcMG>vxCw8`>>{xKKSJ$rVtwF+ zfmid2VxG{pHstBWn~Rp12hHWYOIB;25}IX(-pRbGvUp%j&A>S+cH0>Sy6#pCKqpbC zU?y$XA@z;$c7Tc2(LM{R`5xW7?QPn3KSkaB)~7c&caJ)RS}w+M3a7DnO|*`k0TvwZ zw<~wZ+q78jG+8zYi@fz}Q*Qq8vf6JsaX25lCY#0G=_>)e5%w>-G+7atSpl-;Rt~Ij z)jefb^}RG?C?H6$d*~9EBzM&^YG_OuZb0#ReOiM zD~@Rv5A0`2&hT=$sD2p3Py6Wu=tJg6n@iEW5Ojw=RiS%^9Z3?m=4M4QO8*Ddp`-h^ zQGS9+rf&XAiN>w!<|my{$Eb@IA;0ntUFY!}tD~l6>yTyy#0=7KBz8sLwnp7~mT&;$ za|zzR1V@yl%+HUZrkG45bUj8>eMdyUC-H9?G1O%fpMMnB0w(ZzGm3JT+E8v>Qok5& zAix0i&ljI<9rAQJ!;N!WpnhbMJ>*uC5R=&exNT&cs73$$+6%_XJdBnmkQ=4iF^I8T=OfMl8V@{b*9%!<$MN)k;^adMsOQJ2A`^?!}ITDT61{cul}>>4}N@22SMQPZ~Bx6(f-slN)no(Wvpg2G{4Ko6@r!R(5P3 z%lGfQL5ui@`|i~V(1n{CvHl7y<2|gqk~=$BXViX@X91V1dHnNpQ0SuN>5AA9*dHo@ zndBK!x?hiMX2Z8U;l2RNtnASHxBsBvI;y7NsvxQ$xkJGXrvQ6Qk?yQeT-U<5)iH5~ zZSwgg{8e^Jd2XP>_NLF75lFf({!~XAYwQSh(M|uQkwaa)0Qo+PukB1PTuXPF7q8!9LJ^|r-O5hk^+1H(=SAMn&#bX zyCV1~$9QjX*Hbh8a%35xTSAs8SC0JDe>qjtbpk|ienX92-&OPnHE(G#f0)0&*e-j} z_7$nEX%;eCFy-Hb9T}7t>%YE>32lo!sP1M9D3?iQYVi@gdGwn{hK{AJF`VJc_o^mu zi9g<-L;_tg6P<79g)F*nnoj7Gx_KDP={D3Mb@30&`oK&;*eZ9u5$o|;I>A6?{=xhP z!frHwlVYtsVV;EOJcai0qnA{que-7;+W^Sbz`n%gpcQWe0t!ZVt=@4x%5a5%Bv!Pm zVkj&8AJV^Roip|zzoEIG^H)6Z-sAG--^i8Fy4yHoA;t}J#s^vwE;}nbT4Se{Zgn$< z6_<$1dmt>(s>ab;R54U#G5UHY=4-q2N4@6S>2GH59uz8nYV=i0`1JN`Pi1%2sTtn0 z@`~@epqm*T>i4(C93_QpK!}r#*Uk z@z$!qo|a~p8~ls4+>PQz!k8u3|Sa4zB1V< z|DG-fzTu?M5yRv375$(~Y=gIr!z72u_|-QL;(IKW!6SP^PJf9d0Ze2~HQ(Dhi57Wyx`s_)lTy z`*&T|?q5Tvo&gn26aYJ%=zsP4w@&4ge^bV{Zc>3ybO1OHzz|lEW~wW#1z3otJwua~ zOM}xadz<1q9BQ&WiAGVc)Ppmot_{MFfPehwq^{-;8;2?o2zEwIMn#kLV5aB-qs)QB zmOGnOH?oR45F;e~7*>hZ1M@BIb z$ZmKe4m?C_MXn$i9q#o@e_cA~qlH{<->wdQ!_VJ%Ti@;qO>xaCF_#N zRqYc(7kB~+-unlnX2|p}qFs-$-7mmT&Ges|vWb{EcirK;g}_IwW#yva`Nc4#3SjA% z)_ux`a=Z#0!UOhiO3}_obI}s%|urYGt*HUFWAI7Iz-qBwLeP;68YTqt~K; zWM;;WKO_z9dNs$aKX;?GHG*v{A&V?P&dP)ZMRw5syH-Nd`j&KTpHaF?Q|C@DzDpQp z{EJXOF#EkdlUQA39NYWD-1~>P_5z>lc+S|a+Q!7Hq`${$8w6)}`WpWM+ckn*p#;Wv zPwey%`x)!6GPOH$N1JKxB^$+0t4$2C&>qZ1{kS3boegNAndqfy#@cP!8Fc^be)1LK zEa?(3PZ`H}jIdnRxhvmQ6q%u&5nZ3q-ArkeBar;pt(Wua1-{@PdMSONz_U51J5zy( zN$|M2=4sXRli9kcqeh3UF5w2jS~Zqj;+$)e>-XR{VoZ2RO+3(S#HRSr=2XXL&)2bVme44OU zseG!oN#GOu^vt8?MUy!zWNXw9K<<2TNEsNiPQEW3Qs zLT!I3XYS-J;7ReSW`R$^FklGHa3j2B`n69lYZ0&Gszsf5jW}_U{?)c3<=U>1=X>= zu8t1uV<8Pw6aFVtw~Y6kk#tNc#fmAw|P__$^q^I0+{LK*)dgbLPBjo_FS)HS=LUWM!><$VzsS zoqb>Tb^R`%Q8KKBUR_=FY_M9H=dP7>WJn3Pi7_kApz;xEl#Ejd4NJRxwqX&c>Z3Fsm5$De6*@OP;Cr(#Y z-7hNVQBLypz1iRV!*vCqexe!4YH`-W$#S_%e9m1P;t9#)%&KQHIKTDLdw|bT`2f7C z*17kx1p~r`y3MxgR%p?0ZUiCX{O5Sbw|@NcR(+MApWXnt!>X*%e{poQs~IWY!-5Ytr zi`nFmT;^T=)q+JN{O~f{cx&^*xXR%yW6wK8!S>o6XMhc=+%d_jit(=Ea5gdS7e1$Q zq_2(>CM)*OSJil4LXfj7yHQ5nXLKD1n}%npeN-lcpvWtvYk!IHwc-D*i z4f=E`UEO7>4qw>r&{I;bXp+Mm^I{+ywgDsZCI=?_ooGQIHD)&&)lQ4eTh->XY>X6; zHkqhzd*a40W44v$gy>NW(3nt2NR-*M2n%e$q;Y%a~e#(il%Y2tn3H+9ws=Rh?1 zShCxvjYl;H!b`1uVxg*F|^&aN_CRYkyiD^N7=To z4_V0K!Zhy4*#!{Mzs&wB_>JS+*`*jp1y9ls=wqP_(n_qWiAhCZocy#{#BlnFi}*s% z&mOK%j~X@XB%gfHA^VoreAoJZEexJS`{7CX zz6EPyeujT@K>?umkKPc^I4!Nu(zHPhn>oh(8_!7TP57MN>QFAeFQ~yqU3>0WiAJ3_ zVd#&-UDq*nFy5E3WMX9M(yVjb4Rx_(*+Fss;Tm+YHVzwaOI9|yNu(w3jU?4|A$87c zCr_#?sXhu>*V2cNP8C1v9L*BYef1OL%F}jjF?8cJ8~m&gYoVF-OZC;LajB2$l*fme{lR%P5HIYe;vK)HR$dDJ) z(QwC0+$SM-hhVPP)w-)ST}5eXf{d>jx~_Dc_?U7qk;Xe<3vh6cEd`c-uhuqKv(mzW9W zTvOOS+p(F{sUrG0)&mu`uwp9sSfELr>HR(Z7n5~u&Tl^W*%fReM?ob7aui?aBWrsg=wBPTWU+0ZsCx_ zFXc6u#K4Gybt4Gbwd8E0Cx(a;sXgKFDC zY=|9285Y`E|8*b-!B`SK2tll?JDK#tF|Ap8TTJ%PGbaKKs;mWQ#M3D39NfsXd? zK$x2#S}N509Wr%&FJ@%iuH$VU#q&6&r5Q{nN!n!C2|vFy+Ob*EEw^?7DQEXC&l-jt znkD`bSY^=7TlvbT-7+j{{&m(*yDbnWG4A{`YI`;e#^5iuTC@e{FKk z`-LJeuhw@MZ%}#Avdlap`@lzf%7iZj2xF}{BGfnATA~o`ROqFT#ydPim3xHLrF}H^ zaSGL4kCMJDMc?tF&Qr#UTwD3mt|vC#BovAk=DT=yIo37I{D|cWEX%=bXgm;q+9aqh z*G~{((_U9LQN%y_H6^VT3LTp~DzH+<;VioKz`?y-AZEaai z_weg-Xd7N_dQ)!xZ*pPk*5{ZP6uL(CLDGkP<3Tf*2fna6=c|ay3TxL8TQ7>u^dX28 zqs%dJqUqf2%5pjThhg_t!i|Lxp*A@(+GOXh=-gzVQm3n*MK*kl%X3*D{l*rwgpX7{ zP4sGhq2_(sslg18!6TJ7trD1<)7E9mk;<}<5if}2E24fb#M@1{n$_hdRA!pbbz%O- zziVgrXYIBUoXXF2Rd_yG=>v3i7?~T#GG(dVV|s5|`t|nHktg(Mj_{6^67!kD%D&L@ zZ5ClGCRuRnuWFj?(+1Z$At8;;mTwDRe-JBDWY=_jYZpY1WUqtCA?)lk73~Z8yXXJR zJOTgDnFsb1Hl6p&E&G~(Zii($soMc_x4o)dx*{_QT0TLRR!_q9#r&DTNo(u#L}PA) zNdeAhq``|lCVEEvqnVi|TOmb6qe8iYriy*!W%4ueewOgv3V8OCw~F0%)nMLy-#Ji) zw$cXsYdj-X4`s#b$faJ}%p6}Hx;>0@*HU^b)_Tv-eyoz`r5^K(CK zz5W1Z4A()PkTdsyldw1nA%%9C%)!)Z6Pai3;JT<)h46ZKzQA)S2?b&I@WaHt3Nmr_T zf*Gxz zUp(HZutoC%`xOaWUj)2NCd8N38xyJyOE&=mTU&fRJ!Q`=ff9YU)}LkofLYz)lJbNGuvX**FU* znbK}N8kn4yS=g+dIA~*AAm#tj=5_K5&=&~)=j{&h8z5A_6H2uqB!6;a093;PeQ0An zPP?I)8?jYfgrikxDc~r|yJGrAviom|NaM-P=`TwUyFMuwh5ljvE`R(oF27*BW21F16D#v$O)M zF2nNtf^*hkLQ&7pXFr6SX)P?7l*ezr7qj}xT&T2t`f-WzY3O?5OFX5l(qH0~OPk%z zz%Gs9h}@_*YJg9AGkMSA$6K;q#iAa$9q@5xslB|b`Jpj&QVP8I26TYs!!C&#R2+F; zTAs-Z{jG|T=j-O6z^ZgLe8O2_=wJ%duPS5Q8sy!Q&lR$d<4-_}o@SCC4K)hw%;;R> zTvoo$jxmfY%8aXV4|_a%Xq^80?w<$M1Oy~|zi(GmoXsy>;gpZX;8`7K*qfn@SpJg# zA>{losQ3i`^RZk165;-P;W;70f03G90>l0#xdF5T6UlWbs|8kb^v*lv$NY=Ojz!nn z+a06d4xjQ)8O=kwQI98Eg^2b_{46E56zn#aal}ohDw@X?UTeAar7ab8;o5NP_n$nm z7hWSFy+Y|z(qsw7#}+M3=8zbjzrIKKI}7zbKqS*KbdAm;JLR2lB56yd)zhHTtDrn9 zNqyfDMgt$VAD*&|G)u2fbh(CwzSgCPJJ=p-t67~D1WS!ceU+V8UU)b<>Ki;lb*1q4c8_w?^z#BEVnSfYNpLQw6Nd`BS!nHa;n$J$@f?%Jc@ZmhgFhJV!l zv3*QxSVuMGNVmQ*Iny~s-LOFg)eHGF1EX^Gb2=&-6#3Z5s+T9BGQ0J6Rwd#=IU9+Z zX)PZ@g^AlFk;3KSwvO^F=}MBX{w%t0Y_@0~^{m)J&BIktmoQxD(SvZX0tC<6fu3GY z4k3A+T4S`yeWyA1rmZ)iLWR&DwccftZQ*_8U2#2kYlGuRtm9;7`)Qs>S6STVm!mYJ zAlAJQoe`ljGvlBD6Hob5F5LNnvEay9u?Vo$1uArAp8-Ogi0*$cx+nOzMyL1R2q5oe z>;4OvYy^_TE85^fzmysN*Ei&!`&%cB2RGM}{z2y-uwp@_E`gnBRPD;OR-1|Lj2%rs zl-vez?Tyk|f64cWAh9z}CKb>_czeR+{B2kNM*A$Oq6TIS8|=O`d}kILU0PZ73`MP9 z;#2VRdG)^at{9V^JW|^Z?K@rP%@(G+L_(&On^VZ$VQwVe27e&V4|qAqTil))froVu z$^ctWNdqKYSh!a!U_3^_^C`Kz@>_xtrB}g`D)a}t&2m0RYC(lnMMXuZ&{ychmo?=S z!hN!thc5G#W*VM+K?2BSM!N;j+WdY8Rec9DemFBLEl?%8UWC;oamTJ5V)oj`@ncSm z@Y}R>Mv(~j0lyBtxvI(0_jz#Quyzr|>Jpz(Mkpn=R=>Xfw$LDycjA0Y{dn))>M~iY zHDRF{{2OS<1DpU|U+AC(E$lSg*N>EyE^7j$hm7jFT1(9hLDkqM;h}CIamRfN1b>g? z!4R)g#fY{F6kuV86CrF78P!2$FV7p4ITEGad#{WwEx4Tt^MtHByp4=L->np89eRB1 zrHLCgJcsWbD`&?DpkYu|xq#tkli{0b%A$@Cs|!zaS6)=J)Y2&G3I~|3!}9RMV5(Lg zpTc0(iNvDSBWi4>sYQq;>pk6b*Wc8dCpvwD3-m(?o1si6GJn=&t%YW{XCqnxOZ9`B zGCXw$^$z>PYtdzuYtbvAJU(CFqq#me-v-H9=hI4#^L(tDBc^IaHxBniG@LkE8oGaZ zSf>>LvUNI>iWx5J#kXPP5kehbf?l&^YCTICft0+Y{r|llB7n*{?55TISohm*%IPGgNmRCW@`4Gs#;kORexg0J0+j|skH109I zlF(prlVdH=pMI~x^}gG7$0UJysrTIPWH~xc>%!VIpcF4BI5F;M@M^eZ*LdcRx5v7)v&L-yC3m~KhM0EbGQBIAW|GIa=h-suT zYoY`U2(*S}Srslb&F7DA7%L$~!NQ`Y)G?+IRbNq29T2{~>hC`Q;nC0NvA>v`kY zXQhzW)h;$xF1$Laoz2s}@P)7kK0wl4@^$~=eI-hHPp<~ogsA#++Q>M++0C7;02Bwh zSKuu>B&vshD$7N@W>Z7zW@~9y()i*{!{JroXJrwP71nJ*E$b{>8=m|#aWO9)^qzd# zfIgHH#L+bx5!lh2RPWOKRjUB^aN_6@n9l#lp?4UoTq5%XMQ4^phF)w8%M%(cqLn)( zl?&%Ui)a{d;3k$SD}%M|F*<*rr;O@nzHX{bMReKIJW_io@UX>Tz`*pX^wUD*y<6F* z5Tl#;V4A#|tunM4Lc-GDQN1mOt=?&xwQi59aL2>BNNE!IYf*h2 zps!<6cWh%c_*F0epio*!_LfUwMeT&|_Ja0aY0$1e-+pyIY><(IsoWLEh5q4sryG86 zmWBSXNh&M$&m$7q&vD!*B5hr*2I=k+48k$DQtd-dz}dj+51{4N_HmHl1)bWZuqA69 zq#CPYmb)HDcC!j?;5n8 z_XpE$Bnqf=?@5=u3XDSVPBtqOpp$Sk7TV~dSZO7Fm>@)Qp@*U$jng+{g(OJq|J~1& z(0#D$;6!5fIE?KuR>NpOb`VUU%n%G|$M&prPz|r>((V{HgJUujDqyHi?TT;<%ZTQ5 z(G69&7ju~Qw@hPiWa(xDd?)Il{)hj1H%Bcv?j7zH-9_NIdTtPz+iNPZ_KW*Kk>hWf2reG2OiIJ6lU^oYf{;)wo$`+XC;^KeUi#<7cFAAH z@5RW3ZNl+3+bMg2zlF%SsrfI98eOC1RAP4K*z=_i0}K0lk_i0s%qA6|t%}i^V;3}N zu#xAdNNt`CeS{E+G)G-A&v%+g6=!n2UyBdUDuG=h1s1fLmk1WSBswJ}Pt!FSzkN%L6 zX|JF`7;HqhUnM}vTT9I~XCL<6A9@~&mi-Xw5Co0L<&7LPMuQ?##&#!NUVRVqN|o-J zWJr!@PHX)gbu-?n3W`;uz2^1j1E%G}!m?cz!h^bPpP*vJxLTg!#mp{3d)s<3rh#Mz z{|gC%_|9A0-xg+JbN?YAZ&kxYoxj5rMJRHywW7FMV^I(}Q3q<_;k#3kpAortB)SI* zf3&4`76R% zn%07_&v(^O{x|Pl?oE_X*=x&HT;q~PYl3A=K3j`ZJ?glSw8CGc0(NL;Ux%$RWg@er+xs|0?(x9kr_{88l^Xz$VqXbUA zf;6R!OhBo^wL@vNd=0l|1`{IIx)tq}!_*O=^(AP=*qo2?aH(>bo$Q)1_%?=Pe-E9w zhrkO>pWc8i+ov6-w&YE{paf29F}5b|6?}vDJbM`L4y;5hE@!h89b{s1L*wK}a>^iC zOG%0AGx#n=rF_tz^O=ie?M*UuS6jbC>$aEH9(-S>GKDp6zL$4kUwMPEKsC-PH@@!| zpb5wAhXOcZ09L45f0G&dWg}p2dGqM9!O`u|BkL5hVr`t}{Hn3|Tv=9VEnXFzSdmnr zBVA+!8A&|>qDF@Se-GZEz4Wj*XyP6e;e?NzRLC2{SjPI6W>u#QQ#Y<0`txJ@tcMZr zd0sG(&LLrMZjx2rs>Fugg~@Cyi(xW>k}Z$?ZS-PV{rF~6W7e7mr@s-^7rJM3BxZxR z`}i55LuN3WDPYSRKg+@3Q=wuy>oX|Eu2vBe5v=rM>Cbt?MYRr4I*jZceK6Rh_^U(Z zpZBQ+8#DGU)MYkmnsn~mUf%Y#bzZ|l@95+*vN9uR8Hbs`+B7a!@S2c!r*i)xi1%f| zm!aeO7_8_dt71jHg|@v@UEM`C857*rC{i-?Spy>6dm^cxFb%`#oQ*lCTOp8u@BTr* zfegkOm}>dn83ZJ&+L#q2dpSAKX!u<3Face8Ye4pU-zk-qE{68J01HL8^pvbt1X&4` z3&x0ktF6!2nCrE5G|3x$1Lrh!We!F4_B?0ns-6p0vNHc1nF7KMHG*YF+(jE0d5Z)F zezfRox2RR5Ky_z_aEmudp-vTkD`Gu24uie9Y_sniQgy?%v!6BT{u<$R{+9BDI~J5D z@q1E&f!S8DSg>+PMH?sZ59|=*_+D7imLpbbN%CcL_Wn<8^Ftxyusye}hSVTydji@z z+Vsn`nooTjK=zRsPjX#~ALqFL2%8VQ_$;0Td^N;H%(b5JGZOVNAsx!qm^8f6E%HgV zI)anzuwS9w;ikO9{wO-M_FXQ0)YD(Hiax6r6bwLzkiqPJxkHfLQABrz;>1D>55qU} zide~%(zWF$JYXoDfQ`GRW|$5eV_wPWT)D4CH&Ey+^>t@0TeDz7+p}Q0$$Q!<6LbX2 zt3on#05Cbt@HgYY3c*4<&o4c|R(_Z~+qBHphx@_fhb!o3Y-Pu^c+w_}Duvhir*T)Q z9QWNUNl7rQ+tqjfY8`CQdMSWvrSnWOA#<mQAXx?h{Q5op52Z-(aLN)y&fNMuR-v_}bc= zM1*S<>@8`(sfG^60>aA^|ZryHACq%?1pf@8$+b)6Tu>})#@Kp7~du*^E*@lY1i-$THGxRE8-_rRC7d5Z)(1<@$=q^>598w ztqEcnh+hh@Pj`K4fvMg({KO?(7;Y3&!MuA|QG0kAn4{?W*@NwMoBd@XbE$_%YL=${ z9@8~|APzh{nk+ftz|lk2DVxv>D;eQGwyVla)z)0~E2P;}N2t$jojz3uX*ldANJ`u< z!&h^DrGF{?%nW13*=oQ@hao;y zD5O>SEXz!?f3dgrGucNU<8hffW!z=l!hiC8hj)0*#WLF&0d-2GH3TE8I}xn5y3FBk zhvhS9R5m)@^I^NPDDRbZs6TE97_9#g|5~qRMbm`xwJVERgrg44#X6RlY%3s&*uJ`F ztyns$s&*39c2L{gtTS8d400|x@4(Tjt*I6PW{C*Y!!b8u2NvZIFru7d`tH|!%iI|Q z&nbpkVd#{hxu&Pj-#1-TwicZ`-sDQ@&Zn;07loffS`u`O)2n>gbhbZTz}=#&_+KZ} ztVtQY+AfwbgDV8q2Q_MnQ9Y+CII@TCjp53oB?SX|A<=ykQIAT57KRURELvdigie5@ zFdqiG>QKLat$Q04tT^84xK6>0k52 zh|kAwnsH`DIG0&Gi@zKGqRX5&a(n>G!h zEO!HBSySx#8kBl3>wRl`TaF*#rR}zhm7C!wQU9%nGEn8zTI@M}e*88AHrXOqqIkni$+z!RjwvVp#MJ;RAMg7)u0@FGS zw*hso6g|u5ndyX)X0DrQ&B*>u$;&e41hD7&Lm*sA*+E%H@uC;TKDL4(3isnq-ew$I zw%|xkA^YX0y2+G0_;53=>S^E%V;D?gxWvDGw7Z>as$RtFjYfW!#brGS3^~lC7Z1N1 z7o}HLU*l01Xp;VM#N~NJ5v4=!we!+8?h3LSa&h0^IjqN_()69~ulO}&oF)D^lpHK& zpe@((L>cHdOE2i~FRn`e4}pyeGG7Z@v9bVc=#e{leKKNF)MT?F%K1|_+b?aWpUslI3}3w2gqeMj3?DX9#p$apgLekf|7Y> z{e1npAolc1K-yg~<>cH2eL8!gKktHUPgvDjhzn|2Cf@mp6cODreQ6`p_sJpJhUuBQ zJ%Hq4e$#Z}&9%xFk9fg|L^YLBa9QPb-w$;HmG^9Y(rsYmk+6;%RW>JgJzn29`1`AF zTKMQtOyr<)r7?FvpJGa1vwTcl-;(RSXSx3PFL(EWKx*UC2KX6rIR)#r~~<{`+W_Y~PXXmfuijn-CTI%bLM?{7p`@?|nYzKLjk7%LY?!(m|J1 zq6HGVl5P$ve}X9An|u#;njz2hmA4UJVEM8^fHp-pT@c9LoLN@A$H}+zU>?X!#4o6l zPm-_m19?Sms_rQzP$EmkNO18E{sB(@+AqD#r8+dAQuQU=adB=|O{5nR6ZN&q%Y(IgC8 z)dh#qPHDIOKH&`h?5H1+9QvKD5Bi<(hSt;CzMby6)PMXbu%{{?4y=~Iq9)_)WHXdat8rvMZ6-dS zYnpCkg40sZdP7+r4Q=b-_hkOXNq95$Z?|Fb9$C^^!}8e}01~EnGxcw?;Wvtd|I#Rp zO#Uwu_jrNOgOqHa z3@sUkjkiqm_GIkzx}OhDM02irxA8paocf|Dyr`415Vj=9lZJ|N(Am$vNQqg;}iV-F1 z)h@=zD64*EXB+j_JZWE&{EzC~c9%>apKypxbf66rY`d*Euq64rEOxbQx0O8UX1>82 zlKbNeaZ#EC5iqJ(Gm-T!Z@!P1GTw3Xfvno&5o}hve7YguGq@jH6Z-%QB*+N~|8qIG zns>mrMs*vfH{o-1PnR;i^fI}8ESqc1*M<45WwQ8&f9Uv#scI?aw+23Il7XFf4`w-N!4ZRcFvZjReUyiC*zB9>s~ zKjJ3GQ2M&PebPtp>B-+j4=d|};MWj!asvfbHS(gQk#=3GH?;f6E?K(V(*F=7E`Ptd z`*o$pX>DgTnv1kH%|!UCt6lq`rp^KHMXHIP){6t(h>m;8GC+ zkA4`k@8jWWZ5-IWI_CAviEy+i%;a;n_cPwhr761pYmVQc{$Hk25&UY zz5(M1@q%>FN)KpVjNIa*Pz`52y)7Z9b=!q(S14K=q+pIsy?)~?kIJF+29ueCtXxbC zxGo`oEe4@c$ z)Qj8Wc}e_TQUyxW+6T4b%KPG`UwQ8umaw~I)-Sv5<8s?yrFbyX=@N&R?^x5(eYL^Q zELOKo=&F@E12L}b^KERkK_s^u0`NTwvwh9f?0O=>i?fPIN`Rd}Dd>ciC z&IDquK)%yo0X!M}EC_P1X;!p6nx;Qg04fcH<(@o0R8@~JF1Lvl|6@5j=7V)z9Zi6D zkm3Ry*F(wUw3Kvpzx;)VIpO}u)YP=TEBI^6CGqwCZ&~ttgdr8^7Cfo0SC#+u>+qfi z7Rt<3CG*XS2@4Gn-{hS?ga(#cLeWcf4-^Q#+M~s*+oSG&oy?KzZ4Ce&6dvqtz@BuY zSZyC;o9k;z+mTsu*;^iOEE@7O6oh`Jw9m9vZG#(TyGQTgo??~ORU(kY2~u>Jr6~`s zyY-uY)8Fwlv}hE-GxpeD(^9)WB21tB%g^fc7Sb7N3!aCp_W^Dtr#v$MyuNnEC!;WG9%R=9Xch-X4&c5szQTRXPi$wJcgAyhTgu{oW^!GCFLQ}x#SwP%mXFPd zMBkW3*Bgt7AhniijN40*ZL$aB(-eN)EZ~UKk~1YogSrW+Ihjj%=1KYezNWCszcvJe z_lb15KcLF6ke(~X1Yz!W^m%;|q(T3Wbx@APp+fY`(_8#zB)8t%%k70JK~Bo>q@NU_ z0OrAp1>@;to>7Fp8hmbQb!h{MBNIaSJWL(dPbQN~8Gj+C&q?~N`Z?oxw{g0>Xd%;y za#XL~r7O9EEjhcb$(-7OOudz{@AN_C!u&ogLmx~D8wh0(?Qp1?PZxy=IcIIfgqHY+ zZ33yevf_?4d!_b2^h3rq5_Rf4CtsuHl;0wF4VMS87kJWuQrQ?ErdEz0&dqMg5Yhl3 zR~*3I(wwTIaEq{$I$(unk(1|xYh0h=NCFd|g@&{r8&Wxm;`e2SeM|{??L`_FAJa5! zgU4+a3g!vPZI(P0ZN0O0aR5h;u7WaS-^Lk2fxXbPCAwyr9JGwL ze#1KldtvXcvo1NVQT5~zVmlC77hOwW{b^~73gfl2x=X3q<-c(XWdTn^rMHr;BlMmm z$G`3pe>81_k){i9uM`cMKXN;lSjDB1$RAb)ktQRS(=~;bymVJRYjqueIJYMN|AB*G zxI+mhYE3yCIJMI5Ts>==aoq@FO(1<@b6<6T+71Vx zR<#Gsp^EWsTTPG=qs6JGKFnabcH;rISe72tRe85$6Su;`5{OKx-8BaQAj21_8 z%ZB!F*z=7Do7;H>=btvtW3C(8a7jJ6RQIb@48O9J!K_U34cf{l>vOJi4(Knnu3rIv zNzYo1)-94KWYQJ!_t0bPuH7sQm0icq#|Ror!S6P0KOSe&xoLNp`bHLU)LFACE{8;u>DH?@yIet`U6I6z2iNM>N9N*inngUjSp#ChZyxVg0JE}r+?+O z^=PeJjCYiyzvKk^wIFL->FY`K!)s#nyUmR8r^BkI8{_-ZL?HQrUDWf)CD&=B0GDx+ z1IgPJnxV}YW!=>zHs!*=tHdHN-l8B6NnJ0cjYu<5ZX2_u`556L4erzw9mr^p!?eJ2 ztAUJ?1yGx}avvu^j=Y=Ht#7*M>HamKf+|L3v$Zm_BJaoI%@*1uNl^*I`aI4IJyPvl zu~YLl;5>zBuE*$H{!EQ@SMxEsgv4E#BM!i_hJ^&XtFQ;ZsPyO67V1`J!}zxN!Q7Ci zW({eXG%*h>d;bc@I()iAl{HjNqpw9+`DTT<_tp>CB#L}mQQDa@fvBp~e20-G*i+>b zdQtwxLqR4-){n82PrYA+$D8a8ds_>=kohs~^bT)TjA;xP?(q-#GMQl!?P?e?>APjV z$81)IoHWYc_v)Yw=EdK}2CasY_XpklxDw5T{H$Mz8#oyf7k1Fj&UQO!T1bsw=d18G zLLcGi`py%>yTFtjzftrU@~9q(<)=P3lG+I<^;0-JXURU@S`s}Zmp^4-=1?rk!;CN&NExvg8Bs7SWjCFWD-73v$kJpQXYU6}d0 z^W*9h^dIHww3%Uyf4WXp50j>dd`x|SfOCu6jJASXQWY0g01a8mL6u=1P5#bhLD!EY z7b#w_G~^Vhv6@>T9t?AJC-eR3ePT~OUU|vr(y&rY+-D`0cW!r6Ax-fd+1Du#4^y;V zr^tHEE}oWg$OK6KlVAbT4jsf3j-( zB1^CBxOKVq65VR$Fg)1ehCBE(BAz_ce)r}}$4V9lbvql*1c>Rak1{$@eB1UD-_>8h z1_o?3HZ?{}uO+l@QyVBDgb^N`zVBtBYO#r&jin55i{wu;{p&idwT{X`L5X6Hj!=+m zd#+j*&K3BkfP$X`4%6b+XDd~7pkTfBy06&@G_x970tR!hxLW(0H-|<@AKgpVs!rV` zW>SQARmE}ulbD?dSPSDAt4J-HDjRbeS0SdVOPi7K>4nd`Nl9d+SsKCPQoL30w2yE; z#nlo*Oz!@9Mp;)a@)mhp*@Tp7T+1>}e;N^=7-%m6_$! zTT)`-@)#K*F;GTkZW*@6{k{=|jtTy0-Ab7*m?1=zZy;`vi41w?gqf$Jo~j5hGcRNz z9Z93LEcLBNI=6u4xu+|qr>8qSx2wY18ACgD@@Ine9$^yWisqb5;LqNsY6e*S)p>t- zxn;nlLu7k5bx@Adh-sA=$wAf54d4}uqTYbem1RKOQYwKYL)y+RIWRx}{hv9YQHon4 z8F4!#SXqH8*0)F`=pBCjr1ft^?YjuU&q$GH$O)@c(JL>Z0$fgRripnj$MrupigpJ4 z1YR8I8*96%`sN?Oc`OQTRZx7aboHLl!Gqg?$nK6yiM34Zc?k-^eyAi>k+QTFV>hmx;ES}g}<-A(VSda83j z{=>}H%N`@rUXee{kW*m#vZfdFB|n1Gf$(ifvIz`D{CZ`k?>BV5W1X@0z~(|5of$RZ zbh=aVV@j+FY7>SUb`+^m<$+6-e3HPb63lqgwqFV(#|=CpCNn4=O`ee26uS1ppx*;Xa>} zH>(}N+3t6^k`q;egb;W_SRa@ie4f-lUC=`=YlM1;gpcf zAu8UD==U$~Dul%cMTBJBxqBwp-;Xk={|`ac7unV-t5)o&5HsS>h3RZRSma`Al9M`%xBp-p*a_jqvVTBI9Y)=zYXyk?58 z++0~_e!!BgWWHN*iEju!-xb_@ISW3%5pClhWu8$C!O$X%mFdS1f%9mES`WL>)c3mj zj)n<0&R>&UGLx2)8q}?R&5jJm-2VP|X!BMdo`CP;p9C9>1sjP);Dqv>VS*iFr>1AF zU_*FqL*&FxuG#urj91yync~QKgjVz3-9*E8h->MpPH0qvGF=wtD;760tn4$<3dyC(m?1K+OYHWZzLU5MI~n>6XMVeMhs3M!*`uBBz6T7e zpDv%id;P9grs`XnuiKt>D47L1@bZkuseV?s_Zl~ox3uj~RE>f3C=<=#>~dMrtF0Kd z7#zg0sK*Wes>`ec$93*UN!st@`d~QP>~>uAvCfKxTknoHG!9JfvoLyRo7P#LII{l0 zM%zs6P?|qtqB{e6-;9RLVxHdYBF#yAknRc4-CT9R^7p->_*#gp;beUh#STkDUa4m4 zG7@asBW05E@ReFRvwCux8q?hm4@uumRM>K#SpA9%5kU3o={8b_pm-pyr|u4M-YXm}@dU4NYc9T^sEDG&MkI_hA31IYWY zuS36FDC@Re`0tqOW7VEV?c=TDiumS_xTmZaAWX-V116E&=?>=iRDFnCgSRA@3w>BRJFNa>M1#7g&A=)3HFQP=G!AzD*dl?t-248WF zcY{AsWX6w?i@U~A7un-~uC+e@?w!B2SQonLfl~v%Y*qft77Sb(lQ6a(pc#+IJY3Y? zxbaWop#uCpVAf#%=%!dx*023{yXt;0KUytLDrrB*s}o67TX<7(ghv!RyXz7oEo&7Q z*Z|E4)E{h@@h(@}su3+4d3cr}X`F|+vb?JNLbhNE*05*Qb*2@aP2>}5qDv$#AxIQ_ zcN*e@v*kIig&a06Bp@4dTANbgxv{e+$^mifqdhmYow;07(*GeKan@V5K>Qs2sqHIL z!TEV{seni}cEO-MB-^xRG@UT~x?v&wG%D)t^g*44)7jpF$O~hF%L{p*eB|%H9=&t9 zW@he>pLnH^tjjSqQ+4Uy@i$Rxp6~_}`3I>@RQ}bT_y3387k#73Qw#}gj*9m& zGt#`9Ina6b^nPBS8>9s*QuM<)Fyh>cJN2Hs+S5`h;^ok7p%FzRK#)=e(y8Fo&~1md z%+)|aESC=FQ(-&q4^x-%D&LANzDm^>&rbtQsgCadGI8HJnN5;9om2#ubTSVFw7+HQ zm3@z8NBF9c9^pw*C7A-NL7D40X@d*>o;A#*C{v zsV);j7pQJZ^x$%Dn_TA31pn8Ccx4LzyCd=c)`;f`4CU=y+dv;KaT&Iyn?{>G^`~kT zKRmvlt5&|isqALU?-euWvv<{cBy6vOZ>~Lq?@o6(sl2}kl#QYU#&l=dWQe?W?V_+a zNSmeAm8@3aj<>-OV;Z|-X4ABvv61Bz_s)^4lFmN4`$>;MqDZ~&7cUE##U3>IG6%D# zF$RJMVt}Eu3;S{P=2576L1?mr_4qtZNU(?Q|5*(Ju`QAK%UyyKkCWk2@2x_>a0XgJvI zj9giKyUunO2C<-yDH3?ojnX*mko9gjR%tk1%;xRYD~#)Z;%t~O#nX)6x3uTIY|((^ z2U_(l{f}C0QvW`6tXSC|>JcN0Z`7L5Y5TZTcD7*x?mJDHRn*9FZIXzQB>}?{$g?Ia z_~IOY6Q&5k*sgJR&?+-jBpep`Ig-n_M|gO@ZEVSvsOCoZ3k868eT6v12}F)%TR)mi zE!Qj`P(iL=2CIZVp(C z{ZJZmpo%&oX*0^;uh{Snkg1g@d-vj3_@flbv&_CcEcfzzJP#z$>iY`F8OEXpb!01? zjt_L6dfRwBZ7g7@_@|$D`jM(I${KP1!Ji4=Wq8p6>srzWSq>^;#V6%G-_$CH{Vy_? zZ4=kte!53sL_-8B8g)<+-T$%jp;5NmO68`a)dM58Y7?wHC2cax1@8#Efo^6Gu=t{!qd^`p*^N9Px5&&u8Ay13AeNQ=Zev)Nr{8ZDnA1YE#SA)otph# zu`mL~EG`ZeX;AO{Lzt8wY6p!j>I9Gk;jORA7x^MuWqoI5{3Zh`=x(tipRo+i_5BSX z%-|LvJ$PS`1k`{4xXy(*i!m4%7^jGZN=Foq zv6;>OYWo0Wj<6InQop9eVS*j>vn}wqQaS<@B+U`)8zQ0uRJ3YZ?~ShYmuKi*n#QNVhv$Xd91Or0Ex<2`zs`6 zJJJMCH)gBY7-+W`Yz(gWwPDg6%=ynqj%8dm>4AV5HP%M&VS@GVelO^=`2a3Voh&5_R36dQkoAF38k<;29xxCsDbf^{-R()UtC}5 zF@@ey)&x9PO`wIn{Urx+Xs2;7qjJ+~RaDm2m$d{Hty%Au!ImHp&9+KjiE!8LBa)}x zOz{FazeRbjR~xus+h&&2qWt?*LOt43l3uC*~gtW6xRe{rm>KHfcrx(tiY+7~i zIFq}p1Jo{#f3A(+?$CiPf@|EWu66t&2)Hui?6>h?v(^5eG8)Ah46@=nHnhU!(IfGS zX?FJHa`r+eQM%FXim;ImT0qN53JdhjFL9aJyV7YY=D@zT9Xm$ae~Uh_n(1F;93DfA|liK{S8N`tvV?q;`Dk zwFd@vSb#Frjt7rx|dY?&WLP%P9a=h}oIB30YDIJk9fw}c}DYR=4$ zx|CVRr564V*4{Iy$^YHzxdUHk$NN^AF+11{lpw4o=XMraPShTMa(-|Qr4bma z5H+jX8!7V`?GyD?ZfjPYldJdXwA_8WawUAVfR8TRy)!n`QEtL7oMp!r@jK z({oKXTJfXAgMOPvxi7Rfuh;h$S>Q0zN_gFPQm7wa1OgbT!93~GT0eavzT`I4uOFu2 zm6uoRz4FRwgGqa|k!QXsZ36p42Ka)Q8t%z_slCN}uc@QHG1C5*P@K27{OYi~FH1jA zaLvl;uMas@JO1eLd3@O~g@dUiT1UP`$Muv!8H;*vzEN0Ho^`y`T>AyceZDNbpyCfX zEA!o|JNypeK3+2XC62nEP8vAv*Ov6uy6#JC^FjyTh-%LqYEBF#t>N8 z*RmqscHVR#+?m~VnL)rQ@9>l(WYJjZx$d`yOB+J`( zr;!Rc-`?EY@4teCpJ122T!0sCn{uV4OQL;wy5iQtQm<-KE>^v6`#Busg&iLlk3E9^ z0&<@Wk9w~3zVT|B>*k|FH8@&q|9*D4D>-@Hk`~TVTlZn?G(FHwRwi7mM)s4)FkMvp zTIpQV`6=MhFdo7aKLT>MIf{(3*kk=OJa#;Rz&5}XtHIy{NGSg0B{LqfCcRs>28N)q z(j^rg76-jv2F$0wRtyY|+2Pz(Sk{eab5^&3TpGuQYX z#Bx2tMkl>2Qp^W~c!>GKj#;VC1{$T6Ug>>rQ7r;58*^uk*j`kgzQW)93LOK|N+P9; zBq!29dB)R%$PT46J^$_ae<+ZL7}JVxspZy1L;bgm`{GVijzKR9J$);y*2tyzg}7#t zaIZ=>Qsa8_uPW3=`lhEkyIfn{R^ik3A_me+B1`R4;U<_nyR6D7TfUMB z)|YL-W5Aa~HQ3GGc}sR?)3Um1szbP25lco!OZu#RHJMP7q8>o^hLfwqhPA`+o0sTCML9>r>SBnAHg{GW=8vw_k#jJN3m{ z#VQ0vjTK5F8z&dp+(5{<^(Gshob39#Ue4?S>)JJC-Y%e5RFd+fX=zmnd^ud^4+7^W zb0V_l={uDEy3@!HQC0~c52s+*@2NGVcz}n25$0x(9aX4BDL$IR7Bj2*TcUKTBzjr= zO`=-{W&94ui=Vz}+e3<#fCX5+d-tgRYEu^<4PME58hm14Wf*VS+R~tH{k(2eU?i?B zt-?iwBT9nZ$6{>asA&L*7qP|PTr(JtKngn-dp73M7C0gT!d~kZykK2#Y6|=uyL994 z{AU@aebdO{b5bc;3==lOw__I`;h@m;AQs^p?5G+}*vZr#9NNyiQau{!P<6tf?%q@oIJ0 z%qzE9*yi$EmxlPd`!NmE;#4vMmpB-PhIH>HGUzIxHLejOG_HlpS<>1!~j@Ny#{?i5dNj{ zFjQeKlnxWP&-Zlpp7o|;I!9?z#;oqT_WBJy#yc*of{$EX1$c+z!9Y#rCbr@x9ZcCk z%5O7F*6zZZB=16ZqsBdabrI0!e1P1^A*$DuZy)m>6SwKoeg2B4F?zY{jY;h(WS91$ ztc(2qb2nRXAvQn?15DD>#vJrN6s%*pZ;S0}=4&!VT_`!ZES^w{gQFGCGk(p@cihGC zrlTeAhgsRrNHl<@=sNsP3txYH%)3e5mjBZv)72z>@NNLS?_hx*6E@ciK>7ALN@Mp% zS7Hfwar2K$79WHP=z$qh`JcgCh4;hTST>F+S;quv@UknRw}V=6b1 z29MYAIY!%gVYE*#HNm`cp5Sod4&g`(Cf%jJENxm1^My`g^FYzh-yY zjG5Cpt$6MyUoGEW27C7Q$&{`LYpOnoTFD!okk=>5%kV+^gmJVs6bnpnBfRAB*O7`&!}? zIuFWX3q?UAnU(cwp~D}1Y_z?eMSy>m3l5sDu)Hc5uCTS!NB9+DZ+XcF=g5 zB$FbUkOg}wYM;Igc3=aw_lB-trNSKnlUsW z&}=D$4CyLRhtRf!>`94c1`2%W`u4;Bh1M8YU8eS|%u0hrKWceGjvTvp${-F^3ko4?#jC{3VfL~)i>F9zl zR($nvq<{l7jGD+VZysAb&4gzTDtKFz!0U}PkKNG&1eO}`Panm2HijGd9F68=d$qO#npQ0@l(hDu{9QY124Q6Fq_&fwJ@4TZNec2b24g& z_CtSmGN5q*-Rep`XKVuoIQq!d$j8&WE;&4Bn$#7BZHA#Ota_A*-d4ueQfvFJ52I{n z+@Bz8E>xjh0-ZGrP#erms#RHX%sF>MKJ2q&T8hG?rJml=Gt;(U#fBN7Pl&80vaWQZ zv-(nt#rO*Ox^cVg9}2!n65mftzdsix|4`J#{XBqfPGFrD@bP%j=ei0p#6|H3F5pXA{p2d)R^W2W7FBFG+2|)tL zNoYo;7=4@x@aK~OBU5PgWnxxWUa)F<2W{&DF4I zHf0A$1KA-qt_Wi1;@R(6({P>@Mvw#-37K^FKf0k7L^Y8zi zu=pQfu>VP7EeQ2(qIMnckUzQ-@fLQ*BEF74`|v*(S3``2c5B92 z@NuC{B-!bF&K$;G{s5X1j3SOF_O2~A{Qql3rRs7V$Po`e~mylkt*IV37g zdTP9i=cxagZ0Yp+X{3OX!;p>Lx||JqBQ8nhJ7hH67B&%jEoMx_1>uu@$NYZH-Ys=I z#}KV1#PK#tXPytM2e|F^2G2iGpwtn$dm+^x;N@PL!#MNjQY3FQ<4vKh`qT&7DrjJd z=@myZdLNSTHvDQJ#CYz6_=HDV_j}4{b8B|~H@SBdoD#hs3m*x_QC!t!C1)9b02b1F zIyng-$m%7L`k+Tc04W!ieD49W@v{zJw$&(g6&&IEiiO-CMB20fsQ$}*tO8Ha5dKY& zY*gY3%ZheSJ~GZVk_PuJ{^IW*e2=91niCyBH!2s=*`}?LGWP&)e-qKu;nLvPIa}8M z4@G5AM_6CD$=LlZ^ZXKWHiokL?ab7KjY3!$=dpB31Moc`)|iLdh`O=iBD$oAwWG0P zYArwOOxP+*<|8McS=-;6ut*1-3`0F zs}L)>ccSNNIqhu`Z*yOJatL!5>L$t!rg%3(;r96G7T^_xo=m2K>^)xdf-p!hmbRDM z<5Qj&%z}3$^G8SE+`LgX)+(~!`Q*V#Ll$`%zexNJAd=)H!a!)(cDs>16}YhY!Rl}$ zsiz41!W{ih`EH7_*EC5iFr_z~RgDu8vPREskFS{}UD(A;NPDmQA+n{JiiOt`oora2 zzW{T;`+;c@brLoGLXPuYj@wmA0>*!x;pR17X1h(}S~L{IOzbOUH#3S)K=OGTAn_K( zgXL48DvCj(ysIml5z8 zzFQsae__{2Jbw#lu-l7t{CaUkaR)-OqvCQ6X}Wtq7WenpMW|_BT9{J+WL=3RBw3)X zEqoF}XkTCKgvi`CX;b%l{`|cZ*GPV!=x}cLxBeJUL zT)gn0CC4|%RkjkNv!0)4My>c|y}&kTmd?=39F=}(<#nJ=aF4dvQB#*t!+qL#CN=ve zH&Gx9uRxwCT6Z%`QWnT%XMNV>x<~-`whGy6$%s#RH2b19bIN4mI1aM**3Q}~yg(2l z+553I16-YW2ka+YN-T!5ghH_6yBk<$z4V^oxr77xfN4OJ{3vJ1%=LyemG;CpTDsv#ti1Oe3%6slCJTPJV<+! zJL)3Q(l_u;mbik{Fm$z&ZEIA+D7z`sV;}Cm&8j0r{gw5Yk!QDh9(-U@q?+&OhZl56 zLl<~y@mgz_@LTqv*2enqQVDW3jr9OmNvO-MxI? zn$X^A_%ie(f82+kF&@jbt{)=(C(aO19ViNA6<x_U`Qe%8Q=1>^>DkGV|Zpmi;s^ zcrKu9Y(VqUJ`9way#P+&JaD9QFTHSgMsr!6j2vbSyW{EdZ$ zq{QhBoQ0uptG%;c7T5St%5d|F{Y^hc%w0!^it0^~3&jqyOdJ6w zu;J)?#$!-(i3&vT1v4W~$^5=3B->OkcA>W}BZzkBLt9Q>lxd!cgFvbaWmueJ2jg@G zl}fqek|L=J>ep-BZ8qw|@MFj@H`rHo=+w&Kq@gB#H}&vOA0J*=xLca6p0T>(mJ4|i z#mf#OSzMV}UzY_D$weaINj03<(RbOM~pCmJ8+bZW4gU1g~EHu`|7|H z%u+`RI*)shz)kmQpcl~bao$$7{K0rbvsV5x$5)CQP7$UzX50)_e&?80Q$M3C_uCC) zb4dF&u+jYaEzYD&#qRNey43D|^}M)h$3QU|rwv$zaW(ZjK#k&7Xc-m*G2ucycACwt z)>9@=E#e;*rdi&)6C3~jV_nf#7qH)bV73NVc$eJ2wyZ4pWI8}^FnP<`;Dh)x13%#o zK?0o5pDm*ZC0Hyt!=~q-l53+VR-U@x+jgBh|Myz%mdDptQ#~8rJ0+rnLxy`WQPM9y ztRb9&5RR`T8$I?m+c5OEx0?z~J#kxR{m$*Ws~$zJOhxCWw003aBBo4g-}hbkbn)U{ zwtPJ>>MgPtcRBBNYT;Hb6}W2krl*viK$@PLlfGQ7#7JLunw}cGcLl|cKIj^KHf)F^ z7j;b{XnrPQQB}IwmpxEYEkVA#mDSb~siU;1 zR0Ye|o6Roaa&j`)Xfao>pakenM_uuG-L29|Z&mZzdu`RD+lv7-kExOyNyMmj!J(G@vE zR+N9w53-JK91aunL~qD9X+dDasm}h!w}19^$mGZd8zrq^jVmG7LSM9E**_dtD_N!M zAfxH5%sQu8U-Pz^|oXt>DI7$wMw14jUu1iF_(lX@Wa2{5=KJyI+WHw?3UgIq9-@kQOS)3*3 zZDO^3VikN)eld@A$ArQAAAJ_&e_N+=r?hz>F#?jV$_I4Vjy-V^1Ugw+6QzJ*nr3H=Wf7}Nf+n=>p&<%aM zlfR&EQ9tE-WIy>?WNl}v#9%7^b6R4DNQtmVr$YS^;6eB*9LA)O1Q-C&A;o5`W;=M| z$JQ(^19CBw7h8*38@nim!K*?6F5m4&UTV6M%&|JXUXm)PJ#PuH0%c2+hyUUiXHNbY zvl(kYN~>LI@?%UAZ**FL45i3$D@W&ipNs4c7Skorq8d>xh?9RmKux*CrUyes+mauYZE)#%bF9+9%!fXth@X_S8#f_+T6iPsLTOA2L2e>jzCq zZStSV{2c2m(h9il6^~2l4Vcjo^z^UyO4~s}6MLRc9u#}MtFy6VW-+?sJILQ%_hQJ2 zmX*tjy5d1m6%I^F3BaDBhV?Qpmbd6pHLv>mC5sCL{oZ$DW!Y?)H^(TGB4oX8t`6*0 zuZ^S1dh3KE6BhO>%lmsvO@4E()oqT$n&&OwaZ)9#ONKl8Gu7U2_n!2-H?<&IlfLHOGKp_hd2rpv zn&B}gC4<*V3h9d7dAm6M5oD30aGLGFJChk9HM{dJvvB+kWECfgIHJ(uSnXsMQ!U0e`N2))2g(ma|xyTzI4@#_KBQoEtHVNjFbqv zpg-@B_t4{Jqgu}_p_$(w8INT`_IG)a4%c)2iVw_udniKVagfJY$#C7=Qga#ny&f1nS+Jx)hZ zN3>&?PRsb^Pd)pw)kI{Xl4MU1TT4Fqo=VertPJqLtAt#_ss8$URt#3?IbU0+4F3V+`Gu_7*^v_; z4)mmVGwKxo3m~`b8+pApqeOfgPNbbazLJDFxJ|A?dAJ*A{t1ot|68NNw@F{Ca5OrK z%*SWF=^DovSYWDy3=53nTkmgcKA`-86EJjHwZ=WQ#HJ; zj5*uw>H-kEOeg5@keaV4&_}6>24LEs+AX9=v2^94qb(Ik#iu-^ocr7@eWpd< z&Yc|bVQ5R7Vq<|5nZCNfD6pQ)P1ajUkLKEE=$M~2U{CXTGCo1=^#+AA{r5*g(n*1p zCwkV~Ww*6n{BOanZiPOi#syL@c*Ki9$#rM4IfAZrW`4FR&2p=YwT-;QQQAd zuKa&x%iF4$PVy$~X6S2dVgVucHz={RX{q~V8mb#_Bc9208~o$6lqWVpJ}2yeBs zCOvylQ7s>AEiu6SF1I`;zv{p{>lmQi=>+&)ggJ{K$^GqQAl>VGiMHdRU8)Ku15(KH zdXQu;>#OcjCY`v&eJS8u>%$)}*2c+%bl5e5<|;5AN3feTIUqd5_&{7kOZ`A#1XZEP zx7zD;8%PH6t2FsrQkXAa0F^U`l6(KK9ML)ijAC2B9^?{BSTczZ zIUDL;z16Cs#w7-H7;rpDnby z)YD&avgy>YkaKGPW%^HPmNbFb5eBxnp^V|uCm9kovd5jVRvLVuS2ZJ<0WyTNenSA! zxg%t5(A+ov?e|#&b<-6b!RW93od+|2jCcxs4L`44HYt9VTCVv;cBZ!GEm%PF{W`nz zLSVFyUC}gjW@fl)_O!9g%+sUgMK89oTKfAUXtUZqLW|pF_S;PGSSiP(;Z?r4t`}Ew z>XS2$4|eIk>~wMfK%KM>TQb|f{zAF)E{!Z_jt8HLzxw)+_QBx2)v800xUZb|Dm9&Ng$v50R#cq?^8Z(YFNsp>LqY@@U*k;;7Bb+m7CE14~62$-qM(yV*#^t zrc^|xWXSNL248G*M;862Z&A-AaU=~4)RKfigo~QASM&w3O$286soJ!ff?!!6SwAQ5 zsomqO$8RU07n+3{vJ8RCj|I*|&^E<>QjAo;`CpUS@+#*J0R)z_RiSpA6&eylutMvL z6Wx0q8IiB$!!(2o?Aq*#Sl*n!9^h8}nR172##~!SSU@riX04&#Fn2`$Y zzstt@spCZ=Y4W&DlKy%9)Y}DRd7{b~OH*S5BF-tAD)q_N`yy8?9#K#{prEj*I8Pwm zTKj?@=vkrImn1kBdA3s4d0EMBp`dluEEBe`Vtr@`zshsmUsSPt&Z3B+4K!LvKmCCd z?h21nx%ocyVK{q?ZJ3NgUOw<=@+Qb)y+Gi-bH+2V$XiZ}X*NC$;t(RWb*F2zb^LcP ztYk%f#w#Zq@KCGwc!qbWQoqtO(#!6CXf@spJFJCQ!k%eiAu&+{r-m8K z0+0ZiOpr}}ahi_zjXweY_Z}JBQCEDqvI(q>8K~Ad{eTAuA*yt)%)D)Xe4LP18G60V zC0>-WkKzhP+$YvMu6o>$sXLBrU#@9;?Xax5OCvYN#NDhxYA|lQTzPIi;lR>{)^qUe z5<-nk^o*K@A4A>&nNH}$Fkb4WQ#~r5PqWx2vrFP#5vi#YUDvH2P(HXDAqUI^)Mch( z+RfI+yDKGCcTuhbr@6}t>%N0D`XC07lzCm^_rSu;yUji9sNbf&0V|E;dwMm2X9GYc z4L0DiW1w$0n{3|;`Gh1DUtEq4KnmN83kkS>!)P5^$2*tj{>)0w!Oj}ZKeUi z5V%p>Phwfr>y&$g+h)C%@tH4qZT-_cCHqSDn5`~t7jgvs$WELgq!9+b`x5KE222#h z86}1?-!6fVQa@HWX+N3Cd;aY~^kd3zJQ3)C?~(`$-za0Xfl~%z3DN>LdD))}jD^t0 zewl=h`#`EC5$&Csf>K{OnPibonGTBmK8?l)q$)mMVg=cy1BvCkO>W}j2vpL+J$K}t zl-HHyZ)_riX!`%zu8pK(Yxz}et&D5$x*u9tnvX$k z*lBwD^p+nj)>3n%@9K=6a|4>L&_6?vbrpu|1EjIX6`H#m~#=a}t z3yF)5Yz#lCYx5K{^`5naxHVZB+3mGdlQ&2PxPv5uFa~(jb`%@}!Pae#7Uk~Gg4k$A zAC0zG??367G`SnC+w|q39IGTEBIJO;yn|7Sg^Cbvway}TMvY8jF1@#TWREP|()7Sj zdZ9MiZmu@AF3Wmd+Ru~nbl~L5v8C1Uh{o2pBsm-o_swk=bPI8stt42 z#os8JF9K}Fej0qCy4blsquWAlXa`$zpc%x)EaCZc@cxO8&Xv^fk9#O|UHPLacfXNU zZVU4>6dp45>&Vm1`W(CXK(;%)zCXYs$f2cR>)CAEPW5he?fJ%~BWZAj2Wdbq)F|rj zxQ6Z3xc5sTwrVp1vto{D3gl9?-dldi6vVGuf9usZSJc0?O#nmZG0IjCbLZ^WZ$EeN7a(jYQEzYf)uBffr<5vR-_1`Q|J8A#v=V*7FvcgQ>gKt=_k_^Sxdw|EZj((Z)P5F-KE9f% z$vg(t3A(6`^q0Qn1{I(O^W85HitJ4C->Dv3IDF$Cx_4tHF#oZtFYuRv>rMyjM5q}t zpNJ^>?fDPI{9Nj`A`sH3M;i9y4Q;_J-X3HZ_Nw7*D)c`sZV>07l&c?&hseSi%esr_7Yx~1c1a+k93#Vt4r{<{r5 zmW5q84aJ^xLF2cV=FN? zyAM#RHn`o>In-H{nw6TVwdeQ#Iu1cyM!Mp!%G3OJ6VHPvk)F4LcwG5+Q}Dt{?~uM^ z&pb(F4(a7u5g2x|r{y^HXht%39?f{eMk@5{eB#h(z1Mx7#=k4Fb&RX%^0CZ^eP;HJ zE956Y3@PWL(J!HA4R4zda(3UdPk+18BMx%?3dIC~8eoNr(&|4S)o2QA9 zM*f$rCY6#A%Zh5bK1u`e547fNVlfmSUmJEj z7v~thE|5W&*eDyu*3ubGqL?JNuhBooCdY6ZNb58tPqO)Gr8yLBW*Wp-xcD#bcWH0B zDQ~tuyW}$Y1nQRy0Eu_(lE4Gzg?8+gHC%T-ZHOuloI5SlolBCPKh=f|6o`#z44$ z_`Cr|yn7#0pwmK^BX5kQE`MFb+Zn0#%cl{l>GH3-DH?~G-xs}c4gUE(BD#>&ysVKHZ9S5RF=P{EeP9usW`EV2Db71rB_#TQA4O&H6>^3V5A)P{zhCVrKt zXw;=@{wqf3i?)hD8lc-%dr$+B$2@kArW(T%o^?#!&7GZd+BFgrGA&2wnKaN|d*A0% zpopt!!Wc-SYx2>=XF!@o{FqIyJj~W)*pLC0E z)P(6pv=yRvNPJ~a6&{ssO?9+m)LAc+KOn$I2|FbhX{6U5Qhes-}E4S3h483dDe zKvlPkza8XQ?RwOt(TdW6?AMMwY-6LEK01ltijhOR(4Fpg;^*Dv_qDKBzYqq(O*Aa`#_SPM((kZUfh^r={=16$-~IeQ0*(HwHS5|ZTujdnA4_zz*{Oq$H|4f+=-b<> z7w&Mw=Dr}ImeqXco_+F}us-0uHgtkQnpa(q2XM#g*R-kUCUXhrc4&)LwZfAAzsiul zIoLhD9op>fVo$sR{~}G0EZT;GTBg9RK~O@0@$Im)+r9_6!(^zjGa7brgUnnF3ddIz zSiam9XmpQST3+;I=Bz2p+%%Qhe7>>3XJ*jUlu7Orr&|73op_SI9N!D^S)ec2|$Tl_WOunBethm^^w~WR6YJSU6`gXfrS$yw?$#|}>XV@ZHixc$Vjm->x9Nr^&+Ze+nm${QnJt8W$02A+%dbCVU)=fA{g!cUq2 zC%?k~()>q~=)3=8kSOa|s4gy?Abt>2Ac8ZRzfKu@i}-V zEAe>gUQMybg4R?+GpD453B~Ivfke%;fh+-rU|Q{z z%=dliw?H@VpYSaVpWFy#MiYs+^c-_DSUxNz*>A*NucMM^&E6TFdtDJ zQ9PkGkJ@dbdJbl|)i%29Oii=DkO}`C&OjPx4kX{E&!;*Vc2J$Cj$d+bK=vSv^AQ4{Ua~nAPUo;(YQ(`8zctXr@|OOTWm0>?z7i5X^GTw!iHV(`S((4hP)= z)aA}i;`gV|Gq$yD7E z$$LlN0CEvOu8wrN&iw)Gl1(|3%lK3@AOXsS}3YN~_jEoSI#boAl}wcs!k{Ym;R~p!bfu zOE0C>!`OW)PU|yt#axf^C)}Z}I-vu&9$FCaZs@3LGMW9uH@zbr>!pP}%caewj3#f( zV|7&gAz*&(Gz0r*kG*JH4#d_J>{eMqb)%%r;hTp3v*Jpf`-HlCE*X!{?ao~4M8sjL zMDkGURoVGoLj*hb0ja>2>WeXW#vJaC`jz#w5wSSY3pIV0!{hoVeCXaoV7~5dfo!5j zn0qevP{T9kwwuKfa2M!4?6{{Olu-q*M9t1Z0)$S zgya__k!1ID(NCtkCVbiE85UaN$L?ey+6nf7kFkON=2n3;wgq>mfNk>S#482P1EI#Y z5RVB9OORx)wA_9sMN-As#*>3rgpgGuyx>4DSQT?S!wUmr5A-5iXuZCjXX%3lQOnCH zad-DLMoZxg3zPVf(DvTShmW`?tR>voOfHb;MPE0(w_%kEhsy-BkM-em#vSnlCP?}Pzh;dw~I|qoSVO3 zPEJmoKsu)9^Z;)f`evDr^s9|4cquFqUp&BfsvOob4%>8hTeTWls83pG3_UqkhdzZ) z0-AHuINI9j4T>1-KLL0e=TzCJEZ&qdKVU z0ylSz@r(yTP|4+R}bE>wZofV^H4Xk;;I zX{P?Qv>Kgn9x=*E{rr3DM;oT+*E9T8WQ&|+jbVfI(J(ewZ2ph-I*(j4n!dP?D(Fw; zKh=0|!O0`MBaj#R3&kEI-|hyyy`9^aT<`8xX?tz+_pnfgf2G<>8^d*h2R))giHx%y zc68Zmj-pS#wx-uxK3h>I9i4?9MJl^-UVm=LWXLM2nJf3_)8||(P~T<6=|n%OZ9yL} z4T-c3=o?!*m#Rm}i>{Jl$ z4wzq9bA=5Y-0uDRO??R87&RI_@B>c|Wy-!uZX=A#tJ~4jpiiLAhcC_14gG3a- zl3;)av-h_OjwNAu?)NxO?E9ZzK+9fbDIV^<*lAU|Zbw_u!yobGg!TB7L#PF3cU2JY z&;VxsgDf&qrW;dt@ehS<(x=kmhW692DF+_Heh%Ki2e*HY)MRMuY-{b9 z6xSh|?t$5sobL*;YF|A<)-&1H0$Rdv+X2I4I@lqsjE-@?)BR_&sS6x5Vo$eCatK%@#YYw|Zdl8P_*L{r zJv2|7@CQ5?mc7WSko7WqYohLAYDui4obwS)iTAgvlL`zHhEm*%YgYG52%qejw zJ_lXzJ!DecJM3XbSl@YR|Oh1)bs|SAd5a zg<#kEF1o#BC72yS!KH=%w)>V=rl;qxa!8gzEPviqL1rG!pNoFQ6L*VliQY{X-yus; z+`T|-+1pDvioV~Lu9w8opw|GQz87>q%Y0UlwruFf!g{f&f1SSY&s+B>)9zW|7lpW) zqx&kFrh+tf#*YET%`qy2a>xj4R?6)+-zFpU-i%!+@6H^X&dxfP&4*)6r00tU0K96d zt3(L;Z2p7{cVxD&^zhaFsIY4#L@|12Y$$#r+kEfMHE|hQP79#U={5YdwUx+@J2*=O zj^%OL4oM)F9-poyW_VhDCHrQY$L}KfXea-|dlu%IizDSn+6k9Fq5inCxQ?X~pmp{X zc=)fSt&7mYaMCs1me*4mFB0vTyt$JnkMQ^hENDajg>!oR{={tNU{P4d;ncZs_6b442`}4 z8RDJD&W>_M7pEH}jD+nSrgITXRYUKThf8*+u{}~1pGo2}{hXhs5g^uOIpQ<@z2V-t zs6rX^ABy+q4~y_jq|LywoN`n#`B4aX{?kghW9H%79a6?=0D(EHdsc&$Sn;+OCpc}p zS$rDs@o)N;k?=ga`H)5p-Z|`c<9hQW>W?(#{jUcPfe}!i(C4#K(vk$gY6@du)~=Su zFO*b{!ggP$ppyKvA7q0mU`ZpoQ;W==`wXZnOE?Z^Oo@jvG=#uzBdW|$e}kn;SiS>q z*~tw0Nw}0J`Exp(r|N~vz^K_2!?TL?SuK&mY@em_cNN2HUIAd)KZK)C%R3Qy&9?rOUHcK#UB*I)d0$kk|by5NTaaEvP2CIk24i$K5y1H{7bh> z&%YO+Qd&{!=V{^~&Crswa0b_I~xp!!(E#|Z)jIkKc8Gy1p9Ao0r_%`Gugsz zzoOFjh_AwRuxwsN8a?4J+|1D`ER%KVjsFjA=K&1o`?q^3k_e*rAX=2wdzVD?AbMGB z5IqQ@#oA4X-hvt_-e0(8?qOJv zUL<+-#|Hk$1?Dc3QL6{n8F)?rep67y-K{{UJH7rzvEb6E0Kr_cGv0d46GoQ^>Zc+) z$<@3$KzqL2qqf_y?{y`!+i}00XjfJZsl;J44b|gV+`W{aU@B4PNMK{A^R{=)vuSDV zGwME^eG$bdve&Ik6P50nki;t_pae-&^p)%WEw2<3&7+s}Fpyz4J<-#A_wd5i)gaPj zVx$13h}BwW+F`W&Q*9BR-4@*67*nZSusSPq%6IRSy~9uOfn!=&D2&37Rc)%Qy{~xZ zk~t=Sss0a~&+%Z~Qi_-F?T_f7r+v4lb%Ws!tRZkRc@3d(U`Kw`ZO&4E!Z3j!(h8ON zZhOD0iZ z%z9HQb-nmrfx4`$&uiq*N)WB=Kw}y!rC+dCyQQXpu2xH3CY>wI#FFcEz*<7Mh-?eJ{$W zD!RU3ki|4FF)txblsonr7qtDYTFJsfkCQt!xoTxM6H8NS7-aNCL-&g(FZQ}C=mr_<{#Elw!OMdCzb zHspuZ7?0*#T%@{IYQjFit%0_^WhD&2!7J#%7^kBa_L?Nd$Ti){-JXjKy^U8~ii|%r zB&jS7KstiGc$_Z^UytWUTy`Z#EU#o=*>fP9zb?jXh~{4n^gJDCQ|kGBRCeCh!g|vW zaaJD1WaxuyCSQ;cj+7U8UDn>zeX2JZqanTQ17dGv0k^r>Xa!Md1Cr2 zpU!+4;jeI(3(9k$o*2a2N~;juwEPwy?I{9*XkAh3UKzm#S?@zlP>pY(gqXW8CLd(E z5)MyE1%(ZP ziVgGo&m%3y&l#HoYR@;{H`|KaLkeJk)bQ=mbJ1dl zq$Ny6Fnl!ui1Jjl8s+z_>oQ=SC%f9;%0{OVjv!}x9}$7>54nXigcCPK5V!cuEL63y zVtJ%G;nXKfO zw-QaOblN%4`rsWSkni_myo7@@688F^)&~F&LdjtI_D9y&4%e00k{;Gt?#NRidMp(( zSr!uR%HNylYg;zJ>60)Ymi#o?f!SMnL0<^JrGb`8h6u2W#hP(VezVSP@I_Y&WX0c{RM zYTzW>Ow#?wQq1h=9glDKPv4q0`{#3O)+%f?14Z>>5skidKfYf2EjG99jC44Fu6E2U zwao;ZCEiW6r?cMaK`GI~JEh#K> zeGlo2Ufdx0T;vU(I%4*tdxA|xF&lK@c_vn;-!bb@5l$ujkhAo>_bBLobtOr8o@jLm z@9mq4gxEHzj~&)Zv=zZH@*QH-7!x+~CxB`boVJ%5aYD2$_R5*wZu!BK!?VK8ORW-J zZS#DHA=DIRzIb2|HfISft8aI3Cv}hz^9BoCwmRE-kk*;&j6RsxN*mRR7ohf?GF$Fh ziOZzKYF~-q*rs4NuyEyej8LS!tJB#+o0>uM@u4Aq?3;4?3<_FZKEJROw~sHwe+vb( ziQ*QnB%svTI84c!V0^A)q6S&$DbpS}25@EhV&=6Ap6`#elly9HWz{rB7dMhsR_P@u zq<1SlaO+sj6SZDYTK-xL_o0x2(ruV~d*$ySi<4_7`mlc&|bCuMpmX#TM5SCD}ng7rJk+s-*YjQS?7eoVAPO9$!z{*ISyKR0EUzTljk$ zs4_6}WEsn`CYZZ=&FDIIofwE9)gAEM_vsPJpt{%f#mHp&F99#tY^FlPD%pNk4h)$^ zEDu>DWtrYu(?!xumY3VL(e^T>|A{bHFBQmzh$GAOZVn^%+-|Q}wGKd#VuasB0@rFO-`~GpDP* zZHvM4U48xBidx`%=eUmmA@yiMYfTb?ap){7#x|du>Qe6+GrDEl6@gU+7-bk9seUx% ziNJ739R}U8(_grtxy*+oz^i9E<6=HTq3F;I?^OYpE@IS(p{4WtrR&<{^ynpQRiC{c1D6n? zgWsbmTs$Hnh7;-u8X2;DqrjNhV`;Wx;&mWBF9UN=T}59|TXXa9bT|-OF6F;#a57)g zpUhDRdya|yxCTDZ8B(7SUot+|O6l)tsBVdM65w1Msy5Qsl+^2Gy35yHRWYixzxYS@Elcm;wzxec1LwVtgvzW} z00ID%izOJfx5R{}$auzd?P8SixYktQdGK(k+TjHI044Gc#Ov^aW)7~`&JUHtf{UFl zsf%VmzEhf|4Ds@cH(uGy6##vun=W+>#57t+|nJ{u?P*^}>^=&FcZZPa#{u z?s~Nv-}a!-wS`0Uwkib(s$j?OV?0yvD%%_ z977{ecZ2bFv8qZWeyqyDPsa5f8ik)9aSVX6Qhz6?I>cAfc1K28fM^>d|>4k5O_*Yhbr?#XQu|0a!m5al8;)b$xr=<2uujkn8FNWVW{hEZ)DN?04^H^%h^6*C#@T-=Q?G-BZI2 zFW|k)l$eT6cz6YBEd2dLJnIZceW?1umg8@ek01Fk0}QX@echRozTSC|7nJv4cVSH- zZ~2}q$DDahdQzj-#D^DO_3wx7)o#V_gVsf)_XEk6e$^Zm;LQX3PDjiH6p_8fJG)R+2(N?O`7!dqXI5YSD-!U*(k&Y|J~1aEv1WbK4~F{a1ax-Cx>=v$oY@>Y+#|B#r&E{Y1^kYff99iwINKXJJRrN zlBn5FuTN7KYhRj*dT>@pQhbN`_K7Dic58(~002ir#2;2l$9D3c@8T$&6&)7514u>b z1rJ;MC^a^RiI(D7XLHG#&2Bk_KTMK zqh}9Y6VF9>y%@hJrL+SK#2{<@Pem$BdyxaGLOZwGT$aVmcK} ztEewQx9)VyqT)tvDuEiXh>^x2gzXtLD#~-1&oxKR3bOkVUlbB8eO9wsq8%DVbu@oOW)|n)a9AWpfgusi`F?FWKKLO0K19NQ_d0^LK)Fpw^W% z?sZgWRxRB}1UjkI+}Xv17RLJP;E*iiA!bZogF_JZS}v%u6ZOSg-|)|00tP@bjk}!1 zB=zQ^!+O%RlRx^3C&Vxz=&%3pjHEFR3h;Y4I#kpWYLjabQE$8Mm# z`y%Cy5R1+*4%wvU9@LJ*@p^qM569by=H8LbvR{Sc`wMmc_RG&M{!}-AaS601bAT(5 zRSZcV5q;e#d5ly&^muE6^)_w+J2mf5hwUGQ;f1lpJ!#(<-6GcE4_stpdXFAY>Q0qy zC2JR()#u1?-zSo0zM)W3QPCB5bHxva(@7gXCs#RhA`u0@isvz?Bv<1DJ1R&&?l9=E z){R_#gsnmAfIBFyVsx%Fe*K=vZF>vdSyQ);H#Z&|T_52C2R#d#a~)nzwoI3|Gf~Zx zf#{}qtu^*_??UB1#@YrW12la#HA(;ihKEz_bh3+T?Rx}bT;jsu${*iVjg!Qv#;hv^ zEfdZB0V}v2Z(Z4{{5-(VxFgh!ABXLqjk6_7FGdByP92{W9(O)hDoQITvdi8{c^{kW zdnXGq*L6-O<*Q%n@syI+!Pn;zU*YWp9fI3wxTfo}4tD{QwJ@X{^DPuzq=XzR;m*rG ziP540qS}j!3VKOYYjwYM41m%I3$>ZrOaqm+-l|T`! z-@g`b1Q-1!=sWEQJEqC-#}~o(a^TxGwf}oi`sM9^7tH=OAN}NER&R`pDSE3*iNU#@ zRfBVSzc#8QN`%tggB{tUS^i*67+s_=W0xVddb7PL@AD`7GAZWjw}yDm*$a&i{A zDuS~)V`^x2aS^n%ALe~Z_WO=4*R&Rm>-U_>OP$6R*5LO0Xnb4Xnl2euu3J_p%I(vz z_pG=h?M7ZASDFSnXDmaksXJlQR-4WY%u;F(53};!F_~CyPn#dxaINczU-yOA&P3L+ z-dfpv&k~;(b->uI9c)zl>voRxpY-%!L0}~b`UCR9&sFnV=ardnjhdrY7;u`cn4XoO z+G}`cnp;KAcDxH?Xi<@4il|E9)`+NTC7Ae^V{Y^l<-v)8WRDOFuX(?_D2cd`RuH^k zPstX;d{$PZRq8yWZ(90x$x8m?c`3;#g~4m*4>dFt+5E%A%n(ML5ZVD5Z!d3&5+Lqj z@2{%I&re#n9uwR8jER8Ve9Aqd4_K0PjxG zy5iW@-NRG#9dC8bKTKlKY~MQMhOw2JLN>m}lRO*^c2?;_oad&WC1%!(TG zpd){;xgu2DRTn%_b)8jY<%H4latMz9-9Koq=zpQUnc;xG>H;8!?ob04R2j06D9=;VZ!Z1cQFxGI96XV)ev+TKo1E*CJSONd(FavO6>>~0n< z{*m9EiG7zDV2|`-#)|S6RL$DsyQ!`dP04&86Je6ouB``2sNGE!5sI3_jEfg-YG>h? ztnLE^2?%8ms)HK5%krQNV^@%hD$H+4o7~?azVOuMoFK~fkQ{%@5k)9gdDwNC1oWHT zaaz8Q@%e}nB6YO752tiGFHr*uI`_8&(* zK`%$;EiJ1sI!mRwrIVJX1s5vG_YeqbI4Ft8w|EU??`~}a-l{~rNo-4tf7QWIp!W>o z81IuDr5*SHw5p3_jZg$l{Q(IvV?9@1G=O=8N{_6yv~1Q?t!oCt^xOFxElPWGNkf_Z zMgk*lcDj5 zK$u)Y_X*Ry1J17p3uIf3i_24i222r{((qI<0bn)$pI5oV8Y{Ab1jmD3-&^LNLXDr+ zB|V~2FWo1DQ2CXv>2Qrn!L~!j)wo6U#*R z{#7M+zzN_B^qmNWCd2rE$?k{!cWn@J45x9zXi7s6&#gX%ZhuL<@8=I+pM5$WfxEbUO2`Sn=_Vow&IidY5{i7@~6d{HH<#mck(W`dB@&ezSdtp94E zbES5si)=m$1#9|_dxGynlAJwWg|H~RgqtRhx#0!Q`8E-p2su?_fjm>V2!Tm zp$u5wHEgTF>e21)f<1H>S~)=B&(!*}a^X!8`ErWL4c|i2x>T>wSI{C9ukD^P&9j2Y z1-Ln+=)4ie){9OCNA`=opgZCoPERh{PQEPSIbxEmYhFBS#+_huuipF3tVu<>)s6)_ z^1lPg53v+ZYY1%Ys>Z%f9QsNVOR4xOUw&AX2-MiCqzppewd$C`-^QLm(Duz^2$y*Q zWOLxqbIusMTOT>?rc8U-$+vq{e|t-JmU%_k81amhmr(Bc0LIp81JqJSFRtils2XDNI*0t!%B-G2wSnP%Z)7IbnhuHs! zdEp5$et*WfB*=G_dw<9O>IGDz37wP@b@x+F?S$PFaN&rGRbLLQTjE$RfPjYT22k(0P%Kxb9-)gIc9Bas-mjxWd_kE z+v-by<>YWO%%kcY_2rw1*rrB7VoQt9`;wK{8Dm{T3I@n?bC#l_r>JXVS2;~`09$62 zpBGB3Bs2KTK9R|G`A6{~hsSM_v`hCh@#{RC8roREMR(#4y-;rZxI~QGx<cx8 zg?^pw{rYURi7E9fMj2$dLDXeYCfDM9e5#mE)0faQUJ=@3aQ5?yh4q-b5Acc0Yv*eA z{fWy#pC1UVZF^&Jb`^e^>pjBGWWV>!Y5q)KxoVCHzOGHCGY)??B)?lyS?nKe^pxfd z5vzC~ck?<9C$X+X>-Ts;8SRTaQ0khG84bNmu01#LPv(!urC%xFlv~hY2Q;hxP^m)Q{Jx^S>G!Y4!$`Nxb-frh zNIpah^997xgGfY!6djw;kLzqpiCu4+3a({D#1h$?%4a9MHCHA6AS?>zo&Yvm90ub! z71{#9c<&P4B?0><^iLlR64~-An&|s-29re7{3_wGUO(1D@T}R& zXMJopvqs^Oco}S}_xElTkX(<_pK=vAT%SHbO+BW2Vdr>1mnh3?U!))QWZ|ie&z8g) zH;zgR=z86kmsw+Fb(!|^3sA*~1D~w9v=`x3b;FJpQ3cTjr!N%QFM9tt(dY6;?ClB9 zr4NGw=qJtqzn|8ru~%eseQo5hw-FgOmr9Qsj1Y-IH!x=%Zw_367eqn?)SG)zcT&6&#E4Q{sVnhzJFClgk}0$*@LR>v4*mq3YtXuJA#p!Y!X9e z3z@v)`x)g)Nu_D#^?&4RG|(%ZN3(ZP0gGVs#hv6?+QJ zXZS-J2k7l(uWcnlz)1^U?+ZgrL8as|11>^Iz6C4neZI~*J`5CQp)&+YuhiwE4~>aY zN@%^6xkGpqgebAM*{V`}#2p1ta|@HtZ(TDU|LRS!=tbTfdIa`H)J5!`#3ADRkHXesOI7#{D%)O&oG;mjEHy*)3QEKSF zcLg@-s4*=b6i$fZwO^?bucqm)d%77H9nGZWionuQvzCh2LDu}$84nt9;FL2ve+@v=YDo8bu6HwwMSN$#?yyFiBW4F}}D=+8Jy^n(sm2ZbNFFFAe@Ogv&gq?NFA zaDb|hmt5AS|7>lT(IG1G?%lIu%XN_cH!gl9{>^5qzXXA)@)F7GZ)b}QYwW;eVMPHN z&-7aACZfKWFIZ+q%mF3dol0oUu{(2qISQVAYp{l5tf;zm^F(RF^x&HQUxF6z1g!{; z1mdsY2R?z{K%hdd4{~@OY#91vZEPRm?~cIMbf25^mF>gl@Sw>Wfs+0>?k_(rAImq< zKR@PouYO5m7Vom#F?)WtSB0kQR=V$}g|wngAf+8NOE^N(&J-Bj9Fwokm1vCO`B=A9-mR_qZHPI0PjwbE_A*{}*yB9)W4j%iIXZnpg8_2QhWzbK32Ty-&( zp2s_mDLf_!qa*#o^)8Rva!h%O>iM6Bb=#e{f3U%!UXDL|Oq@fExO9y8f1#LdYoM_v zCc378Fw&Qf9Xl(-jsUfZYT>mRx;-xbdCryj(TDYw3!?Tap9}qHC9l_>V}xD%2RJ_z z_4lsesOE6i<*=XiwC@$;{Bs9Ty^Uc#CUnNfISXAziTe#ADKFIRqKnyvKowv0ko_tTv}UTIU}UWfAld`QucuC@{bl# z^7OZ<7ZwW}PJNaEKoy)0`?^I7aac0hqwcP>G9uMtJxw{zG_561ljQdFS>V`onTzHa zgFBK%`#=a3$*^&K4VTc%TE^#k2h|PUs%d6+>Nfg)ArR5$i?duN9`})iN?$ASvq}t# zJlOOXE$$CT@^w;TB=QR~^+!k94@)_`^{%#OoIh}jLYr=9jI^9OoONQgilLs@X*loI z5lZc}kw0m=HeU_4#@xkyDLRwi8J#dvu$;Z3gROrShTj)op><{<|8@9o#C(41#jpLx z0Rd6q!g=2B05~l-m%u3L<86x1Pw%vQNh89G=!-?2{N-3{{XC)u&`HIugJ0~pb38RQ zKt6$gI=r*5RIWH-6Z1zsmJp;O5vEo0EwJ#ayvO;5-j?ZfG}Vec+!b2%F3y8EeygWfR=d-{6>tdwV&;HZTR(UG(ykvj=_9BQRgrkkf57US<;`nrSj={)<{`6jwG+qRCZ$^rLbN00wQC?= zaH99C+>`P6Aj#-AQ38hrJKuNi`?*}{UJZzGOT)_A!jVymUuch}GwZJ}V`i4Dfw2gTi) zcQWS=9NIs}@ zemsD1|8XpidocN@!ET{p7ygugvlabz1jSYN&A(X_d}6h0;#+O3r)xN&wjZ|7i*W}7 z-B-o|BR<&O6m!)Q!9<$V-1C#J&)w|eBUzbGxaPq{_lbtwY)_4#%)rW#^Ao6fbBJku z*8Kd8g>j0jHta=9QiN80NICQ`fshCPU>SS)QA>+wkft!C)#d2;Tq-22whebazH^>? z!5W1MMP#lSQ}lG!UXO*ys7R)Kc|E^VKlB<*t{aSJbe23* zWCPx8V=~n{yh=>Zg!w|~J%=VgTkrZXkG^z~=csn~q^d=eF;-gIt8QR!5l`jkWjX`t z&7`lNsPz{g5p`)yLlG{zy31Gf>d#48^j>Y*#gT0J4nB#HqVX$fUpjp+*wgd)&$#aa za8#K29Uv7WACQex95*nUKFo`pH_NRLlG8GCI~3&d`V>pgW|CkcpHW!)mVTWeeq;q0 zoe@sr#PVGFjG9}kr!r0VS0`&rhKBka8~jma))5G03S%>=@5i&Qfr!Xe@4cY|S~!8l z5;g!Sl?);C7O$S-4%STGDQ_L&&7n(ar zzje&S@~uYLrG7*=bOmJlb1Jyd?okoLZQqJmoD52d92mjFI==5I(oFpkFzLyBP(N`x zTid3nwVmBe>PPzJR?;|3_)GMLP`_Efq;gSIfKoCRpgqb}8N$?i-K>d<@tDukOF08*lzE-{1RJIq>Db zaX&vi`j6?W&hP)HH2AMFA@KVDLt6fydje(;@6@ZyFzM=eC{I)biD2!fV+5(aO4MPz zDulq$08V@UzvHx-kg_WO2b?zOHza~Z5UY1Zw73JK#zN3zngA#6)j_$^>t8`-!h{jRseFyTgtj zE}a=EZkx1qpcf*=_-#<{Td}5l%2EJN$=psLZJgIx(83u4tLD8X*G8fEXxqi#g*;6o zzlma=h7ItD&4!GPDjIqExhWd=nXS76J_2mYnGjYB$Mzjtu@A-%T{jdc`~P-d=x|6Y zYw$siie%&}5W@KP<`H4w7Zd4P;PCR~TW9NHp{glf304Yd1HgLa4;5f_yVKM{#dqwb zD9yH~Ma-WaCmD%S#{d+dNU>PLxXxYG}AcSjXYielFUWtk61lvOPfBe={NBqEQNjhI->hf(&`t z-SineOH~bn#5(VE2p<4*?^GqmxCk!v6}F<=1qJet&zWH{8yX<)-`-FD_<-AVUCnWB ziYT7O{*8#vVy|?Qsz}$u=wE{Am55^;vq@NyQ5jgtvso))q(s5ncv)k9rq#DOP*Lue zK`#qA=0O%J#-zLXi|lgl24I9U>$#DBrSaP9p}x7O8~E#QJ9Zg%{sj09=WD>&AM_SK zv<$*}2v%S?`jX#=h1D(TOkPRp{&a(8*AMEldwKAXj3$WXe2?f7hk+0EE#6$2bXze` z;#g55pr;c8_{kU4;xb8hxD8Nye-K+0PJlk-z$+*5AxX zcF7Z(;g2v*u3l-_^mP&RI;tZQXFA>CW_eemWs0;SeZ#-&o|R=f+GopNEI4}WPKOvy z0GLnQ!p7f?7JzDdly{deSPUvIpgz8-oabtE;EQk6*Xwvc`_^m}NYe@P&|H>4!u}G} zs;0Z3qt0@$VW@ub5sv5ewNtQ37wen|!qS&7BIF91*Ykd3BD0G4;PFKoc$~V!+B&lpVQUooju78HT+4G+&BdFdxLQ zi-Nza$Qkmyc_8|PL19b+*rY3&F73c?z?jTd<`$i1&hU(r){QkS5damOc3OD68Nh<8 zKPn;!x+fu{C`J{r6%*)MQ`d3Jol@HC@c;{Byja;oYl=&%*Wo(8_4L|`g3ezS*4R9U%Nug z%c=9*8gOnMw>GbpQLgxu>{%Da&)*hy*`L?7#y+6~o!5WRxwqI6AhCJk_fejAEl_pp zQA>3dfcbdcFiDgzOy|yDoBdLKmY$#H=_{Dgw&Y`MIoBk6D7YGpe9%7xEy;Qc$?2#D z&Jiu0j9VYxxidqxqwthVT1azS%cnW*w$)V)EgvPRy87LWMPY%16j>XV7|y!mMiLt5 zlO)-wC6|gFyxLJK7&+%=6q*~|X?T75`d}zP{8IB^?{(YeQEq+g(5g1E*$kc^i+F)v z2`dwXs;p^i_W=3hyIxJVeto8)d1`OZre|0~{yqK*fnMk$MPL2nm*=0!nit64F>bbQ zrSP}%52cA4o@=Tq+a>X;v`9ynH`C zzwMSw3Yxyo!wU=j(EZpB%%kS;GamWog>|3$+88&@DDTPlEPv|dN*2Yw^10KibK_Ed z>eJ4Zsa&5IMiWb-Lr0A^4VO03O+w`AUhXXz;ANiNI(oj3kfz=|gg$ zVH$Nhttf&aQA55T#=sqQCas(ksl>}TsvMG^^$BWlMR0R&HC6auf9Y^STxZI=!V!@A z>~cRjJu~PYvv>)0h9OOJ3@d}&%Usfdq*r~u$vN%j$xy&ITq8{k2t;go77Gg*5KB-TpCP5c@qN`C^4?En)D6nJeG)onqpw_;qj(biv zqer@-^RvogqXNk$;L_g%5wHDHMXlMzGSWSo0NZQ7OQ*5Q|;+uxo3JR!a8a$ zW&~S(&d2>K%oF$j63qXcE9=RK`Qp@OYpk~wn(*T2ektPhL(-6vP2-y}{Lih!3v)V{ z1Axtlk_Qx=YR{lxp`-UH!#sksG(Bc*>EgXqGqk~7*?kp2mVzLdnUGUmDu4oN9u{O` z;^7~NQXTJX38G@VfNp*Z|Lupy`bC5f)O}6@K?;&Su4b`deb*F2Xn}B_{Umtu^^cP> zPSTAkmB0ic(?w7b&ky1Lewq%5KTyJ!O}1FZTz6!9AtgU@B0ot!?Z7=k2U02V^pXQ; z*J=KbfOt#g#gCjSd6#upAe9p0Ekx;;Vi2tM^K`p)A$=(5+4p_|0#UQna3dqa)KsIV zoVV6liQsNRp>R5hy+GP|ORettq{Rr*FR};C&l~iG->}QOv){RRa$`=5?qy3vkJm4x zem+lEUV`WRR>h}5F_OUhjo-M4bg2I%M!IrsxwoB}w~>7>xr?;Af$jr9cB}x%PUatw zU5wPc_|S-IFDRnaZn13h2|%)2$c+ZTYbpvM?s}GY6VlDU15reBJxCH9ux76Unmsmg zt<6^#Em`7@8oQ&WFp?27ops~N^17;v|A@b&{qd{(pQ=^zFgGImms5vIH7f^*HBxSH z<#@Zu%EA!BWtV%RRg;oF_e1jB#wh#!9MM75;~PN9Q?6Sa(!ZU-MzI1^p%}JHfj*MS z)UR=dCTK(Ar4IP(e2ikKJYC^6lHnnJPnHU>#Hx#N=;;g@^rbjsSC~W^>l5C2jL+AJgYs=1gf< z-$%{?jfn{_Mdo>wpD!>;pI_ppfCak6d1x&Lj;i=rR@daZOdPNTemNPIxljG10nuW1zLRhC@xnCRH<_yACbB9-TE_bzL|r)3sffo#8B4d}0A z#xwHF`Q}(b0pne8A;6!9o}CT)1I2JDnM8cwdAaX}XTOAH;E}A=aoqw+XI_(nbs#3P z@Cj`E`mZ{ox@!r$hS*J3Nv=qczcSy&V~zC_83+E~lD#UBVOAoX1ZEu@r~Ff1pkN7` zqBoT_SQ|QZTW4fcV{!H#fz4}vnrBru-|ag9ZO(x#WIn7D9+XLs_9-iTTD1HAoqpZa zNUTapY1Qcme|rE7IpsR&H9w)dBA%kYCVV{?Djt=%>QxySE(<+UlxXXqPN0Y!D~m6 z4OW7o4EgA>VAmt4g2X_#Q?(M1a~d+{5YgT2COEN`3rnK!-_eud5p<~TD381pEN$#d zU1;l|v)#D_ZLK_9b^;pc5>ZN_@_JmECAQwhYIh?}Bg{A>D(GG$Z!&=!o9IRTJ@2hB zfLL!co{Zh_Q|`_b!_=h&;S3Pw&Hyy0wh8*;@BK(!p`s5BCYl?)NdwKH~2qJ;n#= zS^U{nrqZ4)taYgRvf218g^t9HV&3E0SBVNrj7~w$S47vAf!FE6B*tz*B^rLcvh*^* zFn>C$@GNDXo~Qqsk310iVk_XroMR#?N#kYtIO9qXM~2GI`Mt2JsnOmbA>xhS3ehS{~ zJ{#bODf3ln*>o2KwN=y}F!ie9q`GezwP4%U%H+D2$$!$GL#Cel7^fM3Z9K^^ARJu} zq1Qj$e^y9>EDloZH`)4OVkmr?7@J;ZiMwPS_c!RmSeY0|j*3hm%y_wmICBZ<^4DhC zhX24c%*PChuX6$a!3qn0gi)csWlfiM+dL)2UE*Wjyf%U%`RvI6fB5lp%%|wDs5c)u z4r~Y(Ws2GfaT={yU5r|10#44Q!Ub3p3zJ5rD!c0Er1|b$ zKL_k@7_Zfg^7taZyKAtz0?YZ`&$V>TAT@zsk&S8w>_1A;QezLp`&?e%RZi;fy3SB? zV4d6QZjNa{l7%on&hYa4Tvu!U?S017iTOo%=|HtVq(9xZ@KJF;t*XI?eX?Be4b6IX zzL@7t-cIIwmnVv1f@_N~v&5-n+n^*Bb3wkmUrmfIE^RDJWI6v#kZjQ>tVq1bPkAb9 z=JW8nHmN7o33@jzc6~h-R42$yA2~dt?W*dt;5{vw&qO%nI5qs^!zK*Paw1-|SXxrA z>LF3j&sduMQ2d=zLz;jJ5}#Fj6j#>H3x#2TdY&D`bgLBgK*8+j$wfS$^1Ucw*&6OI zC;W*#R`lxN`=jcYLwKT-@6If;*Xi<>Iez6b~n1Xo5?oxtFf4uO)(vgPT;IeSW{VDP0;(`ON!}&cM9S~ z3%)n&;>k~&VU!iafEkOgc7FftQLWv2U?(}R z;gX9@b6x-)wwu6L^H`bW4bWMgie!_ma)OAQ`Mu^(B>`*9vc};**o+(xpglkrw`n8a zZjWo8g=o$CkdpOS)a4ekBASIAt2bGK*)FU z?X%7pYwdB?80TW2GtR}n%Eipg7)j>*&;R?r&+~hdb^)h-w)};pzMroyVG(db93yTV z$1*<|?q#8Lf6p*2uzYoSWrSali9OqF*T;rQWaG}exb`3TZ~aYmQ_yf&1+0eGUixQ6 zk8k#WaTAU3cy9W(Rl;(A(qu+Q&eJ({8!=&ty}T_{vSp9%VZz*2yRuW_Sbl@@>ChCh zUhPdks)PY=d6&O%*prhXDz0dV)0j==ZHoMg->rQEHb(U!@Ov?Qa|tT3eq?}KGn{S0 zYzO4T8979c2%Wwe&1n}XQTY~49D2Oez9b)IhJSN1^y!Q@|54QuRJ|IZ-c)>>5bi>; zsP}eCvi`?2O~ZClj!iD2OaIoRQj~=%$QU;4)6hIvVO7@9)ZXzsDOV`p2)sQqET+i% zQM{0|BH>MsRH->Fz4RpTpghtpY-9h*jag{m-R@!9POQ-iLTkYX&=Ggw)O|72fN4fa zdUOkc!LZ9hd{cOJC{MMVS+DK)+=zmdi8nX>W0>*nO` zYOG>vYrKZPR8KRUazwnz@lELfh;DxyAAGwWJG>LTlyfoJfk_BP%OI^`$Q9Zye%DrW z+QW`5HH+4^ShbjAj=MV1271+W#-ADHUxoVc{Z=HstyZLgsxEL$ohvaejg|c*O~a=} zT?BbbR0weCGLa@XmfgE=_w!Ega1PW8|DS%u3Ssb$XajV3Rz3%+rnnq;dQJ7f64CGO zsi+wcsmYN>qo}q~M8f64ytvpk+SFacXz<-gQv^=|`f`C``8amgZr9dIE}NR&U6N~c z-q_eOV&bw1| z2Wl60fA2;avZ>yLrjB}rGSn#Qx7m=p`qt&V$|JY*oHJ{T*xp|3hjA|jBPrvpJ8B`y z>t9@vr`9j8&y+P8#Y?JoE_YIj#QK?tRF?-DZHy@Dxi?dFT#VHPzphEC`Zxg+&rH>S zukSxsmaFV+N}I88>ww9*tkos;<>0B#L9{5}_;Ut%C(m!MjlCDc%&dP*a8Gx{fET$< zp<`cS`>fLKojfUb=b(X`!4yzJj8#DG{xeF^ekS57eRY=-1O?}|P3S#4OM&g|=d;j? zc1D4(DNBGaxGC6OucRdjq+<1Yw@L8fl?a)o>3)n`nzoHM`yd0qiSt$pp~zv9 z_TtTRDNXJphii74dR^LBW3jXJLVizeE31{Qg`8Pz;B9G;5{R7MIT2zo0kmAmBK z#H16Z(GU%O$ogG_nj+*U{_YW%$@od@!iA59^jMFWM!adEKk(d5&{X3=v@+j6mb(S* zR}?G6}=FI7*}go%VX`V#$+K3l#jEqN1hl-ADd_Tq&vesNe&N&wf6 z;ok}vw1``y8WuBMpK5Au>1>bgYqR4{;#BFg?ROhdeogu@ixUs0P6rH{7ptEruwTJ` zEdrzc-o7pk?;Gr(hR)8nS{eAxEnUoY{%t={LcMV(1NpF%$t!OJ9E`y6nR>67jKiKg z_x1L?a05K>$x8klEl?e2tR$W>{28C~-17pn@O`a`G)i9PE2hwVs_7f@M=frw$h!Nh zOL2Rfnje!mV~;5pf%JNt+{@*~+lMofV+!;-O*2gg8bXpc8V0MY)AM31dP5-soSY%F z_*5qn0s_Dm97`)|(t(%QfP~qPTBT2WMI)-2rZ_(pLJDqlehG5X+i>}Xsx9B8tg39v z5Ls;zr1;~2>&rM--@SU^$%2TRcS+QmNdrq}Yt3sLgNhvj{Eh?I4+n4jVI(dd7|#vE z{p-QT6^Y&rMiIpYsRlU?>d_)nF9Qcp-rW!PR8{VNx~433mG0<)fdlP4DUT9nwdLuh zPw#VOOA}NUQbZcu<4C+Gg#kLCnMQSq#tKIqTu+<(EP3|yc;boQ8Oap7F_PXCz%_da zalhEuF+4XMSlPKCPS>nV-`4rdus3yWiJGFdwwfi*CJd8`z_hJ!AHj!aPngricPB>B zbJYT-QOASUC#7jlOPG|tcBq3od)lkZ=8BJP>eisjGc`f5p$@qEu;Y5|NEhX+hq*yf z4fYUEdq0;S!c@@C1@r0xcpD!iX9hJyh2vy? z*`T7LBw1Bh9kts}j@&7#DN@=(B|}ZX)3k)1HpZ`{wF#20X;E>TzTrX7oef-rXlD}^ z7P0ld4)TtIIqF`^bgz}7my46r-&G-Wd^65zpJAZxJb)7m$D|*1?L(gZY-^$sdoQfC z#LX)!-(UCyT#!AjVrPepjv*I5LDe_9wfJ{tnuMiyjoM@9jEf;(V~Rd}iVYn!TBjlL zNR?gq3Juli&xc z(WhnKvZ8`xj-Vi<@S_0}en}Ja?s$3>&-c5kiKcV2&xk^P+vL(nEHA(!hxG?X^-2SV zI~3t^NXxOPKY9b3kNpIyS*#8Z^I%R+dyDvuK~vP>?k4*p^M+!zgJ049BM6;#pQJ7| zt%Sw$%k3qGtuOj|mf;Cu!x1mk9Ei#4x3My4MyYOqZYZ+2tvT|wi>+m*SR`>q;C)8M zquhmaE?@+VHrSc&wm?w|k~P%$#jde4=WxlYdFYjeshUTa+Rvpe*%ce zK|Y-+IVf9I-|u1dAhAmrdL`&>F#7Vv;)nrYPjGKmdig!Z6K}6?uE304B%vqcrKpSFJse^nuVD3XZ zO}pFK&&|fk&z`8WSr|Twx9)R2pKdMA3O+z7rX_qZ6Mdk$^V#g99ghfDr2VRBrim?f z-fgewXl_K}3_sr*rlO^yfmlI>{mMmZOILQa>F(L5IDMoad)>Qg&!aaS)+IfCj~DKD z(AUEf)DI&JdW1=34eke0RehcNy7Vp|x4(mZxxatF4f5cQV~PDyY_G@a*GrIlQynNm zdbiGUxmF#lpj6w-9^;|=crvCttdgi$N9(jf=gbW8Hl}0_F>es468p4P5A&aqW&b;Q z<9{b_{Qo6+ngal=~x-SO;6MtZU` z14l9_3+3LM6t(uCS<_pT3_{;;%`oc_ju`PPbfLRQlUL1%ci2?r(dNu`V$=&DJ1i@< zP0u!YgT+U+MN7%)CbB6dZ48JnL(1JxXpV&KGoQ~Jwplch*mNO?#Xg65hx0zTCv^_Q zJ|Y~*&RZBfVc2Wobdi_8=9~=VRPNyE(3}E?X(wgGYI-++lp)w9byRN;T81@H^}EO9 z-$AzyS@d2o$hmM!3wl0RfZN^riy47N=r zAS9M20T^HBO4~&aYA?=Yb%PMsQ-~i}`WNfV2b^EgkPfBxooz!M$s0Mo@$^>95w}j* zT}&zNei9m_g7&_MTZd6Q`$vVAobffl=T96$oin8GZL}voxA1~@Ckqad)x|7!6&x_$ zlwMd)VVT#1!(U08Zpuu>LMTB?3c{; z4*^^?Ii5ewZQVg{^_aJ)Y$`)T{Yy>M_6uIJNW0HdeYUPQPjwc@@ET#6hBK!&C|mn& zK9mbd^$>D~oJfk4>{fcy)YU!LEG+tVF%aZxpXz5~w0IGoV94ws#kQ&X@7~3URlch_g(TpRDsot=esLGijOy z<_ntbq#x#tF)M^v=qFhv2Jmzwo^r;#sEZm;q1_Vu>bT76V`C|ro2cl6(Lo+idLc|L z_orM^u7q|@x3%Ld(!!Dq#4rm(o9NHkpUrh@)OpXX0u=n&r!9H<{X`xq4jabz)RXDQ z8D`eV=w?eNo@!Shv;|?c@CKzwC?gWKc+y+=y(PuMg??Ua_2-yZtEaZlAL8D8Z{ssw zfFUz$Wz%q-fB+GY1z+x#;7M5h?2VCGV6f+wIY^PGsjf#QcGXMp@g><8jto3=TqmRV zN-UR#Y7$ll8v1gS;!Eqt3Xc z!}OvGUt%^<3sxwlm}%s>l{IamW7FqB$@eu4>YOqh;u_KG4~;VJ;8&`kFw$r|;=;$W zW2fGdP>o6q{O3UsG|}*nPXT;5+qKi2?dzL-zq*WFuH%v1ZzIojVG% z>(JD?B4Ya}`;3c=?dr(Pgr4c|TuZm-H;9E1niuBa%spFkek5yAG*igv!JQcU`eoHe z=tPJyaE5D7+a1HLKA`Q+cpHPy3g_!xJExO2#NXz@6_Z%MU3{Hqc8aGu46j^uU^D)b zbl=eSub=#e4F=zrXAJZx$An%;%@x5r$e4|03sMCx~w!0ArKXC1zE-l2<5kc?ist zw(yN4=}y(`%`;2C{||u|*UR;eZ)Zld?ven}n-{oAb|xuUg7qUEZRF8O9Shyh#iH&L-=j*Q;E z*5X~o6Qf5jWage$yL(ladTy?0t@ZCAbwrLwaeh*M+$rwD+{z7-cYMU_4$`_F`oHsE zIN&=>*zDHb&^_E;?+!4{Ig*XfJY5?5V79VzBY$d9mH2af{IH(HkuOsS@{@FP@^A#D zJG|EP4?&_WYUdM~>0Tz1XYTKwM(UbQNLu8((%qDnI*m`nKjbSaJA#l<8BA~yR1n1$ zfn+7)qRT2=;;G_Eq22y|Rh(v9@rAWju1>!_FY!f{xFw~fl%`SIrFlypULszzTe;yx z`>wHyhl2KLs|n3VH?0X?SZBl33bddGI)+ZVxQ+S_qmvRPg#i1|kP2ZEm5%N|vv(^y z`i_Le-UF6w?HGKa$x{=I@ef%7#ZU_yY)NR~_a)uf^ZPu3f(G$jDjO0k(WB#u@$glE ziD9U+V6sN9QXU+o&yME+uiim>FAU_d4;~b_=8JT`2HqboRT-1|0X)xX_7HkspF#E$ z+I~O#omoiE*0t^hD`pO<`w(KH6q&8|sSIL%(?1`%!z_2x(jCz0^I_Uja@Cw*$E;zb z*~l-h4m?`wEu>=(+0(1lH^U0zC_90^f1oW&JiT_$O(I<~YuT#fm1|?5 z`Qm+0VAx0_%TR=+2~BwE+tjXXfTnxx7+}$L^50?0p8UI7p4&pWBRgTxY!G$JuP!Ih zhg372-QTWDpd!Hh8;w=Yl#Iv)W3nHkqaR9{Qy2qXV|93|#=^JXYU%qpW7LtgSejRO zHfsbFPzJW6m}r z(@DJg{a)^iI`9XC-v8sr$*1XK7tKoXs^jP*pKv4jYwe3 z4(cSP%ZxU$nMhM|K6%N~N>Xc6fTf=~!uA>BK4o)8eWXF4lJ2aqH;5c`!2H==sK(ap zYkO<5CQCiuZ)y5rRGEmnm!z#bpQ$159%4cm=QJba=$$p&zvFE**IdfaH+pm0YL7jH z>f#*_xLX*W%ZHb^MGd&KyNn@Ax~CT2)KArLDf@D}z03NUp@-YO%cCni{Mobz6`}SI zLEF=U=6>WJ(xt-d;<-fpCVl?KcEV88&a}CpAdh`$+mYxnoC+t<8~k-|l@qlP|D?Ss z#qE5|;virIuVmWM~(vlg^_p{oDGZ*OyRzcI_S zqkmUTGA9(1Js9S4v8DwzewRgtgUwD|eHllg{HFb)+)POB%Q=$vO zKLoW=rX&3fWA8qH0*)sDOtW61S+Y|dbreyRLZ8Ntz+Y)!?EOlXwfi(fI5h4-`y!u> z8qj=v-LvL#?L@ML0ot*w(VA-sKx@RNhJ=*@yS=(Im#o|a6_4<{0ecL+1~3j(g=sXm zaHn4~`{@O~t6@fG^@nyh(Sw6VBjxrR6HPccSj?$ zXICGiii;1y<(M}sNxz|0q+kHwF>H02wk)|!ZoE+g`5e2)5k|n5eQYURtrzoZ0$!wDe^Y`YJc|M)Ihjx!`B*zzC6e) zs!7-YK7@E$)!hKTY$&`qGRNH-*r~m0m}`PIW9UTu>{^bS?fSrBxU^O(sio-fty)k5oA4-rET`;O&h3+ivrgw7JC~5p~tGfp0XDcy#150@e^(p2x@d>*rwM#I^yCgXg*AD2U~!z^|eI ztsUgwW1;^IqWvzp(qA3Cmx&$kWs>?YR;K^nuky9^9|8+c{7Iy^kY)vCcU;RZu7m3K zjx#|U{s8_4u%g0+%qb{);93y44))tS75)UPGfJC7qQh6&&Bk8;mtsTj&VPgg{O4C< zu&!a_loz7=m0o9PU*9xeTU$qavif7OGNI$+0b;#7+-V_qr10Bw=6)O{`Xoszi3z{> zpZ;MZNj##u5LjLo?mSL`N!;6J)6YuTe)%KitMOZ-&Y&@d1SG6IKR*o z*DYjyW$nI*#aN30*an5B6&Z=ervUG-wK*Uw(xQHZ3s?Ew@PTLYGGU8-36}4 z2%w#W#)7x#eQoJa;4(=Qz?7fCAyl%i+~oIqaC6h{Z7#~+|8Da_2vBuFQj}V%q*#(l z+|tFDM%mL*6SAmXLsoBjE+2J02V5M!0HEPVAjQf+d4+O?Z|R`$klFD|AO^6uS2= zTiZ8l+ZgZi<-B=$#}~{vq}#XFIynS?2+7*qsYD$~$#qNgUGp?ocP&8yuPxSe1XR78 zG9HT@bs~)cB9HsqeX?wTg+W9MSpFJF&|{QiVWBG%8?2>|=T~X01;|~P{=EPvkD=@1 zK8km=n+&yh_Obgv1iu@H@!7f&Wmt2JC-HDBOh4v9GxFS?UV4YzTQ&Rl2S<}cTEmCq zo#?vff%UhEiV@}*Q3ox6zttt4TCbG*TvzhD161elvNxLsA0Ic7;QP-cY z#j*eKReIRNj!A_Sp>}GE$9Ber-58e^j-v6)+NwrEQAUc5$~ryir}Y`vj^@>B@4|hb z1#^XoqDioyyDwwn4!_f8`%MxI2s1pmf8nYK~B&2H5nx5+fpq|V#) zQIRi~h!7r&U#|}8#`Uprqz&LX8c`u9TOFBa{C-3qC!T!dioJjo>S-zo6bO|4p?%46 z$7&0ogX?hf8UuQTCdP#!;p~5on8!+1T(jTH#6A2-^ogkK4fu0k$NDp8)OXtNS1=qI zEjrE|!-&M^SyQ6G`xqtlx%q9@bMG6;U#}d6!=JtU0T@lX>!${<-e1{p}4_Qm$+2YF@3~nqckVj%mMd z(tlUHC@k?lt)H7>%ZrJhEcF&jGvnKvZZu;M>wGo_OT$VNAd6KeZ&B(z|LVMNkkeN1 z@FXiHZ4k(+$f3N65#>TFBw*)F<^#qo77u~#o7Szes02jnA%Bz-s;Z3iI{-rSPHhwBYqj6eD$4Bs5SL%%ZXwTOJxrVS9 zP6%*OD3U?%EtsTEJmOp)5PBCq!pQZYK%?kQe8N=Sei49h!#%pCho^a(OIr@)awHs4 zo=QYEgB^&3dUN?m{2?udws4kk-H9)k74==PIGDXX;O(_vw(5txk#=}|#pN)1WhFD3 z)d@av@H)p8!RpxfwW?@bm#6>X?N;b6E0v zy87van*Mgff(2C9t-RWBZ{f_h-yB~-vos&Et4z7^%|Sgjm@j~eXVA)>_GLHjlvh7q zj;Ctfyrnfu^c()OaAp9E>Ii}Jz32-hS`1JuvQwExCT+`1PEAGh{xWTuUSc(b9Zu$!d-R4nWBbaAw5DU z>9le@a=WCIg$m^D6aOp5rY+G6fcOCrBNDnJz))v0G=nZZgx^p?jc0mz4DZAv=_e;djlSYsOfOS0ox$gcE-$yn>nBe#HVegQK%2+vQ_n@CsUF@Cd6ma$_P2Vg&B#jG{vO=rg+C=7V%bw@0pP&6hAl#yeSNE=CPsk&S zBSz2eJ+=M1d>(Whd$D?H&??h8dz)AQm&Y@m-IoAExI36u5bAP6u{faO_d%9eKkZPh zC(qnO-fS!pGxyb)x*)@hi=0v02P4w8YewL!(4l^2ou6bAa*~&Cu%0n(Alg36V8npt zTk+U*C-zAFK)|H;*<#5k_Uaa2lC6I=pU4`JTO)!Bcgq5>T$ia!``61CDL>9u)XcbB zV_&3%BrrUjrX6d*wyCa&{*emez%9Wa-~lcnN=+wm$5PHB?8<19QqP(_*-8}}=8Sw@ zY3KAvn+`@Eu{v(CJ1iAdak-vK?tgvCXq&d~v;@VMZje{M z9kZH)YE~_FPvDv^neuwGSqnDIzAWyj>XG<1K74G)#lR}~H|#ti~I%Yzeq(($E>@P4=uHPV-ZU6 zt1?;bL-^QdI}selXm91xXcOy=kCtAFcUi_!KL1(lU%m$FX`RDq+$s&eKOqNFhL57e zlQ`YpiY>{v>a~K(wf0x=-tXEvrQEw+2OE$7A)xBHzqcxk>8y12SA&(CyNq8awi6e3 znI{}-J>-GsBi_Uxv4|DD$2d}#9a*!Y1#x7;NKqoFdMBzT3pt@Zz+bd4?y@w9Ndafl zCuG>u{rUbSwl%v*CcU_j*(@WBiU(iaeF|ETb&AGOV#rlcxh*q$tMb}$-D<*W_js}e zHJC?F?OQY0LCm3pPAX*GDPoO*$el6vsLM@8YyA~=7xnP702>gX0IAifB_05(Y3VfQ zopzA{QwdMQ-GPb051TX6-Yy(AwY!_qu!`!;2zNyzoGqW^*#~I|`M%greD;iV8Q4H| zL|O?2q2}w0AvwAMx^x%^WXr6Zih#N|eEdFdZ$fI&UVqsg&(Jo?dL9YUCnP?l%B z*$#VjrYTh3oS|_l@#6z%TRhi9phspk&BGTgaW)Y399$OeWmzEfE{58n>BFSpRQrPK-6H7o&NvIO+qB;a@z#!bO6TH)8_ml7CyUz4pGJ|x z6IvIY_;$S#hQ0W2WAhatA07b*Vp!cVahoM!0qgLiwY!kGew?tz-w9F8wyd{3i5Cn# zGlA|zpW;PN+Y%iei2g2VaD_#AqUVF}L8AK6kWOn9xa3oyNSoW=98h0o%hb~HFl~e6 z^mC(hzZ@P?u5n@j!=Q&E<82PqIU61;1vb%i2q?O!-r>8a8yYPDLFIxisF-k6jQBd$!Z?MLipx)+u`+Wci68k0W1;PYP zxs***yv)3$b~9dMiD>EAdCf=^-;ubHaI2udt+{^+Rxhx=H#J!!-98G0$kt(DiA~`(ym_AV zpogs!HFz7bwcsPZD!4y2$^8AX!0W?LdRoxsRHG59%l5r41$5eXHj(2%o=v z+n%|%ZP6}l&Kw!D5&hsv8q@;6QIK=v@x~`$0f&PhN$MCV1iwKgMT#C_S<5j_+B)R= zZ5@%mU9pnF`~jwK9)63s7xNk(@Pe6SH`wQ(5xea^;?e<6DbO6@J?{W!VOf12 zcXo)~FfSJ3KH#q#{QxG`(#2$a4p4GT_fFJ__mLspelBk$1EYcR*=_uR@+rkinnKOw z9Zef_ zgk$6a5xe#4zB}6(hmBjM&G)MusPlPQ`pCa>#hnZGIwpQFV}$Dyjio*frl*#VlP*!Z z%;H}kB!v*oT9jSg-iV$ZAWX(>*96@Il^*By=;~ToWgHcw$T#y7(80a36w{z3idFF( z&DL3Ot4D9T)Utp4h+TA+X-cX6*|v6zoRs?Y2d~g%hg9?fdZy&Pk=3?i>PbImYu-x* z_-)p|5nGYqN@3_z68>}wdu6Qvz7bfPK-Kp4Jj}j)Gs80@&s>giy}lTdhU)m#Icm&S z_(hxZIZ^1foET`-Zva2xq%gHbKm;Uztgq)`TU4KaRAkcy>ge!tguhcGBmdwO{s=Nbv_38c|_!5dDkip=BOxxrCKBb#QV1ml`s z&v?sp=4Gq5M5q4whk)b$WgGXMwqDWiCu~*H`Am^(eW?)F$)WO%fd$^4Hr!O+gKrnD z2}grHgXyGRXV9JHhj%Nx(m7Le4G~{}SedB3aoo8*;=%wF5F{dl~V^uZ7BO5(KtL2F{@8s zdQoa?jzjvMZ+I^(=)3R3ZvSN21v&H#64$(mpt`U9&HT^8Wd~KX@LzcSK|`0xS+rfc zz==lDQ^d->z$h2yI;{{W9A5%A`o?ux5f4Y#!n9k^k~n@{YNe>AgkZgyDxd0@`g>B$ zkm>a|hBRNoIcVe?B7!{A-Cck^`I&fX!+V^y^R!797=ga*Icccf-3ny>hR@wZzfA&F zI(KB0)D~NnesK@9k)0$OyWR5UF%1Ya&1N60CB)Y1-!asd0LHRG+apU!K9ND|0 z9MpX2H5P7+Zx8J#6kL<=AO-@_{v;xi?Dw1Xoo#LT*T)Ra7Tx-A<*jNHPe05 zNxb~gN5sRL_(l;bg;tLbVutcr#IZlX1ovf=PgGg#`y0>Jmaj|*c@Ee0y?fm{(w>s9 zEL41PJGbidLQcA%_SP4nJCK3GulO}femMFCa8P_5rg}XOptm3-)MfY88tANbQfXna zpDf?u|Lw^{U*x#521nM=Gf!*ZP56>_f6MA~6d)Wcu?Zt7#&8qx1q zu}y?b!niur+TGLBPG9uFlu$B<8C95o-i2%0LpmKlJ7nbv)t~Eue9?I+;@nB9j2)?T z{Dh~$fL5E^+LxP{gJb0YjEdb6R!1iN&L4X_0~IV;G1aB~CYDZPUc|rk^bJ9=u2mbu z_oLS}X&?*p717F`oA<3&-lW|v-8hTDo9<3l>ln0dZx9b!0WXj_Pon>WFVvcD|HYjM zH9vRkZ28^GJ|1D(0k(a-ML~0CrvjG1P8Cis!On_teg$rwOuMmNdv8(Tm*uf`y7P1^ z*{PyX=B18bR6l-Ov?_*&iLhWi@%)D7(kLjQSoW~#)bXxNM~sCZcys0bFHQs_oui-D zq_ipR)(Zz%KfJMdH3jdXS>KH+iBq*(Kl1QSP^H$4bb4r&fF@*E;miAw>JWO$*qAJ# zBefwT%PEL1l=K9dUneG^0lj$K)}dsz;1Cl@X$5eJQe}E{(lFHQ z7@X)K?_6cJxsF|@?%gT*)x!%}DcG^#bzZ5inZA0+PaQu_xARc>d*4Hbb*E@l z)S+j&IfNHq$ugCPE@=ZFSVID|7YfnV_2pk)PesR<>bBVs7c>-P#Y!i$9GU2S{nC?g z6(kKuw&owyEgNJBU!RAGS@wB90>oeFFis3Ez=oY>% zU#IL<)xc8=6}o4fAGmrKZ+BLGZlo+U)dXwc*GAPC(+TNqz8T$H9w54%c=#IOe*Gu- zoTPmJzr@L=D?8!J;RkqQ;2+1*|3p5UJ^wET%>O+5`G1p-{~r?&ftvqkJOO26 z3_twv?*^;C956nJ(Y-}9$}6eYTi@B7#Bl#Z5Dk@C=a*u?hZ%>A4JTVMQpim4egP@O_U-;i zQ1aL5O&6K>Gmw8l>L$aUG+^(|-V0)%y3&pPtg&e8mj>ot$XcR#E!n$#6JNF+b7F`dlS+#S3d>a#gkNF8&UnjT4Qg} z3z0QlVi)Z^p^P(t}#zw5f&Gw(;V%e4&jKkY2ih;dB#$=R2&JaF~dwOM@mwT-!(SWl%%^$xrwaL6yD z*P})UNS$S4V_un1XfPF?o7SP9Ha}&qVBlY?8;D=Ws$9(7BZHBIb5&i8MXHL;WtP&_ z8$X(g>8pjFsb$WeT9uK4hR#?MHQgKeE$>Z0!*Neh*j0*_7HyjB(YMnIsAOaT2SG$& zG@s(%oBL=%BtmG^FT6y`ivoKk3%fXN0$G-6w z-C^@6EcKa2Fl|vs@F3V0(HH6*=aMCBX$WKp0ZI{1|G;O~23Bv`_=*@`q^_xc-ZmJT zy=YqfgLMjfevw77zDh`|vnmcYKd`F$hhSvy+ddHWhW(*#E%fd}s&;veFkWTg2?nz? z(3w6uoNsvi5@Ni@)k4agmt+8%!zs7|3A_B>LGPfo%~0FZ3d?Vo94?AD@~6FHN)pw) zyiIk+28y3&U@kNM_#5q$+!st+fZ9jYT?;?xYm? zjB=ikeRWHq+Uj15-SL_C4yJ$Jwa{!4BgzYpd+&T{@WVc1lvw|aW|xeB2=z=%mo~x7 zfeGU3lU@x{T$>-*l9y7H8L#)7=O2wA<>Qge8d&o!$$_`a!5Y^{dk8Ru>ufn?zcEz( z_0D?x5<-{myAz(0?v?V$-^z+I)T{Axt2n}3QLV$-#0p+er4e$^*Z)JZG?v~ua z3)IFd@Wq#)aX_%5S=1>zq~S&Zw@B$`dce}hQT-hp zNRDqI0O&aacb;5K`u-0=Gii8rlM(~MQk^G#H88Taq+>A9ejs6kpV1Wj;hPzw+1tmP zAGt*Pm721!G*dlnm?!w@WSB9UG}c>K6xw=CQqL{1Y}Nbe%$%VhNxbC#X*BOkjaTg| zn%BXq0_ps7Iy&^B6JmbQO(6xfsuQ=UGvxXS!vWi~_Eywo)cLKt)$DPcq^wDnJJ0wT zt;)CwH*pSG)i7bm{k`nltlL=JJ=e86I8t*LwkNl1G2Ytk-r%=$d}f8s*{ZKi^)p^x z*~W7G7LlKn05u#*ozV6{?eQ8U_YfR48z#D%tVH8|hJ&5h!tMqQbHgd?>g zlnQmoeN2EX^zl@rei6TJiN27eA zUZjJHQSRK_d{TG*0svr9S$PZv+;}6f9Qb~XF!=_4zBBn6oi#AwK2hIfWn4m+s`{8B z!PAp~gdFyC>@GN&RA8ieIGqe5SgsdF9M7sM+uBy~VAX}|bER)xvi%OzqnqYZxnleWe0)U# zA3IAjFQ!^AQVxOj>LF0W8x<@Vb=>*htr{zb9K$qQO!#a}n+X>MnAs$o6@|P%gF%D& z-x-rDGCP~xengW-pTq9EJlgNrDR(Gz`2cp?T0~dF>+)wbfdcFmqq}?Tke%0F}4G+L?z*|)oY7MyL5H8v2 zGU7t-LM$u9o_rjYm=RI{=?<*YPC-H6mjCo{P8~`evF*CU@YBf=Pj`{|2c3ly|@9_g+hiE5zLK5e*o-8vL!bF|QOch7yjM}pc{UP7)w6h5;xUz6WFgZiR} z6N2rP7$G@MSRO@D)BxaO$p}o8^$0jdneK@g7APdmRyifQ`tbAaRu)g9pO5?B#SY^q zF6P&+iK}9$gIn{y;b(oefyIgrbVcp>k!Hm>ly2W7F;?=%9m~n~@E4T- zVg=@k8<=_0cy{5o2p=_GX${zXF|?Uj(h-Y&j%poJdbF=71&p2sEu3t+h$td%8)&t^ z_#E}JJk^19p7y0Lo`UZW2K|DHq7@brdYJHtaKO|c<#BD1x$C3hyBP`gnU7OKLp90B zS?+2Mds=;F8G1hQGdoEzY5UrrU2agG5g3VTd;k8RqQ0tww_1=79K_>P)U=ZgrL}$84c52Q)t)`95pqF?!ByI2Lt*UN&H}hUid{BJt01%-) z@WExR1vb!(n+MzSb+#gWcDO=?ZA`)$<^T^Hnpi^nNBc8BjQflW8W$>$;_*CPtXc0Q z#kY_~rkmr4W@rIOS<=WWdBZsJbuBsHsG^1sk@5EIUYUOEJu-lC|}uzFI1b074%I&=KLI3jFYi z$;CcnJ0&!!qjL*fnW}O`{5f>^%=1DP-DH59WxEsAH(xNM{e!n@Ryg}wW20ReEI2w$ zHn7f-V#fuNcNum1h^qxm+1HmE}-?w>Gn13rcB4OlI8l zFLS-z#?(ua+VJ$_^U@8Q{~JNhzv3K{2c>x6;WUo@hl%&@buqpUj`@e+TkO>AKLnfC z!2T<;pI!eD7{UKeDV>YGd^AfJyq|;XP{KvJ`iD;58U`<@d z;TZ0wfPV<;2AJfGK18}OhN|U6%PITlS&$N>g~c1eX}IQhFu@xdSQ!xUMb9<#zy|Cs zILOlYSdKQ2l~MUQsbGf{pUXbjW3P5a_7RuDgJkCgCZDJ(i$6YS^51Tb zGP=$ zG}23pF$cHo#lYp*+(irrc?xZ&53pwtrc_zi!6m%R&L=%g~8oNXD41g z33$flXB;!+ktv!xGb#9jAxzyh@!U#0hRwUu*S^8@m#OPm@@R`I$P)X)L1m9C{4iN_hL1p+<)e)QyVi)A!xX-ln9_n(j z79%?ujvH>gk<)6J#Vzjaj^Dg))jwQJl)lY+G4d1p&JOlP-WSC@kY)XF2Fj36C|er# zZML~wxY`SIURmC>9nd|mXk;EAx%5=N#3Lip%nq0;mE$+5X^oEl@Su|3A8?Bks9Zh&*ucq>DnSF`YH@>D9Y@H*}x~HuhG?zwMz|(Y-yyKc% zD!{M5I{3s0gIu)ojjc>YykD45A6m%c>4R0qBNeHtZRyji2B`wrc&L*RS z$Pdg(qk{y2&OoxJfZJDtq`G;{%oYLc0{etpBHvtTcOzES95Suaz@e{_#Bw}dvG=ln zS`|h)PYbUp!>7+JMA;^)mKOKL_fp0{@2*+u=uY2DBh+)s85oe(Ri?*dFY+uMriw2+ ziybc4w$J#qW$>5#dFH~;3ln@hN-+WBv?+=)g+0JZY{2UAbtXP8z@_CnYEgboX5`Ec zum~sbWUkMp*!)`2F`Q&oG*<-`Ey4eoIyHFfj1Rt-vwNF%xc4F1I~3rmXyalSCPsqE`CUMvF3s@ED;& z8VQ0o-#ItC(4=_WV4ypien{q8rhiQ1*c~s&kqyY#?Y&^LaDQ;#o#vOGj|l)!vz6O+k-A(t1e~)c8XqR?Y`Kp3g5^ z05#XH6gL?@QhAqelXVmqr+=Z_crTvscz4Wpt{SPdh&$=ee=;KvV2?OLqHQq;rn7F% zuk)XHUB5YjPN_Lirjh&A$)x0xfCmXlq*7f+;0Nw7z?1@8SZedp47La#8P;u%(7qML z2Un7BCcyho9$L91AVsM`=-)1JRjx8ivgYz8(#2aqv1yCw?c^k0H9?Ax()1ykcRO|O zyPDV3BNIe!Eb)W^B-^}*@U(Wf;E|^1g{H=s>dsfP8(roolCI%lC6d3o(d=|m+9Q9D zK+34<-6(L=SlfAw@IzN1yxj%7<-+M#Xq75DN&b2buV(qwtf{G~>UaJAD8Q?`%>Th)D0C(z{ZFlpsiN(gmdV zE+vE>ktV%^BoH9u@ANv_d1UgUt~{%~ zGO0)zVRo}89=H0W?a#|hnDhxWU8VK_M~d8E1g}zZh5T}A@x*}omTT{m;3^wk05K*a zTApE9(ABC-$p*cV<}I^{HVTzkB;>d^AO@+PPBRVFwuTLvJiqWrQ~jR8Eg$T*19U2S zE<2hU=u7hkP#P|HRvucqGtx|N7wYr>#^$i^! z=o?ApqSV&8{d+3WNu7s#$Nnd_;m;gQ81lihU6q1Lx& zAB5M(g{s;8XN@en!|eiejeNj!>Dw3Pqxk)O#3debXrF&-ORJ-+^Upei<3#`Y4nX_q zKaJx2cNHu@JU`4HX-$|p& zd|^Q<%bRZYt6S=FUF^$n!9)^cxSgX;k-XA;qT1u{IPV&qO*2L~KHX7rpxs|aaloEc zRY#g0PF1pDJ@zW|8tAcwq~M2gWU#3f4olQQtlQ~|?9(n@<&7goubP^bWf6TgIZV|k zc8R!FjhR%F?5Ho?_M4IyWA{HPq{US^$mT@1DnjoR@QOW~os(kFd2)wUDJ6}qJub1I zC99A?P0Cr>-&eQjK{mvyd>>8es$=`%*W2CxoZDJ`8oXKV%dQCh%l$><(D+H5ESL)G zu7aT`siWvDeb7Ic<|$^5&}39KNr|OCzF$d5D)?vaj}@TzUoN=}O9&NtivfqLMapYZ zzo=`OvT$W@Q{mv2<~}%DTgiQ#Zzv44d255anHQjdZ9&B`!_Sq`R8ctP!i8JZPH@F2 zUtee5S^ldBoC3Wj#`jrCxt`o=3?M1lVXnz2b0*!kFWIK&^`T-n$(H8bCScsmdCK&} z`g43hSwBO%WwErId-lox(&eA4%hP86xceVKgXRb6W=G9egWCh96ZH-5K{=Qc=spL= zx|a=dx)D~1)%%rMxsyX1?diRuNh8VN>{tZV@dHE>Ha;{i@x}wLm22`&YH%jG+&`6P z&Y03z#YZN%XBg<0HFU}6mEE*VVQH($9Hv?~Tmk2!E`DNqdasmM$`=!awxJSWSsVv8 z9oX>Q*vTx74d4Td(Q#Vc}uF8;p{lJ|&>3N-08Lyhq)zh1N?4G9YkLAsG z`bwDK59pw$GFacwSTK3|%&*N4x;;*%B6i>DYQD=lmNd=zdgouxU%kOk&cbd4QJ7+f zG$0W@$-C0j##@sr0v%Zc61tlAk7S!n?IbQd$}-#(#)olXoIG|)QkZc$~m6(_1clqv=tKBidj3pslhK|pey~|RPf#97gV*o zH96#lT0V##X73$%7T4`&Kh598_naht?+QG~2nh2g4)n&)hh27P)H>RFd;4D$9+yMA zTh7lqsi-8soF&W;^qE)7A=0!=wwtOU=efy8*wF4Nkm4-=eo=y%#^QP_O?Co3gVVl3 z*BuW9u;|RvpJ-Rz)iYD{{mkYL24VLP@2@~$@x3LdtUc_~So+$9+2g*EtRQovHTPb& z&>SYLKdRD#t2>v*O_AGif{YlS?^t*p0)I%aRUoq_{@ad7kY4EM-=5# zx||#Ti7!|p&X62N4vORPj}a~%(y(qwvQ6UX8z4!kgWBnYP)-XTn|PHkKd#8WXz5rK zwnfa1)m^zWPV{}Wr_f{=+B2ZvffppDBxz^PVGXiTowHFUPC>~)=1S|oWUesum@51~ zWv=wflU)%9kYJrri=sW9Z0I|N@X_=~%?+8Gx*cum#RU5w?@!6n>-s(vc=^N7Tr5PE ziU~i*M%sR(cC5fzQL@qE_0oqNa(=#!BMXbf!o)l^{X`Q+#y{crZSKTg28E(1M0;iR znM-2IO?EDAuG%XRWRoBpc(0jrIr~cL=dR@tIim%E6sLh+3HXUC+mQF8jQCq$ob^j( zy>?vSDb}KD1z@gcozmBxe-XU5&_0XBk71x8hj|c8Us%bILu=sgx0yZ9l)2xKz52{< zBmBW2`tH6!gpI)+n2phZ6Y zAb(M+H&G)-B+I{C{CTbzoCU;}*s~x{e5IR{@yIT}t~Wd^7ud?V6P)LXVxKLo{?vTxwxHcJGHT()TJ@ zwZDbzt-K~=OCS9Brd%Lpdr~Jg%XDeTD&qlaz^YUqC*;5qnP{jqyRhNiq~#wU zG=KQy-IJ6hv1H3VS7M*4gJRyz6l*|blYr=usvJ!;aOQA=Wegg4znGkc%6N=@riW^CQmL3>H}J| zR2XR|Y%v_2%wLdh+Rn7ii7A0QUIrG?)6*yNbaYfVzL&|5d#e9Jg+L$}@QxEaHgrC4 z)Y0EoO`aVHz>TfP23gBnD%Qy6wv0TKNT1hgDrird@MC>&C57+LxpAGIZjjZ@1~;v# zE?eQ5m7Fik+-GOxB%S9{Q9l8+b(! zKbm_bs%V7^*i*EWA4`_2i~EZ}%4*OI9AD{z$rgeMsm-NK$SI{pl zrzh*3{JAz}cI}+X4>^}*8Wr^jZ{Ga2E0FZ@%Yv^4tP3`YtQINx5$%y6HByW%zTDor zVta`t@7?Urq5Clxo=~>+!HPYT+*NPjIFpx2gEU%$_LeRqVOOw>tzM!91qd=0?(I$* z^xHH%ab=~ZA4Lu(89S4ZHZqcpwq#MY)%Rm6L2}C&kO+nu5D<`Lf?zA9v0hv4{;b)x zIF)uYQDWs9M>Fr3S#f7<8&zXI@z_D$NG5*uJoKE)W3{Bn`gT(EJhr8hs5Ri<7UpuM<1Y!hDu~8KP?VCW@URvQUNb9BCx_@ zLgJGbe}P%>FPrA9b?a94sCp%uU0Gx@iiOPEc`VY9RW`XlEp1NwerBxc&28=Sf~Sc& zLN6s-KC363ug8#yU%|iiXY~5|;NI8%MUd{MfS^w&kYM7Jwi+~2~fbGu@uxfi5%-yMVk!c}S|?ob?7Nw!CdQ^+ zD_IjL1^I4ixY<5~9@32;q0H1YeV2>ddHr|UOK1&#iaD*?ad}^CObarbx%6h5xZ|KO zzoby8i8`{#I~6tc(O1API;Nh9bKqU8idI)sSqjVgoMGpt>t6)Ln;kz&E+%0%z$bPe z3x0`*y|F^_W?O&sX19wcg&UGjhcU^VqdH#$+I}Tg5UPJACvo+GcE8l6mm!ijK{tmy z`?-4B#|JpUQokdzS6i>x8~ryNnV!4(-AMM!_ze|=qhm09bv}y z1_Zzfts;Y19gz}x!f7%7#r>6`UU?d{6nE1%ZyVb@TqFGSK}+tZrKqAjx;ngFB2evl z$OX~3nNyDT_lZY?>MwNF^TfXXq`z~cTi|>2u>#jG2Ix{lOD-?`*g@hG3phU8O}YKOX-&7_s0|0V9BsFkMYl$(C}z`+z?`Q*9k zd;422FJtbyCepHp{z~ zVeMR{EgB$E5?4cr87f~lxE11El&MPk-ZuMj>6@V>o_Ab|A0(z$V@UB7PO?2g(wJLi zaLPF1u?WUpDNeci?tN)r>89bg_T~v<$ZLXkY&0S!mZ+BMo%Eb`xEZXq7QT&yM{Q;8 zgMYz+37o(0_!VLF5iB0g3q{G*Mr69B`qdg6n}fdc)=7Q-DBPa={)z&*o@9KXK94J2 zOy!8Cv;9yd-`0hv#Vkd*w?8cJFT)PKndZX8R~KloHU#=9)Nhrgqb5qeWXHA@Lf(0E zW|-G+7~UaPIdQ+-#ycMbLP}YZt}I%TJqI*0 ziK-?U2?PXW+-QPw_W%5WMQ?@$u?47O#zNYy?NQn^*rqG9HuT8Jr`agpglfmSp|X@= zM~dmWLznImLjp%k(d)3(U{wQQY_%Wi1nXb8jU<9#;|dqH6`A9YRa^W;X)MP40+_9& z7Ey+gsyh=UEN}eYl&i!OR%z-Qr3)V6{A%6K)^Yw@f)^IuPFLuz-xPa%Sj{COm z&Yv)gc~S5g<6behRZmL7wVTJ*b&~S|!atyxoP2k>*<$w+$$6fd0}owAu^T@}6?Q#W zBSLT*SL^{A7=|z+hFSQlNps_^%$aG?^`$?9QQ66is~SA&Zqzo9W4SZ>m2)3WwTpwT zT_r~o%1p8(=j$goj7-8ey2y{d8mNsVDfi$1ZhyS+nn_hR?nS}jk)vPkpA1%S*^_d^ zU;3#I9)k0H{4ZY)93jk1N=`pj3;Xz{;U7%3t5j$eIY~cKc9-nv^0Q@%{I+WU#@M4R zn#ho?XLqV>9Lra^6mS=V3lc}WWii1fQMb>fePAvjv_7|go4)#%X|Ry>wJ=4D_$|48 zK9=E%F+l&iAV4kW5N>?Op21>>eK`@mM_yCR@nxLNm5X7?|oh zx)*}Mzx$bbzsr5w5WSI5%=CIk>N_Xg;(azW+23+tw_~i%9kyI1b-1!mufWxHw1oXk z4_yEDL{|Wg{y1ZH-eBFw@cO9oiEhL@K_K=38G2>4wL}|4iL<~cMR*mX!98&|e=+!u zaKr4I6K6?lauy3cq_yvhARQ#SLPDbg4r9qMCa8bbv~wtBP}h{4`Qc=2A?-?R_C0ImR$-yTY$h_hs*66+-;XV7 z4{1VG;~U>U=4jk+o%#ubBiUM|Z|xk>C}*zIR`e|pKe-vps;aT`DZ~?1u3KmXFLw`$ zKXa~qesb}qe?x|obCKOy&aldZI{g2rgIy@4x=-CXLExfFoOc@4p5ypy%4xBOMGvOizVMBDiI zX@!VI^CG*7Y(uZxrX`j~Eu*y>DXj5Kbiwcw($G~Q zP$WSJYfBkZ#kdaZ!?lzkO??oLtDM=?>^!HKz*1x6p64%-p0}?b z5B%Jn?1Wy&{zc%pD0t>DbsA#^yFG#ujPt-Vz<}xdtJh6+vD_aKV)c);j(^Baw z-&U28eohu^P^!aI>%TjZlR%>;fnt47p0qAnKe~H9O#a;V#-q5bUjUO zAceR4R|Re5WTs;Gc$bvf${GY;nW!y^-RH&r7-vmJY?y_9-cL&fmVZ*pPF$=2IK7imn`Dc}Ou- zU)n{h9j)#{v~Ml!$SPFN78mR?3oH(}`g6Kx+@twvts-<+b!WKvwejZ7!=*5*J1175 zxm1l-Bp^SxTgk;QtfLOr#YVWq8wR+bH$B_h?h?E)yIqlYWASsBVWGuLYKrN0XA>?V z9aY0O)NrRFhcH3D;+G>*tGUL2dw(et5CdGZt$=@t(mUvkm1f&5)=EsjJBtC?94)3d z8}0>O)J}|HdCs8aRzRQiK~i-WdZy#Fs_8ZQ22+dI*VjbN7vH#j+S2(P_&-RmT}Jd$ zVfn_otfG;R(tD-xtgVyYLme8D!Y@}{X=tQzxsFh(La0tU!=cM@mQigy|(|AOA(+0 zIE=KJYuetGESS%mFv4{t2AFItBA+X<2UIA#1+PV49QUxX2(>GrYbH0Rs7Rt8j644^;IRp2gpfdb8>1$RNt@E@!hHr_6vwPS?s| zH1ij>2I1NS@1%3n?~3Lyh*t29lakw`PcN*xy^I6kDX6w^^!Hb zr!aMZR21mAu4pNULd@X;ze#B$7Bc^F}oY?wS9@@+<@4N3Y&v z#JA7&oE|Mop3oof`05%fdvt}GtJq9tf!5^~GUy-8`#u?ZtRw_-M$JVA1X`m;SoAR7 z5wR!!6wZJ>%cs!3Y<`C_C#bOkBY&2bHcoHFAr@Wl^1gfI!&Bq;n6ao%I;?i@C!ZM1 z?T4Z^*w6ls)jNuuoj>YW*`PknX@XJQnq-Cx3#~l`8p}!I?L=f9#^h?gFl}53>uZ#rZY3*K^?fofM;?pgY*m)kQfSbXsv0cJR=uu^E$AxqKD( z$T2NZ?W4O>I^JT+?<1MwwCM!7i&tdG(@ zQjGc;lpc6%(qW8&Fk>AI=jhnVL0zrz`MlS5P=C4dn&0!lM$%kB9$ zCF)KdocK7-fDRT-5-k!RSGZGI=5*F{7F8Hi*}~qIYD(@yPNY-%t;D$W@xCxes@E%TuGMXamfrA|kvFS$=-SW_4ed9kNd0m>-Kl;q4yS_!tm34={whGO z6lAo@omm7gMYy@jTbC_4%=-9NlSOIOFUByvO9_2QPS;VDB=_)^`kB;w-E~-6Ztdyu zP6XYEyVCCE?vcYKOAm}LKzRB3*~XC3jN*W|i_o3A>l`D**-&^BWL-bBQ{Q{_U{yF+ zxf)D~E!D)BOV@83SvkcI9tA3TuGhQdFg)Z8_-TKK^!IOtsM-{OT&u{_X>qU5*_*DU zqZZ`8a?zPY$}sfKuVRtsSA~q+bD( z(9hPul`4T4zoeLv}4>$X^Y2S0SydEHT-&=5M)xH|q_|C9+sH7w;nbBA{3Tr!; zd7{+&$*lY=mF`$_sppVpi!` z43(&P|Dwym)>aOeNfoKcfjJLvq|olQqUCCs0z~hef;UjEoX4+Q8vXqw*3+I8wI%&x zv~nJusH}RNPqQ4wC^##z)VL0{G})CPw&t1NnUz_*UDjSi_RyC^XSr8i3FDI za|XEZ62jH>P(+A3c@T6qMpR8Z5J8Y#6DuYo^PAh#O!6ooml=Y{vZ7K$B}Br|H38DT zmDnWm1V%sl$8Kp;I!WYmY_b~+O%abGTv{2D_ppY)J-j5?n1KX7)U8VN)pIBY@K?O6 zn8${IvFZ{dQX@5z&d!=y#(QqlTI4<9>T5`odqdtHzblx<61=@Pv3y{y?6k8vgEDyI z_W<}+?fHJ|M@h^f)Ccu*T zcYxu)C5ZmLCjZBKI%3!*BKLAj>4X^g5%4Kg>2w^tMgH`kN|%eA4bw@YX|%*qCDpDgIzlRqh-#6CwXsh{GYhtDUfk(XoIN777)lK+_1%)B3p1tN zHPMe7)4Q2z?a{X$TCt2gv*$u*tpr7(tyYjx%P`8A+`Twn-gv(DZ$lDQqmvr{bHDX9 zk6$><;0>)b>ikzV`Ko(&oM#s+k7oD;#3Aj8>7+I7gqZBW{m6y50Zy*qpXCBK1s}4X z(Hgc_EHsTTdppVI%nuw}p6>=82AwNC4ln|6tbrJU$)Kr1oc1JS#BI@l9Wrx5-v~|B ztXV!5ni5;_rH(}K#furg*9Ok5!lsi1=l1a6Nb@m>J%RbnVn1GXu&S}OT&7}2S$1`HX+{7V;9$gNLR z7MRS+iRR8c`LW-uo#VP&850AwaNjOYOH*6#gP;?O=OnTjer9&fhAmH=&d9TWw z3ZAm6-Jm><8}9L-H2TVceTTWH@dKK8xW_(?N}4r(A^zAR{dmUcUgCfu)=jVcnWQx(YjTER46_`X;{4w!@1 zxp#>^039eX?pjfvw8aJ5G0UJZzU1kFjn1nd` z&jGXMh>L|jSkyOpN~J8}f<*>$1#`E<2|@nqPCB;dtGV;FXBzd_6=1tXivZ$>)%)H$!Sqn0q6D5hIiHzFv$JK=!oT!?|QkD_#%c4Vi-)Tt7Q ziA6ZHZo)c4#M}5rfY1RVXz2S36Kk;~W)-7n^e?YzCQsUgsb2j{NSDO5;wUY&sSy(O zKAJS~Spg@|!2?pd9uW{2RGdGwo#uE=yUyxnxw+na@Ob2-@xp77Ff|QBR|spi;+5OE z{{gUWeX{TVr;?yUpUZT1W9Zda(wUp^S=l*ifS{2L~9GNAh5j$k5Nm5X0wRS zZ?0cQ&+L*@yL2De{9xQ-l^Wo!PuVNkM;BeYg9qnM+O{0>eTi`+wVGzf9UU&M+h^4r zGEDNfv50Ok3!W3?|1;<&x<9yGkiM){I@l}D3BR!~{D9Zwovr?&Vxj#S=XEyp75xYD zqfq;?JtQMG3I&koK&zHYKU9aYN8U3s;aZ0{Y zN3lO~U8*zb4W62oW_ZfEtCPvSUo;!BHkU>ClkCn-FqW@sTNV=EQDWvKYrEfBSh}dn z6LK(VkoNFvY`B{4b3)m>PKyB%Xf{-C6rM4F9UFw_ZbM_xUyvltGp_Afnnf*jSDa?6 zqp7Ca3Kq89kt?dt!w6rOoWk}WVnkopV`j4}wlZI0Lshf7_e(YX-@0%$hw64p&8H#d z5TyyXs|H6nm4>CCwSAc5hr5w?z*x-YP9&TV072IoTYRjT51Vbg7C`kO&+zb3|BKEs zN4lQDxQ`;UV39|!Et(3OZoQ_>37&ypOyK!I@pJv3s3HQ)N&p^>X-+n3ZfZ{N$K+b% zo-Fryxp2Ff*29p14bFi6J5@`*KE%~jt7_3jSS{z(5qooV6*V?#7Vb)-GIbKuma%Ws zk|~3VS2GK7XL>bJNEE%mAS240-L0hMgENeo*`Y8gx~#+tOK(;AcWji~myX#}%q-AP zSq{E!igz?%_9GNed8$2(phn!}Bkj+V*jMe9R8ZU))!>bmi_GLrLK;S^+#%(8pl32V%P)Li3 zZMF`z2*iPTp6)G2>7s{NPl`pprC+1Q_NCj>1x$M3TaEJoxO*>sEB%6NJ6fd6Apx5;&uJH!994XwlK-|UjC9q749nB56 zzmv8FYxm=>TT!4&d*vjlc!7&`qg=z z3hv&YBZ4vNPKYziv@BieAn(p$iglDu`&1n}wPeL4ypmcJZ`&Lvd`=#wK2wnH$?JLS zYPo5OJ+9o^Mg5)?7SbpJEvcY;D_+)S2p{z2*x0f3*$^JM7QGFKNtJoR-U8S3b^atx z+ljZmjN7^v#kyaJ!y&HD+T+6XyLzyusp?GQ<$D&xbsR}*WXx{wZ*BM(+$`t5F;EFP zc546x;F+UwRZf|G*(-8~lqT4Xxo)3Ki@q%3p4zzgr1bl1jv+#kRWHk)N4!V|jirfT z!K>N{Zr;0EYHuRCk3puJy{)xjQ?KhAnwf*m?AnfM)*?NWoh(eft%?MkHmIG zf_?4agfqaOu>vOx=s4kDFG-Go+fuLLZVCAgwb|{|n6|#l*#>mxxlTL!JDjTLxk3-K zYgpB;f9bO(-GvIj5jo-Rht!3?IU^quxm@&(6*#RkFxa;+XajgS0o8xq-2R=g{U6lv z#JQJ%1*RqeFzIFHWMz=HTjo&~JdE_^DG) z-haS+6SzD6s{p^E)gA}x1*!;f!?OP?!|wl!b$az_hlk~@mn`fbJ&-HtXsNK(~T?nk~S*iolj&Lr7?SLMvC1c-tFHtV8u=Y#lP zAeWQeeey`r{I*n-Mq<$vDtq-gZTuKT``{b5*xw%c4u{u%K~GR z9~p%qEmfTUf4De4zxY;jYAzRhGa;ix%a66~N^?inC@es<(rjCit~0{m%A{k?8YA2d z@_cnb6HX|go33u>3lP5z6S0$b4lPlqu zJ~V@gzx$|o`^@ZLXcXFsE&N(gqzx`U80oZZ1v)IabB=k{L+2p!QryjXwa+-2R_~@9 zd8OhQax)Dfb_l)B#T$eSIX8dXhq@mI#3V%gzftv#fRy$I8WKBeD*72GU1Tym-rjV^ ztkq8adqUkdvc7`grMhOhl6MprN#@ZZ)=`^wVduwlTl5anA23AFII-TFswu`0_Dxxt zN%nE45|Iow*))A^2ssiYBodKocx#1wjbVuEv!cKbp+Y!bO|8(b$6ToBi5D~%C>0m!0?lNJvxMH4S@JPa3em2qN*HBw2}vrswl zCz+;Mwx~v!=BH?_GX{)fNB<(=|8{OKr(yZskP$1nOdM+U1;o<*p6zaPvPrBX{gpTG z9dpUw^H(UQjQWeUa>l$0f70kGpy>}fRo`3?u?Nxn8dx;njuKLmT1~TK zWO?G~siNWR4Niqy@!78N71v%%Ue^9>0U*5LId{?75J*$Rip4!uXjAi*Ikn@Z*CTGd z3rp?Hd|F~K@J~?sJZR|$hWHFXdQ5E(QN0x{$X*S@Ij^~CT2uRuZXB9?g}I3Kf!<6E z?fuA1(&uVr0mV>7jzu(fD6MQHoug|Sz%`Mge9mg1HBYzk$oG*0_k-or1$@fv3`R*v zN`mI#VSRC^ZISjnV93eCldy33z+;B_z z8Jv}L|rV9s7}aNdFtT=+7VhIWs|2Ig}S5)s$|Or*Cks0eg0HL zafB?@YxHe>D86a|gj6Kk?aI~TYRQ2ShH&|*=nJtHcC3V{%T(TpM;NYD%;p~y8Iz?Qd! z4X0-Aue5Ods^JqNMa5`hq8V3pQ-q3$@JYFLlzXEnA+U-H0JWEYrJ$o*&2rOpPt%0J zEhWsc*wZ{$f;4Xx-Pf;gt)eYs%gLfCj;U&w12>hLvU8wRsTnxf z+yBOqB;INew>p2!r5-+V<)>;Ea>Oo8+-YaelhZJqW%I=uHSgJq0xU|y-$NIsMO!) z$axf^9jz!kb*e?)O^p>)Zo%}GQp{YzMWgI2#NdOs;_k$GxdhB6<~U5NHmwDs%n8JY zc3}{y;u4%%D|#fN``XOBX|h(hao_S>t8x0^l`jpqt_;+niWT`H&hFWWWDi9*?i<`Z zx}%V_E$|G-tU0hnF)xJ&&tuSFMs|f`{pl7t)Z|a zM%R^DJ|lZ)LAjRa^qG$e2NCD>J3iqj3RJ5bP?QyoL#u7>XE%wh&G9_Ut#T2V&zacv zkH$$AZq=JN)sGT{>dQ$P-4-UY^GkNq1TJ0Ad6yRL&yCA_E0VRnmNo|)k6Y`H6>_36 z?xX=A3}qAY?u<8>82F~5#(c@Kj0tqF%BoynA|Jca)^tS2K}GALoi2f3EaPIy@Eaow zno^X)6vMvYyU=~V$aCqpCU<4U7O}Z5@A+R@f?91M)(n@}VN26Ns}D$yizes+@>=?6 zq9b50>qlB^?arlzuciG&iqY^TY(I;;sg)>)0Zmzp(m3=Y*S>3s=yom}p2aLg94*IH z?YS9jTu-;Zdi(rnWz_7w^gajbkj!a`R#KZ9i`k#Pw2Qtte|-(y_rR4aCbpI0)6Ne6 z+U`6A+)`m9*YR;08IQ@NGeXeMRN`@J@;N~bW8T*=ibGS+#i3Go2ksHVO5&w`IMP}| zXW(;-&S1Vb3HxIMZqG)qQdgFJz-Y2I-sZQ9g+T`&xNt)Q$=B^q^86f8kH8)JXQUnRAMwps8 z2in$nN4oAGdXpzmJBcsJK0QG1wfA2h%86~(mE?P6EUEkd5m8Ksqm6${d z*I>NyU4Wk_;XZ+wbGH{5!PV8;lzInZozu8OSF~GowIw z;}!+eN6!5xuZ=uR+eCM*j;&{h>i!^u#we`vt0NW;;_xec$E;lr)6|Sagn6K zY>6Mo`1a{aufrWm(CJaGIQ`6ut$~$?T#d3{=6Dy(pw@uNso$SWT;#8U|X%$k_%k?EMmndtXi>a-O*pMt7-uhg1F|?tG@)xjbx>5`oeiHUhBIr z-?{T1Fl09zeugAE*-X_|^Fi7>V9?en$t(m*qoKVTb>jF&(quLPZ+?B z@u{xmJ#|>K9%v9-u4zK|I4G0UHSPnQ<}m{nevN;F41*yRr8K|SdDiS#gxAF*EHbNPQxRK^I}Cy z7=Zj;%Gv~rTPV_RE0T@x<#q+#p8~A>RU$5pm4VOj4(ztgNl*BWi^&DW)iGS{z+CPT z_xHAYN?q>ZUjsO>_5~o*hg_MOGV=#^VYiEtfA?va&?Xs3H@ND)rsW@_8>NEN3&v>O zF~(B$wuaZ%a6?UfqV5}hv>35w?lV2bAyVQ=8-$$b?c*)R5=29zp)km;&y47fn%unI zPtZttWy$qMR<^jRYIlyDi4cot8#^0}nd1;CDXX-#h9~jU2sCJwg=6(Lb{o z-D|jaE8|KIbWhVlli4RfP^4g1*w?ed*>`Sg*kx0iz9r2s8*~55SLwG2DeIt0O-vBW z*nKOk?<)ZH4^%K7+{~SA?q|j)*HVVDn(M!(UMHy!0jQs~es-(J%1?eXvC>}WH!jgS zG1CLGc5H&`c>8lMm3(ZBUdW=*snnlIRcaca98oa|-{!4rGEP}eVjzuvlt(E($J;z2 zeHI8rP@smas1c6PZk@)CT%E>vt@me|nr2b620*BZsr4O|o}&ZOV4C^9r(9IO*cxXO zQ1kLnJ|Gz|QW1HeFysU29_B{+36l|7)r0o}4UNA)(zaQw8ZX%o?lF<;VzsW`;uNtX zt19TFh#K5bRwPgBkKFxP@tEI*T%M$P%}F4cw_R@U!|D=a!wEDq=6&$#i&H<=3!JRx zw2!Sm$uV{kfmqr0AX-d4%s%k}N_6F&%~HpXSGNOmP+Yu2Uv6ZvdbAKn5z%N#YhtOF z7X`b|GX>^%jAj|M-Hs@X%sM+$NV#dAMF}0t6*=rMs#Y;@V+MwExUoMnmEsD}CCMvs zp1rNDhZpZ%_{A=$+$ikgewz$_!L6ALn_&Aj2{gmtgoA^&Uyu# zR)Pxe??cGrj7&Q_TTJYD06D zMjKF4wdNokZN8+O%c!)*t%Btj~(n82hL{I$4ESQiADJ zP_$DuuA)=FMJaNMz1{6UjF%ak`m3)S^V;10Y^wezI4bl=|qrORnxwMji2lbv^(ye zaE3~u$sdaDXTC+pH86d6K{>>izMez-BcM#fa(4GG0t#%o*(lyR_0;3ydLQoyoi9Q5 z!NP(FL3~}G)?`Z(ODwv0>Qd(CM=Fro)^BY_kDVR4tBLD4GSrfp-T#?jba1qddwQouuTw)vU4+@Cvv>#vraq%hG(z;b&djnzE=bbBo zZhlp;hT7m9#ETGNfulZQ)?SG=Z$LJQu#y^~)I~1$id~nmYX&4AT4iG|5VFhwo$wYm zS!b@+n?lU5XigXfo#xVdwjpDC6#cE3TIe&44S$xs3QbLKckJzhvix1xX&@fm)-fus ziB(<+v#(lkSi?d`vC8aH<`tzO(8gMV>lOx(;gN_xdbcVj-7k>JDQ`3V)ax$O&{ zbMi}k=h=U^_GA@;Ws3vy!nga*+S|*Sgnc>p3*a`!=c4n-^$o24{jl)rH3I($(Abya z_z7p|jQ)0rp90#TIWR0x4&Nq#s2KeHSgCOzwpojp1^)^b)-eG8+tL5|MgMXo|9+|d z&!zis@~OKi`kzjREjv@~T793V%5>ob;{FEwBlwTQgntM9Io#yyx1^lHb6~~I(S4O0 zani;OX?<%y5jNDni;c_KW0%i~K848CO4nU~^8!uj$>v4}sMIX%kQb?*GlUPa2`ETy z*SHqO%lSJLsx0&x6Rm%Gi<{YNeA6-Ky^eLEGWZ9sPqg{iiZ0;xWV>cLat8=M84ar$ zsptmy{jJtrnRRd>}|)%|z(%ij~T@S2?JofX|a!$>2XYVX8Q&=23%1!Lsn23A^s_$T~2S;foig-xs z)RO97>UN6TJYFW)9FKe9=#k?&FHqqa{(5}uR>U~Dd*`6z?Gs5m&UBfiJYpOC@IXBF z2PgqI7w4Zl!P8D><^qx?>9fbYA(&sJ)#ofFOim&+_xJR?rIUX$>gn9fi+#1eJA!bj21N zNAR^%Uknepl?o<{d-*?d%jiiSSKXM&;2fQas@c?#*G5$@dcVYRb`P_NWfY?28~|7X zks31`3pia7lc5+tRyeO{)df&@Ut0gxU|e9};MbpFQH* z5tM-JbC^3C_Yn*hN%aCm;DWseoI8xJH8jXN^kg$H@xY2kON%0fX;w3K#V4d=G9 z5VeD5r0fC36YspQ2LAxHtUsn}k4gjzKEpUMfWy>fugRE=TU_pRi2=bbmWTJAS&xI5 za9aLCYg5Mkh4W2L(Rr){YhY}eufzQ$5EBC|&I9;(Z|bq2P?mr)w|j{4R$fu%LDU%J z2dEwznyRxheZOm`_}%#2>&s%$Y6B6ohLsKgK9%~NzbEw<9P`iF3g}O=rGF*L%>S1- zW;yW6;V%GiuJ;2}05Sh7oC^9gf$`>F(A0lSDOAW=E9)5G*uRuO28`3H^%?a@uaDll z!$my5JSpX;xMofYI_~H`xns+CAlSx zoMBh>f6Hay%!GAnz>~u?ovP+3a4&Lo(FSHkt06TcWck+<{ws$ikFQy0Pn+}FE>fWs znkssPuo#*O8T{k19Qg~6hk{DGj?5t8?$nryBUwp@QsQAv8lyURId4b@a3^CU@22Us zf_4)IE8NRm*$hN_nH0KDbc=YWr*a~}?iJHop~0mw+{YrO&s8C+l{*O^_n}|I`Sv(1 zg`(l1@RE_;q0Gx%cf6&gUD1x_QL}y3lr^GqP25-}PdhcaPQgIYON@*AlEc^A+UXl7_WiF7HL}N^bn_-DIBa{m$r!S(Sbye$ImkI+u_`%g`W1vM`1=TlRe7(4bk%T zgOxs}T}z1Nf*h{g#N<5d32Cs*y$sy+>A>(F1O9CbM+{SrC^5D(MzdI{8f*Ob=*Eqg z`HD(_O9Uj#bioBHiBn$6PoQREiW6-tk(joAyMWy1iu8=7z0>itIGbnBwD5lE$~k^a zXW9@f%!UHdb>{-}Ew-F}AX!KdhY!V`+fT+rabq>Q{o#P@zZt2(yHX1+~@Z=UiFuqupoZP zC%040v zDz_(Bxxr2%Na?w(=mXgENo!9R1;uUW4`OkT*p>S7WAph5{#u$0pF6_@I1=-5n#aO+ zbt(G>HbFQ_TVvNM<+L%OulG}1Z)d-q&dr2Qg>Sp^3gsokooX+NcU4)iMP~I|ChY1# zd6*NrXF7E3Ojj1JC098Tn<_B!jv{*8CI`A)^Z5PA8W`;yO>WxWcV(;PZLX0JQUfr07!K?hF5u@c=t7tbh}FLfYHjL^p$W` zW5|r3O7o$336LQ#r?MV%VXW9o2 znE=s)t`yCP>Q}?pF*pw^uYSKW-%%Ct zH1TfUU96s^IYNh2=o6!jbm&+^KBLS4DCek7P+m!Dpbk7jEMu;JQ&SM`Rf0RC+#}I( zy1}ZY>c5N_IIcbMS(;iCU!j>XZ3^d60+i0<+lDZN+q;IX;S&E`kp$P{%5}Q+@2on& zgdEG0rC!oi%(jEq25x6Jdcd=%intpiMH0v zwwOuS%6dnx;W9o_^Wh6;_7to~!nnn(pAXt+6);6R7D~pk8aRO-P8!aWX=Y9{8g#i9 zaCcHG!ei}q-G{z^gdPnOm6LX z2UjZhw>zTD47a;md&Y_g45l!{Fve_&!r#-lJ!pJ96wG9vGv&_>SKfL<(VaR;ia51^ zVx-NFi|*+rB69cKIs|sI)F$RBGXCf}{b%a$cRRkOgo1+#6GLkqOTQ_*KvbbG{V}^yhD<=t|5!-jn~}~2w@Iq8|QXz z)cx}K`4eclBSq7z;1Q+}oi7pAxh-js8t?6Y`Iag=Sc>F7L$oa+2H5sym>!a|?zxmH zq8CJSQVG{K0DI;#cFK0-T0(5$E=B|2QL}lCwA-Zhm{)744(k@7H9Qkc4+Hbpqm`E) zIZYqKEO~cgmpd2QwTqy|4`97$f#mKdc0&C#EPsXXtFiug%yEN;y5?bJ=wA7wiSmhJ zdDV_ub(fgS(5FLV1+!kG77J1H_ae{y*%E8>&y+k+9w0~y*Z}{pu7AEH#((?81k_e>qIClkhD3k6 zBR34>c`u=aWZq|rzKP8gfwOk9BQ92AX9RHGANiV0ESE$w==ogk5vrf6{1L8{>1U&K z>6@2%6O3i=5mZaDUp4B^EH_E+fvRWmVxAP@x`GN1cn5!bldgD~1)QBGuq6FK3 zR~+~p1TT9!pwU$ySvdfQCsqG_1ou9C2y4#&O(iJj6zXPzDNLL9l>KOtqx_kmYk6Vw z&L-lpLIKia#n-}V+#T!PfL{26ZSXNIg@@C>5gc~?i(sivF3N7EZcq8U(wl1@aCMh= zT3cUTIL{6`qRC0>$+c;o7z0eDBYHN1OWfAss2%%O1L515A~X5m7FBon(Rv;Y>f9Z& zmM$hJYO4O=;)Vl0g-RZa5>2PuJdGR`=b=5!x)-M&mTFm8f=2UbdW4NJkX<=*i9{zc zA1x7j;97n%L=_EqPa01ch5BumJFoA*zjwPQS^~81*Cb))mk0g~4fo#eXc1>PpafRy zkA7bUTM}y5cuT^aFxUGYUUW3@RC^`+u+2H;^jED1LK1OfCaz$8+b}UkO!h&RSN%t? zujD1A?=<;eTi%*LCUF75Lk=cyMV+sLH8WE)G4>2f8}NfnBcspt%WB$Jl!}iMn(;$b zE7h|*fyorV?!o;EUm{^gH&%EP@o|-gx0x`@OGf*Yq64;WqrmtzQt|5W+yII%LTO<) z5M5G*ccSC_xY}7Eco^Kk50VaRd?NSR)xF)J1Q+d-sgjk>1qcEfyZBTpM1R&f5+q~U z^vN~D;J#tJk4VW2QDg?~%CGU!o!lfN>5`87-C`Cl0hZ|?**OB*dvO3hu)B(=8hYZX z3(>7+dWHbC92V!R)tGw~@DZkD|9kV#N~-ZtjGGy$2Ko(}L9Yg;3Y2lM5?@I@cw>gYlHMVEpBBYghvWaS@a`fmt^0~p6kGAOV}L!< zWTC}VZ~INd?p8Rs=V4!ju%iRhyaOdfxY)Rxhb>};%u=V#HA=oWQZ6VCCo0f#QpltpUFsV z*fCyRd1uuYq&t}%9mY}JQ#qgGFuYxv-gz|lX4Bi4e)W?kvVk={GDaRrttQ4+!pnEg z7ahhTk>rW!z16Zi*+~4=PNZpB0qS{^B*h*ZJfHSu0s1o;eH1e;JvFcd;!qQsN zSCz64^n@hbSH2RYji&?muEi)6Ah(&!#F#o-tc*`3eZ{^@51O%au`?Bt{?IF{Rdeq!GEGmU zQlOpNo%=%hwG=2IWbiA9;|hmIG0hqPsa~>Xb{k31RmWgfNJQi2x@=*BJhws&b70NW zhzXg5r3!c+SIb&(P3b53c&Ah4yE|RWLdxS_xEcm#~lvsM4kSI^;LOtWqL-Xyx8Zw&t3EbXe$VnmnNHl+ImS+h~v^zBR~5Z8Hn?45S*n zFJt4e^S^z$es#iBs8jasSajyot~So3ub?Z?^Z!BtFopg3$YQk^BZbLa9%EhY5|}By{(WOymKMx}Il3O^`^ydaim0l||d%DBL%s z0A-O4F;u>kGLkCh2IA)Y>q>)i&toTVUhATUHYp!XzdY7LlIDs(k(g_16Qpu2-_AWJ zxuv$03Lgc0Z*cKvV)RI)NEh8W>9@&llb50b#<*^fz3cIr^)>0ichf1i@r`et)FHmI zdFs}7))pNf>Qs*LDV})b_?6$l^N?@5xIVXsfK2k$it-a6woh!-90Xcdxf|f+`W?XL zbGEC19kRAAYmgCx1;`}?VrE17GAC@NIrGvKIw64S})sPSIJ&LF?QBu$q5- z^SO|-Kk+rfPy-$C?UAB?wf?Ig{-2G9@+$9wrveuD$CBbBE0689RRJ}bmJPTl)qvn4 zLqQ$=^Bk+n6cMB&AX24>(mN{B#Rv#U3Gt(dAqGTxjr1l}ih_Uw(jihqk93qK z1c)Tm&`ThphJN|ZJ@>TdoZmg?K6lSv^T*7dJ?ovlpS9k#)|~%2p9Neq(9zccP*6|+ zUR)f2a~wbmKt)OUcfV-V7oFxZ4GlFl4IM4*rOOO-3=H&i^z@8ZS*|f&Wxh&Je~tYb z^L17>HZ}$(4o-GfP8L=+*1spApt^X5n&t`(%@tNgdPdg&aXbG3V7?4!2MkhC+yYQC zQ&2HeoOc5F0RRe`3vK^a_@5gE<%N!yXfI!(qrVtXdksKIK}AJLP4&0d7o!6&?gOZq zX;=jAJ-Bq;_%GU9ZmcrFNnbAuKCEnGGZ`id$=baQxkAUz!O6ufEFvm)TU<_FK~YIr zMeC8aj;@}*f$1|dbBpJeR`w2#FP&aNoZUS^O?(H9t z50C!FMFF7t-?07#*?+*re1VISnwpB5_HSGil-?IY#Y{~jaPJb!17q61+^*k}3BJtw zFzIV$+Z91s6C#`4+hIC(A-OqW(%;bj3E6)SSjhhqvVQ^gueh)P1}ch+#iL>dXaY_p z@DljN;74UXSx6oIo6 zksq{b5{$st3%)^4Ke#j83)c^cHX3OXudu)SLPKZ!i(U|%cn;V&2axEXIoxZsZ5CFS zzT){Q*12s9Uzg`wTTZWyL@f+rM^FznrNeJxz%bxnrX{nSu9;(w$lGUG9pjMIolEjI1hoC9L3%y&SxD07See*)OL@%uR- z%--nY6w(R3zN*rK$=P?^m=Shh(XZ0J^x7brZ*+ahg*se*$GdYT_)HR`Ap^0BPnfm; z%k>MiQF*vFkX>Db-e)%|8%JQ)mm9=XrW(J=ot}6RR{Z)f9OsoDf^s5gwVlbK=YKa- zLFSh`#u+W=K zCHb~?tT)>!J^-W>?Bx{sh}M2T=rpH7gY74={ZviT@O>YC31V9W_ULUxr~oT;+sbQQj}a}J2(w@)}8 zIS0%vp98oPMRUI#-+)i2pPd6V$;10f=YSUJ(=#~f%axTPjUN7kZ|4Bi(3xCdyylkS zIRKt>@`}>$znTn?9TU3Yb`J0ZAD^59=5_zfpY5U!4$lGI@BY8OMp|=B`qTq>%J6KD zX8Gts!;0v0z}J}UcXVR8|0B71@r9nD_J%cg@0pHr;a%rkJ2nTTj%tQCm#xJ9tI7=V3*Q;TppNEx%wmI z_2wm9uN22VA?&uCDu7it8>MumJw+PN;JI~E(~%Rb7M($tP79meD|})*y*2nTQfjVH zw^@QA7`>~TJ+isky-$nWCM+VWf*Bi5kEvcCD9R+3(C0aMl@IlROu7Qh)dWc?0eaQd zWdAZ~U*JAS1zfrI)R*t+42)9r*Nq&3Hpi)*G=`6*s-jbh2k!7~Y2r?`adU%(N9zIG zIRGiGK2*7aNL6zu@!-K7>P%h6*5offxhpGJjgrO)1l09ahEiiwGJS*D7vziY+T6Y| zjxp|hBO_eT*woC6@l4mr=^cERNwhH_8V|IpAJ1zYmQrB?$l}B z`1CfuU0X#SFkG`f}!t2bmc2HEAwRUni(f|&QgHIP~GKkH*pMUoAT^k=KTvrKmGla_e5c64lkf{QmJMMvSUU>eJoWT9fV);v6; zBEiZ5Tbr*?hVedfo@~dwdZBI7^_8hn*tp&W)J%}rC|pV}sDter2Kqsltj#kMpl7@s z-sswc>S3=|dUE+}PBhE3_M9~53g7MI{@V>k9Ht?}A3UnwQ4@8`kZ!-(BXg4gFQUV= zMN%N#b9pTx4;PrJ+mcSOxYE?Wt@s%&pvr4lwhd z^~UZbUpL{U^10}_Mv%l4f8{)nde6zE$Q0a0#C>ly1Kj24m_ygLtxM3ShQv#7GVnxO zeAy=Jg+ELwx8&_Gpe{H@V}vK`9H5N-<&`88(AdIp!iHE~pT>4f_Z`guF~f&BFk>($ z1YW}w2h-s8SuzB&cg-_#tcC&=k7{cd!+RoYqLv%(4GCSho`{}%Wk0>eyC75ZP~J{N z`|TmNFiH)G2Q&BxcJhgl8w#1Ou1+fk3y>5e_lz{ori=*=G=52r7_1?Fye$IzrhrxE#0PgD{2LP9{n5*t=VH1#1!E zS#J2aHrvn;#nKKl1tRP38+K|9R`))equ0Lv#lEJ_Y(Ey%1YTg$_Fml~tmmPBW|gzG z`IzDtkK=@l31;U2rb8N5!Hf>g!`hrY)CK z1ww?Sg{tnFX;TR$`v9))b(3}H;T<_q+{k^4@DunPoW(iY+HhY=(6X*E^F{a41W($J z-k;sdY=S9s>-V2*YU~RLRVO;OAUSB zJk#Pz`ozhe8etak#w|dKC}B=q?u@%#)_l26r8^7nPq3ZGOMr0v$W?SpC(6Fp-9ulI zo-2Bu`S$z9N&)v>jXV;6yOnONWPlVLAIIL;dC)6VGwdRN*}kRTw2ASCaOn3#>qMq0 zjfk4fT7pcUdF9BaJdd8d>S7W>@>`ZUH2gi4K-`r+n#rapTAm2MF)6EbYt--w!8Hr( zZC*1WRu8w9Khzv^_Sx!?W*}#tanKw@i4a>W=Ro2{Dz7}5@ltlYmWVsk4j#wUA&_qo z6O?@)|FlQ;zmH-IW!{uC))_ViX%3zPiVj>r7YiE_Bld;zAIRl@?4e0OMjyoEoaf|l zl2fOJgzMZEQ)Ua#llpsd5#zsxQRo7?lINf9*d<v&^pApl4c?JU;pJO^;#w2N012)_6%D&xo>2MR-{EqEru4M*wMi#u9E&mXjR zhzCPOmZNIIy~;hMIVR6Wr>QW_7R0Sim7r38x02^pO;f9Ht+0?jPUb^@X|5xF6}xBm zB-zY5oh8=SZX-N}8sRAx3oTN)`Yc;gCn$Op2BYn@aj`L}{%?%qzhoFvguSVVwwnGd4= zGOK9GpI%KL_T9Jmu3kfOk!V#kDQlo+PSoqYIc{cu8=Yd`WaXEEP7a$Ft%3*RZSOUV z)bfV~UCOi_JF)aGomw>x4AmjFB0QborMB|TPF}~}`uwg!HSq%XH@1mi)19ozIqpP` z*-N2i0lH(7FG-Kgz5D|EF&xIYHqYYTl8=y&;En=m=WEin;_0~1X8tUbY|3sx1gPqA^S%* zNDMZ-YjOnFKB8u@B^UoZB15Ys+P*3I%{{bnaYJqH2UIS`RWZ;Xg1XbZiw?8Pt`MI_ z0Na8zRS_8)96sodAZfA`iOQ6u*$L9>ks*UYsFsZ7_H4<($X_dg6@!1$onbI=c6g$ExepH{lClc?Ncrx)LSq$eirTRwa3fuTIsas80iA{aY zmV=GDCT)3dgs*1H>Vfpo&kNh9_t%9p`P-rVXF~mN=x4~zsmVD2^XMG#y9;=qDQvswV>IE!&X~~4`fye93u?F&b$#XCSZVRS>7c8@EKgr81w$PCsCn2Q&)|8k4L6iHvCh;YBt= z*B)H~a3uAbaov3Dmju46`9Ef;BPa;eM;4pAIdE&y$CfAF=r$#zTPC5=7l<>u;WV&0G5w16kIFT)yoahps zoByE=y5Of|Q7pFPb&u(swsG0K<^zzt_`#Hh%`5XYz)%*QWG2*ts ztAf));nopU-_$u^VH`7YXuH&)jMxXEb`fXVYa1w@K>h#b+SfrBr)YaL)XC9!O}bZi z$@ra)N@orYX%35wpd3fx4&jL68|*RJ9(Q7Ec_6|(Z#RefwJPqBw-De}Kk8O7@&~4l zXb0kj5h&DW%=!XmalYety^|fU%n;1*hN&9InsS=A74Wmxz~JsOeEi@XFk+iYSn6AF zagk^O$Ds-@sIs@VTMkXLR*?^K_8@p~z-pf0SMcrYge?eIY1*Hr$DCDHL?_ev89@7` zVz9QD_K6FV$Hre*N|H=Lo)<3h%lF(EF~C0y<-enI4}8yx;p@5Z6}!TJq7ZaPaWT$* zfdikDjaa>z<&1=z%UNSMuNkN${_0S>do#4RLZS_R#h!?aE+p|4;{(0Bt#+_*r;fmi z+Nw-z*c?_YuP%hMdx_5S7Y8hg{@RzT`=te6p~5G167KZ2UED^(-xIl56eQVx?a>)1 z(S8-5jtI|dJVSjWzhW|TLhc>mmhHOOx?bh5dt|}!Pl{(t{Tc0eb)QrpJEU7Q2Bg)E zP)MgeG7>XSr={)JzLyweA#|4u%-pK73cu>G@EsyK>d0P}E*@NN6*CXmHCGzhvxXjpw_K`-4c#T+E~YMLdJxSsEPx8D^*3D8T zWhyP55_{L`jl-#lSD&bSu!+wk9qWvqI9-j((5Pkq?lAWtfH6p|wU7%WQ$IJY24OR;ltx^t*lkAktyg1VZ~<#fZei7>sv zk*W^A?R@`d0Rx-Ypp+`9IMWk=(u6+)$J_od^Q)vxL2FU0Bfp9xkS+3Tx zldw4J0v1i8FZvd1CV{KEHCtGep$yIa`Ddb4fRrK6qM2=8~=NYot**o^HLI}4> zw+q5ae9(*mal@HiE@>ib>|vh!XDW+F$$OW!23*+TAZ!`(Lq$76Q*8BhGswNdhJB|i3D z8eF3uI6ZmV5!afT+UWtPtW1}jv88(38%tgTrfC6i7V9;m0qOZ0wgO~W9vP)YER3o} z5zHrC^Q^R8kncj~n!A%dL+-X(vkZvQhErFIr|r%hoi*;S30KTuzW7-@R;~yoI8E8C2iyHv4!DsBcvIcVzzV-_f6^ z{~8yr{F6mN@DB%FCl_?gN0j3sCxLkDEEa1XZ9~hiBhAq#J#oVHeMYYtH*B>`AX#hl-pnZo9g&KNsJ;aHW0ME&)wwI2Hps$hmXV zGa2x&JwNB-EH%^&@z1Jve|lPcQBfXIpgJ(3bq&H*9@%QH1`P$22*2WSbzdmNkg z$(v=!)!#{`k74-xuSS(*F1>|oZkDY~uMS9{9@cl1 z#u*AX6)r2OZHwRF5Uolpwq5_(pa}nrqFMIJKWxdJF$x&b52D{Wbn^yZ-ILPn&bh)p zDCql*{PNfK$TqQ205o3N#f5$H1RuE>8c#+@5fSauoPPqIqxY0+)SVe$&U7ARROI3P z;l zl95o1KYUx*_i@Nog62@~6szc8Jj-!{^!RiCdu+YKm&yx)CSFo_GPg zQxj4FL*#N14dKjVslnS}E+dw7im2aSBcw893yiehn%0cknkO<0z~{FZu&YS+O6NKR zN92~VlP-shT9HE-eIl-WL`TE)4@o*k&h^qOq)Jbeygx6!ULBp&sJui95*aJW z=B>9Nz8FO%T1@$Eq;^2nc9>8LlYLq{>d{mbMg&_uu4NQyn!83F4}1u4!(*6J_C9 z=BDHI;Y0n`<1h2A61p9>>|=K>!XRXq-xwl^`mXf~_Ogs%=qu)z^&bKHT0&djLqoL7 zoH*MQ=E%#$>E#ZNAfZS+Q}{O`As;_JZ(-#82dj0jThKRj!$O(=w(^2GB2+`r2Z&cs z?OF~yG0yYJ9h?S=L*qD}#%wC(aA5~{?$T1<;Onl1H8dvAzzz3~vzjcAxQdD%Jb;~n zi59aS&mxmnpVb(78<7-JVI{AQ!YfJ(Y%0joubnKvrn?d1Uh?BU0h{?~aEgl&OommbV{eue%pQl578S7r= z6KYZUyC(KUL7{y9cdk0@w0~0p#(spDrUTc26xo-r4TraY3&iadc_YkPGjR)(&uV9bHA_ zLNd>$ik~~b8G=D7y-}IBDxYCd_a=2{MPr7V$g4ygkT{SKwb?4*V~*>Su)O?<9Q`j{r%Akt*eLo9sn!Nj{VymrQok(;@; zDkFOfylUY#b-%xmfjTKUKeUYtUnjnR^LCK1zMmT-ZtxFtBwFbB+F3A5?Wwil=o#-t z`VSTnJO^ij@Cl|tOG`m74f}Wk$7Oq9>YZq7Tofu`PRA@oR>zwv=3q^1Vg|i)QHZ)Z zWqA&;3IYv%&_O~yiGp~=h+Xs4%@eBt-7+#1SRL}vwPr|(%kfIWOx2}J zjYBlrv%vQ=Z1U@X#ICYgv+YSZz_voqkcXA!wSDY4=# z7MIs|I_BD-v_7M|xCI^W_4eNJK3@1%2(y@S99bUBVG4k_5fAn?NA`>q#1_YXsYj$! zhc5WzV#h-!tWR?kp6{$QAe_nYS)41tN7Lwcc~;@E414zK4<=95O5ef&dugHfn>`Ko zAV${Qvhq{7^-OD4Xf6naAiH1>=yqJO{FWs1P-1N7K{iWuWkXBs<0fCH<}pX~^!Poh z92NHXD~7%Kl&l;4g!dNt!&(;F?Ka6Kbv?lWS{TG`8?m%Aho!s*%(!x7+ah%Ip6HD5 zF2u@O0(r}JYz!HAbTigue%6A}OM{H=D%4n}=rbnrPMfYRlDLSB%jwLh2=$bc+6Qk` zi|yPwcoT97ax!S?o!^vxb0JVyo6+6fx1jYHy6#a+@N_9v@{gfASgbxqkezq85dJ4k zL^3c6iTqD{OKIpmw?3I9T}B`>WaIfv<)0Q%>bpbF0v(pmjsR?EluDHFep<8~kd!D8q35C$Zw|oNIK(%saUpZt_qm1l&|95`nsO0YHrNu3|jsmDfoh;5^{Z_Rk@p1CoYJ@8)N_$xrCOp?jsLZ<;kistNcLSJ^Uu#^5jh+ z&#v((Q+f@f>2qroZNPmE!STYe<_Gi80hS$u4<@O*Ti>HAX7yOmz7Y!1Fg#qIRj)tZ zGRlh#*(=Prj$+IFJktN!R&Q=Bx?v%PHB=TG140$SqNK(8o*o+?O!X zGq=~B_2myQyHA;iwb(8W`dr?yJ~wUnvIDZ=Sqgo9F#p=7TGwG_!l&vRfpt7av6V!|hNIi~iaFm(~qX|f7q_Odi>f6Hfy|LV}K z8Fh?l6L_^@`^vG#V!HqmH`x&oH6r$EpG`~xRYerOh)Qa-TUsN_eCl}MOg}sWp+h8> zVo!*h`q0O;{fKF3WSAJG{-=j=O)sbx?IecfHA8Kg$4(#|F%>ndGv>N6FSSSSn2bQ| zI3p}!><_4`M0p&1CerO*#Kp#)^0a4wBlpx@pMJ01mXWk52d70Aa0#nR^z9Z3rCtg1XXi# zR}optW9ypG8!Yal(}(tqGX4FCj71@7)%&-eyV1Q)Nqlek7w(3|@U5{L1lHZGx}Ky^ zS-OhJ=H?h)J*euIDjUMlg~uo*aReu|bm%?kPz8MP3$tQ-&%HNTl?WTHfaTVt1rm0& zdGval+=C<1v=U{!-#)n{(Kp8{0%y@jv=k7m4EZ<4>v#Aw0~hyUgEP(ggR)!tAOjh~ z09>`}8@YD-#HMA_p)R2AP-$j62$ddj0tV@J@kx-AXNW0KTYfN&k1eC2zLB6w+A#a( z15ZJl!K8ZYaQ>Ikk4z&HD1j+k@&)p|UR(IBb}760POC<&PpDy2+I+{EovuAqtkUPi zsF)Gn9_3H@SlyrB*=ft_Pd^9o+d#04!NX25J=#?XMs>BJ&zfRx!>&ab`lssOZ;E0* ztC;Txf2u#sRKGA-An9iqkGPjhnEuh4q`Os_{f^sVCG5bI8#jum65VjD1c#BW!nBI5 zasAT$+KOSB=8UtZAoC!ktJl^}L2wC_-g|Z{inh~l^avTH2J_9eg_t;-v}Wxy%THdR zv~s=MJuKA>T*{5+O6t3J^~b4}jd>=~^`f{L_mTvv%Tig}HkA5dF?z?LCIZ6ox?0v+Bae{Sb3nwfgzs7=$~tac!*$(jYcbDYip3m#K^MjTeLC?! RFQ)uw1(yGFjrM%ve*rx+s6YS! diff --git a/lib/DFRobot_BMM350/src/DFRobot_BMM350.cpp b/lib/DFRobot_BMM350/src/DFRobot_BMM350.cpp deleted file mode 100644 index b29b225..0000000 --- a/lib/DFRobot_BMM350/src/DFRobot_BMM350.cpp +++ /dev/null @@ -1,483 +0,0 @@ - -/** - * @file DFRobot_BMM350.cpp - * @brief Define the infrastructure of the DFRobot_BMM350 class and the implementation of the underlying methods - * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - * @license The MIT License (MIT) - * @author [GDuang](yonglei.ren@dfrobot.com) - * @version V1.0.0 - * @date 2024-05-06 - * @url https://github.com/DFRobot/DFRobot_BMM350 - */ - -#include "DFRobot_BMM350.h" - -static struct bmm350_dev bmm350Sensor; -/*! Variable that holds the I2C device address selection */ -static uint8_t devAddr; -TwoWire *_pWire = NULL; -uint8_t bmm350I2CAddr = 0; - -void bmm350DelayUs(uint32_t period, void *intfPtr) -{ - UNUSED(intfPtr); - if (period > 1000) - { - delay(period / 1000); - } - else - { - delayMicroseconds(period); - } -} - -DFRobot_BMM350::DFRobot_BMM350(pBmm350ReadFptr_t bmm350ReadReg, pBmm350WriteFptr_t bmm350WriteReg, pBmm350DelayUsFptr_t bmm350DelayUs, eBmm350Interface_t interface) -{ - switch (interface) - { - case eBmm350InterfaceI2C: - devAddr = BMM350_I2C_ADSEL_SET_LOW; - bmm350Sensor.intfPtr = &devAddr; - break; - case eBmm350InterfaceI3C: - break; - } - bmm350Sensor.read = bmm350ReadReg; - bmm350Sensor.write = bmm350WriteReg; - bmm350Sensor.delayUs = bmm350DelayUs; -} - -DFRobot_BMM350::~DFRobot_BMM350() -{ -} - -bool DFRobot_BMM350::sensorInit(void) -{ - return bmm350Init(&bmm350Sensor) == 0; -} - -uint8_t DFRobot_BMM350::getChipID(void) -{ - return bmm350Sensor.chipId; -} - -void DFRobot_BMM350::softReset(void) -{ - bmm350SoftReset(&bmm350Sensor); - bmm350SetPowerMode(eBmm350SuspendMode, &bmm350Sensor); -} - -void DFRobot_BMM350::setOperationMode(enum eBmm350PowerModes_t powermode) -{ - bmm350SetPowerMode(powermode, &bmm350Sensor); -} - -String DFRobot_BMM350::getOperationMode(void) -{ - String result; - switch (bmm350Sensor.powerMode) - { - case eBmm350SuspendMode: - result = "bmm350 is suspend mode!"; - break; - case eBmm350NormalMode: - result = "bmm350 is normal mode!"; - break; - case eBmm350ForcedMode: - result = "bmm350 is forced mode!"; - break; - case eBmm350ForcedModeFast: - result = "bmm350 is forced_fast mode!"; - break; - default: - result = "error mode!"; - break; - } - return result; -} - -void DFRobot_BMM350::setPresetMode(uint8_t presetMode, enum eBmm350DataRates_t rate) -{ - switch (presetMode) - { - case BMM350_PRESETMODE_LOWPOWER: - bmm350SetOdrPerformance(rate, BMM350_NO_AVERAGING, &bmm350Sensor); - break; - case BMM350_PRESETMODE_REGULAR: - bmm350SetOdrPerformance(rate, BMM350_AVERAGING_2, &bmm350Sensor); - break; - case BMM350_PRESETMODE_ENHANCED: - bmm350SetOdrPerformance(rate, BMM350_AVERAGING_4, &bmm350Sensor); - break; - case BMM350_PRESETMODE_HIGHACCURACY: - bmm350SetOdrPerformance(rate, BMM350_AVERAGING_8, &bmm350Sensor); - break; - default: - break; - } -} -void DFRobot_BMM350::setRate(uint8_t rate) -{ - /* Variable to store the function result */ - int8_t rslt; - - uint8_t avgOdrReg = 0; - uint8_t avgReg = 0; - uint8_t regData = 0; - - switch(rate){ - case BMM350_DATA_RATE_1_5625HZ: - case BMM350_DATA_RATE_3_125HZ: - case BMM350_DATA_RATE_6_25HZ: - case BMM350_DATA_RATE_12_5HZ: - case BMM350_DATA_RATE_25HZ: - case BMM350_DATA_RATE_50HZ: - case BMM350_DATA_RATE_100HZ: - case BMM350_DATA_RATE_200HZ: - case BMM350_DATA_RATE_400HZ: - /* Get the configurations for ODR and performance */ - rslt = bmm350GetRegs(BMM350_REG_PMU_CMD_AGGR_SET, &avgOdrReg, 1, &bmm350Sensor); - if (rslt == BMM350_OK){ - /* Read the performance status */ - avgReg = BMM350_GET_BITS(avgOdrReg, BMM350_AVG); - } - /* ODR is an enum taking the generated constants from the register map */ - regData = ((uint8_t)rate & BMM350_ODR_MSK); - /* AVG / performance is an enum taking the generated constants from the register map */ - regData = BMM350_SET_BITS(regData, BMM350_AVG, (uint8_t)avgReg); - /* Set PMU command configurations for ODR and performance */ - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD_AGGR_SET, ®Data, 1, &bmm350Sensor); - if (rslt == BMM350_OK){ - /* Set PMU command configurations to update odr and average */ - regData = BMM350_PMU_CMD_UPD_OAE; - /* Set PMU command configuration */ - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, ®Data, 1, &bmm350Sensor); - if (rslt == BMM350_OK){ - rslt = bmm350DelayUs(BMM350_UPD_OAE_DELAY, &bmm350Sensor); - } - } - break; - default: - break; - } -} - -float DFRobot_BMM350::getRate(void) -{ - /* Variable to store the function result */ - int8_t rslt; - - uint8_t avgOdrReg = 0; - uint8_t odrReg = 0; - float result = 0; - - /* Get the configurations for ODR and performance */ - rslt = bmm350GetRegs(BMM350_REG_PMU_CMD_AGGR_SET, &avgOdrReg, 1, &bmm350Sensor); - if (rslt == BMM350_OK) - { - /* Read the performance status */ - odrReg = BMM350_GET_BITS(avgOdrReg, BMM350_ODR); - } - switch (odrReg) - { - case BMM350_DATA_RATE_1_5625HZ: - result = 1.5625; - break; - case BMM350_DATA_RATE_3_125HZ: - result = 3.125; - break; - case BMM350_DATA_RATE_6_25HZ: - result = 6.25; - break; - case BMM350_DATA_RATE_12_5HZ: - result = 12.5; - break; - case BMM350_DATA_RATE_25HZ: - result = 25; - break; - case BMM350_DATA_RATE_50HZ: - result = 50; - break; - case BMM350_DATA_RATE_100HZ: - result = 100; - break; - case BMM350_DATA_RATE_200HZ: - result = 200; - break; - case BMM350_DATA_RATE_400HZ: - result = 400; - break; - default: - break; - } - return result; -} - -String DFRobot_BMM350::selfTest(eBmm350SelfTest_t testMode) -{ - String result; - /* Structure instance of self-test data */ - struct sBmm350SelfTest_t stData; - memset(&stData, 0, sizeof(stData)); - switch (testMode) - { - case eBmm350SelfTestNormal: - setOperationMode(eBmm350NormalMode); - setMeasurementXYZ(); - sBmm350MagData_t magData = getGeomagneticData(); - if ((magData.x < 2000) && (magData.x > -2000)) - { - result += "x aixs self test success!\n"; - } - else - { - result += "x aixs self test failed!\n"; - } - if ((magData.y < 2000) && (magData.y > -2000)) - { - result += "y aixs self test success!\n"; - } - else - { - result += "y aixs self test failed!\n"; - } - if ((magData.z < 2000) && (magData.z > -2000)) - { - result += "z aixs self test success!\n"; - } - else - { - result += "z aixs self test failed!\n"; - } - break; - } - return result; -} - -void DFRobot_BMM350::setMeasurementXYZ(enum eBmm350XAxisEnDis_t enX, enum eBmm350YAxisEnDis_t enY, enum eBmm350ZAxisEnDis_t enZ) -{ - bmm350_enable_axes(enX, enY, enZ, &bmm350Sensor); -} - -String DFRobot_BMM350::getMeasurementStateXYZ(void) -{ - uint8_t axisReg = 0; - uint8_t enX = 0; - uint8_t enY = 0; - uint8_t enZ = 0; - char result[100] = ""; - - /* Get the configurations for ODR and performance */ - axisReg = bmm350Sensor.axisEn; - - /* Read the performance status */ - enX = BMM350_GET_BITS(axisReg, BMM350_EN_X); - enY = BMM350_GET_BITS(axisReg, BMM350_EN_Y); - enZ = BMM350_GET_BITS(axisReg, BMM350_EN_Z); - - strcat(result, (enX == 1 ? "The x axis is enable! " : "The x axis is disable! ")); - strcat(result, (enY == 1 ? "The y axis is enable! " : "The y axis is disable! ")); - strcat(result, (enZ == 1 ? "The z axis is enable! " : "The z axis is disable! ")); - return result; -} - -sBmm350MagData_t DFRobot_BMM350::getGeomagneticData(void) -{ - sBmm350MagData_t magData; - struct sBmm350MagTempData_t magTempData; - memset(&magData, 0, sizeof(magData)); - memset(&magTempData, 0, sizeof(magTempData)); - bmm350GetCompensatedMagXYZTempData(&magTempData, &bmm350Sensor); - magData.x = magTempData.x; - magData.y = magTempData.y; - magData.z = magTempData.z; - magData.temperature = magTempData.temperature; - magData.float_x = magTempData.x; - magData.float_y = magTempData.y; - magData.float_z = magTempData.z; - magData.float_temperature = magTempData.temperature; - return magData; -} - -float DFRobot_BMM350::getCompassDegree(void) -{ - float compass = 0.0; - sBmm350MagData_t magData = getGeomagneticData(); - compass = atan2(magData.x, magData.y); - if (compass < 0) - { - compass += 2 * PI; - } - if (compass > 2 * PI) - { - compass -= 2 * PI; - } - return compass * 180 / M_PI; -} - -void DFRobot_BMM350::setDataReadyPin(enum eBmm350InterruptEnableDisable_t modes, enum eBmm350IntrPolarity_t polarity) -{ - /* Variable to get interrupt control configuration */ - uint8_t regData = 0; - /* Variable to store the function result */ - int8_t rslt; - /* Get interrupt control configuration */ - rslt = bmm350GetRegs(BMM350_REG_INT_CTRL, ®Data, 1, &bmm350Sensor); - if (rslt == BMM350_OK) - { - regData = BMM350_SET_BITS_POS_0(regData, BMM350_INT_MODE, BMM350_PULSED); - regData = BMM350_SET_BITS(regData, BMM350_INT_POL, polarity); - regData = BMM350_SET_BITS(regData, BMM350_INT_OD, BMM350_INTR_PUSH_PULL); - regData = BMM350_SET_BITS(regData, BMM350_INT_OUTPUT_EN, BMM350_MAP_TO_PIN); - regData = BMM350_SET_BITS(regData, BMM350_DRDY_DATA_REG_EN, (uint8_t)modes); - /* Finally transfer the interrupt configurations */ - rslt = bmm350SetRegs(BMM350_REG_INT_CTRL, ®Data, 1, &bmm350Sensor); - } -} - -bool DFRobot_BMM350::getDataReadyState(void) -{ - uint8_t drdyStatus = 0x0; - bmm350GetInterruptStatus(&drdyStatus, &bmm350Sensor); - if (drdyStatus & 0x01) - { - return true; - } - else - { - return false; - } -} - -void DFRobot_BMM350::setThresholdInterrupt(uint8_t modes, int8_t threshold, enum eBmm350IntrPolarity_t polarity) -{ - if (modes == LOW_THRESHOLD_INTERRUPT) - { - __thresholdMode = LOW_THRESHOLD_INTERRUPT; - setDataReadyPin(BMM350_ENABLE_INTERRUPT, polarity); - this->threshold = threshold; - } - else - { - __thresholdMode = HIGH_THRESHOLD_INTERRUPT; - setDataReadyPin(BMM350_ENABLE_INTERRUPT, polarity); - this->threshold = threshold; - } -} - -sBmm350ThresholdData_t DFRobot_BMM350::getThresholdData(void) -{ - sBmm350MagData_t magData; - memset(&magData, 0, sizeof(magData)); - thresholdData.mag_x = NO_DATA; - thresholdData.mag_y = NO_DATA; - thresholdData.mag_z = NO_DATA; - thresholdData.interrupt_x = 0; - thresholdData.interrupt_y = 0; - thresholdData.interrupt_z = 0; - bool state = getDataReadyState(); - if (state == true) - { - magData = getGeomagneticData(); - if (__thresholdMode == LOW_THRESHOLD_INTERRUPT) - { - if (magData.x < (int32_t)threshold * 16) - { - thresholdData.mag_x = magData.x; - thresholdData.interrupt_x = 1; - } - if (magData.y < (int32_t)threshold * 16) - { - thresholdData.mag_y = magData.y; - thresholdData.interrupt_y = 1; - } - if (magData.z < (int32_t)threshold * 16) - { - thresholdData.mag_z = magData.z; - thresholdData.interrupt_z = 1; - } - } - else if (__thresholdMode == HIGH_THRESHOLD_INTERRUPT) - { - if (magData.x > (int32_t)threshold * 16) - { - thresholdData.mag_x = magData.x; - thresholdData.interrupt_x = 1; - } - if (magData.y > (int32_t)threshold * 16) - { - thresholdData.mag_y = magData.y; - thresholdData.interrupt_y = 1; - } - if (magData.z > (int32_t)threshold * 16) - { - thresholdData.mag_z = magData.z; - thresholdData.interrupt_z = 1; - } - } - } - - return thresholdData; -} - -static int8_t bmm350I2cReadData(uint8_t Reg, uint8_t *Data, uint32_t len, void *intfPtr) -{ - uint8_t deviceAddr = *(uint8_t *)intfPtr; - _pWire->begin(); - int i = 0; - _pWire->beginTransmission(deviceAddr); - _pWire->write(Reg); - if (_pWire->endTransmission() != 0) - { - return -1; - } - _pWire->requestFrom(deviceAddr, (uint8_t)len); - while (_pWire->available()) - { - Data[i++] = _pWire->read(); - } - return 0; -} - -static int8_t bmm350I2cWriteData(uint8_t Reg, const uint8_t *Data, uint32_t len, void *intfPtr) -{ - uint8_t deviceAddr = *(uint8_t *)intfPtr; - _pWire->begin(); - _pWire->beginTransmission(deviceAddr); - _pWire->write(Reg); - for (uint8_t i = 0; i < len; i++) - { - _pWire->write(Data[i]); - } - _pWire->endTransmission(); - return 0; -} - -DFRobot_BMM350_I2C::DFRobot_BMM350_I2C(TwoWire *pWire, uint8_t addr) : DFRobot_BMM350(bmm350I2cReadData, bmm350I2cWriteData, bmm350DelayUs, eBmm350InterfaceI2C) -{ - _pWire = pWire; - bmm350I2CAddr = addr; -} - -uint8_t DFRobot_BMM350_I2C::begin() -{ - _pWire->begin(); - _pWire->beginTransmission(bmm350I2CAddr); - if (_pWire->endTransmission() == 0) - { - if (sensorInit()) - { - return 0; - } - else - { - DBG("Chip id error ,please check sensor!"); - return 2; - } - } - else - { - DBG("I2C device address error or no connection!"); - return 1; - } -} diff --git a/lib/DFRobot_BMM350/src/DFRobot_BMM350.h b/lib/DFRobot_BMM350/src/DFRobot_BMM350.h deleted file mode 100644 index 67600f4..0000000 --- a/lib/DFRobot_BMM350/src/DFRobot_BMM350.h +++ /dev/null @@ -1,250 +0,0 @@ -/** - * @file DFRobot_BMM350.h - * @brief Defines the infrastructure of the DFRobot_BMM350 class - * @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) - * @license The MIT License (MIT) - * @author [GDuang](yonglei.ren@dfrobot.com) - * @version V1.0.0 - * @date 2024-05-06 - * @url https://github.com/DFRobot/DFRobot_BMM350 - */ -#ifndef __DFRobot_BMM350_H__ -#define __DFRobot_BMM350_H__ - -#include "bmm350_defs.h" -#include "bmm350.h" - -#include "Arduino.h" -#include -#include -#include - - -//#define ENABLE_DBG //< Open this macro to see the program running in detail - -#ifdef ENABLE_DBG -#define DBG(...) {Serial.print("[");Serial.print(__FUNCTION__); Serial.print("(): "); Serial.print(__LINE__); Serial.print(" ] "); Serial.println(__VA_ARGS__);} -#else -#define DBG(...) -#endif - -#define BMM350_INTERFACE_I2C UINT8_C(0x00) -#define BMM350_INTERFACE_I3C UINT8_C(0x01) -#define BMM350_SELF_TEST_NORMAL UINT8_C(0x00) -#define BMM350_SELF_TEST_ADVANCED UINT8_C(0x01) - -enum eBmm350Interface_t { - eBmm350InterfaceI2C = BMM350_INTERFACE_I2C, - eBmm350InterfaceI3C = BMM350_INTERFACE_I3C -}; - -enum eBmm350SelfTest_t { - eBmm350SelfTestNormal = BMM350_SELF_TEST_NORMAL -}; - -void bmm350DelayUs(uint32_t period); - -class DFRobot_BMM350{ -public: - DFRobot_BMM350(pBmm350ReadFptr_t bmm350ReadReg, pBmm350WriteFptr_t bmm350WriteReg, pBmm350DelayUsFptr_t bmm350DelayUs, eBmm350Interface_t interface); - - ~DFRobot_BMM350(); - - /** - * @fn softReset - * @brief Soft reset, restore to suspended mode after soft reset. (You need to manually enter the normal mode) - */ - void softReset(void); - - /** - * @fn setOperationMode - * @brief Set sensor operation mode - * @param powermode - * @n eBmm350SuspendMode suspend mode: Suspend mode is the default power mode of BMM350 after the chip is powered, Current consumption in suspend mode is minimal, - * so, this mode is useful for periods when data conversion is not needed. Read and write of all registers is possible. - * @n eBmm350NormalMode normal mode: Get geomagnetic data normally. - * @n eBmm350ForcedMode forced mode: Single measurement, the sensor restores to suspend mode when the measurement is done. - * @n eBmm350ForcedModeFast To reach ODR = 200Hz is only possible by using FM_ FAST. - */ - void setOperationMode(enum eBmm350PowerModes_t powermode); - - /** - * @fn getOperationMode - * @brief Get sensor operation mode - * @return result Return sensor operation mode as a character string - */ - String getOperationMode(void); - - /** - * @fn setPresetMode - * @brief Set preset mode, make it easier for users to configure sensor to get geomagnetic data (The default collection rate is 12.5Hz) - * @param presetMode - * @n BMM350_PRESETMODE_LOWPOWER Low power mode, get a fraction of data and take the mean value. - * @n BMM350_PRESETMODE_REGULAR Regular mode, get a number of data and take the mean value. - * @n BMM350_PRESETMODE_ENHANCED Enhanced mode, get a plenty of data and take the mean value. - * @n BMM350_PRESETMODE_HIGHACCURACY High accuracy mode, get a huge number of data and take the mean value. - * @param rate - * @n BMM350_DATA_RATE_1_5625HZ - * @n BMM350_DATA_RATE_3_125HZ - * @n BMM350_DATA_RATE_6_25HZ - * @n BMM350_DATA_RATE_12_5HZ - * @n BMM350_DATA_RATE_25HZ - * @n BMM350_DATA_RATE_50HZ - * @n BMM350_DATA_RATE_100HZ - * @n BMM350_DATA_RATE_200HZ - * @n BMM350_DATA_RATE_400HZ - */ - void setPresetMode(uint8_t presetMode, enum eBmm350DataRates_t rate=BMM350_DATA_RATE_12_5HZ); - /** - * @fn setRate - * @brief Set the rate of obtaining geomagnetic data, the higher, the faster (without delay function) - * @param rate - * @n BMM350_DATA_RATE_1_5625HZ - * @n BMM350_DATA_RATE_3_125HZ - * @n BMM350_DATA_RATE_6_25HZ - * @n BMM350_DATA_RATE_12_5HZ (default rate) - * @n BMM350_DATA_RATE_25HZ - * @n BMM350_DATA_RATE_50HZ - * @n BMM350_DATA_RATE_100HZ - * @n BMM350_DATA_RATE_200HZ - * @n BMM350_DATA_RATE_400HZ - */ - void setRate(uint8_t rate); - - /** - * @fn getRate - * @brief Get the config data rate, unit: HZ - * @return rate - */ - float getRate(void); - - /** - * @fn selfTest - * @brief The sensor self test, the returned value indicate the self test result. - * @param testMode: - * @n eBmm350SelfTestNormal Normal self test, test whether x-axis, y-axis and z-axis are connected or short-circuited - * @return result The returned character string is the self test result - */ - String selfTest(eBmm350SelfTest_t testMode = eBmm350SelfTestNormal); - - /** - * @fn setMeasurementXYZ - * @brief Enable the measurement at x-axis, y-axis and z-axis, default to be enabled. After disabling, the geomagnetic data at x, y, and z axis are wrong. - * @param en_x - * @n BMM350_X_EN Enable the measurement at x-axis - * @n BMM350_X_DIS Disable the measurement at x-axis - * @param en_y - * @n BMM350_Y_EN Enable the measurement at y-axis - * @n BMM350_Y_DIS Disable the measurement at y-axis - * @param en_z - * @n BMM350_Z_EN Enable the measurement at z-axis - * @n BMM350_Z_DIS Disable the measurement at z-axis - */ - void setMeasurementXYZ(enum eBmm350XAxisEnDis_t enX = BMM350_X_EN, enum eBmm350YAxisEnDis_t enY = BMM350_Y_EN, enum eBmm350ZAxisEnDis_t enZ = BMM350_Z_EN); - - /** - * @fn getMeasurementStateXYZ - * @brief Get the enabling status at x-axis, y-axis and z-axis - * @return result Return enabling status as a character string - */ - String getMeasurementStateXYZ(void); - - /** - * @fn getGeomagneticData - * @brief Get the geomagnetic data of 3 axis (x, y, z) - * @return Geomagnetic data structure, unit: (uT) - */ - sBmm350MagData_t getGeomagneticData(void); - - - /** - * @fn getCompassDegree - * @brief Get compass degree - * @return Compass degree (0° - 360°) - * @n 0° = North, 90° = East, 180° = South, 270° = West. - */ - float getCompassDegree(void); - - /** - * @fn setDataReadyPin - * @brief Enable or disable data ready interrupt pin - * @n After enabling, the DRDY pin jump when there's data coming. - * @n After disabling, the DRDY pin will not jump when there's data coming. - * @n High polarity: active on high, the default is low level, which turns to high level when the interrupt is triggered. - * @n Low polarity: active on low, default is high level, which turns to low level when the interrupt is triggered. - * @param modes - * @n BMM350_ENABLE_INTERRUPT Enable DRDY - * @n BMM350_DISABLE_INTERRUPT Disable DRDY - * @param polarity - * @n BMM350_ACTIVE_HIGH High polarity - * @n BMM350_ACTIVE_LOW Low polarity - */ - void setDataReadyPin(enum eBmm350InterruptEnableDisable_t modes, enum eBmm350IntrPolarity_t polarity=BMM350_ACTIVE_HIGH); - - /** - * @fn getDataReadyState - * @brief Get the data ready status, determine whether the data is ready - * @return status - * @retval true Data ready - * @retval false Data is not ready - */ - bool getDataReadyState(void); - - /** - * @fn setThresholdInterrupt(uint8_t modes, int8_t threshold, enum eBmm350IntrPolarity_t polarity) - * @brief Set threshold interrupt, an interrupt is triggered when the geomagnetic value of a channel is beyond/below the threshold - * @n High polarity: active on high level, the default is low level, which turns to high level when the interrupt is triggered. - * @n Low polarity: active on low level, the default is high level, which turns to low level when the interrupt is triggered. - * @param modes - * @n LOW_THRESHOLD_INTERRUPT Low threshold interrupt mode - * @n HIGH_THRESHOLD_INTERRUPT High threshold interrupt mode - * @param threshold - * @n Threshold, default to expand 16 times, for example: under low threshold mode, if the threshold is set to be 1, actually the geomagnetic data below 16 will trigger an interrupt - * @param polarity - * @n POLARITY_HIGH High polarity - * @n POLARITY_LOW Low polarity - */ - void setThresholdInterrupt(uint8_t modes, int8_t threshold, enum eBmm350IntrPolarity_t polarity); - - /** - * @fn getThresholdData - * @brief Get the data with threshold interrupt occurred - * @return Returns the structure for storing geomagnetic data, the structure stores the data of 3 axis and interrupt status, - * @n The interrupt is not triggered when the data at x-axis, y-axis and z-axis are NO_DATA - * @n mag_x、mag_y、mag_z store geomagnetic data - * @n interrupt_x、interrupt_y、interrupt_z store the xyz axis interrupt state - */ - sBmm350ThresholdData_t getThresholdData(void); - -protected: - /** - * @fn sensorInit - * @brief Init bmm350 check whether the chip id is right - * @return state - * @retval true Chip id is right init succeeds - * @retval false Chip id is wrong init failed - */ - bool sensorInit(void); - - /** - * @fn getChipID - * @brief get bmm350 chip id - * @return chip id - */ - uint8_t getChipID(void); - -private: - uint8_t __thresholdMode = 3; - int8_t threshold = 0; - sBmm350ThresholdData_t thresholdData; -}; - -class DFRobot_BMM350_I2C:public DFRobot_BMM350 -{ - public: - DFRobot_BMM350_I2C(TwoWire *pWire, uint8_t addr = 0x14); - uint8_t begin(void); -}; - - -#endif diff --git a/lib/DFRobot_BMM350/src/bmm350.c b/lib/DFRobot_BMM350/src/bmm350.c deleted file mode 100644 index 21b7f72..0000000 --- a/lib/DFRobot_BMM350/src/bmm350.c +++ /dev/null @@ -1,1781 +0,0 @@ -/** -* Copyright (c) 2023 Bosch Sensortec GmbH. All rights reserved. -* -* BSD-3-Clause -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in the -* documentation and/or other materials provided with the distribution. -* -* 3. Neither the name of the copyright holder nor the names of its -* contributors may be used to endorse or promote products derived from -* this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) -* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, -* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING -* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -* @file bmm350.c -* @date 2023-05-26 -* @version v1.4.0 -* -*/ - -/*************************** Header files *******************************/ -#include "bmm350.h" - -#ifdef __KERNEL__ -#include -#include -#else -#include -#include -#endif - -/********************** Static function declarations ************************/ - -/*! - * @brief This internal API is used to validate the device pointer for - * null conditions. - * - * @param[in] dev : Structure instance of bmm350_dev. - * - * @return Result of API execution status - * @retval = 0 -> Success - * @retval < 0 -> Error - */ -static int8_t null_ptr_check(const struct bmm350_dev *dev); - -/*! - * @brief This internal API is used to update magnetometer offset and sensitivity data. - * - * @param[in] dev : Structure instance of bmm350_dev. - * - * @return void - */ -static void update_mag_off_sens(struct bmm350_dev *dev); - -/*! - * @brief This internal API converts the raw data from the IC data registers to signed integer - * - * @param[in] inval : Unsigned data from data registers - * @param[in number_of_bits : Width of data register - * - * @return Conversion to signed integer - */ -static int32_t fix_sign(uint32_t inval, int8_t number_of_bits); - -/*! - * @brief This internal API is used to read OTP word - * - * @param[in] addr : Stores OTP address - * @param[in, out] lsb_msb : Pointer to store OTP word - * @param[in, out] dev : Structure instance of bmm350_dev. - * - * @return Result of API execution status - * @retval = 0 -> Success - * @retval < 0 -> Error - */ -static int8_t read_otp_word(uint8_t addr, uint16_t *lsb_msb, struct bmm350_dev *dev); - -/*! - * @brief This internal API is used to read raw magnetic x,y and z axis data along with temperature. - * - * @param[out] out_data : Pointer variable to store mag and temperature data. - * @param[in, out] dev : Structure instance of bmm350_dev. - * - * @return Result of API execution status - * @retval = 0 -> Success - * @retval < 0 -> Error - */ -static int8_t read_out_raw_data(float *out_data, struct bmm350_dev *dev); - -/*! - * @brief This internal API is used to convert raw mag lsb data to uT and raw temperature data to degC. - * - * @param[in,out] lsb_to_ut_degc : Float variable to store converted value of mag lsb in micro tesla(uT) and - * temperature data in degC. - * - * @return void - */ -static void update_default_coefiecents(float *lsb_to_ut_degc); - -/*! - * @brief This internal API is used to read OTP data after boot in user mode. - * - * @param[in, out] dev : Structure instance of bmm350_dev. - * - * @return Result of API execution status - * @retval = 0 -> Success - * @retval < 0 -> Error - */ -static int8_t otp_dump_after_boot(struct bmm350_dev *dev); - -/*! - * @brief This internal API is used for self-test entry configuration - * - * @param[in, out] dev : Structure instance of bmm350_dev. - * - * @return Result of API execution status - * @retval = 0 -> Success - * @retval < 0 -> Error - */ -static int8_t self_test_entry_config(struct bmm350_dev *dev); - -/*! - * @brief This internal API is used to test self-test for X and Y axis - * - * @param[in, out] out_data : Structure instance of sBmm350SelfTest_t. - * @param[in, out] dev : Structure instance of bmm350_dev. - * - * @return Result of API execution status - * @retval = 0 -> Success - * @retval < 0 -> Error - */ -static int8_t self_test_xy_axis(struct sBmm350SelfTest_t *out_data, struct bmm350_dev *dev); - -/*! - * @brief This internal API is used to set self-test configurations. - * - * @param[in] st_cmd : Variable to store self-test command. - * @param[in] pmu_cmd : Variable to store PMU command. - * @param[in, out] out_data : Structure instance of sBmm350SelfTest_t. - * @param[in, out] dev : Structure instance of bmm350_dev. - * - * @return Result of API execution status - * @retval = 0 -> Success - * @retval < 0 -> Error - */ -static int8_t self_test_config(uint8_t st_cmd, - uint8_t pmu_cmd, - struct sBmm350SelfTest_t *out_data, - struct bmm350_dev *dev); - -/*! - * @brief This internal API is used to set powermode. - * - * @param[in] powermode : Variable to set new powermode. - * @param[in, out] dev : Structure instance of bmm350_dev. - * - * @return Result of API execution status - * @retval = 0 -> Success - * @retval < 0 -> Error - */ -static int8_t set_powermode(enum eBmm350PowerModes_t powermode, struct bmm350_dev *dev); - -/********************** Global function definitions ************************/ - -/*! - * @brief This API is the entry point. Call this API before using other APIs. - */ -int8_t bmm350Init(struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - /* Variable to get chip id */ - uint8_t chipId = BMM350_DISABLE; - - /* Variable to store the command to power-off the OTP */ - uint8_t otp_cmd = BMM350_OTP_CMD_PWR_OFF_OTP; - - /* Variable to store soft-reset command */ - uint8_t soft_reset; - - /* Check for null pointer in the device structure */ - rslt = null_ptr_check(dev); - /* Proceed if null check is fine */ - if (rslt == BMM350_OK) - { - dev->chipId = 0; - - /* Assign axisEn with all axis enabled (BMM350_EN_XYZ_MSK) */ - dev->axisEn = BMM350_EN_XYZ_MSK; - rslt = bmm350DelayUs(BMM350_START_UP_TIME_FROM_POR, dev); - - if (rslt == BMM350_OK) - { - /* Soft-reset */ - soft_reset = BMM350_CMD_SOFTRESET; - /* Set the command in the command register */ - rslt = bmm350SetRegs(BMM350_REG_CMD, &soft_reset, 1, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350DelayUs(BMM350_SOFT_RESET_DELAY, dev); - } - } - - if (rslt == BMM350_OK) - { - /* Chip ID of the sensor is read */ - rslt = bmm350GetRegs(BMM350_REG_CHIP_ID, &chipId, 1, dev); - - if (rslt == BMM350_OK) - { - /* Assign chipId to dev->chipId */ - dev->chipId = chipId; - } - } - /* Check for chip id validity */ - if ((rslt == BMM350_OK) && (dev->chipId == BMM350_CHIP_ID)) - { - /* Download OTP memory */ - rslt = otp_dump_after_boot(dev); - if (rslt == BMM350_OK) - { - /* Power off OTP */ - rslt = bmm350SetRegs(BMM350_REG_OTP_CMD_REG, &otp_cmd, 1, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350_magnetic_reset_and_wait(dev); - } - } - } - else - { - rslt = BMM350_E_DEV_NOT_FOUND; - } - } - - return rslt; -} - -/*! - * @brief This API writes the given data to the register address - * of the sensor. - */ -int8_t bmm350SetRegs(uint8_t reg_addr, const uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - /* Check for null pointer in the device structure */ - rslt = null_ptr_check(dev); - - /* Proceed if null check is fine */ - if ((rslt == BMM350_OK) && (reg_data != NULL) && (len != 0)) - { - /* Write the data to the reg_addr */ - dev->intf_rslt = dev->write(reg_addr, reg_data, len, dev->intfPtr); - - if (dev->intf_rslt != BMM350_INTF_RET_SUCCESS) - { - rslt = BMM350_E_COM_FAIL; - } - } - else - { - rslt = BMM350_E_NULL_PTR; - } - - return rslt; -} - -/*! - * @brief This API reads the data from the given register address of sensor. - */ -int8_t bmm350GetRegs(uint8_t reg_addr, uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - /* Variable to define temporary length */ - uint16_t temp_len = len + BMM350_DUMMY_BYTES; - - /* Variable to define temporary buffer */ - uint8_t temp_buf[BMM350_READ_BUFFER_LENGTH]; - - /* Variable to define loop */ - uint16_t index = 0; - - /* Check for null pointer in the device structure */ - rslt = null_ptr_check(dev); - - /* Proceed if null check is fine */ - if ((rslt == BMM350_OK) && (reg_data != NULL)) - { - /* Read the data from the reg_addr */ - dev->intf_rslt = dev->read(reg_addr, temp_buf, temp_len, dev->intfPtr); - - if (dev->intf_rslt == BMM350_INTF_RET_SUCCESS) - { - /* Copy data after dummy byte indices */ - while (index < len) - { - reg_data[index] = temp_buf[index + BMM350_DUMMY_BYTES]; - index++; - } - } - else - { - rslt = BMM350_E_COM_FAIL; - } - } - else - { - rslt = BMM350_E_NULL_PTR; - } - - return rslt; -} - -/*! - * @brief This function provides the delay for required time (Microsecond) as per the input provided in some of the - * APIs. - */ -int8_t bmm350DelayUs(uint32_t period_us, const struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - /* Check for null pointer in the device structure */ - rslt = null_ptr_check(dev); - - if (rslt == BMM350_OK) - { - dev->delayUs(period_us, dev->intfPtr); - } - - return rslt; -} - -/*! - * @brief This API is used to perform soft-reset of the sensor - * where all the registers are reset to their default values - */ -int8_t bmm350SoftReset(struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - uint8_t reg_data; - - /* Variable to store the command to power-off the OTP */ - uint8_t otp_cmd = BMM350_OTP_CMD_PWR_OFF_OTP; - - /* Check for null pointer in the device structure */ - rslt = null_ptr_check(dev); - - if (rslt == BMM350_OK) - { - reg_data = BMM350_CMD_SOFTRESET; - - /* Set the command in the command register */ - rslt = bmm350SetRegs(BMM350_REG_CMD, ®_data, 1, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350DelayUs(BMM350_SOFT_RESET_DELAY, dev); - - if (rslt == BMM350_OK) - { - /* Power off OTP */ - rslt = bmm350SetRegs(BMM350_REG_OTP_CMD_REG, &otp_cmd, 1, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350_magnetic_reset_and_wait(dev); - } - } - } - } - - return rslt; -} - -/*! - * @brief This API is used to read the sensor time. - * It converts the sensor time register values to the representative time value. - * Returns the sensor time in ticks. - */ -int8_t bmm350_read_sensortime(uint32_t *seconds, uint32_t *nanoseconds, struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - uint64_t time; - - uint8_t reg_data[3]; - - if ((seconds != NULL) && (nanoseconds != NULL)) - { - /* Get sensor time raw data */ - rslt = bmm350GetRegs(BMM350_REG_SENSORTIME_XLSB, reg_data, 3, dev); - - if (rslt == BMM350_OK) - { - time = (uint32_t)(reg_data[0] + ((uint32_t)reg_data[1] << 8) + ((uint32_t)reg_data[2] << 16)); - - /* 1 LSB is 39.0625us. Converting to nanoseconds */ - time *= UINT64_C(390625); - time /= UINT64_C(10); - *seconds = (uint32_t)(time / UINT64_C(1000000000)); - *nanoseconds = (uint32_t)(time - ((*seconds) * UINT64_C(1000000000))); - } - } - else - { - rslt = BMM350_E_NULL_PTR; - } - - return rslt; -} - -/*! - * @brief This API is used to get the status flags of all interrupt - * which is used to check for the assertion of interrupts - */ -int8_t bmm350GetInterruptStatus(uint8_t *drdy_status, struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - uint8_t int_status_reg; - - if (drdy_status != NULL) - { - /* Get the status of interrupt */ - rslt = bmm350GetRegs(BMM350_REG_INT_STATUS, &int_status_reg, 1, dev); - - if (rslt == BMM350_OK) - { - /* Read the interrupt status */ - (*drdy_status) = BMM350_GET_BITS(int_status_reg, BMM350_DRDY_DATA_REG); - } - } - else - { - rslt = BMM350_E_NULL_PTR; - } - - return rslt; -} - -/*! - * @brief This API is used to set the power mode of the sensor - */ -int8_t bmm350SetPowerMode(enum eBmm350PowerModes_t powermode, struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - uint8_t last_pwr_mode; - uint8_t reg_data; - - /* Check for null pointer in the device structure */ - rslt = null_ptr_check(dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350GetRegs(BMM350_REG_PMU_CMD, &last_pwr_mode, 1, dev); - - if (rslt == BMM350_OK) - { - if (last_pwr_mode > BMM350_PMU_CMD_NM_TC) - { - rslt = BMM350_E_INVALID_CONFIG; - } - - if ((rslt == BMM350_OK) && - ((last_pwr_mode == BMM350_PMU_CMD_NM) || (last_pwr_mode == BMM350_PMU_CMD_UPD_OAE))) - { - reg_data = BMM350_PMU_CMD_SUS; - - /* Set PMU command configuration */ - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, ®_data, 1, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350DelayUs(BMM350_GOTO_SUSPEND_DELAY, dev); - } - } - - if (rslt == BMM350_OK) - { - rslt = set_powermode(powermode, dev); - } - } - } - if (rslt == BMM350_OK) dev->powerMode = powermode; - return rslt; -} - -/*! - * @brief This API sets the ODR and averaging factor. - */ -int8_t bmm350SetOdrPerformance(enum eBmm350DataRates_t odr, - enum bmm350_performance_parameters performance, - struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - /* Variable to get PMU command */ - uint8_t reg_data = 0; - - enum bmm350_performance_parameters performance_fix = performance; - - /* Check for null pointer in the device structure */ - rslt = null_ptr_check(dev); - - if (rslt == BMM350_OK) - { - /* Reduce the performance setting when too high for the chosen ODR */ - if ((odr == BMM350_DATA_RATE_400HZ) && (performance >= BMM350_AVERAGING_2)) - { - performance_fix = BMM350_NO_AVERAGING; - } - else if ((odr == BMM350_DATA_RATE_200HZ) && (performance >= BMM350_AVERAGING_4)) - { - performance_fix = BMM350_AVERAGING_2; - } - else if ((odr == BMM350_DATA_RATE_100HZ) && (performance >= BMM350_AVERAGING_8)) - { - performance_fix = BMM350_AVERAGING_4; - } - - /* ODR is an enum taking the generated constants from the register map */ - reg_data = ((uint8_t)odr & BMM350_ODR_MSK); - - /* AVG / performance is an enum taking the generated constants from the register map */ - reg_data = BMM350_SET_BITS(reg_data, BMM350_AVG, (uint8_t)performance_fix); - - /* Set PMU command configurations for ODR and performance */ - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD_AGGR_SET, ®_data, 1, dev); - - if (rslt == BMM350_OK) - { - /* Set PMU command configurations to update odr and average */ - reg_data = BMM350_PMU_CMD_UPD_OAE; - - /* Set PMU command configuration */ - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, ®_data, 1, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350DelayUs(BMM350_UPD_OAE_DELAY, dev); - } - } - } - - return rslt; -} - -/*! - * @brief This API is used to enable or disable the magnetic - * measurement of x,y,z axes - */ -int8_t bmm350_enable_axes(enum eBmm350XAxisEnDis_t en_x, - enum eBmm350YAxisEnDis_t en_y, - enum eBmm350ZAxisEnDis_t en_z, - struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - /* Variable to store axis data */ - uint8_t data; - - /* Check for null pointer in the device structure */ - rslt = null_ptr_check(dev); - - if (rslt == BMM350_OK) - { - if ((en_x == BMM350_X_DIS) && (en_y == BMM350_Y_DIS) && (en_z == BMM350_Z_DIS)) - { - rslt = BMM350_E_ALL_AXIS_DISABLED; - - /* Assign axisEn with all axis disabled status */ - dev->axisEn = BMM350_DISABLE; - } - else - { - data = (en_x & BMM350_EN_X_MSK); - data = BMM350_SET_BITS(data, BMM350_EN_Y, en_y); - data = BMM350_SET_BITS(data, BMM350_EN_Z, en_z); - - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD_AXIS_EN, &data, 1, dev); - - if (rslt == BMM350_OK) - { - /* Assign axisEn with the axis selection done */ - dev->axisEn = data; - } - } - } - - return rslt; -} - -/*! - * @brief This API is used to enable or disable the data ready interrupt - */ -int8_t bmm350_enable_interrupt(enum eBmm350InterruptEnableDisable_t enable_disable, struct bmm350_dev *dev) -{ - /* Variable to get interrupt control configuration */ - uint8_t reg_data = 0; - - /* Variable to store the function result */ - int8_t rslt; - - /* Get interrupt control configuration */ - rslt = bmm350GetRegs(BMM350_REG_INT_CTRL, ®_data, 1, dev); - - if (rslt == BMM350_OK) - { - reg_data = BMM350_SET_BITS(reg_data, BMM350_DRDY_DATA_REG_EN, (uint8_t)enable_disable); - - /* Finally transfer the interrupt configurations */ - rslt = bmm350SetRegs(BMM350_REG_INT_CTRL, ®_data, 1, dev); - } - - return rslt; -} - -/*! - * @brief This API is used to configure the interrupt control settings - */ -int8_t bmm350_configure_interrupt(enum bmm350_intr_latch latching, - enum eBmm350IntrPolarity_t polarity, - enum bmm350_intr_drive drivertype, - enum bmm350_intr_map map_nomap, - struct bmm350_dev *dev) -{ - /* Variable to get interrupt control configuration */ - uint8_t reg_data = 0; - - /* Variable to store the function result */ - int8_t rslt; - - /* Get interrupt control configuration */ - rslt = bmm350GetRegs(BMM350_REG_INT_CTRL, ®_data, 1, dev); - - if (rslt == BMM350_OK) - { - reg_data = BMM350_SET_BITS_POS_0(reg_data, BMM350_INT_MODE, latching); - reg_data = BMM350_SET_BITS(reg_data, BMM350_INT_POL, polarity); - reg_data = BMM350_SET_BITS(reg_data, BMM350_INT_OD, drivertype); - reg_data = BMM350_SET_BITS(reg_data, BMM350_INT_OUTPUT_EN, map_nomap); - - /* Finally transfer the interrupt configurations */ - rslt = bmm350SetRegs(BMM350_REG_INT_CTRL, ®_data, 1, dev); - } - - return rslt; -} - -/*! - * @brief This API is used to read uncompensated mag and temperature data. - */ -int8_t bmm350_read_uncomp_mag_temp_data(struct bmm350_raw_mag_data *raw_data, struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - uint8_t mag_data[12] = { 0 }; - - uint32_t raw_mag_x, raw_mag_y, raw_mag_z, raw_temp; - - if (raw_data != NULL) - { - /* Get uncompensated mag data */ - rslt = bmm350GetRegs(BMM350_REG_MAG_X_XLSB, mag_data, BMM350_MAG_TEMP_DATA_LEN, dev); - - if (rslt == BMM350_OK) - { - raw_mag_x = mag_data[0] + ((uint32_t)mag_data[1] << 8) + ((uint32_t)mag_data[2] << 16); - raw_mag_y = mag_data[3] + ((uint32_t)mag_data[4] << 8) + ((uint32_t)mag_data[5] << 16); - raw_mag_z = mag_data[6] + ((uint32_t)mag_data[7] << 8) + ((uint32_t)mag_data[8] << 16); - raw_temp = mag_data[9] + ((uint32_t)mag_data[10] << 8) + ((uint32_t)mag_data[11] << 16); - - if ((dev->axisEn & BMM350_EN_X_MSK) == BMM350_DISABLE) - { - raw_data->raw_xdata = BMM350_DISABLE; - } - else - { - raw_data->raw_xdata = fix_sign(raw_mag_x, BMM350_SIGNED_24_BIT); - } - - if ((dev->axisEn & BMM350_EN_Y_MSK) == BMM350_DISABLE) - { - raw_data->raw_ydata = BMM350_DISABLE; - } - else - { - raw_data->raw_ydata = fix_sign(raw_mag_y, BMM350_SIGNED_24_BIT); - } - - if ((dev->axisEn & BMM350_EN_Z_MSK) == BMM350_DISABLE) - { - raw_data->raw_zdata = BMM350_DISABLE; - } - else - { - raw_data->raw_zdata = fix_sign(raw_mag_z, BMM350_SIGNED_24_BIT); - } - - raw_data->raw_data_t = fix_sign(raw_temp, BMM350_SIGNED_24_BIT); - } - } - else - { - rslt = BMM350_E_NULL_PTR; - } - - return rslt; -} - -/*! - * @brief This API sets the interrupt control IBI configurations to the sensor. - */ -int8_t bmm350_set_int_ctrl_ibi(enum bmm350_drdy_int_map_to_ibi en_dis, - enum bmm350_clear_drdy_int_status_upon_ibi clear_on_ibi, - struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - /* Variable to get interrupt control configuration */ - uint8_t reg_data = 0; - - /* Get interrupt control configuration */ - rslt = bmm350GetRegs(BMM350_REG_INT_CTRL_IBI, ®_data, 1, dev); - - if (rslt == BMM350_OK) - { - reg_data = BMM350_SET_BITS_POS_0(reg_data, BMM350_DRDY_INT_MAP_TO_IBI, en_dis); - reg_data = BMM350_SET_BITS(reg_data, BMM350_CLEAR_DRDY_INT_STATUS_UPON_IBI, clear_on_ibi); - - /* Set the IBI control configuration */ - rslt = bmm350SetRegs(BMM350_REG_INT_CTRL_IBI, ®_data, 1, dev); - - if (en_dis == BMM350_IBI_ENABLE) - { - /* Enable data ready interrupt if IBI is enabled */ - rslt = bmm350_enable_interrupt(BMM350_ENABLE_INTERRUPT, dev); - } - } - - return rslt; -} - -/*! - * @brief This API is used to set the pad drive strength - */ -int8_t bmm350_set_pad_drive(uint8_t drive, struct bmm350_dev *dev) -{ - uint8_t reg_data; - - /* Variable to store the function result */ - int8_t rslt = BMM350_E_BAD_PAD_DRIVE; - - if (drive <= BMM350_PAD_DRIVE_STRONGEST) - { - reg_data = drive & BMM350_DRV_MSK; - - /* Set drive */ - rslt = bmm350SetRegs(BMM350_REG_PAD_CTRL, ®_data, 1, dev); - } - - return rslt; -} - -/*! - * @brief This API is used to perform the magnetic reset of the sensor - * which is necessary after a field shock (400mT field applied to sensor). - * It sends flux guide or bit reset to the device in suspend mode. - */ -int8_t bmm350_magnetic_reset_and_wait(struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - uint8_t pmu_cmd = 0; - struct bmm350_pmu_cmd_status_0 pmu_cmd_stat_0 = { 0 }; - uint8_t restore_normal = BMM350_DISABLE; - - rslt = null_ptr_check(dev); - - if ((rslt == BMM350_OK) && (dev->mraw_override) && (dev->var_id >= BMM350_MIN_VAR)) - { - rslt = dev->mraw_override(dev); - } - else - { - /* Read PMU CMD status */ - rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); - - /* Check the powermode is normal before performing magnetic reset */ - if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pwr_mode_is_normal == BMM350_ENABLE)) - { - restore_normal = BMM350_ENABLE; - - /* Reset can only be triggered in suspend */ - rslt = bmm350SetPowerMode(eBmm350SuspendMode, dev); - } - - if (rslt == BMM350_OK) - { - /* Set BR to PMU_CMD register */ - pmu_cmd = BMM350_PMU_CMD_BR; - - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350DelayUs(BMM350_BR_DELAY, dev); - } - } - - if (rslt == BMM350_OK) - { - /* Verify if PMU_CMD_STATUS_0 register has BR set */ - rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); - - if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value != BMM350_PMU_CMD_STATUS_0_BR)) - { - rslt = BMM350_E_PMU_CMD_VALUE; - } - } - - if (rslt == BMM350_OK) - { - /* Set FGR to PMU_CMD register */ - pmu_cmd = BMM350_PMU_CMD_FGR; - - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350DelayUs(BMM350_FGR_DELAY, dev); - } - } - - if (rslt == BMM350_OK) - { - /* Verify if PMU_CMD_STATUS_0 register has FGR set */ - rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); - - if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value != BMM350_PMU_CMD_STATUS_0_FGR)) - { - rslt = BMM350_E_PMU_CMD_VALUE; - } - } - - if ((rslt == BMM350_OK) && (restore_normal == BMM350_ENABLE)) - { - rslt = bmm350SetPowerMode(eBmm350NormalMode, dev); - } - } - - return rslt; -} - -/*! - * @brief This API is used to perform compensation for raw magnetometer and temperature data. - */ -int8_t bmm350GetCompensatedMagXYZTempData(struct sBmm350MagTempData_t *mag_temp_data, struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - uint8_t indx; - float out_data[4] = { 0.0f }; - float dut_offset_coef[3], dut_sensit_coef[3], dut_tco[3], dut_tcs[3]; - float cr_ax_comp_x, cr_ax_comp_y, cr_ax_comp_z; - - if (mag_temp_data != NULL) - { - /* Reads raw magnetic x,y and z axis along with temperature */ - rslt = read_out_raw_data(out_data, dev); - - if (rslt == BMM350_OK) - { - /* Apply compensation to temperature reading */ - out_data[3] = (1 + dev->mag_comp.dut_sensit_coef.t_sens) * out_data[3] + - dev->mag_comp.dut_offset_coef.t_offs; - - /* Store magnetic compensation structure to an array */ - dut_offset_coef[0] = dev->mag_comp.dut_offset_coef.offset_x; - dut_offset_coef[1] = dev->mag_comp.dut_offset_coef.offset_y; - dut_offset_coef[2] = dev->mag_comp.dut_offset_coef.offset_z; - - dut_sensit_coef[0] = dev->mag_comp.dut_sensit_coef.sens_x; - dut_sensit_coef[1] = dev->mag_comp.dut_sensit_coef.sens_y; - dut_sensit_coef[2] = dev->mag_comp.dut_sensit_coef.sens_z; - - dut_tco[0] = dev->mag_comp.dut_tco.tco_x; - dut_tco[1] = dev->mag_comp.dut_tco.tco_y; - dut_tco[2] = dev->mag_comp.dut_tco.tco_z; - - dut_tcs[0] = dev->mag_comp.dut_tcs.tcs_x; - dut_tcs[1] = dev->mag_comp.dut_tcs.tcs_y; - dut_tcs[2] = dev->mag_comp.dut_tcs.tcs_z; - - /* Compensate raw magnetic data */ - for (indx = 0; indx < 3; indx++) - { - out_data[indx] *= 1 + dut_sensit_coef[indx]; - out_data[indx] += dut_offset_coef[indx]; - out_data[indx] += dut_tco[indx] * (out_data[3] - dev->mag_comp.dut_t0); - out_data[indx] /= 1 + dut_tcs[indx] * (out_data[3] - dev->mag_comp.dut_t0); - } - - cr_ax_comp_x = (out_data[0] - dev->mag_comp.cross_axis.cross_x_y * out_data[1]) / - (1 - dev->mag_comp.cross_axis.cross_y_x * dev->mag_comp.cross_axis.cross_x_y); - cr_ax_comp_y = (out_data[1] - dev->mag_comp.cross_axis.cross_y_x * out_data[0]) / - (1 - dev->mag_comp.cross_axis.cross_y_x * dev->mag_comp.cross_axis.cross_x_y); - cr_ax_comp_z = - (out_data[2] + - (out_data[0] * - (dev->mag_comp.cross_axis.cross_y_x * dev->mag_comp.cross_axis.cross_z_y - - dev->mag_comp.cross_axis.cross_z_x) - out_data[1] * - (dev->mag_comp.cross_axis.cross_z_y - dev->mag_comp.cross_axis.cross_x_y * - dev->mag_comp.cross_axis.cross_z_x)) / - (1 - dev->mag_comp.cross_axis.cross_y_x * dev->mag_comp.cross_axis.cross_x_y)); - - out_data[0] = cr_ax_comp_x; - out_data[1] = cr_ax_comp_y; - out_data[2] = cr_ax_comp_z; - } - - if (rslt == BMM350_OK) - { - if ((dev->axisEn & BMM350_EN_X_MSK) == BMM350_DISABLE) - { - mag_temp_data->x = BMM350_DISABLE; - } - else - { - mag_temp_data->x = out_data[0]; - } - - if ((dev->axisEn & BMM350_EN_Y_MSK) == BMM350_DISABLE) - { - mag_temp_data->y = BMM350_DISABLE; - } - else - { - mag_temp_data->y = out_data[1]; - } - - if ((dev->axisEn & BMM350_EN_Z_MSK) == BMM350_DISABLE) - { - mag_temp_data->z = BMM350_DISABLE; - } - else - { - mag_temp_data->z = out_data[2]; - } - - mag_temp_data->temperature = out_data[3]; - } - } - else - { - rslt = BMM350_E_NULL_PTR; - } - - return rslt; -} - -/*! - * @brief This function executes FGR and BR sequences to initialize TMR sensor and performs the user self-test. - */ -int8_t bmm350PerformSelfTest(struct sBmm350SelfTest_t *out_data, struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - /* Variable to store last powermode */ - uint8_t last_pwr_mode; - - if (out_data != NULL) - { - rslt = bmm350GetRegs(BMM350_REG_PMU_CMD, &last_pwr_mode, 1, dev); - - if (rslt == BMM350_OK) - { - /* Self-test entry configuration */ - rslt = self_test_entry_config(dev); - - if (rslt == BMM350_OK) - { - /* Updates self-test values to structure */ - rslt = self_test_xy_axis(out_data, dev); - } - } - - if (rslt == BMM350_OK) - { - /* Setup DUT: disable user self-test */ - rslt = bmm350_set_tmr_selftest_user(BMM350_ST_IGEN_DIS, - BMM350_ST_N_DIS, - BMM350_ST_P_DIS, - BMM350_IST_X_DIS, - BMM350_IST_Y_DIS, - dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350DelayUs(1000, dev); - } - - if (last_pwr_mode == BMM350_PMU_CMD_NM) - { - rslt = bmm350SetPowerMode(eBmm350NormalMode, dev); - } - } - } - else - { - rslt = BMM350_E_NULL_PTR; - } - - return rslt; -} - -/*! - * @brief This API sets the I2C watchdog timer configurations to the sensor. - */ -int8_t bmm350_set_i2c_wdt(enum bmm350_i2c_wdt_en i2c_wdt_en_dis, - enum bmm350_i2c_wdt_sel i2c_wdt_sel, - struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - uint8_t reg_data; - - /* Get I2C WDT configuration */ - rslt = bmm350GetRegs(BMM350_REG_I2C_WDT_SET, ®_data, 1, dev); - - if (rslt == BMM350_OK) - { - reg_data = BMM350_SET_BITS_POS_0(reg_data, BMM350_I2C_WDT_EN, i2c_wdt_en_dis); - reg_data = BMM350_SET_BITS(reg_data, BMM350_I2C_WDT_SEL, i2c_wdt_sel); - - /* Set I2C WDT configuration */ - rslt = bmm350SetRegs(BMM350_REG_I2C_WDT_SET, ®_data, 1, dev); - } - - return rslt; -} - -/*! - * @brief This API sets the TMR user self-test register - */ -int8_t bmm350_set_tmr_selftest_user(enum bmm350_st_igen_en st_igen_en_dis, - enum bmm350_st_n st_n_en_dis, - enum bmm350_st_p st_p_en_dis, - enum bmm350_ist_en_x ist_x_en_dis, - enum bmm350_ist_en_y ist_y_en_dis, - struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - uint8_t reg_data; - - /* Get TMR self-test user configuration */ - rslt = bmm350GetRegs(BMM350_REG_TMR_SELFTEST_USER, ®_data, 1, dev); - - if (rslt == BMM350_OK) - { - reg_data = BMM350_SET_BITS_POS_0(reg_data, BMM350_ST_IGEN_EN, st_igen_en_dis); - reg_data = BMM350_SET_BITS(reg_data, BMM350_ST_N, st_n_en_dis); - reg_data = BMM350_SET_BITS(reg_data, BMM350_ST_P, st_p_en_dis); - reg_data = BMM350_SET_BITS(reg_data, BMM350_IST_EN_X, ist_x_en_dis); - reg_data = BMM350_SET_BITS(reg_data, BMM350_IST_EN_Y, ist_y_en_dis); - - /* Set TMR self-test user configuration */ - rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, ®_data, 1, dev); - } - - return rslt; -} - -/*! - * @brief This API sets the control user configurations to the sensor which forces the sensor timer to be always - * running, even in suspend mode. - */ -int8_t bmm350_set_ctrl_user(enum bmm350_ctrl_user cfg_sens_tim_aon_en_dis, struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - uint8_t reg_data; - - /* Get control user configuration */ - rslt = bmm350GetRegs(BMM350_REG_CTRL_USER, ®_data, 1, dev); - - if (rslt == BMM350_OK) - { - reg_data = BMM350_SET_BITS_POS_0(reg_data, BMM350_CFG_SENS_TIM_AON, cfg_sens_tim_aon_en_dis); - - /* Set control user configuration */ - rslt = bmm350SetRegs(BMM350_REG_CTRL_USER, ®_data, 1, dev); - } - - return rslt; -} - -/*! - * @brief This API gets the PMU command status 0 value - */ -int8_t bmm350_get_pmu_cmd_status_0(struct bmm350_pmu_cmd_status_0 *pmu_cmd_stat_0, struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - uint8_t reg_data; - - if (pmu_cmd_stat_0 != NULL) - { - /* Get PMU command status 0 data */ - rslt = bmm350GetRegs(BMM350_REG_PMU_CMD_STATUS_0, ®_data, 1, dev); - - if (rslt == BMM350_OK) - { - pmu_cmd_stat_0->pmu_cmd_busy = BMM350_GET_BITS_POS_0(reg_data, BMM350_PMU_CMD_BUSY); - - pmu_cmd_stat_0->odr_ovwr = BMM350_GET_BITS(reg_data, BMM350_ODR_OVWR); - - pmu_cmd_stat_0->avr_ovwr = BMM350_GET_BITS(reg_data, BMM350_AVG_OVWR); - - pmu_cmd_stat_0->pwr_mode_is_normal = BMM350_GET_BITS(reg_data, BMM350_PWR_MODE_IS_NORMAL); - - pmu_cmd_stat_0->cmd_is_illegal = BMM350_GET_BITS(reg_data, BMM350_CMD_IS_ILLEGAL); - - pmu_cmd_stat_0->pmu_cmd_value = BMM350_GET_BITS(reg_data, BMM350_PMU_CMD_VALUE); - } - } - else - { - rslt = BMM350_E_NULL_PTR; - } - - return rslt; -} - -/****************************************************************************/ -/**\name INTERNAL APIs */ - -/*! - * @brief This internal API is used to validate the device structure pointer for - * null conditions. - */ -static int8_t null_ptr_check(const struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - if ((dev == NULL) || (dev->read == NULL) || (dev->write == NULL) || (dev->delayUs == NULL)) - { - /* Device structure pointer is not valid */ - rslt = BMM350_E_NULL_PTR; - } - else - { - /* Device structure is fine */ - rslt = BMM350_OK; - } - - return rslt; -} - -/*! - * @brief This internal API converts the raw data from the IC data registers to signed integer - */ -static int32_t fix_sign(uint32_t inval, int8_t number_of_bits) -{ - int32_t power = 0; - int32_t retval; - - switch (number_of_bits) - { - case BMM350_SIGNED_8_BIT: - power = 128; /* 2^7 */ - break; - - case BMM350_SIGNED_12_BIT: - power = 2048; /* 2^11 */ - break; - - case BMM350_SIGNED_16_BIT: - power = 32768; /* 2^15 */ - break; - - case BMM350_SIGNED_21_BIT: - power = 1048576; /* 2^20 */ - break; - - case BMM350_SIGNED_24_BIT: - power = 8388608; /* 2^23 */ - break; - - default: - power = 0; - break; - } - - retval = (int32_t)inval; - - if (retval >= power) - { - retval = retval - (power * 2); - } - - return retval; -} - -/*! - * @brief This internal API is used to read OTP word - */ -static int8_t read_otp_word(uint8_t addr, uint16_t *lsb_msb, struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - uint8_t otp_cmd, otp_status = 0, otp_err = BMM350_OTP_STATUS_NO_ERROR, lsb = 0, msb = 0; - - if (lsb_msb != NULL) - { - /* Set OTP command at specified address */ - otp_cmd = BMM350_OTP_CMD_DIR_READ | (addr & BMM350_OTP_WORD_ADDR_MSK); - rslt = bmm350SetRegs(BMM350_REG_OTP_CMD_REG, &otp_cmd, 1, dev); - if (rslt == BMM350_OK) - { - do - { - rslt = bmm350DelayUs(300, dev); - - if (rslt == BMM350_OK) - { - /* Get OTP status */ - rslt = bmm350GetRegs(BMM350_REG_OTP_STATUS_REG, &otp_status, 1, dev); - - otp_err = BMM350_OTP_STATUS_ERROR(otp_status); - if (otp_err != BMM350_OTP_STATUS_NO_ERROR) - { - break; - } - } - } while ((!(otp_status & BMM350_OTP_STATUS_CMD_DONE)) && (rslt == BMM350_OK)); - - if (otp_err != BMM350_OTP_STATUS_NO_ERROR) - { - switch (otp_err) - { - case BMM350_OTP_STATUS_BOOT_ERR: - rslt = BMM350_E_OTP_BOOT; - break; - case BMM350_OTP_STATUS_PAGE_RD_ERR: - rslt = BMM350_E_OTP_PAGE_RD; - break; - case BMM350_OTP_STATUS_PAGE_PRG_ERR: - rslt = BMM350_E_OTP_PAGE_PRG; - break; - case BMM350_OTP_STATUS_SIGN_ERR: - rslt = BMM350_E_OTP_SIGN; - break; - case BMM350_OTP_STATUS_INV_CMD_ERR: - rslt = BMM350_E_OTP_INV_CMD; - break; - default: - rslt = BMM350_E_OTP_UNDEFINED; - break; - } - } - } - - if (rslt == BMM350_OK) - { - /* Get OTP MSB data */ - rslt = bmm350GetRegs(BMM350_REG_OTP_DATA_MSB_REG, &msb, 1, dev); - if (rslt == BMM350_OK) - { - /* Get OTP LSB data */ - rslt = bmm350GetRegs(BMM350_REG_OTP_DATA_LSB_REG, &lsb, 1, dev); - *lsb_msb = ((uint16_t)(msb << 8) | lsb) & 0xFFFF; - } - } - } - else - { - rslt = BMM350_E_NULL_PTR; - } - - return rslt; -} - -/*! - * @brief This internal API is used to update magnetometer offset and sensitivity data. - */ -static void update_mag_off_sens(struct bmm350_dev *dev) -{ - uint16_t off_x_lsb_msb, off_y_lsb_msb, off_z_lsb_msb, t_off; - uint8_t sens_x, sens_y, sens_z, t_sens; - uint8_t tco_x, tco_y, tco_z; - uint8_t tcs_x, tcs_y, tcs_z; - uint8_t cross_x_y, cross_y_x, cross_z_x, cross_z_y; - - off_x_lsb_msb = dev->otp_data[BMM350_MAG_OFFSET_X] & 0x0FFF; - off_y_lsb_msb = ((dev->otp_data[BMM350_MAG_OFFSET_X] & 0xF000) >> 4) + - (dev->otp_data[BMM350_MAG_OFFSET_Y] & BMM350_LSB_MASK); - off_z_lsb_msb = (dev->otp_data[BMM350_MAG_OFFSET_Y] & 0x0F00) + - (dev->otp_data[BMM350_MAG_OFFSET_Z] & BMM350_LSB_MASK); - t_off = dev->otp_data[BMM350_TEMP_OFF_SENS] & BMM350_LSB_MASK; - - dev->mag_comp.dut_offset_coef.offset_x = fix_sign(off_x_lsb_msb, BMM350_SIGNED_12_BIT); - dev->mag_comp.dut_offset_coef.offset_y = fix_sign(off_y_lsb_msb, BMM350_SIGNED_12_BIT); - dev->mag_comp.dut_offset_coef.offset_z = fix_sign(off_z_lsb_msb, BMM350_SIGNED_12_BIT); - dev->mag_comp.dut_offset_coef.t_offs = fix_sign(t_off, BMM350_SIGNED_8_BIT) / 5.0f; - - sens_x = (dev->otp_data[BMM350_MAG_SENS_X] & BMM350_MSB_MASK) >> 8; - sens_y = (dev->otp_data[BMM350_MAG_SENS_Y] & BMM350_LSB_MASK); - sens_z = (dev->otp_data[BMM350_MAG_SENS_Z] & BMM350_MSB_MASK) >> 8; - t_sens = (dev->otp_data[BMM350_TEMP_OFF_SENS] & BMM350_MSB_MASK) >> 8; - - dev->mag_comp.dut_sensit_coef.sens_x = fix_sign(sens_x, BMM350_SIGNED_8_BIT) / 256.0f; - dev->mag_comp.dut_sensit_coef.sens_y = (fix_sign(sens_y, BMM350_SIGNED_8_BIT) / 256.0f) + BMM350_SENS_CORR_Y; - dev->mag_comp.dut_sensit_coef.sens_z = fix_sign(sens_z, BMM350_SIGNED_8_BIT) / 256.0f; - dev->mag_comp.dut_sensit_coef.t_sens = fix_sign(t_sens, BMM350_SIGNED_8_BIT) / 512.0f; - - tco_x = (dev->otp_data[BMM350_MAG_TCO_X] & BMM350_LSB_MASK); - tco_y = (dev->otp_data[BMM350_MAG_TCO_Y] & BMM350_LSB_MASK); - tco_z = (dev->otp_data[BMM350_MAG_TCO_Z] & BMM350_LSB_MASK); - - dev->mag_comp.dut_tco.tco_x = fix_sign(tco_x, BMM350_SIGNED_8_BIT) / 32.0f; - dev->mag_comp.dut_tco.tco_y = fix_sign(tco_y, BMM350_SIGNED_8_BIT) / 32.0f; - dev->mag_comp.dut_tco.tco_z = fix_sign(tco_z, BMM350_SIGNED_8_BIT) / 32.0f; - - tcs_x = (dev->otp_data[BMM350_MAG_TCS_X] & BMM350_MSB_MASK) >> 8; - tcs_y = (dev->otp_data[BMM350_MAG_TCS_Y] & BMM350_MSB_MASK) >> 8; - tcs_z = (dev->otp_data[BMM350_MAG_TCS_Z] & BMM350_MSB_MASK) >> 8; - - dev->mag_comp.dut_tcs.tcs_x = fix_sign(tcs_x, BMM350_SIGNED_8_BIT) / 16384.0f; - dev->mag_comp.dut_tcs.tcs_y = fix_sign(tcs_y, BMM350_SIGNED_8_BIT) / 16384.0f; - dev->mag_comp.dut_tcs.tcs_z = (fix_sign(tcs_z, BMM350_SIGNED_8_BIT) / 16384.0f) - BMM350_TCS_CORR_Z; - - dev->mag_comp.dut_t0 = (fix_sign(dev->otp_data[BMM350_MAG_DUT_T_0], BMM350_SIGNED_16_BIT) / 512.0f) + 23.0f; - - cross_x_y = (dev->otp_data[BMM350_CROSS_X_Y] & BMM350_LSB_MASK); - cross_y_x = (dev->otp_data[BMM350_CROSS_Y_X] & BMM350_MSB_MASK) >> 8; - cross_z_x = (dev->otp_data[BMM350_CROSS_Z_X] & BMM350_LSB_MASK); - cross_z_y = (dev->otp_data[BMM350_CROSS_Z_Y] & BMM350_MSB_MASK) >> 8; - - dev->mag_comp.cross_axis.cross_x_y = fix_sign(cross_x_y, BMM350_SIGNED_8_BIT) / 800.0f; - dev->mag_comp.cross_axis.cross_y_x = fix_sign(cross_y_x, BMM350_SIGNED_8_BIT) / 800.0f; - dev->mag_comp.cross_axis.cross_z_x = fix_sign(cross_z_x, BMM350_SIGNED_8_BIT) / 800.0f; - dev->mag_comp.cross_axis.cross_z_y = fix_sign(cross_z_y, BMM350_SIGNED_8_BIT) / 800.0f; -} - -/*! - * @brief This internal API is used to read raw magnetic x,y and z axis along with temperature - */ -static int8_t read_out_raw_data(float *out_data, struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - float temp = 0.0; - struct bmm350_raw_mag_data raw_data = { 0 }; - - /* Float variable to convert mag lsb to uT and temp lsb to degC */ - float lsb_to_ut_degc[4]; - - if (out_data != NULL) - { - rslt = bmm350_read_uncomp_mag_temp_data(&raw_data, dev); - - if (rslt == BMM350_OK) - { - /* Convert mag lsb to uT and temp lsb to degC */ - update_default_coefiecents(lsb_to_ut_degc); - - out_data[0] = (float)raw_data.raw_xdata * lsb_to_ut_degc[0]; - out_data[1] = (float)raw_data.raw_ydata * lsb_to_ut_degc[1]; - out_data[2] = (float)raw_data.raw_zdata * lsb_to_ut_degc[2]; - out_data[3] = (float)raw_data.raw_data_t * lsb_to_ut_degc[3]; - - if (out_data[3] > 0.0) - { - temp = (float)(out_data[3] - (1 * 25.49)); - } - else if (out_data[3] < 0.0) - { - temp = (float)(out_data[3] - (-1 * 25.49)); - } - else - { - temp = (float)(out_data[3]); - } - - out_data[3] = temp; - } - } - else - { - rslt = BMM350_E_NULL_PTR; - } - - return rslt; -} - -/*! - * @brief This internal API is used to convert lsb to uT and degC. - */ -static void update_default_coefiecents(float *lsb_to_ut_degc) -{ - float bxy_sens, bz_sens, temp_sens, ina_xy_gain_trgt, ina_z_gain_trgt, adc_gain, lut_gain; - float power; - - bxy_sens = 14.55f; - bz_sens = 9.0f; - temp_sens = 0.00204f; - - ina_xy_gain_trgt = 19.46f; - - ina_z_gain_trgt = 31.0; - - adc_gain = 1 / 1.5f; - lut_gain = 0.714607238769531f; - - power = (float)(1000000.0 / 1048576.0); - - lsb_to_ut_degc[0] = (power / (bxy_sens * ina_xy_gain_trgt * adc_gain * lut_gain)); - lsb_to_ut_degc[1] = (power / (bxy_sens * ina_xy_gain_trgt * adc_gain * lut_gain)); - lsb_to_ut_degc[2] = (power / (bz_sens * ina_z_gain_trgt * adc_gain * lut_gain)); - lsb_to_ut_degc[3] = 1 / (temp_sens * adc_gain * lut_gain * 1048576); -} - -/*! - * @brief This internal API is used to read OTP data after boot in user mode. - */ -static int8_t otp_dump_after_boot(struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - uint16_t otp_word = 0; - uint8_t indx; - - for (indx = 0; indx < BMM350_OTP_DATA_LENGTH; indx++) - { - rslt = read_otp_word(indx, &otp_word, dev); - dev->otp_data[indx] = otp_word; - } - - dev->var_id = (dev->otp_data[30] & 0x7f00) >> 9; - - /* Update magnetometer offset and sensitivity data. */ - update_mag_off_sens(dev); - - return rslt; -} - -/*! - * @brief This internal API is used for self-test entry configuration - */ -static int8_t self_test_entry_config(struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - /* Variable to store PMU command */ - uint8_t cmd; - - /* Structure instance of PMU command status 0 */ - struct bmm350_pmu_cmd_status_0 pmu_cmd_stat_0 = { 0 }; - - /* Set suspend mode */ - cmd = BMM350_PMU_CMD_SUS; - - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &cmd, 1, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350DelayUs(30000, dev); - } - - /* Read DUT outputs in FORCED mode */ - if (rslt == BMM350_OK) - { - rslt = bmm350SetOdrPerformance(BMM350_DATA_RATE_100HZ, BMM350_AVERAGING_2, dev); - - if (rslt == BMM350_OK) - { - /* Enable all axis */ - rslt = bmm350_enable_axes(BMM350_X_EN, BMM350_Y_EN, BMM350_Z_EN, dev); - } - } - - /* Execute FGR with full CRST recharge */ - cmd = BMM350_PMU_CMD_FGR; - - if (rslt == BMM350_OK) - { - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &cmd, 1, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350DelayUs(30000, dev); - } - } - - if (rslt == BMM350_OK) - { - rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); - - if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value == BMM350_PMU_CMD_STATUS_0_FGR)) - { - /* Execute BR with full CRST recharge */ - cmd = BMM350_PMU_CMD_BR_FAST; - - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &cmd, 1, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350DelayUs(4000, dev); - } - } - } - - if (rslt == BMM350_OK) - { - rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); - } - - if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value == BMM350_PMU_CMD_STATUS_0_BR_FAST)) - { - cmd = BMM350_PMU_CMD_FM_FAST; - - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &cmd, 1, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350DelayUs(16000, dev); - } - - if (rslt == BMM350_OK) - { - rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); - - if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value == BMM350_PMU_CMD_STATUS_0_FM_FAST)) - { - rslt = bmm350DelayUs(10, dev); - } - } - } - - return rslt; -} - -/*! - * @brief This internal API is used to test self-test for X and Y axis - */ -static int8_t self_test_xy_axis(struct sBmm350SelfTest_t *out_data, struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - /* Set pmu command */ - uint8_t cmd = BMM350_PMU_CMD_FM_FAST; - - /* Setup DUT: enable positive user self-test on x-axis */ - rslt = self_test_config(BMM350_SELF_TEST_POS_X, cmd, out_data, dev); - - if (rslt == BMM350_OK) - { - /* Setup DUT: enable negative user self-test on x-axis */ - rslt = self_test_config(BMM350_SELF_TEST_NEG_X, cmd, out_data, dev); - - if (rslt == BMM350_OK) - { - /* Setup DUT: enable positive user self-test on y-axis */ - rslt = self_test_config(BMM350_SELF_TEST_POS_Y, cmd, out_data, dev); - - if (rslt == BMM350_OK) - { - /* Setup DUT: enable negative user self-test on y-axis */ - rslt = self_test_config(BMM350_SELF_TEST_NEG_Y, cmd, out_data, dev); - } - } - } - - return rslt; -} - -/*! - * @brief This internal API is used to set self-test configurations. - */ -static int8_t self_test_config(uint8_t st_cmd, - uint8_t pmu_cmd, - struct sBmm350SelfTest_t *out_data, - struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - float out_ust[4]; - - struct bmm350_pmu_cmd_status_0 pmu_cmd_stat_0 = { 0 }; - - static float out_ustxh = 0.0, out_ustxl = 0.0, out_ustyh = 0.0, out_ustyl = 0.0; - - rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, &st_cmd, 1, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350DelayUs(1000, dev); - } - - if (rslt == BMM350_OK) - { - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350DelayUs(6000, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350_get_pmu_cmd_status_0(&pmu_cmd_stat_0, dev); - } - } - } - - if ((rslt == BMM350_OK) && (pmu_cmd_stat_0.pmu_cmd_value == BMM350_PMU_CMD_STATUS_0_FM_FAST)) - { - /* Reads raw magnetic x and y axis */ - rslt = read_out_raw_data(out_ust, dev); - - if (rslt == BMM350_OK) - { - /* Read DUT outputs in FORCED mode (XP_UST) */ - if (st_cmd == BMM350_SELF_TEST_POS_X) - { - out_ustxh = out_ust[0]; - } - /* Read DUT outputs in FORCED mode (XN_UST) */ - else if (st_cmd == BMM350_SELF_TEST_NEG_X) - { - out_ustxl = out_ust[0]; - } - /* Read DUT outputs in FORCED mode (YP_UST) */ - else if (st_cmd == BMM350_SELF_TEST_POS_Y) - { - out_ustyh = out_ust[1]; - } - /* Read DUT outputs in FORCED mode (YN_UST) */ - else if (st_cmd == BMM350_SELF_TEST_NEG_Y) - { - out_ustyl = out_ust[1]; - } - else - { - /* Returns error if self-test axis is wrong */ - rslt = BMM350_E_SELF_TEST_INVALID_AXIS; - } - - if (rslt == BMM350_OK) - { - out_data->out_ust_x = out_ustxh - out_ustxl; - out_data->out_ust_y = out_ustyh - out_ustyl; - } - } - } - - return rslt; -} - -/*! - * @brief This internal API is used to switch from suspend mode to normal mode or forced mode. - */ -static int8_t set_powermode(enum eBmm350PowerModes_t powermode, struct bmm350_dev *dev) -{ - /* Variable to store the function result */ - int8_t rslt; - - uint8_t reg_data = powermode; - uint8_t get_avg; - - /* Array to store suspend to forced mode delay */ - uint32_t sus_to_forced_mode[4] = - { BMM350_SUS_TO_FORCEDMODE_NO_AVG_DELAY, BMM350_SUS_TO_FORCEDMODE_AVG_2_DELAY, BMM350_SUS_TO_FORCEDMODE_AVG_4_DELAY, - BMM350_SUS_TO_FORCEDMODE_AVG_8_DELAY }; - - /* Array to store suspend to forced mode fast delay */ - uint32_t sus_to_forced_mode_fast[4] = - { BMM350_SUS_TO_FORCEDMODE_FAST_NO_AVG_DELAY, BMM350_SUS_TO_FORCEDMODE_FAST_AVG_2_DELAY, - BMM350_SUS_TO_FORCEDMODE_FAST_AVG_4_DELAY, BMM350_SUS_TO_FORCEDMODE_FAST_AVG_8_DELAY }; - - uint8_t avg = 0; - uint32_t delay_us = 0; - - rslt = null_ptr_check(dev); - - if (rslt == BMM350_OK) - { - /* Set PMU command configuration to desired power mode */ - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, ®_data, 1, dev); - - if (rslt == BMM350_OK) - { - /* Get average configuration */ - rslt = bmm350GetRegs(BMM350_REG_PMU_CMD_AGGR_SET, &get_avg, 1, dev); - - if (rslt == BMM350_OK) - { - /* Mask the average value */ - avg = ((get_avg & BMM350_AVG_MSK) >> BMM350_AVG_POS); - } - } - } - - if (rslt == BMM350_OK) - { - /* Check if desired power mode is normal mode */ - if (powermode == eBmm350NormalMode) - { - delay_us = BMM350_SUSPEND_TO_NORMAL_DELAY; - } - - /* Check if desired power mode is forced mode */ - if (powermode == eBmm350ForcedMode) - { - /* Store delay based on averaging mode */ - delay_us = sus_to_forced_mode[avg]; - } - - /* Check if desired power mode is forced mode fast */ - if (powermode == eBmm350ForcedModeFast) - { - /* Store delay based on averaging mode */ - delay_us = sus_to_forced_mode_fast[avg]; - } - - /* Perform delay based on power mode */ - rslt = bmm350DelayUs(delay_us, dev); - } - - return rslt; -} diff --git a/lib/DFRobot_BMM350/src/bmm350.h b/lib/DFRobot_BMM350/src/bmm350.h deleted file mode 100644 index e1653fe..0000000 --- a/lib/DFRobot_BMM350/src/bmm350.h +++ /dev/null @@ -1,595 +0,0 @@ -/** -* Copyright (c) 2023 Bosch Sensortec GmbH. All rights reserved. -* -* BSD-3-Clause -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in the -* documentation and/or other materials provided with the distribution. -* -* 3. Neither the name of the copyright holder nor the names of its -* contributors may be used to endorse or promote products derived from -* this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) -* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, -* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING -* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -* @file bmm350.h -* @date 2023-05-26 -* @version v1.4.0 -* -*/ - -/*! - * @defgroup bmm350 BMM350 - * @brief Sensor driver for BMM350 sensor - */ - -#ifndef _BMM350_H -#define _BMM350_H - -/*! CPP guard */ -#ifdef __cplusplus -extern "C" { -#endif - -/*************************** Header files *******************************/ - -#include "bmm350_defs.h" - -/******************* Function prototype declarations ********************/ - -/** - * \ingroup bmm350 - * \defgroup bmm350ApiInit Initialization - * @brief Initialize the sensor and device structure - */ - -/*! -* \ingroup bmm350ApiInit -* \page bmm350_api_bmm350Init bmm350Init -* \code -* int8_t bmm350Init(struct bmm350_dev *dev); -* \endcode -* @details This API is the entry point. Call this API before using other APIs. -* This API reads the chip-id of the sensor which is the first step to -* verify the sensor and also it configures the read mechanism of I2C and -* I3C interface. -* -* @param[in,out] dev : Structure instance of bmm350_dev -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350Init(struct bmm350_dev *dev); - -/** - * \ingroup bmm350 - * \defgroup bmm350ApiReset Reset - * @brief Reset APIs - */ - -/*! -* \ingroup bmm350ApiReset -* \page bmm350_api_bmm350SoftReset bmm350SoftReset -* \code -* int8_t bmm350SoftReset(struct bmm350_dev *dev); -* \endcode -* @details This API is used to perform soft-reset of the sensor -* where all the registers are reset to their default values. -* -* @param[in] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ - -int8_t bmm350SoftReset(struct bmm350_dev *dev); - -/** - * \ingroup bmm350 - * \defgroup bmm350ApiSetGet Set-Get - * @brief Set and Get APIs - */ - -/*! -* \ingroup bmm350ApiSetGet -* \page bmm350_api_bmm350SetRegs bmm350SetRegs -* \code -* int8_t bmm350SetRegs(uint8_t reg_addr, const uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev); -* \endcode -* @details This API writes the given data to the register address -* of the sensor. -* -* @param[in] reg_addr : Register address from where the data to be written. -* @param[in] reg_data : Pointer to data buffer which is to be written -* in the reg_addr of sensor. -* @param[in] len : No of bytes of data to write.. -* @param[in, out] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350SetRegs(uint8_t reg_addr, const uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev); - -/*! -* \ingroup bmm350ApiSetGet -* \page bmm350_api_bmm350GetRegs bmm350GetRegs -* \code -* int8_t bmm350GetRegs(uint8_t reg_addr, uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev); -* \endcode -* @details This API reads the data from the given register address of sensor. -* -* @param[in] reg_addr : Register address from where the data to be read -* @param[out] reg_data : Pointer to data buffer to store the read data. -* @param[in] len : No of bytes of data to be read. -* @param[in] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350GetRegs(uint8_t reg_addr, uint8_t *reg_data, uint16_t len, struct bmm350_dev *dev); - -/** - * \ingroup bmm350 - * \defgroup bmm350ApiDelay Delay - * @brief Delay function in microseconds - */ - -/*! -* \ingroup bmm350ApiDelay -* \page bmm350_api_bmm350DelayUs bmm350DelayUs -* \code -* int8_t bmm350DelayUs(uint32_t period_us, const struct bmm350_dev *dev); -* \endcode -* @details This function provides the delay for required time (Microsecond) as per the input provided in some of the -* APIs. -* -* @param[in] period_us : The required wait time in microsecond. -* @param[in] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350DelayUs(uint32_t period_us, const struct bmm350_dev *dev); - -/*! -* \ingroup bmm350ApiSetGet -* \page bmm350_api_bmm350GetInterruptStatus bmm350GetInterruptStatus -* \code -* int8_t bmm350GetInterruptStatus(uint8_t *drdy_status, struct bmm350_dev *dev); -* \endcode -* @details This API obtains the status flags of all interrupt -* which is used to check for the assertion of interrupts -* -* @param[in,out] drdy_status : Variable to store data ready interrupt status. -* @param[in,out] dev : Structure instance of bmm350_dev. -* -* -* @return Result of API execution status and self test result. -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350GetInterruptStatus(uint8_t *drdy_status, struct bmm350_dev *dev); - -/*! -* \ingroup bmm350ApiSetGet -* \page bmm350_api_bmm350SetPowerMode bmm350SetPowerMode -* \code -* int8_t bmm350SetPowerMode(enum eBmm350PowerModes_t powermode, struct bmm350_dev *dev); -* \endcode -* @details This API is used to set the power mode of the sensor -* -* @param[in] powermode : Set power mode -* @param[in] dev : Structure instance of bmm350_dev. -* -*@verbatim - powermode | Power mode - -------------------------|----------------------- - | eBmm350SuspendMode - | eBmm350NormalMode - | eBmm350ForcedMode - | eBmm350ForcedModeFast -*@endverbatim -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350SetPowerMode(enum eBmm350PowerModes_t powermode, struct bmm350_dev *dev); - -/*! -* \ingroup bmm350ApiSetGet -* \page bmm350_api_bmm350SetOdrPerformance bmm350SetOdrPerformance -* \code -* int8_t bmm350SetOdrPerformance(enum eBmm350DataRates_t odr, -* enum bmm350_performance_parameters avg, -* struct bmm350_dev *dev); -* -* \endcode -* @details This API sets the ODR and averaging factor. -* If ODR and performance is a combination which is not allowed, then -* the combination setting is corrected to the next lower possible setting -* -* @param[in] odr : enum eBmm350DataRates_t -* -*@verbatim - Data rate (ODR) | odr - -------------------------|----------------------- - 400Hz | BMM350_DATA_RATE_400HZ - 200Hz | BMM350_DATA_RATE_200HZ - 100Hz | BMM350_DATA_RATE_100HZ - 50Hz | BMM350_DATA_RATE_50HZ - 25Hz | BMM350_DATA_RATE_25HZ - 12.5Hz | BMM350_DATA_RATE_12_5HZ - 6.25Hz | BMM350_DATA_RATE_6_25HZ - 3.125Hz | BMM350_DATA_RATE_3_125HZ - 1.5625Hz | BMM350_DATA_RATE_1_5625HZ -*@endverbatim -* -* @param[in] avg : enum bmm350_performance_parameters -* -*@verbatim - avg | averaging factor alias - ---------------------------|------------------------------------------ - low power/highest noise | BMM350_NO_AVERAGING BMM350_LOWPOWER - lesser noise | BMM350_AVERAGING_2 BMM350_REGULARPOWER - even lesser noise | BMM350_AVERAGING_4 BMM350_LOWNOISE - lowest noise/highest power | BMM350_AVERAGING_8 BMM350_ULTRALOWNOISE -*@endverbatim -* -* @param[in,out] dev : Structure instance of bmm350_dev -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350SetOdrPerformance(enum eBmm350DataRates_t odr, - enum bmm350_performance_parameters avg, - struct bmm350_dev *dev); - -/*! -* \ingroup bmm350ApiSetGet -* \page bmm350_api_bmm350_enable_axes bmm350_enable_axes -* \code -* int8_t bmm350_enable_axes(enum eBmm350XAxisEnDis_t en_x, enum eBmm350YAxisEnDis_t en_y, enum eBmm350ZAxisEnDis_t en_z, struct bmm350_dev *dev); -* \endcode -* @details This API is used to enable or disable the magnetic -* measurement of x,y,z axes -* -* @param[in] en_x : Enable or disable X axis -* @param[in] en_y : Enable or disable Y axis -* @param[in] en_z : Enable or disable Z axis -* @param[in,out] dev : Structure instance of bmm350_dev. -* -*@verbatim - Value | Axis (en_x, en_y, en_z) - -------------------|----------------------- - BMM350_ENABLE | Enabled - BMM350_DISABLE | Disabled -*@endverbatim -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350_enable_axes(enum eBmm350XAxisEnDis_t en_x, - enum eBmm350YAxisEnDis_t en_y, - enum eBmm350ZAxisEnDis_t en_z, - struct bmm350_dev *dev); - -/** - * \ingroup bmm350 - * \defgroup bmm350ApiRead Sensortime - * @brief Reads sensortime - */ - -/*! -* \ingroup bmm350ApiRead -* \page bmm350_api_bmm350_read_sensortime bmm350_read_sensortime -* \code -* int8_t bmm350_read_sensortime(uint32_t *seconds, uint32_t *nanoseconds, struct bmm350_dev *dev); -* \endcode -* @details This API is used to read the sensor time. -* It converts the sensor time register values to the representative time value. -* Returns the sensor time in ticks. -* -* @param[out] seconds : Variable to get sensor time in seconds. -* @param[out] nanoseconds : Variable to get sensor time in nanoseconds. -* @param[in] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350_read_sensortime(uint32_t *seconds, uint32_t *nanoseconds, struct bmm350_dev *dev); - -/** - * \ingroup bmm350 - * \defgroup bmm350ApiInterrupt Enable Interrupt - * @brief Interrupt enable APIs - */ - -/*! -* \ingroup bmm350ApiInterrupt -* \page bmm350_api_bmm350_enable_interrupt bmm350_enable_interrupt -* \code -* int8_t bmm350_enable_interrupt(enum eBmm350InterruptEnableDisable_t enable_disable, struct bmm350_dev *dev); -* \endcode -* @details This API is used to enable or disable the data ready interrupt -* -* @param[in] enable_disable : Enable/ Disable data ready interrupt. -* @param[in] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350_enable_interrupt(enum eBmm350InterruptEnableDisable_t enable_disable, struct bmm350_dev *dev); - -/*! -* \ingroup bmm350ApiInterrupt -* \page bmm350_api_bmm350_configure_interrupt bmm350_configure_interrupt -* \code -* int8_t bmm350_configure_interrupt(enum bmm350_intr_latch latching, -* enum eBmm350IntrPolarity_t polarity, -* enum bmm350_intr_drive drivertype, -* enum bmm350_intr_map map_nomap, -* struct bmm350_dev *dev); -* \endcode -* @details This API is used to configure the interrupt control settings. -* -* @param[in] latching : Sets either latched or pulsed. -* @param[in] polarity : Sets either polarity high or low. -* @param[in] drivertype : Sets either open drain or push pull. -* @param[in] map_nomap : Sets either map or unmap the pins. -* @param[in] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350_configure_interrupt(enum bmm350_intr_latch latching, - enum eBmm350IntrPolarity_t polarity, - enum bmm350_intr_drive drivertype, - enum bmm350_intr_map map_nomap, - struct bmm350_dev *dev); - -/** - * \ingroup bmm350 - * \defgroup bmm350ApiUncompMag Uncompensated mag - * @brief Reads uncompensated mag and temperature data - */ - -/*! -* \ingroup bmm350ApiUncompMag -* \page bmm350_api_bmm350_read_uncomp_mag_temp_data bmm350_read_uncomp_mag_temp_data -* \code -* int8_t bmm350_read_uncomp_mag_temp_data(struct bmm350_raw_mag_data *raw_data, struct bmm350_dev *dev); -* \endcode -* @details This API is used to read uncompensated mag and temperature data -* -* @param[in, out] raw_data : Structure instance of bmm350_raw_mag_data. -* @param[in, out] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350_read_uncomp_mag_temp_data(struct bmm350_raw_mag_data *raw_data, struct bmm350_dev *dev); - -/*! -* \ingroup bmm350ApiSetGet -* \page bmm350_api_bmm350_set_int_ctrl_ibi bmm350_set_int_ctrl_ibi -* \code -* int8_t bmm350_set_int_ctrl_ibi(enum bmm350_drdy_int_map_to_ibi en_dis, -* enum bmm350_clear_drdy_int_status_upon_ibi clear_on_ibi, struct bmm350_dev *dev); -* \endcode -* @details This API sets the interrupt control IBI configurations to the sensor. -* And enables conventional interrupt if IBI is enabled. -* -* @param[in] en_dis : Sets either enable or disable IBI. -* @param[in] clear_on_ibi : sets either clear or no clear on IBI. -* @param[in] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350_set_int_ctrl_ibi(enum bmm350_drdy_int_map_to_ibi en_dis, - enum bmm350_clear_drdy_int_status_upon_ibi clear_on_ibi, - struct bmm350_dev *dev); - -/*! -* \ingroup bmm350ApiSetGet -* \page bmm350_api_bmm350_set_pad_drive bmm350_set_pad_drive -* \code -* int8_t bmm350_set_pad_drive(uint8_t drive, struct bmm350_dev *dev); -* \endcode -* @details This API is used to set the pad drive strength -* -* @param[in] drive : Drive settings, range 0 (weak) ..7(strong) -* @param[in] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350_set_pad_drive(uint8_t drive, struct bmm350_dev *dev); - -/*! -* \ingroup bmm350ApiReset -* \page bmm350_api_bmm350_magnetic_reset_and_wait bmm350_magnetic_reset_and_wait -* \code -* int8_t bmm350_magnetic_reset_and_wait(struct bmm350_dev *dev) -* \endcode -* @details This API is used to perform the magnetic reset of the sensor -* which is necessary after a field shock (400mT field applied to sensor). -* It sends flux guide or bit reset to the device in suspend mode. -* -* @param[in] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350_magnetic_reset_and_wait(struct bmm350_dev *dev); - -/** - * \ingroup bmm350 - * \defgroup bmm350ApiMagComp Compensation - * @brief Compensation for mag x,y,z axis and temperature API - */ - -/*! -* \ingroup bmm350ApiMagComp -* \page bmm350_api_bmm350GetCompensatedMagXYZTempData bmm350GetCompensatedMagXYZTempData -* \code -* int8_t bmm350GetCompensatedMagXYZTempData(struct sBmm350MagTempData_t *mag_temp_data, struct bmm350_dev *dev); -* \endcode -* @details This API is used to perform compensation for raw magnetometer and temperature data. -* -* @param[out] mag_temp_data : Structure instance of sBmm350MagTempData_t. -* @param[in] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350GetCompensatedMagXYZTempData(struct sBmm350MagTempData_t *mag_temp_data, struct bmm350_dev *dev); - -/** - * \ingroup bmm350 - * \defgroup bmm350ApiSelftest Self-test - * @brief Perform self-test for x and y axis - */ - -/*! -* \ingroup bmm350ApiSelftest -* \page bmm350_api_bmm350PerformSelfTest bmm350PerformSelfTest -* \code -* int8_t bmm350PerformSelfTest(struct sBmm350SelfTest_t *out_data, struct bmm350_dev *dev); -* \endcode -* @details This API executes FGR and BR sequences to initialize TMR sensor and performs self-test for x and y axis. -* -* @param[in, out] out_data : Structure instance of sBmm350SelfTest_t. -* @param[in] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350PerformSelfTest(struct sBmm350SelfTest_t *out_data, struct bmm350_dev *dev); - -/*! -* \ingroup bmm350ApiSetGet -* \page bmm350_api_bmm350_set_i2c_wdt bmm350_set_i2c_wdt -* \code -* int8_t bmm350_set_i2c_wdt(enum bmm350_i2c_wdt_en i2c_wdt_en_dis, enum bmm350_i2c_wdt_sel i2c_wdt_sel, -* struct bmm350_dev *dev); -* \endcode -* @details This API sets the I2C watchdog timer configurations to the sensor. -* -* @param[in] i2c_wdt_en_dis : Enable/ Disable I2C watchdog timer. -* @param[in] i2c_wdt_sel : I2C watchdog timer selection period. -* @param[in] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350_set_i2c_wdt(enum bmm350_i2c_wdt_en i2c_wdt_en_dis, - enum bmm350_i2c_wdt_sel i2c_wdt_sel, - struct bmm350_dev *dev); - -/*! -* \ingroup bmm350ApiSetGet -* \page bmm350_api_bmm350_set_tmr_selftest_user bmm350_set_tmr_selftest_user -* \code -* int8_t bmm350_set_tmr_selftest_user(enum bmm350_st_igen_en st_igen_en_dis, -* enum bmm350_st_n st_n_en_dis, -* enum bmm350_st_p st_p_en_dis, -* enum bmm350_ist_en_x ist_x_en_dis, -* enum bmm350_ist_en_y ist_y_en_dis, -* struct bmm350_dev *dev); -* \endcode -* @details This API sets the TMR user self-test register -* -* @param[in] st_igen_en_dis : Enable/ Disable self-test internal current gen. -* @param[in] st_n_en_dis : Enable/ Disable dc_st_n signal. -* @param[in] st_p_en_dis : Enable/ Disable dc_st_p signal. -* @param[in] ist_x_en_dis : Enable/ Disable dc_ist_en_x signal. -* @param[in] ist_y_en_dis : Enable/ Disable dc_ist_en_y signal. -* @param[in] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350_set_tmr_selftest_user(enum bmm350_st_igen_en st_igen_en_dis, - enum bmm350_st_n st_n_en_dis, - enum bmm350_st_p st_p_en_dis, - enum bmm350_ist_en_x ist_x_en_dis, - enum bmm350_ist_en_y ist_y_en_dis, - struct bmm350_dev *dev); - -/*! -* \ingroup bmm350ApiSetGet -* \page bmm350_api_bmm350_set_ctrl_user bmm350_set_ctrl_user -* \code -* int8_t bmm350_set_ctrl_user(enum bmm350_ctrl_user cfg_sens_tim_aon_en_dis, struct bmm350_dev *dev); -* \endcode -* @details This API sets the control user configurations to the sensor. -* -* @param[in] cfg_sens_tim_aon_en_dis : Enable/ Disable configuration of sensor time to run on suspend mode. -* @param[in] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350_set_ctrl_user(enum bmm350_ctrl_user cfg_sens_tim_aon_en_dis, struct bmm350_dev *dev); - -/*! -* \ingroup bmm350ApiSetGet -* \page bmm350_api_bmm350_get_pmu_cmd_status_0 bmm350_get_pmu_cmd_status_0 -* \code -* int8_t bmm350_get_pmu_cmd_status_0(struct bmm350_pmu_cmd_status_0 *pmu_cmd_stat_0, struct bmm350_dev *dev); -* \endcode -* @details This API gets the PMU command status 0 value. -* -* @param[out] pmu_cmd_stat_0 : Structure instance of bmm350_pmu_cmd_status_0. -* @param[in] dev : Structure instance of bmm350_dev. -* -* @return Result of API execution status -* @retval = 0 -> Success -* @retval < 0 -> Error -*/ -int8_t bmm350_get_pmu_cmd_status_0(struct bmm350_pmu_cmd_status_0 *pmu_cmd_stat_0, struct bmm350_dev *dev); - -#ifdef __cplusplus -} -#endif /* End of CPP guard */ - -#endif /* _BMM350_H */ diff --git a/lib/DFRobot_BMM350/src/bmm350_defs.h b/lib/DFRobot_BMM350/src/bmm350_defs.h deleted file mode 100644 index cb9a59c..0000000 --- a/lib/DFRobot_BMM350/src/bmm350_defs.h +++ /dev/null @@ -1,1215 +0,0 @@ -/** -* Copyright (c) 2023 Bosch Sensortec GmbH. All rights reserved. -* -* BSD-3-Clause -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in the -* documentation and/or other materials provided with the distribution. -* -* 3. Neither the name of the copyright holder nor the names of its -* contributors may be used to endorse or promote products derived from -* this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) -* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, -* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING -* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -* @file bmm350_defs.h -* @date 2023-05-26 -* @version v1.4.0 -* -*/ - -#ifndef _BMM350_DEFS_H -#define _BMM350_DEFS_H - -/*************************** Header files *******************************/ - -#ifdef __KERNEL__ -#include -#include -#else -#include -#include -#endif - -/***************************** Common Macros *****************************/ - -#ifdef __KERNEL__ -#if !defined(UINT8_C) && !defined(INT8_C) -#define INT8_C(x) S8_C(x) -#define UINT8_C(x) U8_C(x) -#endif - -#if !defined(UINT16_C) && !defined(INT16_C) -#define INT16_C(x) S16_C(x) -#define UINT16_C(x) U16_C(x) -#endif - -#if !defined(INT32_C) && !defined(UINT32_C) -#define INT32_C(x) S32_C(x) -#define UINT32_C(x) U32_C(x) -#endif - -#if !defined(INT64_C) && !defined(UINT64_C) -#define INT64_C(x) S64_C(x) -#define UINT64_C(x) U64_C(x) -#endif -#endif - -/*! C standard macros */ -#ifndef NULL -#ifdef __cplusplus -#define NULL 0 -#else -#define NULL ((void *) 0) -#endif -#endif - -/******************************************************************************/ -/*! @name Compiler switch macros Definitions */ -/******************************************************************************/ - -/************************* General Macro definitions ***************************/ - -/* Macro to SET and GET BITS of a register*/ -#define BMM350_SET_BITS(reg_data, bitname, data) \ - ((reg_data & ~(bitname##_MSK)) | \ - ((data << bitname##_POS) & bitname##_MSK)) - -#define BMM350_GET_BITS(reg_data, bitname) ((reg_data & (bitname##_MSK)) >> (bitname##_POS)) - -#define BMM350_GET_BITS_POS_0(reg_data, bitname) (reg_data & (bitname##_MSK)) - -#define BMM350_SET_BITS_POS_0(reg_data, bitname, data) \ - ((reg_data & ~(bitname##_MSK)) | \ - (data & bitname##_MSK)) - -#ifndef BMM350_INTF_RET_TYPE -#define BMM350_INTF_RET_TYPE int8_t -#endif - -#define UNUSED(x) (void)(x) - -/*! Chip id of BMM350 */ -#define BMM350_CHIP_ID UINT8_C(0x33) - -/*! Variant ID of BMM350 */ -#define BMM350_MIN_VAR UINT8_C(0x10) - -/************************* Sensor interface success code **************************/ -#define BMM350_INTF_RET_SUCCESS INT8_C(0) - -/************************* API success code **************************/ -#define BMM350_OK INT8_C(0) - -/* API error codes */ -#define BMM350_E_NULL_PTR INT8_C(-1) -#define BMM350_E_COM_FAIL INT8_C(-2) -#define BMM350_E_DEV_NOT_FOUND INT8_C(-3) -#define BMM350_E_INVALID_CONFIG INT8_C(-4) -#define BMM350_E_BAD_PAD_DRIVE INT8_C(-5) -#define BMM350_E_RESET_UNFINISHED INT8_C(-6) -#define BMM350_E_INVALID_INPUT INT8_C(-7) -#define BMM350_E_SELF_TEST_INVALID_AXIS INT8_C(-8) -#define BMM350_E_OTP_BOOT INT8_C(-9) -#define BMM350_E_OTP_PAGE_RD INT8_C(-10) -#define BMM350_E_OTP_PAGE_PRG INT8_C(-11) -#define BMM350_E_OTP_SIGN INT8_C(-12) -#define BMM350_E_OTP_INV_CMD INT8_C(-13) -#define BMM350_E_OTP_UNDEFINED INT8_C(-14) -#define BMM350_E_ALL_AXIS_DISABLED INT8_C(-15) -#define BMM350_E_PMU_CMD_VALUE INT8_C(-16) - -#define BMM350_NO_ERROR UINT8_C(0) - -/************************* Sensor delay time settings in microseconds **************************/ -#define BMM350_SOFT_RESET_DELAY UINT32_C(24000) -#define BMM350_MAGNETIC_RESET_DELAY UINT32_C(40000) -#define BMM350_START_UP_TIME_FROM_POR UINT32_C(3000) - -#define BMM350_GOTO_SUSPEND_DELAY UINT32_C(6000) -#define BMM350_SUSPEND_TO_NORMAL_DELAY UINT32_C(38000) - -#define BMM350_SUS_TO_FORCEDMODE_NO_AVG_DELAY UINT32_C(15000) -#define BMM350_SUS_TO_FORCEDMODE_AVG_2_DELAY UINT32_C(17000) -#define BMM350_SUS_TO_FORCEDMODE_AVG_4_DELAY UINT32_C(20000) -#define BMM350_SUS_TO_FORCEDMODE_AVG_8_DELAY UINT32_C(28000) - -#define BMM350_SUS_TO_FORCEDMODE_FAST_NO_AVG_DELAY UINT32_C(4000) -#define BMM350_SUS_TO_FORCEDMODE_FAST_AVG_2_DELAY UINT32_C(5000) -#define BMM350_SUS_TO_FORCEDMODE_FAST_AVG_4_DELAY UINT32_C(9000) -#define BMM350_SUS_TO_FORCEDMODE_FAST_AVG_8_DELAY UINT32_C(16000) - -#define BMM350_UPD_OAE_DELAY UINT16_C(1000) - -#define BMM350_BR_DELAY UINT16_C(14000) -#define BMM350_FGR_DELAY UINT16_C(18000) - -/************************ Length macros ************************/ -#define BMM350_OTP_DATA_LENGTH UINT8_C(32) -#define BMM350_READ_BUFFER_LENGTH UINT8_C(127) -#define BMM350_MAG_TEMP_DATA_LEN UINT8_C(12) - -/************************ Averaging macros **********************/ -#define BMM350_AVG_NO_AVG UINT8_C(0x0) -#define BMM350_AVG_2 UINT8_C(0x1) -#define BMM350_AVG_4 UINT8_C(0x2) -#define BMM350_AVG_8 UINT8_C(0x3) - -/******************************* ODR **************************/ -#define BMM350_ODR_400HZ UINT8_C(0x2) -#define BMM350_ODR_200HZ UINT8_C(0x3) -#define BMM350_ODR_100HZ UINT8_C(0x4) -#define BMM350_ODR_50HZ UINT8_C(0x5) -#define BMM350_ODR_25HZ UINT8_C(0x6) -#define BMM350_ODR_12_5HZ UINT8_C(0x7) -#define BMM350_ODR_6_25HZ UINT8_C(0x8) -#define BMM350_ODR_3_125HZ UINT8_C(0x9) -#define BMM350_ODR_1_5625HZ UINT8_C(0xA) - -/********************* Power modes *************************/ -#define BMM350_PMU_CMD_SUS UINT8_C(0x00) -#define BMM350_PMU_CMD_NM UINT8_C(0x01) -#define BMM350_PMU_CMD_UPD_OAE UINT8_C(0x02) -#define BMM350_PMU_CMD_FM UINT8_C(0x03) -#define BMM350_PMU_CMD_FM_FAST UINT8_C(0x04) -#define BMM350_PMU_CMD_FGR UINT8_C(0x05) -#define BMM350_PMU_CMD_FGR_FAST UINT8_C(0x06) -#define BMM350_PMU_CMD_BR UINT8_C(0x07) -#define BMM350_PMU_CMD_BR_FAST UINT8_C(0x08) -#define BMM350_PMU_CMD_NM_TC UINT8_C(0x09) - -#define BMM350_PMU_STATUS_0 UINT8_C(0x0) - -#define BMM350_DISABLE UINT8_C(0x0) -#define BMM350_ENABLE UINT8_C(0x1) - -#define BMM350_CMD_NOP UINT8_C(0x0) -#define BMM350_CMD_SOFTRESET UINT8_C(0xB6) - -#define BMM350_TARGET_PAGE_PAGE0 UINT8_C(0x0) -#define BMM350_TARGET_PAGE_PAGE1 UINT8_C(0x1) - -#define BMM350_INT_MODE_LATCHED UINT8_C(0x1) -#define BMM350_INT_MODE_PULSED UINT8_C(0x0) - -#define BMM350_INT_POL_ACTIVE_HIGH UINT8_C(0x1) -#define BMM350_INT_POL_ACTIVE_LOW UINT8_C(0x0) - -#define BMM350_INT_OD_PUSHPULL UINT8_C(0x1) -#define BMM350_INT_OD_OPENDRAIN UINT8_C(0x0) - -#define BMM350_INT_OUTPUT_EN_OFF UINT8_C(0x0) -#define BMM350_INT_OUTPUT_EN_ON UINT8_C(0x1) - -#define BMM350_INT_DRDY_EN UINT8_C(0x1) -#define BMM350_INT_DRDY_DIS UINT8_C(0x0) - -#define BMM350_MR_MR1K8 UINT8_C(0x0) -#define BMM350_MR_MR2K1 UINT8_C(0x1) -#define BMM350_MR_MR1K5 UINT8_C(0x2) -#define BMM350_MR_MR0K6 UINT8_C(0x3) - -#define BMM350_SEL_DTB1X_PAD_PAD_INT UINT8_C(0x0) -#define BMM350_SEL_DTB1X_PAD_PAD_BYP UINT8_C(0x1) - -#define BMM350_TMR_TST_HIZ_VTMR_VTMR_ON UINT8_C(0x0) -#define BMM350_TMR_TST_HIZ_VTMR_VTMR_HIZ UINT8_C(0x1) - -#define BMM350_LSB_MASK UINT16_C(0x00FF) -#define BMM350_MSB_MASK UINT16_C(0xFF00) - -/********************** Pad drive strength ************************/ -#define BMM350_PAD_DRIVE_WEAKEST UINT8_C(0) -#define BMM350_PAD_DRIVE_STRONGEST UINT8_C(7) - -/********************** I2C Register Addresses ************************/ - -/*! Register to set I2C address to LOW */ -#define BMM350_I2C_ADSEL_SET_LOW UINT8_C(0x14) - -/*! Register to set I2C address to HIGH */ -#define BMM350_I2C_ADSEL_SET_HIGH UINT8_C(0x15) - -#define BMM350_DUMMY_BYTES UINT8_C(2) - -/********************** Register Addresses ************************/ - -#define BMM350_REG_CHIP_ID UINT8_C(0x00) -#define BMM350_REG_REV_ID UINT8_C(0x01) -#define BMM350_REG_ERR_REG UINT8_C(0x02) -#define BMM350_REG_PAD_CTRL UINT8_C(0x03) -#define BMM350_REG_PMU_CMD_AGGR_SET UINT8_C(0x04) -#define BMM350_REG_PMU_CMD_AXIS_EN UINT8_C(0x05) -#define BMM350_REG_PMU_CMD UINT8_C(0x06) -#define BMM350_REG_PMU_CMD_STATUS_0 UINT8_C(0x07) -#define BMM350_REG_PMU_CMD_STATUS_1 UINT8_C(0x08) -#define BMM350_REG_I3C_ERR UINT8_C(0x09) -#define BMM350_REG_I2C_WDT_SET UINT8_C(0x0A) -#define BMM350_REG_TRSDCR_REV_ID UINT8_C(0x0D) -#define BMM350_REG_TC_SYNC_TU UINT8_C(0x21) -#define BMM350_REG_TC_SYNC_ODR UINT8_C(0x22) -#define BMM350_REG_TC_SYNC_TPH_1 UINT8_C(0x23) -#define BMM350_REG_TC_SYNC_TPH_2 UINT8_C(0x24) -#define BMM350_REG_TC_SYNC_DT UINT8_C(0x25) -#define BMM350_REG_TC_SYNC_ST_0 UINT8_C(0x26) -#define BMM350_REG_TC_SYNC_ST_1 UINT8_C(0x27) -#define BMM350_REG_TC_SYNC_ST_2 UINT8_C(0x28) -#define BMM350_REG_TC_SYNC_STATUS UINT8_C(0x29) -#define BMM350_REG_INT_CTRL UINT8_C(0x2E) -#define BMM350_REG_INT_CTRL_IBI UINT8_C(0x2F) -#define BMM350_REG_INT_STATUS UINT8_C(0x30) -#define BMM350_REG_MAG_X_XLSB UINT8_C(0x31) -#define BMM350_REG_MAG_X_LSB UINT8_C(0x32) -#define BMM350_REG_MAG_X_MSB UINT8_C(0x33) -#define BMM350_REG_MAG_Y_XLSB UINT8_C(0x34) -#define BMM350_REG_MAG_Y_LSB UINT8_C(0x35) -#define BMM350_REG_MAG_Y_MSB UINT8_C(0x36) -#define BMM350_REG_MAG_Z_XLSB UINT8_C(0x37) -#define BMM350_REG_MAG_Z_LSB UINT8_C(0x38) -#define BMM350_REG_MAG_Z_MSB UINT8_C(0x39) -#define BMM350_REG_TEMP_XLSB UINT8_C(0x3A) -#define BMM350_REG_TEMP_LSB UINT8_C(0x3B) -#define BMM350_REG_TEMP_MSB UINT8_C(0x3C) -#define BMM350_REG_SENSORTIME_XLSB UINT8_C(0x3D) -#define BMM350_REG_SENSORTIME_LSB UINT8_C(0x3E) -#define BMM350_REG_SENSORTIME_MSB UINT8_C(0x3F) -#define BMM350_REG_OTP_CMD_REG UINT8_C(0x50) -#define BMM350_REG_OTP_DATA_MSB_REG UINT8_C(0x52) -#define BMM350_REG_OTP_DATA_LSB_REG UINT8_C(0x53) -#define BMM350_REG_OTP_STATUS_REG UINT8_C(0x55) -#define BMM350_REG_TMR_SELFTEST_USER UINT8_C(0x60) -#define BMM350_REG_CTRL_USER UINT8_C(0x61) -#define BMM350_REG_CMD UINT8_C(0x7E) - -/*********************** Macros for OVWR ***************************/ -#define BMM350_REG_OVWR_VALUE_ANA_0 UINT8_C(0x3A) -#define BMM350_REG_OVWR_EN_ANA_0 UINT8_C(0x3B) - -/*********************** Macros for bit masking ***************************/ - -#define BMM350_CHIP_ID_OTP_MSK UINT8_C(0xf) -#define BMM350_CHIP_ID_OTP_POS UINT8_C(0x0) -#define BMM350_CHIP_ID_FIXED_MSK UINT8_C(0xf0) -#define BMM350_CHIP_ID_FIXED_POS UINT8_C(0x4) -#define BMM350_REV_ID_MAJOR_MSK UINT8_C(0xf0) -#define BMM350_REV_ID_MAJOR_POS UINT8_C(0x4) -#define BMM350_REV_ID_MINOR_MSK UINT8_C(0xf) -#define BMM350_REV_ID_MINOR_POS UINT8_C(0x0) -#define BMM350_PMU_CMD_ERROR_MSK UINT8_C(0x1) -#define BMM350_PMU_CMD_ERROR_POS UINT8_C(0x0) -#define BMM350_BOOT_UP_ERROR_MSK UINT8_C(0x2) -#define BMM350_BOOT_UP_ERROR_POS UINT8_C(0x1) -#define BMM350_DRV_MSK UINT8_C(0x7) -#define BMM350_DRV_POS UINT8_C(0x0) -#define BMM350_AVG_MSK UINT8_C(0x30) -#define BMM350_AVG_POS UINT8_C(0x4) -#define BMM350_ODR_MSK UINT8_C(0xf) -#define BMM350_ODR_POS UINT8_C(0x0) -#define BMM350_PMU_CMD_MSK UINT8_C(0xf) -#define BMM350_PMU_CMD_POS UINT8_C(0x0) -#define BMM350_EN_X_MSK UINT8_C(0x01) -#define BMM350_EN_X_POS UINT8_C(0x0) -#define BMM350_EN_Y_MSK UINT8_C(0x02) -#define BMM350_EN_Y_POS UINT8_C(0x1) -#define BMM350_EN_Z_MSK UINT8_C(0x04) -#define BMM350_EN_Z_POS UINT8_C(0x2) -#define BMM350_EN_XYZ_MSK UINT8_C(0x7) -#define BMM350_EN_XYZ_POS UINT8_C(0x0) -#define BMM350_PMU_CMD_BUSY_MSK UINT8_C(0x1) -#define BMM350_PMU_CMD_BUSY_POS UINT8_C(0x0) -#define BMM350_ODR_OVWR_MSK UINT8_C(0x2) -#define BMM350_ODR_OVWR_POS UINT8_C(0x1) -#define BMM350_AVG_OVWR_MSK UINT8_C(0x4) -#define BMM350_AVG_OVWR_POS UINT8_C(0x2) -#define BMM350_PWR_MODE_IS_NORMAL_MSK UINT8_C(0x8) -#define BMM350_PWR_MODE_IS_NORMAL_POS UINT8_C(0x3) -#define BMM350_CMD_IS_ILLEGAL_MSK UINT8_C(0x10) -#define BMM350_CMD_IS_ILLEGAL_POS UINT8_C(0x4) -#define BMM350_PMU_CMD_VALUE_MSK UINT8_C(0xE0) -#define BMM350_PMU_CMD_VALUE_POS UINT8_C(0x5) -#define BMM350_PMU_ODR_S_MSK UINT8_C(0xf) -#define BMM350_PMU_ODR_S_POS UINT8_C(0x0) -#define BMM350_PMU_AVG_S_MSK UINT8_C(0x30) -#define BMM350_PMU_AVG_S_POS UINT8_C(0x4) -#define BMM350_I3C_ERROR_0_MSK UINT8_C(0x1) -#define BMM350_I3C_ERROR_0_POS UINT8_C(0x0) -#define BMM350_I3C_ERROR_3_MSK UINT8_C(0x8) -#define BMM350_I3C_ERROR_3_POS UINT8_C(0x3) -#define BMM350_I2C_WDT_EN_MSK UINT8_C(0x1) -#define BMM350_I2C_WDT_EN_POS UINT8_C(0x0) -#define BMM350_I2C_WDT_SEL_MSK UINT8_C(0x2) -#define BMM350_I2C_WDT_SEL_POS UINT8_C(0x1) -#define BMM350_TRSDCR_REV_ID_OTP_MSK UINT8_C(0x3) -#define BMM350_TRSDCR_REV_ID_OTP_POS UINT8_C(0x0) -#define BMM350_TRSDCR_REV_ID_FIXED_MSK UINT8_C(0xfc) -#define BMM350_TRSDCR_REV_ID_FIXED_POS UINT8_C(0x2) -#define BMM350_PAGING_EN_MSK UINT8_C(0x80) -#define BMM350_PAGING_EN_POS UINT8_C(0x7) -#define BMM350_DRDY_DATA_REG_MSK UINT8_C(0x4) -#define BMM350_DRDY_DATA_REG_POS UINT8_C(0x2) -#define BMM350_INT_MODE_MSK UINT8_C(0x1) -#define BMM350_INT_MODE_POS UINT8_C(0x0) -#define BMM350_INT_POL_MSK UINT8_C(0x2) -#define BMM350_INT_POL_POS UINT8_C(0x1) -#define BMM350_INT_OD_MSK UINT8_C(0x4) -#define BMM350_INT_OD_POS UINT8_C(0x2) -#define BMM350_INT_OUTPUT_EN_MSK UINT8_C(0x8) -#define BMM350_INT_OUTPUT_EN_POS UINT8_C(0x3) -#define BMM350_DRDY_DATA_REG_EN_MSK UINT8_C(0x80) -#define BMM350_DRDY_DATA_REG_EN_POS UINT8_C(0x7) -#define BMM350_DRDY_INT_MAP_TO_IBI_MSK UINT8_C(0x1) -#define BMM350_DRDY_INT_MAP_TO_IBI_POS UINT8_C(0x0) -#define BMM350_CLEAR_DRDY_INT_STATUS_UPON_IBI_MSK UINT8_C(0x10) -#define BMM350_CLEAR_DRDY_INT_STATUS_UPON_IBI_POS UINT8_C(0x4) -#define BMM350_TC_SYNC_TU_MSK UINT8_C(0xff) -#define BMM350_TC_SYNC_ODR_MSK UINT8_C(0xff) -#define BMM350_TC_SYNC_TPH_1_MSK UINT8_C(0xff) -#define BMM350_TC_SYNC_TPH_2_MSK UINT8_C(0xff) -#define BMM350_TC_SYNC_DT_MSK UINT8_C(0xff) -#define BMM350_TC_SYNC_ST_0_MSK UINT8_C(0xff) -#define BMM350_TC_SYNC_ST_1_MSK UINT8_C(0xff) -#define BMM350_TC_SYNC_ST_2_MSK UINT8_C(0xff) -#define BMM350_CFG_FORCE_SOSC_EN_MSK UINT8_C(0x4) -#define BMM350_CFG_FORCE_SOSC_EN_POS UINT8_C(0x2) -#define BMM350_ST_IGEN_EN_MSK UINT8_C(0x1) -#define BMM350_ST_IGEN_EN_POS UINT8_C(0x0) -#define BMM350_ST_N_MSK UINT8_C(0x2) -#define BMM350_ST_N_POS UINT8_C(0x1) -#define BMM350_ST_P_MSK UINT8_C(0x4) -#define BMM350_ST_P_POS UINT8_C(0x2) -#define BMM350_IST_EN_X_MSK UINT8_C(0x8) -#define BMM350_IST_EN_X_POS UINT8_C(0x3) -#define BMM350_IST_EN_Y_MSK UINT8_C(0x10) -#define BMM350_IST_EN_Y_POS UINT8_C(0x4) -#define BMM350_CFG_SENS_TIM_AON_MSK UINT8_C(0x1) -#define BMM350_CFG_SENS_TIM_AON_POS UINT8_C(0x0) -#define BMM350_DATA_X_7_0_MSK UINT8_C(0xff) -#define BMM350_DATA_X_7_0_POS UINT8_C(0x0) -#define BMM350_DATA_X_15_8_MSK UINT8_C(0xff) -#define BMM350_DATA_X_15_8_POS UINT8_C(0x0) -#define BMM350_DATA_X_23_16_MSK UINT8_C(0xff) -#define BMM350_DATA_X_23_16_POS UINT8_C(0x0) -#define BMM350_DATA_Y_7_0_MSK UINT8_C(0xff) -#define BMM350_DATA_Y_7_0_POS UINT8_C(0x0) -#define BMM350_DATA_Y_15_8_MSK UINT8_C(0xff) -#define BMM350_DATA_Y_15_8_POS UINT8_C(0x0) -#define BMM350_DATA_Y_23_16_MSK UINT8_C(0xff) -#define BMM350_DATA_Y_23_16_POS UINT8_C(0x0) -#define BMM350_DATA_Z_7_0_MSK UINT8_C(0xff) -#define BMM350_DATA_Z_7_0_POS UINT8_C(0x0) -#define BMM350_DATA_Z_15_8_MSK UINT8_C(0xff) -#define BMM350_DATA_Z_15_8_POS UINT8_C(0x0) -#define BMM350_DATA_Z_23_16_MSK UINT8_C(0xff) -#define BMM350_DATA_Z_23_16_POS UINT8_C(0x0) -#define BMM350_DATA_T_7_0_MSK UINT8_C(0xff) -#define BMM350_DATA_T_7_0_POS UINT8_C(0x0) -#define BMM350_DATA_T_15_8_MSK UINT8_C(0xff) -#define BMM350_DATA_T_15_8_POS UINT8_C(0x0) -#define BMM350_DATA_T_23_16_MSK UINT8_C(0xff) -#define BMM350_DATA_T_23_16_POS UINT8_C(0x0) -#define BMM350_DATA_ST_7_0_MSK UINT8_C(0xff) -#define BMM350_DATA_ST_7_0_POS UINT8_C(0x0) -#define BMM350_DATA_ST_15_8_MSK UINT8_C(0xff) -#define BMM350_DATA_ST_15_8_POS UINT8_C(0x0) -#define BMM350_DATA_ST_23_16_MSK UINT8_C(0xff) -#define BMM350_DATA_ST_23_16_POS UINT8_C(0x0) -#define BMM350_SIGN_INVERT_T_MSK UINT8_C(0x10) -#define BMM350_SIGN_INVERT_T_POS UINT8_C(0x4) -#define BMM350_SIGN_INVERT_X_MSK UINT8_C(0x20) -#define BMM350_SIGN_INVERT_X_POS UINT8_C(0x5) -#define BMM350_SIGN_INVERT_Y_MSK UINT8_C(0x40) -#define BMM350_SIGN_INVERT_Y_POS UINT8_C(0x6) -#define BMM350_SIGN_INVERT_Z_MSK UINT8_C(0x80) -#define BMM350_SIGN_INVERT_Z_POS UINT8_C(0x7) -#define BMM350_DIS_BR_NM_MSK UINT8_C(0x1) -#define BMM350_DIS_BR_NM_POS UINT8_C(0x0) -#define BMM350_DIS_FGR_NM_MSK UINT8_C(0x2) -#define BMM350_DIS_FGR_NM_POS UINT8_C(0x1) -#define BMM350_DIS_CRST_AT_ALL_MSK UINT8_C(0x4) -#define BMM350_DIS_CRST_AT_ALL_POS UINT8_C(0x2) -#define BMM350_DIS_BR_FM_MSK UINT8_C(0x8) -#define BMM350_DIS_BR_FM_POS UINT8_C(0x3) -#define BMM350_FRC_EN_BUFF_MSK UINT8_C(0x1) -#define BMM350_FRC_EN_BUFF_POS UINT8_C(0x0) -#define BMM350_FRC_INA_EN1_MSK UINT8_C(0x2) -#define BMM350_FRC_INA_EN1_POS UINT8_C(0x1) -#define BMM350_FRC_INA_EN2_MSK UINT8_C(0x4) -#define BMM350_FRC_INA_EN2_POS UINT8_C(0x2) -#define BMM350_FRC_ADC_EN_MSK UINT8_C(0x8) -#define BMM350_FRC_ADC_EN_POS UINT8_C(0x3) -#define BMM350_FRC_INA_RST_MSK UINT8_C(0x10) -#define BMM350_FRC_INA_RST_POS UINT8_C(0x4) -#define BMM350_FRC_ADC_RST_MSK UINT8_C(0x20) -#define BMM350_FRC_ADC_RST_POS UINT8_C(0x5) -#define BMM350_FRC_INA_XSEL_MSK UINT8_C(0x1) -#define BMM350_FRC_INA_XSEL_POS UINT8_C(0x0) -#define BMM350_FRC_INA_YSEL_MSK UINT8_C(0x2) -#define BMM350_FRC_INA_YSEL_POS UINT8_C(0x1) -#define BMM350_FRC_INA_ZSEL_MSK UINT8_C(0x4) -#define BMM350_FRC_INA_ZSEL_POS UINT8_C(0x2) -#define BMM350_FRC_ADC_TEMP_EN_MSK UINT8_C(0x8) -#define BMM350_FRC_ADC_TEMP_EN_POS UINT8_C(0x3) -#define BMM350_FRC_TSENS_EN_MSK UINT8_C(0x10) -#define BMM350_FRC_TSENS_EN_POS UINT8_C(0x4) -#define BMM350_DSENS_FM_MSK UINT8_C(0x20) -#define BMM350_DSENS_FM_POS UINT8_C(0x5) -#define BMM350_DSENS_SEL_MSK UINT8_C(0x40) -#define BMM350_DSENS_SEL_POS UINT8_C(0x6) -#define BMM350_DSENS_SHORT_MSK UINT8_C(0x80) -#define BMM350_DSENS_SHORT_POS UINT8_C(0x7) -#define BMM350_ERR_MISS_BR_DONE_MSK UINT8_C(0x1) -#define BMM350_ERR_MISS_BR_DONE_POS UINT8_C(0x0) -#define BMM350_ERR_MISS_FGR_DONE_MSK UINT8_C(0x2) -#define BMM350_ERR_MISS_FGR_DONE_POS UINT8_C(0x1) -#define BMM350_TST_CHAIN_LN_MODE_MSK UINT8_C(0x1) -#define BMM350_TST_CHAIN_LN_MODE_POS UINT8_C(0x0) -#define BMM350_TST_CHAIN_LP_MODE_MSK UINT8_C(0x2) -#define BMM350_TST_CHAIN_LP_MODE_POS UINT8_C(0x1) -#define BMM350_EN_OVWR_TMR_IF_MSK UINT8_C(0x1) -#define BMM350_EN_OVWR_TMR_IF_POS UINT8_C(0x0) -#define BMM350_TMR_CKTRIGB_MSK UINT8_C(0x2) -#define BMM350_TMR_CKTRIGB_POS UINT8_C(0x1) -#define BMM350_TMR_DO_BR_MSK UINT8_C(0x4) -#define BMM350_TMR_DO_BR_POS UINT8_C(0x2) -#define BMM350_TMR_DO_FGR_MSK UINT8_C(0x18) -#define BMM350_TMR_DO_FGR_POS UINT8_C(0x3) -#define BMM350_TMR_EN_OSC_MSK UINT8_C(0x80) -#define BMM350_TMR_EN_OSC_POS UINT8_C(0x7) -#define BMM350_VCM_TRIM_X_MSK UINT8_C(0x1f) -#define BMM350_VCM_TRIM_X_POS UINT8_C(0x0) -#define BMM350_VCM_TRIM_Y_MSK UINT8_C(0x1f) -#define BMM350_VCM_TRIM_Y_POS UINT8_C(0x0) -#define BMM350_VCM_TRIM_Z_MSK UINT8_C(0x1f) -#define BMM350_VCM_TRIM_Z_POS UINT8_C(0x0) -#define BMM350_VCM_TRIM_DSENS_MSK UINT8_C(0x1f) -#define BMM350_VCM_TRIM_DSENS_POS UINT8_C(0x0) -#define BMM350_TWLB_MSK UINT8_C(0x30) -#define BMM350_TWLB_POS UINT8_C(0x4) -#define BMM350_PRG_PLS_TIM_MSK UINT8_C(0x30) -#define BMM350_PRG_PLS_TIM_POS UINT8_C(0x4) -#define BMM350_OTP_OVWR_EN_MSK UINT8_C(0x1) -#define BMM350_OTP_OVWR_EN_POS UINT8_C(0x0) -#define BMM350_OTP_MEM_CLK_MSK UINT8_C(0x2) -#define BMM350_OTP_MEM_CLK_POS UINT8_C(0x1) -#define BMM350_OTP_MEM_CS_MSK UINT8_C(0x4) -#define BMM350_OTP_MEM_CS_POS UINT8_C(0x2) -#define BMM350_OTP_MEM_PGM_MSK UINT8_C(0x8) -#define BMM350_OTP_MEM_PGM_POS UINT8_C(0x3) -#define BMM350_OTP_MEM_RE_MSK UINT8_C(0x10) -#define BMM350_OTP_MEM_RE_POS UINT8_C(0x4) -#define BMM350_SAMPLE_RDATA_PLS_MSK UINT8_C(0x80) -#define BMM350_SAMPLE_RDATA_PLS_POS UINT8_C(0x7) -#define BMM350_CFG_FW_MSK UINT8_C(0x1) -#define BMM350_CFG_FW_POS UINT8_C(0x0) -#define BMM350_EN_BR_X_MSK UINT8_C(0x2) -#define BMM350_EN_BR_X_POS UINT8_C(0x1) -#define BMM350_EN_BR_Y_MSK UINT8_C(0x4) -#define BMM350_EN_BR_Y_POS UINT8_C(0x2) -#define BMM350_EN_BR_Z_MSK UINT8_C(0x8) -#define BMM350_EN_BR_Z_POS UINT8_C(0x3) -#define BMM350_CFG_PAUSE_TIME_MSK UINT8_C(0x30) -#define BMM350_CFG_PAUSE_TIME_POS UINT8_C(0x4) -#define BMM350_CFG_FGR_PLS_DUR_MSK UINT8_C(0xf) -#define BMM350_CFG_FGR_PLS_DUR_POS UINT8_C(0x0) -#define BMM350_CFG_BR_Z_ORDER_MSK UINT8_C(0x10) -#define BMM350_CFG_BR_Z_ORDER_POS UINT8_C(0x4) -#define BMM350_CFG_BR_XY_CHOP_MSK UINT8_C(0x20) -#define BMM350_CFG_BR_XY_CHOP_POS UINT8_C(0x5) -#define BMM350_CFG_BR_PLS_DUR_MSK UINT8_C(0xc0) -#define BMM350_CFG_BR_PLS_DUR_POS UINT8_C(0x6) -#define BMM350_ENABLE_BR_FGR_TEST_MSK UINT8_C(0x1) -#define BMM350_ENABLE_BR_FGR_TEST_POS UINT8_C(0x0) -#define BMM350_SEL_AXIS_MSK UINT8_C(0xe) -#define BMM350_SEL_AXIS_POS UINT8_C(0x1) -#define BMM350_TMR_CFG_TEST_CLK_EN_MSK UINT8_C(0x10) -#define BMM350_TMR_CFG_TEST_CLK_EN_POS UINT8_C(0x4) -#define BMM350_TEST_VAL_BITS_7DOWNTO0_MSK UINT8_C(0xff) -#define BMM350_TEST_VAL_BITS_7DOWNTO0_POS UINT8_C(0x0) -#define BMM350_TEST_VAL_BITS_8_MSK UINT8_C(0x1) -#define BMM350_TEST_VAL_BITS_8_POS UINT8_C(0x0) -#define BMM350_TEST_P_SAMPLE_MSK UINT8_C(0x2) -#define BMM350_TEST_P_SAMPLE_POS UINT8_C(0x1) -#define BMM350_TEST_N_SAMPLE_MSK UINT8_C(0x4) -#define BMM350_TEST_N_SAMPLE_POS UINT8_C(0x2) -#define BMM350_TEST_APPLY_TO_REM_MSK UINT8_C(0x10) -#define BMM350_TEST_APPLY_TO_REM_POS UINT8_C(0x4) -#define BMM350_UFO_TRM_OSC_RANGE_MSK UINT8_C(0xf) -#define BMM350_UFO_TRM_OSC_RANGE_POS UINT8_C(0x0) -#define BMM350_ISO_CHIP_ID_MSK UINT8_C(0x78) -#define BMM350_ISO_CHIP_ID_POS UINT8_C(0x3) -#define BMM350_ISO_I2C_DEV_ID_MSK UINT8_C(0x80) -#define BMM350_ISO_I2C_DEV_ID_POS UINT8_C(0x7) -#define BMM350_I3C_FREQ_BITS_1DOWNTO0_MSK UINT8_C(0xc) -#define BMM350_I3C_FREQ_BITS_1DOWNTO0_POS UINT8_C(0x2) -#define BMM350_I3C_IBI_MDB_SEL_MSK UINT8_C(0x10) -#define BMM350_I3C_IBI_MDB_SEL_POS UINT8_C(0x4) -#define BMM350_TC_ASYNC_EN_MSK UINT8_C(0x20) -#define BMM350_TC_ASYNC_EN_POS UINT8_C(0x5) -#define BMM350_TC_SYNC_EN_MSK UINT8_C(0x40) -#define BMM350_TC_SYNC_EN_POS UINT8_C(0x6) -#define BMM350_I3C_SCL_GATING_EN_MSK UINT8_C(0x80) -#define BMM350_I3C_SCL_GATING_EN_POS UINT8_C(0x7) -#define BMM350_I3C_INACCURACY_BITS_6DOWNTO0_MSK UINT8_C(0x7f) -#define BMM350_I3C_INACCURACY_BITS_6DOWNTO0_POS UINT8_C(0x0) -#define BMM350_EST_EN_X_MSK UINT8_C(0x1) -#define BMM350_EST_EN_X_POS UINT8_C(0x0) -#define BMM350_EST_EN_Y_MSK UINT8_C(0x2) -#define BMM350_EST_EN_Y_POS UINT8_C(0x1) -#define BMM350_CRST_DIS_MSK UINT8_C(0x4) -#define BMM350_CRST_DIS_POS UINT8_C(0x2) -#define BMM350_BR_TFALL_MSK UINT8_C(0x7) -#define BMM350_BR_TFALL_POS UINT8_C(0x0) -#define BMM350_BR_TRISE_MSK UINT8_C(0x70) -#define BMM350_BR_TRISE_POS UINT8_C(0x4) -#define BMM350_TMR_SOFT_START_DIS_MSK UINT8_C(0x80) -#define BMM350_TMR_SOFT_START_DIS_POS UINT8_C(0x7) -#define BMM350_FOSC_LOW_RANGE_MSK UINT8_C(0x80) -#define BMM350_FOSC_LOW_RANGE_POS UINT8_C(0x7) -#define BMM350_VCRST_TRIM_FG_MSK UINT8_C(0x3f) -#define BMM350_VCRST_TRIM_FG_POS UINT8_C(0x0) -#define BMM350_VCRST_TRIM_BR_MSK UINT8_C(0x3f) -#define BMM350_VCRST_TRIM_BR_POS UINT8_C(0x0) -#define BMM350_BG_TRIM_VRP_MSK UINT8_C(0xc0) -#define BMM350_BG_TRIM_VRP_POS UINT8_C(0x6) -#define BMM350_BG_TRIM_TC_MSK UINT8_C(0xf) -#define BMM350_BG_TRIM_TC_POS UINT8_C(0x0) -#define BMM350_BG_TRIM_VRA_MSK UINT8_C(0xf0) -#define BMM350_BG_TRIM_VRA_POS UINT8_C(0x4) -#define BMM350_BG_TRIM_VRD_MSK UINT8_C(0xf) -#define BMM350_BG_TRIM_VRD_POS UINT8_C(0x0) -#define BMM350_OVWR_REF_IB_EN_MSK UINT8_C(0x10) -#define BMM350_OVWR_REF_IB_EN_POS UINT8_C(0x4) -#define BMM350_OVWR_VDDA_EN_MSK UINT8_C(0x20) -#define BMM350_OVWR_VDDA_EN_POS UINT8_C(0x5) -#define BMM350_OVWR_VDDP_EN_MSK UINT8_C(0x40) -#define BMM350_OVWR_VDDP_EN_POS UINT8_C(0x6) -#define BMM350_OVWR_VDDS_EN_MSK UINT8_C(0x80) -#define BMM350_OVWR_VDDS_EN_POS UINT8_C(0x7) -#define BMM350_REF_IB_EN_MSK UINT8_C(0x10) -#define BMM350_REF_IB_EN_POS UINT8_C(0x4) -#define BMM350_VDDA_EN_MSK UINT8_C(0x20) -#define BMM350_VDDA_EN_POS UINT8_C(0x5) -#define BMM350_VDDP_EN_MSK UINT8_C(0x40) -#define BMM350_VDDP_EN_POS UINT8_C(0x6) -#define BMM350_VDDS_EN_MSK UINT8_C(0x80) -#define BMM350_VDDS_EN_POS UINT8_C(0x7) -#define BMM350_OVWR_OTP_PROG_VDD_SW_EN_MSK UINT8_C(0x8) -#define BMM350_OVWR_OTP_PROG_VDD_SW_EN_POS UINT8_C(0x3) -#define BMM350_OVWR_EN_MFE_BG_FILT_BYPASS_MSK UINT8_C(0x10) -#define BMM350_OVWR_EN_MFE_BG_FILT_BYPASS_POS UINT8_C(0x4) -#define BMM350_OTP_PROG_VDD_SW_EN_MSK UINT8_C(0x8) -#define BMM350_OTP_PROG_VDD_SW_EN_POS UINT8_C(0x3) -#define BMM350_CP_COMP_CRST_EN_TM_MSK UINT8_C(0x10) -#define BMM350_CP_COMP_CRST_EN_TM_POS UINT8_C(0x4) -#define BMM350_CP_COMP_VDD_EN_TM_MSK UINT8_C(0x20) -#define BMM350_CP_COMP_VDD_EN_TM_POS UINT8_C(0x5) -#define BMM350_CP_INTREFS_EN_TM_MSK UINT8_C(0x40) -#define BMM350_CP_INTREFS_EN_TM_POS UINT8_C(0x6) -#define BMM350_ADC_LOCAL_CHOP_EN_MSK UINT8_C(0x20) -#define BMM350_ADC_LOCAL_CHOP_EN_POS UINT8_C(0x5) -#define BMM350_INA_MODE_MSK UINT8_C(0x40) -#define BMM350_INA_MODE_POS UINT8_C(0x6) -#define BMM350_VDDD_EXT_EN_MSK UINT8_C(0x20) -#define BMM350_VDDD_EXT_EN_POS UINT8_C(0x5) -#define BMM350_VDDP_EXT_EN_MSK UINT8_C(0x80) -#define BMM350_VDDP_EXT_EN_POS UINT8_C(0x7) -#define BMM350_ADC_DSENS_EN_MSK UINT8_C(0x10) -#define BMM350_ADC_DSENS_EN_POS UINT8_C(0x4) -#define BMM350_DSENS_EN_MSK UINT8_C(0x20) -#define BMM350_DSENS_EN_POS UINT8_C(0x5) -#define BMM350_OTP_TM_CLVWR_EN_MSK UINT8_C(0x40) -#define BMM350_OTP_TM_CLVWR_EN_POS UINT8_C(0x6) -#define BMM350_OTP_VDDP_DIS_MSK UINT8_C(0x80) -#define BMM350_OTP_VDDP_DIS_POS UINT8_C(0x7) -#define BMM350_FORCE_HIGH_VREF_IREF_OK_MSK UINT8_C(0x10) -#define BMM350_FORCE_HIGH_VREF_IREF_OK_POS UINT8_C(0x4) -#define BMM350_FORCE_HIGH_FOSC_OK_MSK UINT8_C(0x20) -#define BMM350_FORCE_HIGH_FOSC_OK_POS UINT8_C(0x5) -#define BMM350_FORCE_HIGH_MFE_BG_RDY_MSK UINT8_C(0x40) -#define BMM350_FORCE_HIGH_MFE_BG_RDY_POS UINT8_C(0x6) -#define BMM350_FORCE_HIGH_MFE_VTMR_RDY_MSK UINT8_C(0x80) -#define BMM350_FORCE_HIGH_MFE_VTMR_RDY_POS UINT8_C(0x7) -#define BMM350_ERR_END_OF_RECHARGE_MSK UINT8_C(0x1) -#define BMM350_ERR_END_OF_RECHARGE_POS UINT8_C(0x0) -#define BMM350_ERR_END_OF_DISCHARGE_MSK UINT8_C(0x2) -#define BMM350_ERR_END_OF_DISCHARGE_POS UINT8_C(0x1) -#define BMM350_CP_TMX_DIGTP_SEL_MSK UINT8_C(0x7) -#define BMM350_CP_TMX_DIGTP_SEL_POS UINT8_C(0x0) -#define BMM350_CP_CPOSC_EN_TM_MSK UINT8_C(0x80) -#define BMM350_CP_CPOSC_EN_TM_POS UINT8_C(0x7) -#define BMM350_TST_ATM1_CFG_MSK UINT8_C(0x3f) -#define BMM350_TST_ATM1_CFG_POS UINT8_C(0x0) -#define BMM350_TST_TB1_EN_MSK UINT8_C(0x80) -#define BMM350_TST_TB1_EN_POS UINT8_C(0x7) -#define BMM350_TST_ATM2_CFG_MSK UINT8_C(0x1f) -#define BMM350_TST_ATM2_CFG_POS UINT8_C(0x0) -#define BMM350_TST_TB2_EN_MSK UINT8_C(0x80) -#define BMM350_TST_TB2_EN_POS UINT8_C(0x7) -#define BMM350_REG_DTB1X_SEL_MSK UINT8_C(0x7f) -#define BMM350_REG_DTB1X_SEL_POS UINT8_C(0x0) -#define BMM350_SEL_DTB1X_PAD_MSK UINT8_C(0x80) -#define BMM350_SEL_DTB1X_PAD_POS UINT8_C(0x7) -#define BMM350_REG_DTB2X_SEL_MSK UINT8_C(0x7f) -#define BMM350_REG_DTB2X_SEL_POS UINT8_C(0x0) -#define BMM350_TMR_TST_CFG_MSK UINT8_C(0x7f) -#define BMM350_TMR_TST_CFG_POS UINT8_C(0x0) -#define BMM350_TMR_TST_HIZ_VTMR_MSK UINT8_C(0x80) -#define BMM350_TMR_TST_HIZ_VTMR_POS UINT8_C(0x7) - -/****************************** OTP MACROS ***************************/ -#define BMM350_OTP_CMD_DIR_READ UINT8_C(0x20) -#define BMM350_OTP_CMD_DIR_PRGM_1B UINT8_C(0x40) -#define BMM350_OTP_CMD_DIR_PRGM UINT8_C(0x60) -#define BMM350_OTP_CMD_PWR_OFF_OTP UINT8_C(0x80) -#define BMM350_OTP_CMD_EXT_READ UINT8_C(0xA0) -#define BMM350_OTP_CMD_EXT_PRGM UINT8_C(0xE0) -#define BMM350_OTP_CMD_MSK UINT8_C(0xE0) -#define BMM350_OTP_WORD_ADDR_MSK UINT8_C(0x1F) - -#define BMM350_OTP_STATUS_ERROR_MSK UINT8_C(0xE0) -#define BMM350_OTP_STATUS_ERROR(val) (val & BMM350_OTP_STATUS_ERROR_MSK) -#define BMM350_OTP_STATUS_NO_ERROR UINT8_C(0x00) -#define BMM350_OTP_STATUS_BOOT_ERR UINT8_C(0x20) -#define BMM350_OTP_STATUS_PAGE_RD_ERR UINT8_C(0x40) -#define BMM350_OTP_STATUS_PAGE_PRG_ERR UINT8_C(0x60) -#define BMM350_OTP_STATUS_SIGN_ERR UINT8_C(0x80) -#define BMM350_OTP_STATUS_INV_CMD_ERR UINT8_C(0xA0) -#define BMM350_OTP_STATUS_CMD_DONE UINT8_C(0x01) - -/****************************** OTP indices ***************************/ -#define BMM350_TEMP_OFF_SENS UINT8_C(0x0D) - -#define BMM350_MAG_OFFSET_X UINT8_C(0x0E) -#define BMM350_MAG_OFFSET_Y UINT8_C(0x0F) -#define BMM350_MAG_OFFSET_Z UINT8_C(0x10) - -#define BMM350_MAG_SENS_X UINT8_C(0x10) -#define BMM350_MAG_SENS_Y UINT8_C(0x11) -#define BMM350_MAG_SENS_Z UINT8_C(0x11) - -#define BMM350_MAG_TCO_X UINT8_C(0x12) -#define BMM350_MAG_TCO_Y UINT8_C(0x13) -#define BMM350_MAG_TCO_Z UINT8_C(0x14) - -#define BMM350_MAG_TCS_X UINT8_C(0x12) -#define BMM350_MAG_TCS_Y UINT8_C(0x13) -#define BMM350_MAG_TCS_Z UINT8_C(0x14) - -#define BMM350_MAG_DUT_T_0 UINT8_C(0x18) - -#define BMM350_CROSS_X_Y UINT8_C(0x15) -#define BMM350_CROSS_Y_X UINT8_C(0x15) -#define BMM350_CROSS_Z_X UINT8_C(0x16) -#define BMM350_CROSS_Z_Y UINT8_C(0x16) - -#define BMM350_SENS_CORR_Y (0.01f) -#define BMM350_TCS_CORR_Z (0.0001f) - -/**************************** Signed bit macros **********************/ -#define BMM350_SIGNED_8_BIT UINT8_C(8) -#define BMM350_SIGNED_12_BIT UINT8_C(12) -#define BMM350_SIGNED_16_BIT UINT8_C(16) -#define BMM350_SIGNED_21_BIT UINT8_C(21) -#define BMM350_SIGNED_24_BIT UINT8_C(24) - -/**************************** Self-test macros **********************/ -#define BMM350_SELF_TEST_DISABLE UINT8_C(0x00) -#define BMM350_SELF_TEST_POS_X UINT8_C(0x0D) -#define BMM350_SELF_TEST_NEG_X UINT8_C(0x0B) -#define BMM350_SELF_TEST_POS_Y UINT8_C(0x15) -#define BMM350_SELF_TEST_NEG_Y UINT8_C(0x13) - -#define BMM350_X_FM_XP_UST_MAX_LIMIT INT16_C(150) -#define BMM350_X_FM_XP_UST_MIN_LIMIT INT16_C(50) - -#define BMM350_X_FM_XN_UST_MAX_LIMIT INT16_C(-50) -#define BMM350_X_FM_XN_UST_MIN_LIMIT INT16_C(-150) - -#define BMM350_Y_FM_YP_UST_MAX_LIMIT INT16_C(150) -#define BMM350_Y_FM_YP_UST_MIN_LIMIT INT16_C(50) - -#define BMM350_Y_FM_YN_UST_MAX_LIMIT INT16_C(-50) -#define BMM350_Y_FM_YN_UST_MIN_LIMIT INT16_C(-150) - -/**************************** PMU command status 0 macros **********************/ -#define BMM350_PMU_CMD_STATUS_0_SUS UINT8_C(0x00) -#define BMM350_PMU_CMD_STATUS_0_NM UINT8_C(0x01) -#define BMM350_PMU_CMD_STATUS_0_UPD_OAE UINT8_C(0x02) -#define BMM350_PMU_CMD_STATUS_0_FM UINT8_C(0x03) -#define BMM350_PMU_CMD_STATUS_0_FM_FAST UINT8_C(0x04) -#define BMM350_PMU_CMD_STATUS_0_FGR UINT8_C(0x05) -#define BMM350_PMU_CMD_STATUS_0_FGR_FAST UINT8_C(0x06) -#define BMM350_PMU_CMD_STATUS_0_BR UINT8_C(0x07) -#define BMM350_PMU_CMD_STATUS_0_BR_FAST UINT8_C(0x07) - - -/**************************** PRESET MODE DEFINITIONS **********************/ -#define BMM350_PRESETMODE_LOWPOWER UINT8_C(0x01) -#define BMM350_PRESETMODE_REGULAR UINT8_C(0x02) -#define BMM350_PRESETMODE_HIGHACCURACY UINT8_C(0x03) -#define BMM350_PRESETMODE_ENHANCED UINT8_C(0x04) - -#define LOW_THRESHOLD_INTERRUPT 0 -#define HIGH_THRESHOLD_INTERRUPT 1 -#define INTERRUPT_X_ENABLE 0 -#define INTERRUPT_Y_ENABLE 0 -#define INTERRUPT_Z_ENABLE 0 -#define INTERRUPT_X_DISABLE 1 -#define INTERRUPT_Y_DISABLE 1 -#define INTERRUPT_Z_DISABLE 1 -#define ENABLE_INTERRUPT_PIN 1 -#define DISABLE_INTERRUPT_PIN 0 -#define NO_DATA -32768 - -#define I2C_ADDRESS 0x14 - -/****************************** Enumerators ***************************/ -enum eBmm350InterruptEnableDisable_t { - BMM350_DISABLE_INTERRUPT = BMM350_DISABLE, - BMM350_ENABLE_INTERRUPT = BMM350_ENABLE -}; - -enum eBmm350PowerModes_t { - eBmm350SuspendMode = BMM350_PMU_CMD_SUS, - eBmm350NormalMode = BMM350_PMU_CMD_NM, - eBmm350ForcedMode = BMM350_PMU_CMD_FM, - eBmm350ForcedModeFast = BMM350_PMU_CMD_FM_FAST -}; - -enum eBmm350DataRates_t { - BMM350_DATA_RATE_400HZ = BMM350_ODR_400HZ, - BMM350_DATA_RATE_200HZ = BMM350_ODR_200HZ, - BMM350_DATA_RATE_100HZ = BMM350_ODR_100HZ, - BMM350_DATA_RATE_50HZ = BMM350_ODR_50HZ, - BMM350_DATA_RATE_25HZ = BMM350_ODR_25HZ, - BMM350_DATA_RATE_12_5HZ = BMM350_ODR_12_5HZ, - BMM350_DATA_RATE_6_25HZ = BMM350_ODR_6_25HZ, - BMM350_DATA_RATE_3_125HZ = BMM350_ODR_3_125HZ, - BMM350_DATA_RATE_1_5625HZ = BMM350_ODR_1_5625HZ -}; - -enum bmm350_magreset_type { - BMM350_FLUXGUIDE_9MS = BMM350_PMU_CMD_FGR, - BMM350_FLUXGUIDE_FAST = BMM350_PMU_CMD_FGR_FAST, - BMM350_BITRESET_9MS = BMM350_PMU_CMD_BR, - BMM350_BITRESET_FAST = BMM350_PMU_CMD_BR_FAST, - BMM350_NOMAGRESET = UINT8_C(127) -}; - -enum bmm350_intr_en_dis { - BMM350_INTR_DISABLE = BMM350_DISABLE, - BMM350_INTR_ENABLE = BMM350_ENABLE -}; - -enum bmm350_intr_map { - BMM350_UNMAP_FROM_PIN = BMM350_DISABLE, - BMM350_MAP_TO_PIN = BMM350_ENABLE -}; -enum bmm350_intr_latch { - BMM350_PULSED = BMM350_INT_MODE_PULSED, - BMM350_LATCHED = BMM350_INT_MODE_LATCHED -}; - -enum eBmm350IntrPolarity_t { - BMM350_ACTIVE_LOW = BMM350_INT_POL_ACTIVE_LOW, - BMM350_ACTIVE_HIGH = BMM350_INT_POL_ACTIVE_HIGH -}; - -enum bmm350_intr_drive { - BMM350_INTR_OPEN_DRAIN = BMM350_INT_OD_OPENDRAIN, - BMM350_INTR_PUSH_PULL = BMM350_INT_OD_PUSHPULL -}; - -enum bmm350_drdy_int_map_to_ibi { - BMM350_IBI_DISABLE = BMM350_DISABLE, - BMM350_IBI_ENABLE = BMM350_ENABLE -}; - -enum bmm350_clear_drdy_int_status_upon_ibi { - BMM350_NOCLEAR_ON_IBI = BMM350_DISABLE, - BMM350_CLEAR_ON_IBI = BMM350_ENABLE -}; - -enum bmm350_i2c_wdt_en { - BMM350_I2C_WDT_DIS = BMM350_DISABLE, - BMM350_I2C_WDT_EN = BMM350_ENABLE -}; - -enum bmm350_i2c_wdt_sel { - BMM350_I2C_WDT_SEL_SHORT = BMM350_DISABLE, - BMM350_I2C_WDT_SEL_LONG = BMM350_ENABLE -}; - -enum bmm350_performance_parameters { - BMM350_NO_AVERAGING = BMM350_AVG_NO_AVG, - BMM350_AVERAGING_2 = BMM350_AVG_2, - BMM350_AVERAGING_4 = BMM350_AVG_4, - BMM350_AVERAGING_8 = BMM350_AVG_8, - /*lint -e849*/ - BMM350_ULTRALOWNOISE = BMM350_AVG_8, - BMM350_LOWNOISE = BMM350_AVG_4, - BMM350_REGULARPOWER = BMM350_AVG_2, - BMM350_LOWPOWER = BMM350_AVG_NO_AVG -}; - -enum bmm350_st_igen_en { - BMM350_ST_IGEN_DIS = BMM350_DISABLE, - BMM350_ST_IGEN_EN = BMM350_ENABLE -}; - -enum bmm350_st_n { - BMM350_ST_N_DIS = BMM350_DISABLE, - BMM350_ST_N_EN = BMM350_ENABLE -}; - -enum bmm350_st_p { - BMM350_ST_P_DIS = BMM350_DISABLE, - BMM350_ST_P_EN = BMM350_ENABLE -}; - -enum bmm350_ist_en_x { - BMM350_IST_X_DIS = BMM350_DISABLE, - BMM350_IST_X_EN = BMM350_ENABLE -}; - -enum bmm350_ist_en_y { - BMM350_IST_Y_DIS = BMM350_DISABLE, - BMM350_IST_Y_EN = BMM350_ENABLE -}; - -enum bmm350_ctrl_user { - BMM350_CFG_SENS_TIM_AON_DIS = BMM350_DISABLE, - BMM350_CFG_SENS_TIM_AON_EN = BMM350_ENABLE -}; - -enum eBmm350XAxisEnDis_t { - BMM350_X_DIS = BMM350_DISABLE, - BMM350_X_EN = BMM350_ENABLE -}; - -enum eBmm350YAxisEnDis_t { - BMM350_Y_DIS = BMM350_DISABLE, - BMM350_Y_EN = BMM350_ENABLE -}; - -enum eBmm350ZAxisEnDis_t { - BMM350_Z_DIS = BMM350_DISABLE, - BMM350_Z_EN = BMM350_ENABLE -}; - -/******************************************************************************/ -/*! @name Function Pointers */ -/******************************************************************************/ - -/*! - * @brief Bus communication function pointer which should be mapped to - * the platform specific read functions of the user - * - * @param[in] reg_addr : Register address from which data is read. - * @param[out] reg_data : Pointer to data buffer where read data is stored. - * @param[in] len : Number of bytes of data to be read. - * @param[in, out] intfPtr : Void pointer that can enable the linking of descriptors - * for interface related call backs. - * - * retval = 0 -> Success - * retval < 0 -> Failure - * - */ -typedef BMM350_INTF_RET_TYPE (*pBmm350ReadFptr_t)(uint8_t reg_addr, uint8_t *reg_data, uint32_t len, void *intfPtr); - -/*! - * @brief Bus communication function pointer which should be mapped to - * the platform specific write functions of the user - * - * @param[in] reg_addr : Register address to which the data is written. - * @param[in] reg_data : Pointer to data buffer in which data to be written - * is stored. - * @param[in] len : Number of bytes of data to be written. - * @param[in, out] intfPtr : Void pointer that can enable the linking of descriptors - * for interface related call backs - * - * retval = 0 -> Success - * retval < 0 -> Failure - * - */ -typedef BMM350_INTF_RET_TYPE (*pBmm350WriteFptr_t)(uint8_t reg_addr, const uint8_t *reg_data, uint32_t len, - void *intfPtr); - -/*! - * @brief Delay function pointer which should be mapped to - * delay function of the user - * - * @param[in] period : Delay in microseconds. - * @param[in, out] intfPtr : Void pointer that can enable the linking of descriptors - * for interface related call backs - * - */ -typedef void (*pBmm350DelayUsFptr_t)(uint32_t period, void *intfPtr); - -/* Pre-declaration */ -struct bmm350_dev; - -/*! - * @brief Function pointer for the magnetic reset and wait override - * - * @param[in] dev : Structure instance of bmm350_dev. - * @return Result of API execution status - * @retval = 0 -> Success - * @retval < 0 -> Error - */ -typedef int8_t (*bmm350_mraw_override_t)(struct bmm350_dev *dev); - -/************************* STRUCTURE DEFINITIONS *************************/ - -/*! - * @brief bmm350 un-compensated (raw) magnetometer data, signed integer - */ -struct bmm350_raw_mag_data -{ - /*! Raw mag X data */ - int32_t raw_xdata; - - /*! Raw mag Y data */ - int32_t raw_ydata; - - /*! Raw mag Z data */ - int32_t raw_zdata; - - /*! Raw mag temperature value */ - int32_t raw_data_t; -}; - -/*! - * @brief bmm350 compensated magnetometer data and temperature data - */ -struct sBmm350MagTempData_t -{ - /*! Compensated mag X data */ - float x; - - /*! Compensated mag Y data */ - float y; - - /*! Compensated mag Z data */ - float z; - - /*! Temperature */ - float temperature; -}; - -/*! - * @brief bmm350 magnetometer dut offset coefficient structure - */ -struct bmm350_dut_offset_coef -{ - /*! Temperature offset */ - float t_offs; - - /*! Offset x-axis */ - float offset_x; - - /*! Offset y-axis */ - float offset_y; - - /*! Offset z-axis */ - float offset_z; -}; - -/*! - * @brief bmm350 magnetometer dut sensitivity coefficient structure - */ -struct bmm350_dut_sensit_coef -{ - /*! Temperature sensitivity */ - float t_sens; - - /*! Sensitivity x-axis */ - float sens_x; - - /*! Sensitivity y-axis */ - float sens_y; - - /*! Sensitivity z-axis */ - float sens_z; -}; - -/*! - * @brief bmm350 magnetometer dut tco structure - */ -struct bmm350_dut_tco -{ - float tco_x; - float tco_y; - float tco_z; -}; - -/*! - * @brief bmm350 magnetometer dut tcs structure - */ -struct bmm350_dut_tcs -{ - float tcs_x; - float tcs_y; - float tcs_z; -}; - -/*! - * @brief bmm350 magnetometer cross axis compensation structure - */ -struct bmm350_cross_axis -{ - float cross_x_y; - float cross_y_x; - float cross_z_x; - float cross_z_y; -}; - -/*! - * @brief bmm350 magnetometer compensate structure - */ -struct bmm350_mag_compensate -{ - /*! Structure to store dut offset coefficient */ - struct bmm350_dut_offset_coef dut_offset_coef; - - /*! Structure to store dut sensitivity coefficient */ - struct bmm350_dut_sensit_coef dut_sensit_coef; - - /*! Structure to store dut tco */ - struct bmm350_dut_tco dut_tco; - - /*! Structure to store dut tcs */ - struct bmm350_dut_tcs dut_tcs; - - /*! Initialize T0_reading parameter */ - float dut_t0; - - /*! Structure to define cross axis compensation */ - struct bmm350_cross_axis cross_axis; -}; - -/*! - * @brief bmm350 device structure - */ -struct bmm350_dev -{ - /*! - * The interface pointer is used to enable the user - * to link their interface descriptors for reference during the - * implementation of the read and write interfaces to the - * hardware. - */ - void* intfPtr; - - /*! Chip Id of BMM350 */ - uint8_t chipId; - - /*! Bus read function pointer */ - pBmm350ReadFptr_t read; - - /*! Bus write function pointer */ - pBmm350WriteFptr_t write; - - /*! delay(in us) function pointer */ - pBmm350DelayUsFptr_t delayUs; - - /*! To store interface pointer error */ - BMM350_INTF_RET_TYPE intf_rslt; - - /*! Variable to store status of axes enabled */ - uint8_t axisEn; - - /*! Structure for mag compensate */ - struct bmm350_mag_compensate mag_comp; - - /*! Array to store OTP data */ - uint16_t otp_data[BMM350_OTP_DATA_LENGTH]; - - /*! Variant ID */ - uint8_t var_id; - - /*! Magnetic reset and wait override */ - bmm350_mraw_override_t mraw_override; - - /*! power mode */ - uint8_t powerMode; -}; - -/*! - * @brief bmm350 self-test structure - */ -struct sBmm350SelfTest_t -{ - /* Variable to store self-test data on x-axis */ - float out_ust_x; - - /* Variable to store self-test data on y-axis */ - float out_ust_y; -}; - -/*! - * @brief bmm350 PMU command status 0 structure - */ -struct bmm350_pmu_cmd_status_0 -{ - /*! The previous PMU CMD is still in processing */ - uint8_t pmu_cmd_busy; - - /*! The previous PMU_CMD_AGGR_SET.odr has been overwritten */ - uint8_t odr_ovwr; - - /*! The previous PMU_CMD_AGGR_SET.avg has been overwritten */ - uint8_t avr_ovwr; - - /*! The chip is in normal power mode */ - uint8_t pwr_mode_is_normal; - - /*! CMD value is not allowed */ - uint8_t cmd_is_illegal; - - /*! Stores the latest PMU_CMD code processed */ - uint8_t pmu_cmd_value; -}; - -/** - * @brief bmm350 compensated magnetometer data in int16_t format - */ -typedef struct{ - int32_t x; /**< compensated mag X data */ - int32_t y; /**< compensated mag Y data */ - int32_t z; /**< compensated mag Z data */ - int32_t temperature; /**< compensated temperature data */ - float float_x; - float float_y; - float float_z; - float float_temperature; -}sBmm350MagData_t; - -typedef struct{ - int16_t mag_x; /**< mag X data */ - int16_t mag_y; /**< mag Y data */ - int16_t mag_z; /**< mag Z data */ - uint8_t interrupt_x; /**< X-axis interrupt trigger flag*/ - uint8_t interrupt_y; /**< Y-axis interrupt trigger flag*/ - uint8_t interrupt_z; /**< Z-axis interrupt trigger flag*/ -}sBmm350ThresholdData_t; - -#endif /* _BMM350_DEFS_H */ diff --git a/lib/DFRobot_BMM350/src/bmm350_oor.c b/lib/DFRobot_BMM350/src/bmm350_oor.c deleted file mode 100644 index c587891..0000000 --- a/lib/DFRobot_BMM350/src/bmm350_oor.c +++ /dev/null @@ -1,329 +0,0 @@ -/** -* Copyright (c) 2023 Bosch Sensortec GmbH. All rights reserved. -* -* BSD-3-Clause -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in the -* documentation and/or other materials provided with the distribution. -* -* 3. Neither the name of the copyright holder nor the names of its -* contributors may be used to endorse or promote products derived from -* this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) -* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, -* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING -* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -* @file bmm350_oor.c -* @date 2023-05-26 -* @version v1.4.0 -* -*/ - -#include "bmm350_oor.h" - -#ifdef BMM350_OOR_HALF_SELF_TEST - -/*! - * @brief This internal API is used to trigger half self-test - */ -static int8_t trigger_half_selftest(struct bmm350_oor_params *oor, struct bmm350_dev *dev) -{ - int8_t rslt = BMM350_OK; - - oor->st_cmd = BMM350_SELF_TEST_DISABLE; - - /* Trigger a self-test on every alternate measurement if needed */ - if (oor->enable_selftest) - { - oor->st_counter++; - - switch (oor->st_counter) - { - case 1: - oor->st_cmd = BMM350_SELF_TEST_POS_X; - break; - case 2: - oor->st_cmd = BMM350_SELF_TEST_DISABLE; - break; - case 3: - oor->st_cmd = BMM350_SELF_TEST_POS_Y; - break; - case 4: - oor->st_cmd = BMM350_SELF_TEST_DISABLE; - break; - - default: - oor->st_counter = 0; - oor->st_cmd = BMM350_SELF_TEST_DISABLE; - break; - } - - rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, &(oor->st_cmd), 1, dev); - } - else - { - if (oor->last_st_cmd != BMM350_SELF_TEST_DISABLE) - { - rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, &(oor->st_cmd), 1, dev); - oor->st_counter = 0; - } - } - - return rslt; -} - -/*! - * @brief This internal API is used to validate half self-test - */ -static void validate_half_selftest(const struct sBmm350MagTempData_t *data, struct bmm350_oor_params *oor) -{ - switch (oor->last_st_cmd) - { - case BMM350_SELF_TEST_DISABLE: - oor->mag_xn = data->x; - oor->mag_yn = data->y; - break; - - case BMM350_SELF_TEST_POS_X: - oor->mag_xp = data->x; - oor->x_failed = (oor->mag_xp - oor->mag_xn) < BMM350_HALF_ST_THRESHOLD ? true : false; - break; - - case BMM350_SELF_TEST_POS_Y: - oor->mag_yp = data->y; - oor->y_failed = (oor->mag_yp - oor->mag_yn) < BMM350_HALF_ST_THRESHOLD ? true : false; - break; - - default: - break; - } -} -#else - -/*! - * @brief This internal API is used to trigger full self-test - */ -static int8_t trigger_full_selftest(struct bmm350_oor_params *oor, struct bmm350_dev *dev) -{ - int8_t rslt = BMM350_OK; - - oor->st_cmd = BMM350_SELF_TEST_DISABLE; - - /* Trigger a self-test on every alternate measurement if needed */ - if (oor->enable_selftest) - { - oor->st_counter++; - - switch (oor->st_counter) - { - case 1: - oor->st_cmd = BMM350_SELF_TEST_POS_X; - break; - case 2: - oor->st_cmd = BMM350_SELF_TEST_NEG_X; - break; - case 3: - oor->st_cmd = BMM350_SELF_TEST_POS_Y; - break; - case 4: - oor->st_cmd = BMM350_SELF_TEST_NEG_Y; - break; - - default: - oor->st_counter = 0; - oor->st_cmd = BMM350_SELF_TEST_DISABLE; - break; - } - - rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, &(oor->st_cmd), 1, dev); - } - else - { - if (oor->last_st_cmd != BMM350_SELF_TEST_DISABLE) - { - rslt = bmm350SetRegs(BMM350_REG_TMR_SELFTEST_USER, &(oor->st_cmd), 1, dev); - oor->st_counter = 0; - } - } - - return rslt; -} - -/*! - * @brief This internal API is used to validate full self-test - */ -static void validate_full_selftest(const struct sBmm350MagTempData_t *data, struct bmm350_oor_params *oor) -{ - switch (oor->last_st_cmd) - { - case BMM350_SELF_TEST_POS_X: - oor->mag_xp = data->x; - break; - - case BMM350_SELF_TEST_NEG_X: - oor->mag_xn = data->x; - oor->x_failed = (oor->mag_xp - oor->mag_xn) < BMM350_FULL_ST_THRESHOLD ? true : false; - break; - - case BMM350_SELF_TEST_POS_Y: - oor->mag_yp = data->y; - break; - - case BMM350_SELF_TEST_NEG_Y: - oor->mag_yn = data->y; - oor->y_failed = (oor->mag_yp - oor->mag_yn) < BMM350_FULL_ST_THRESHOLD ? true : false; - break; - - default: - break; - } -} -#endif - -/*! - * @brief This internal API is used to validate out of range. - */ -static void validate_out_of_range(bool *out_of_range, - const struct sBmm350MagTempData_t *data, - struct bmm350_oor_params *oor) -{ - float field_str = 0.0f; - - /* Threshold to start out of range detection */ - float threshold = BMM350_OUT_OF_RANGE_THRESHOLD; - - /* Threshold to start self-tests */ - float st_threshold = BMM350_SELF_TEST_THRESHOLD; - - /* If either self-test failed, alert that the sensor is out of range and continue self-tests */ - if (oor->x_failed || oor->y_failed) - { - *out_of_range = true; - oor->enable_selftest = true; - } - else - { - field_str = sqrtf((data->x * data->x) + (data->y * data->y) + (data->z * data->z)); - - /* Check for the self-test threshold and perform self-tests to catch if the sensor is out of range */ - if ((fabsf(data->x) >= st_threshold) || (fabsf(data->y) >= st_threshold) || (fabsf(data->z) >= st_threshold) || - (field_str >= st_threshold)) - { - oor->enable_selftest = true; - } - else if (oor->st_counter == 0) /* If a self-test procedure has started, wait for it to complete */ - { - oor->enable_selftest = false; - } - - /* If out of range was previously detected, reduce the threshold to get back in range, - * effectively preventing hysteresis. Selecting 400uT */ - if (*out_of_range) - { - threshold = BMM350_IN_RANGE_THRESHOLD; - } - - /* Check if X or Y or Z > the threshold or the magnitude of all 3 is greater */ - if ((fabsf(data->x) >= threshold) || (fabsf(data->y) >= threshold) || (fabsf(data->z) >= threshold) || - (field_str >= threshold)) - { - *out_of_range = true; - } - else if (oor->st_counter == 0) /* If a self-test procedure has started, wait for it to complete */ - { - *out_of_range = false; - } - } -} - -/*! - * @brief This API is used to perform reset sequence in forced mode. - */ -int8_t bmm350_oor_perform_reset_sequence_forced(struct bmm350_oor_params *oor, struct bmm350_dev *dev) -{ - int8_t rslt = 0; - uint8_t pmu_cmd = 0; - - oor->reset_counter++; - - switch (oor->reset_counter) - { - case 1: /* Trigger the Bit reset fast */ - pmu_cmd = BMM350_PMU_CMD_BR_FAST; - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); - break; - - case 2: /* Trigger Flux Guide reset */ - pmu_cmd = BMM350_PMU_CMD_FGR; - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); - break; - - case 3: /* Flux Guide dummy */ - break; - - default: /* Default acts like the Flux guide reset dummy */ - oor->reset_counter = 0; - oor->trigger_reset = false; - break; - } - - return rslt; -} - -/*! - * @brief This API is used to read out of range in half or full self-test. - */ -int8_t bmm350_oor_read(bool *out_of_range, - struct sBmm350MagTempData_t *data, - struct bmm350_oor_params *oor, - struct bmm350_dev *dev) -{ - int8_t rslt = 0; - uint8_t pmu_cmd = BMM350_PMU_CMD_SUS; - -#ifdef BMM350_OOR_HALF_SELF_TEST - rslt = trigger_half_selftest(oor, dev); -#else - rslt = trigger_full_selftest(oor, dev); -#endif - - if (rslt == BMM350_OK) - { - pmu_cmd = BMM350_PMU_CMD_FM_FAST; - rslt = bmm350SetRegs(BMM350_REG_PMU_CMD, &pmu_cmd, 1, dev); - - if (rslt == BMM350_OK) - { - rslt = bmm350GetCompensatedMagXYZTempData(data, dev); - } - } - -#ifdef BMM350_OOR_HALF_SELF_TEST - validate_half_selftest(data, oor); -#else - validate_full_selftest(data, oor); -#endif - - validate_out_of_range(out_of_range, data, oor); - - oor->last_st_cmd = oor->st_cmd; - - return rslt; -} diff --git a/lib/DFRobot_BMM350/src/bmm350_oor.h b/lib/DFRobot_BMM350/src/bmm350_oor.h deleted file mode 100644 index 41b3eb7..0000000 --- a/lib/DFRobot_BMM350/src/bmm350_oor.h +++ /dev/null @@ -1,136 +0,0 @@ -/** -* Copyright (c) 2023 Bosch Sensortec GmbH. All rights reserved. -* -* BSD-3-Clause -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions are met: -* -* 1. Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* -* 2. Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in the -* documentation and/or other materials provided with the distribution. -* -* 3. Neither the name of the copyright holder nor the names of its -* contributors may be used to endorse or promote products derived from -* this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) -* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, -* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING -* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -* @file bmm350_oor.h -* @date 2023-05-26 -* @version v1.4.0 -* -*/ - -#ifndef _BMM350_OOR_H -#define _BMM350_OOR_H - -#include -#include - -#include "bmm350.h" - -/*! CPP guard */ -#ifdef __cplusplus -extern "C" { -#endif - -/******************************************************************************/ -/*! @name General Macro Definitions */ -/******************************************************************************/ - -/*! Macro to define half self-test for out of range - * NOTE: Comment this to use both positive and negative self tests */ -#define BMM350_OOR_HALF_SELF_TEST - -/*! Macro to define mag data minimum and maximum range in uT */ -#define BMM350_HALF_ST_THRESHOLD (130.0f) -#define BMM350_FULL_ST_THRESHOLD (300.0f) - -/*! Macro to define threshold values of in range, out of range and self-test */ -#define BMM350_IN_RANGE_THRESHOLD (2000.0f) -#define BMM350_OUT_OF_RANGE_THRESHOLD (2400.0f) -#define BMM350_SELF_TEST_THRESHOLD (2600.0f) - -/************************* Structure definitions *************************/ - -/*! - * @brief Structure to define bmm350 out of range parameters - */ -struct bmm350_oor_params -{ - /*! Counter to track what self test to trigger */ - uint8_t st_counter; - - /*! Current self-test command */ - uint8_t st_cmd; - - /*! Stores the last applied self test configuration */ - uint8_t last_st_cmd; - - /*! Store the last measurements for comparing against the self-test */ - float mag_xp, mag_xn, mag_yp, mag_yn; - - /*! Flags to track if the test failed to redo it */ - bool x_failed, y_failed; - - /*! Flags to enable self-test */ - bool enable_selftest; - - /*! Flags to trigger reset */ - bool trigger_reset; - - /*! Variable to store reset counter value */ - uint8_t reset_counter; -}; - -/******************* Function prototype declarations ********************/ - -/*! - * @brief Function to read data and validate if the sensor is out of range - * - * @param[in,out] out_of_range : Flag that indicates that the sensor is out of range - * @param[out] data : Sensor data - * @param[out] oor : Structure that stores the state of the out of range detector - * @param[in,out] dev : Device structure of the BMM350 - * - * @return Result of API execution status - * @retval = 0 -> Success - * @retval < 0 -> Error - */ -int8_t bmm350_oor_read(bool *out_of_range, - struct sBmm350MagTempData_t *data, - struct bmm350_oor_params *oor, - struct bmm350_dev *dev); - -/*! - * @brief Function to perform reset sequence in forced mode. - * - * @param[in,out] oor : Structure that stores the state of the out of range detector - * @param[in,out] dev : Structure instance of bmm350_dev. - * - * @return Result of API execution status - * @retval = 0 -> Success - * @retval < 0 -> Error - */ -int8_t bmm350_oor_perform_reset_sequence_forced(struct bmm350_oor_params *oor, struct bmm350_dev *dev); - -#ifdef __cplusplus -} -#endif /* End of CPP guard */ - -#endif /* _BMM350_OOR_H */ From 1f6f4a8664cb89672b51b9611fc59c0344d86a8b Mon Sep 17 00:00:00 2001 From: Siddharth Narayan Date: Sat, 11 Apr 2026 01:25:35 -0500 Subject: [PATCH 06/12] Move code out of control, now that there's less to group, and some other misc changes --- include/robot/control/magnet.h | 34 ------ include/robot/{control => }/lights.h | 4 + include/robot/{control => }/motor.h | 0 include/robot/{control => }/robot.h | 17 ++- include/tests.h | 5 +- include/utils/status.h | 10 -- include/utils/timer.h | 31 ----- include/wifi/connection.h | 15 +-- include/wifi/packet.h | 39 ++++++- include/wifi/wireless.h | 9 -- platformio.ini | 1 + src/main.cpp | 41 ++----- src/robot/control/magnet.cpp | 125 --------------------- src/robot/{control => }/lights.cpp | 20 ++-- src/robot/{control => }/motor.cpp | 4 +- src/robot/{control => }/robot.cpp | 111 ++++++++++++------ src/tests.cpp | 7 +- src/utils/logging.cpp | 1 - src/utils/status.cpp | 19 ---- src/utils/timer.cpp | 87 -------------- src/wifi/connection.cpp | 145 ++++-------------------- src/wifi/packet.cpp | 162 +++++++++++++-------------- src/wifi/wireless.cpp | 92 --------------- 23 files changed, 260 insertions(+), 719 deletions(-) delete mode 100644 include/robot/control/magnet.h rename include/robot/{control => }/lights.h (94%) rename include/robot/{control => }/motor.h (100%) rename include/robot/{control => }/robot.h (88%) delete mode 100644 include/utils/status.h delete mode 100644 include/utils/timer.h delete mode 100644 include/wifi/wireless.h delete mode 100644 src/robot/control/magnet.cpp rename src/robot/{control => }/lights.cpp (82%) rename src/robot/{control => }/motor.cpp (95%) rename src/robot/{control => }/robot.cpp (73%) delete mode 100644 src/utils/status.cpp delete mode 100644 src/utils/timer.cpp delete mode 100644 src/wifi/wireless.cpp diff --git a/include/robot/control/magnet.h b/include/robot/control/magnet.h deleted file mode 100644 index cacc310..0000000 --- a/include/robot/control/magnet.h +++ /dev/null @@ -1,34 +0,0 @@ -#pragma once - -#include -#include "DFRobot_BMM350.h" - -struct MagnetReading { - float x; - float y; - float z; -}; - -class Magnet { - public: - Magnet(); - void set_hard_iron_offset(float x, float y, float z); - void set_soft_iron_matrix(float matrix[3][3]); - struct MagnetReading read_calibrated_data(); - float getCompassDegree(struct MagnetReading mag); - float readDegreesRaw(); - float readDegrees(); - bool isDataReady(); - bool isActive(); - private: - float hard_iron_offset[3] = { -10.20, -2.62, -13.21 }; - float soft_iron_matrix[3][3] = { - { 1.024, -0.020, 0.027 }, - { -0.020, 0.968, 0.008 }, - { 0.027, 0.008, 1.011 } - }; - DFRobot_BMM350_I2C bmm350; - - float previousReading = -1.0; - bool activeFlag = false; -}; \ No newline at end of file diff --git a/include/robot/control/lights.h b/include/robot/lights.h similarity index 94% rename from include/robot/control/lights.h rename to include/robot/lights.h index e78ec83..67c3c48 100644 --- a/include/robot/control/lights.h +++ b/include/robot/lights.h @@ -18,8 +18,12 @@ class Light { private: gpio_num_t pin; + short _raw_value; + + bool _value; bool _held_value; + bool _changed_this_tick; unsigned long _last_changed_time; }; diff --git a/include/robot/control/motor.h b/include/robot/motor.h similarity index 100% rename from include/robot/control/motor.h rename to include/robot/motor.h diff --git a/include/robot/control/robot.h b/include/robot/robot.h similarity index 88% rename from include/robot/control/robot.h rename to include/robot/robot.h index c03d2e0..7b53b46 100644 --- a/include/robot/control/robot.h +++ b/include/robot/robot.h @@ -2,8 +2,8 @@ #include -#include "robot/control/lights.h" -#include "robot/control/motor.h" +#include "robot/lights.h" +#include "robot/motor.h" #include "robot/pidController.h" #include "utils/config.h" #include "utils/geometry.h" @@ -47,20 +47,23 @@ class MotionController { TRAVELLING, // Aligning to the correct rotation - ALIGNING + ALIGNING, + ARRIVED }; MotionController(); + MotionPhase phase(); void set_goal(Coordinate2D goal_destination, double goal_angle); std::tuple update_speeds(Coordinate2D position, double angle, double dt); + void print_status(); void reset(); private: PIDController DistVelocityController; PIDController AVelocityController; - MotionPhase phase; + MotionPhase _phase; double goal_angle; Coordinate2D goal_position; @@ -76,14 +79,15 @@ class Robot { void tick(uint32_t frame, uint32_t delay); void center(); - void drive(float tiles, std::string id); + void drive(double tiles, std::string id); void drive(Coordinate2D goal_pos, double goal_angle); void drive(std::tuple& powers, std::string id); void driveTicks(int tickDistance, std::string id); enum DriveStatus driveUntilNewTile(); - void turn(float angleRadians, std::string id); + void turn(double angleRadians, std::string id); + void start(); void stop(); void test(); @@ -99,6 +103,7 @@ class Robot { Light back_right_light; // State + bool stopped; double rotation; Coordinate2D position; MotionController motion_controller; diff --git a/include/tests.h b/include/tests.h index 5dde1be..456b542 100644 --- a/include/tests.h +++ b/include/tests.h @@ -1,4 +1,7 @@ -#include "robot/control/robot.h" +#include "robot/robot.h" + +// Turns off the motors, so we can easily read data +void sleepy_test(Robot& r); // Moves to 0 -> 2PI -> 0 -> 4PI -> 0 on a clock to test angular PID void circle_test(Robot& r); diff --git a/include/utils/status.h b/include/utils/status.h deleted file mode 100644 index 33dc159..0000000 --- a/include/utils/status.h +++ /dev/null @@ -1,10 +0,0 @@ -#pragma once - -bool getServerConnectionStatus(); -void setServerConnectionStatus(bool value); - -bool getWiFiConnectionStatus(); -void setWiFiConnectionStatus(bool value); - -bool getStoppedStatus(); -void setStoppedStatus(bool value); \ No newline at end of file diff --git a/include/utils/timer.h b/include/utils/timer.h deleted file mode 100644 index 0d38ceb..0000000 --- a/include/utils/timer.h +++ /dev/null @@ -1,31 +0,0 @@ -#pragma once - -#include -//we're gonna need this if we need to use delays which require functions -#include - -// This callback allows you to just pass in the pointer of a function as a parameter -using TimerCallback = std::function; -struct Timer { - // Whether the timer is cancelled after it finishes, or set to run again - bool oneOff; - // The amount of time until the timer expires - int delay; - // The time that the timer started (or refreshed in the case of non one-off timers) - unsigned long lastMillis; - // The ID of the timer (Timestamp timer was created. Same as lastMillis for oneOffs) - unsigned long id; - // The function to be run after the timer expires - TimerCallback func; -}; - -unsigned long timerDelay(int delay, TimerCallback func); -unsigned long timerInterval(int interval, TimerCallback func); - -Timer getTimer(unsigned long id); - -void timerReset(unsigned long id); -void timerCancel(unsigned long id); -void timerCancelAll(); - -void timerStep(); \ No newline at end of file diff --git a/include/wifi/connection.h b/include/wifi/connection.h index aba79bd..9faef93 100644 --- a/include/wifi/connection.h +++ b/include/wifi/connection.h @@ -2,15 +2,8 @@ #include #include +#include -void connectServer(); -void disconnectServer(); -void reconnectServer(); -bool checkServerConnection(); -void initiateHandshake(); - -JsonDocument acceptData(); -void sendPacket(JsonDocument& packet); -void sendActionSuccess(std::string messageId); -void sendActionFail(std::string messageId); -void sendPingResponse(); \ No newline at end of file +JsonDocument recv_packet(WiFiClient& client); +void send_packet(JsonDocument packet); +void send_ping(); \ No newline at end of file diff --git a/include/wifi/packet.h b/include/wifi/packet.h index 6d414e4..f6b109b 100644 --- a/include/wifi/packet.h +++ b/include/wifi/packet.h @@ -3,11 +3,38 @@ #include #include +#include "robot/robot.h" -void handlePacket(JsonDocument packet); -std::string unint8ArrayToHexString(uint8_t* oldArray, int len); +enum PacketType : uint8_t { + CLIENT_HELLO, + SERVER_HELLO, + PING_SEND, + PING_RESPONSE, + QUERY_VAR, + QUERY_RESPONSE, + SET_VAR, + TURN_BY_ANGLE, + DRIVE_TILES, + DRIVE_TICKS, + ACTION_SUCCESS, + ACTION_FAIL, + DRIVE_TANK, + ESTOP, + CUBIC, + QUADRATIC, + SPIN_RADIANS, + BS_MOVE, + + ERROR // Not a valid packet type +}; -void constructHelloPacket(JsonDocument& packet); -void constructSuccessPacket(JsonDocument& packet, std::string messageId); -void constructFailPacket(JsonDocument& packet, std::string messageId); -void constructPingPacket(JsonDocument& packet); \ No newline at end of file +// Checks that the json document has the correct field and type +// If it doesn't contain the correct field, returns false +#define ASSERT_FIELD(packet, key, _type) \ + if (!packet[key].is<_type>()) { \ + return false; \ + } + +PacketType parse_packet_type(const char * type); +bool handle_packet(Robot& r, JsonDocument packet); +std::string unint8ArrayToHexString(uint8_t* oldArray, int len); diff --git a/include/wifi/wireless.h b/include/wifi/wireless.h deleted file mode 100644 index 0bbc5bb..0000000 --- a/include/wifi/wireless.h +++ /dev/null @@ -1,9 +0,0 @@ -#pragma once - -const char* getWifiStatus(int status); -bool checkWiFiConnection(); -void confirmWiFi(); -void connectWiFI(); -void reconnectWiFI(); -void disconnectWiFI(); -void createWiFi(); \ No newline at end of file diff --git a/platformio.ini b/platformio.ini index f49fb9e..8ab31c9 100644 --- a/platformio.ini +++ b/platformio.ini @@ -13,6 +13,7 @@ platform = espressif32 board = lolin_s2_mini framework = arduino monitor_speed = 115200 +# build_src_flags build_flags = -O3 -Wall diff --git a/src/main.cpp b/src/main.cpp index ba0ed19..6367b5f 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -1,59 +1,40 @@ #include +#include #include "../env.h" -#include "robot/control/magnet.h" -#include "robot/control/robot.h" +#include "robot/robot.h" #include "robot/pidController.h" #include "tests.h" #include "utils/config.h" #include "utils/logging.h" -#include "utils/status.h" -#include "utils/timer.h" #include "wifi/connection.h" -#include "wifi/wireless.h" uint32_t frame = 0; - uint32_t previous_time = 0; -Robot robot = Robot(); +WiFiClient client; +Robot robot; // Setup gets run at startup void setup() { - // Serial port for debugging purposes - if (LOGGING_LEVEL > 0) Serial.begin(115200); + delay(5000); + // client.connect(SERVER_IP, SERVER_PORT); - delay(STARTUP_DELAY); - serial_printf(DebugLevel::DEBUG, "Finished Delay!\n"); - - // Create a WiFi network for the laptop to connect to - if (!RUN_OFFLINE) connectWiFI(); + if (LOGGING_LEVEL > 0) Serial.begin(115200); previous_time = micros(); - // robot.center(); + + // sleepy_test(robot); + robot.center(); } // After setup gets run, loop is run over and over as fast ass possible void loop() { - // Checks if any timers have expired - timerStep(); - - if (!RUN_OFFLINE) - { - // Checks whether bot is still connected to WiFi. Reconnect if not - if (getWiFiConnectionStatus() && !checkWiFiConnection()) reconnectWiFI(); - // Checks whether bot is still connected to the server. Reconnect if not - if (getServerConnectionStatus() && !checkServerConnection()) reconnectServer(); - - // If the bot is connected to the server, check for received data, and accept it if available - if (getServerConnectionStatus()) acceptData(); - } - uint32_t delta = micros() - previous_time; previous_time = micros(); - square_test(robot); robot.tick(frame, delta); + // square_test(robot); frame++; } \ No newline at end of file diff --git a/src/robot/control/magnet.cpp b/src/robot/control/magnet.cpp deleted file mode 100644 index b271498..0000000 --- a/src/robot/control/magnet.cpp +++ /dev/null @@ -1,125 +0,0 @@ -#include - -#include "robot/control/magnet.h" - -#include "utils/logging.h" - -#define SDA_PIN 8 -#define SCL_PIN 9 - -Magnet::Magnet() - : bmm350(&Wire, 0x14) -{ - Wire.begin(SDA_PIN, SCL_PIN); - int maxTries = 6; - int errorCode = -1; - while (maxTries-- > 0 && (errorCode=bmm350.begin())) - { - delay(500); - serial_printf(DebugLevel::INFO, "Retrying BMM350 connection... (error code %d)\n", errorCode); - } - if (errorCode > 0) { - serial_printf(DebugLevel::INFO, "BMM350 not detected at default I2C address. Check wiring.\n"); - return; - } else { - serial_printf(DebugLevel::INFO, "BMM350 detected.\n"); - } - bmm350.setOperationMode(eBmm350NormalMode); - bmm350.setPresetMode(BMM350_PRESETMODE_HIGHACCURACY, BMM350_DATA_RATE_25HZ); - bmm350.setMeasurementXYZ(); - activeFlag = true; - // bmm350.setDataReadyPin(BMM350_ENABLE_INTERRUPT, BMM350_ACTIVE_LOW); - // pinMode(/*Pin */ 13, INPUT_PULLUP); - // maxTries = 5; - // bool dataReady = false; - // while (maxTries-- > 0 && !(dataReady=bmm350.getDataReadyState())) { - // delay(100); - // } - // if (dataReady) { - // serialLogln("BMM350 data ready interrupt enabled.", 1); - // activeFlag = true; - // } else { - // serialLogln("BMM350 data ready interrupt not detected. Check wiring.", 1); - // } -} - -bool Magnet::isActive() { - return activeFlag; -} - -bool Magnet::isDataReady() { - return bmm350.getDataReadyState(); -} - -void Magnet::set_hard_iron_offset(float x, float y, float z) { - hard_iron_offset[0] = x; - hard_iron_offset[1] = y; - hard_iron_offset[2] = z; -} - -void Magnet::set_soft_iron_matrix(float matrix[3][3]) { - for (int i = 0; i < 3; i++) { - for (int j = 0; j < 3; j++) { - soft_iron_matrix[i][j] = matrix[i][j]; - } - } -} - -MagnetReading Magnet::read_calibrated_data() { - sBmm350MagData_t sensor_mag_data = bmm350.getGeomagneticData(); - float hi_data[3]; - float mag_data[3]; - - hi_data[0] = sensor_mag_data.float_x - hard_iron_offset[0]; - hi_data[1] = sensor_mag_data.float_y - hard_iron_offset[1]; - hi_data[2] = sensor_mag_data.float_z - hard_iron_offset[2]; - - for (int i = 0; i < 3; i++) { - mag_data[i] = (soft_iron_matrix[i][0] * hi_data[0]) + (soft_iron_matrix[i][1] * hi_data[1]) + (soft_iron_matrix[i][2] * hi_data[2]); - } - - MagnetReading calibrated_data = { mag_data[0], mag_data[1], mag_data[2] }; - return calibrated_data; -} - -float Magnet::getCompassDegree(MagnetReading mag) { - float compass = 0.0; - compass = atan2(mag.x, mag.y); - if (compass < 0) { - compass += 2 * PI; - } - if (compass > 2 * PI) { - compass -= 2 * PI; - } - return compass * 180 / M_PI; -} - -float Magnet::readDegreesRaw() { - MagnetReading mag = read_calibrated_data(); - return getCompassDegree(mag); -} - -float Magnet::readDegrees() { - // // Only works if data ready interrupt is enabled - // if (previousReading >= 0 && !bmm350.getDataReadyState()) { - // return previousReading; // Return the last reading if data is not ready and previousReading is valid - // } - float currentReading = readDegreesRaw(); - // Handle first reading - if (previousReading < 0) { - previousReading = currentReading; - return currentReading; - } - // Handle wrap-around - if (currentReading - previousReading > 180) { - previousReading += 360; - } else if (currentReading - previousReading < -180) { - previousReading -= 360; - } - // Simple low-pass filter - // currentReading = previousReading * 0.8 + currentReading * 0.2; - if (currentReading >= 360) currentReading -= 360; - else if (currentReading < 0) currentReading += 360; - previousReading = currentReading; - return currentReading; -} diff --git a/src/robot/control/lights.cpp b/src/robot/lights.cpp similarity index 82% rename from src/robot/control/lights.cpp rename to src/robot/lights.cpp index ad6f5d5..c7fe06d 100644 --- a/src/robot/control/lights.cpp +++ b/src/robot/lights.cpp @@ -1,14 +1,14 @@ #include -#include "robot/control/lights.h" +#include "robot/lights.h" -#include "../../../env.h" +#include "../../env.h" #include "utils/config.h" #include "utils/logging.h" -static short LIGHT_RAW_VALUE_CUTOFF = 7600; +static short LIGHT_RAW_VALUE_CUTOFF = 3000; bool is_light_value_on(short value) { - return value < LIGHT_RAW_VALUE_CUTOFF; + return value > LIGHT_RAW_VALUE_CUTOFF; } Light::Light(gpio_num_t _pin) { @@ -16,13 +16,15 @@ Light::Light(gpio_num_t _pin) { } void Light::tick() { - short prev = _raw_value; - + bool previous_value = _value; _changed_this_tick = false; - _raw_value = analogRead(pin); - _held_value = _held_value || is_light_value_on(_raw_value); - if (prev != _raw_value) { + _raw_value = analogRead(pin); + + _value = is_light_value_on(_raw_value); + _held_value = _value || _held_value; + + if (_value != previous_value) { _changed_this_tick = true; _last_changed_time = millis(); } diff --git a/src/robot/control/motor.cpp b/src/robot/motor.cpp similarity index 95% rename from src/robot/control/motor.cpp rename to src/robot/motor.cpp index 6c01692..3046434 100644 --- a/src/robot/control/motor.cpp +++ b/src/robot/motor.cpp @@ -1,6 +1,6 @@ #include -#include "robot/control/motor.h" +#include "robot/motor.h" #include "utils/config.h" #include "utils/functions.h" @@ -81,7 +81,7 @@ double Motor::tick_dist() { // Takes in a power between [0, 1] // We use this to change a double power between 0-1 to an int duty cycle between 0-4096 int power_to_duty(double power) { - int value = fmap(power, 0.0, 1.0, 0.0, 4096); + int value = fmap(power, 0.0, 1.0, 0.0, 1024); serial_printf(DebugLevel::RIDICULOUS, "Mapped Duty: %d\n", value); return value; diff --git a/src/robot/control/robot.cpp b/src/robot/robot.cpp similarity index 73% rename from src/robot/control/robot.cpp rename to src/robot/robot.cpp index 5f4ccda..b78abbe 100644 --- a/src/robot/control/robot.cpp +++ b/src/robot/robot.cpp @@ -3,19 +3,17 @@ #include #include -#include "robot/control/robot.h" +#include "robot/robot.h" -#include "../../../env.h" -#include "robot/control/lights.h" -#include "robot/control/motor.h" +#include "../../env.h" +#include "robot/lights.h" +#include "robot/motor.h" #include "robot/pidController.h" #include "utils/config.h" #include "utils/functions.h" #include "utils/geometry.h" #include "utils/logging.h" #include "utils/logging.h" -#include "utils/status.h" -#include "utils/timer.h" #include "wifi/connection.h" MotionController::MotionController() @@ -23,6 +21,10 @@ MotionController::MotionController() AVelocityController(.1, 0.2, 0.05, -1, +1, 0.0) {} +MotionController::MotionPhase MotionController::phase() { + return _phase; +} + void MotionController::set_goal(Coordinate2D _goal_destination, double _goal_angle) { goal_angle = _goal_angle; goal_position = _goal_destination; @@ -30,6 +32,7 @@ void MotionController::set_goal(Coordinate2D _goal_destination, double _goal_ang std::tuple MotionController::update_speeds(Coordinate2D position, double angle, double dt) { double dist_err = position.distance_to(goal_position); + double angle_err = angle - goal_angle; // So that the robot will not back up from a point in front of it infinitely bool is_behind = position.is_behind(angle, goal_position); @@ -37,24 +40,30 @@ std::tuple MotionController::update_speeds(Coordinate2D position dist_err = -dist_err; } - if (abs(dist_err) < 3) { - if (phase == TRAVELLING) { + if (abs(dist_err) < 3 && abs(angle_err) < M_PI / 16) { + _phase = ARRIVED; + + // C++ let me compile without this return statement + // While on -Wall and -Wextra. + return std::make_tuple(0.0, 0.0); + } else if (abs(dist_err) < 3) { + if (_phase != ALIGNING) { DistVelocityController.Reset(); AVelocityController.Reset(); } - phase = ALIGNING; + _phase = ALIGNING; double angular_vel = AVelocityController.Compute(goal_angle, angle, dt); return std::make_tuple(-angular_vel, angular_vel); } else { - if (phase == ALIGNING) { + if (_phase != TRAVELLING) { DistVelocityController.Reset(); AVelocityController.Reset(); } - phase = TRAVELLING; + _phase = TRAVELLING; double temp_goal_angle = position.angle_to(goal_position); @@ -70,7 +79,7 @@ std::tuple MotionController::update_speeds(Coordinate2D position } void MotionController::print_status() { - serial_printf(DebugLevel::NONE, "MotionController status: %d -- goal_position: (%f, %f), goal_angle: %f\n", phase, goal_position.x, goal_position.y, goal_angle); + serial_printf(DebugLevel::NONE, "MotionController status: %d -- goal_position: (%f, %f), goal_angle: %f\n", _phase, goal_position.x, goal_position.y, goal_angle); } void MotionController::reset() { @@ -85,8 +94,19 @@ Robot::Robot() front_left_light(PHOTODIODE_A_PIN), front_right_light(PHOTODIODE_B_PIN), back_left_light(PHOTODIODE_C_PIN), - back_right_light(PHOTODIODE_D_PIN) -{} + back_right_light(PHOTODIODE_D_PIN), + + stopped(false) + +{ + + // Turn IR blasters on + pinMode(RELAY_IR_LED_PIN, OUTPUT); + + // Turn the ESP LED on + pinMode(ONBOARD_LED_PIN, OUTPUT); + digitalWrite(ONBOARD_LED_PIN, HIGH); +} void Robot::print_status(uint32_t delay) { serial_clear(); @@ -159,20 +179,19 @@ void Robot::tick(uint32_t frame, uint32_t delay) { rotation = rotation + d_angle; center_tick(delay); - pid_tick(delay); + auto motor_speeds = std::make_tuple(0.0, 0.0); + if (!stopped) { + motor_speeds = motion_controller.update_speeds(position, rotation, (double)delay / 1000000); + } + + drive(motor_speeds, "NULL"); if (frame % 64 == 0) { print_status(delay); } } -void Robot::pid_tick(uint32_t delay) { - std::tuple motor_speeds = motion_controller.update_speeds(position, rotation, (double)delay / 1000000); - - drive(motor_speeds, "NULL"); -} - void Robot::center_tick(uint32_t delay) { if (centeringStatus == NOT_CENTERING) { return; @@ -180,10 +199,13 @@ void Robot::center_tick(uint32_t delay) { if (centeringStatus == STARTED) { // Set the goal position to a unit vector ahead of the robot - motion_controller.set_goal(position.transform(Coordinate2D(rotation)), 0); + motion_controller.set_goal(position.transform(Coordinate2D(rotation).scale(10.0)), 0); // The two front sensors crossed at the same time, skip aligning step if (front_left_light.held_value() && front_right_light.held_value()) { + rotation = M_PI / 2; + position = Coordinate2D(0.0, 0.0); + centeringStatus = ALIGNED_EDGE_1; } @@ -192,14 +214,15 @@ void Robot::center_tick(uint32_t delay) { } } - if (centeringStatus == ALIGNING_EDGE_1) { + if (centeringStatus == ALIGNING_EDGE_1) { if (front_left_light.held_value() && front_right_light.held_value()) { rotation = M_PI / 2; - position.y = -3; + position = Coordinate2D(0.0, 0.0); + centeringStatus = ALIGNED_EDGE_1; } - // If the left one crossed latest + // If the left one crossed latest, that's the first one that hit the line if (front_left_light.last_changed_time() > front_right_light.last_changed_time()) { // Turn left motion_controller.set_goal(position, rotation + 1); @@ -210,7 +233,26 @@ void Robot::center_tick(uint32_t delay) { } if (centeringStatus == ALIGNED_EDGE_1) { - motion_controller.set_goal(position.transform(Coordinate2D(rotation)), 0); + motion_controller.set_goal(Coordinate2D(0.0, 10.0), 0); + + if (motion_controller.phase() == MotionController::MotionPhase::ARRIVED) { + centeringStatus = CENTERED_Y_AXIS; + } + } + + // Similar to the STARTING status + if (centeringStatus == CENTERED_Y_AXIS) { + // Set the goal position to a unit vector ahead of the robot + motion_controller.set_goal(position.transform(Coordinate2D(rotation).scale(10.0)), 0); + + // We trust that our first alignment was good and we are at 0 radians rotation. + // Once both sensors pass we're good + if (front_left_light.held_value() && front_right_light.held_value()) { + position.x = 3; + + motion_controller.set_goal(Coordinate2D(0.0, 0.0), M_PI / 2); + centeringStatus = NOT_CENTERING; + } } } @@ -224,7 +266,7 @@ void Robot::drive(Coordinate2D goal_pos, double goal_angle) { motion_controller.set_goal(goal_pos, goal_angle); } -void Robot::drive(float tiles, std::string id) { +void Robot::drive(double tiles, std::string id) { const float TILE_SIZE_CM = 24 * 2.54; motion_controller.set_goal(Coordinate2D(rotation).scale(TILE_SIZE_CM), rotation); } @@ -233,19 +275,20 @@ void Robot::drive(float tiles, std::string id) { void Robot::drive(std::tuple& powers, std::string id) { left.power(std::get<0>(powers)); right.power(std::get<1>(powers)); - - //we only send null as id during our test drive. The only other time this drive method is called will be - //when the server sends it, meaning it will have an id to send back. - if (id != "NULL") { sendActionSuccess(id); } } //turns the given amount in radians, CCW -void Robot::turn(float angleRadians, std::string id) { +void Robot::turn(double angleRadians, std::string id) { +} + +void Robot::start() { + stopped = false; + + serial_printf(DebugLevel::DEBUG, "Bot Started!\n"); } void Robot::stop() { - // Set the goal to where we are right now, so the robot doesn't move - motion_controller.set_goal(position, rotation); + stopped = true; serial_printf(DebugLevel::DEBUG, "Bot Stopped!\n"); } \ No newline at end of file diff --git a/src/tests.cpp b/src/tests.cpp index 720d133..b76365c 100644 --- a/src/tests.cpp +++ b/src/tests.cpp @@ -2,9 +2,14 @@ #include "tests.h" -#include "robot/control/robot.h" +#include "robot/robot.h" #include "utils/geometry.h" +// Turns off the motion controller on the robot +void sleepy_test(Robot& r) { + r.stop(); +} + // Test the distance PID controller void line_test(Robot& r) { unsigned long time_seconds = millis() / 1000; diff --git a/src/utils/logging.cpp b/src/utils/logging.cpp index 9430864..482e521 100644 --- a/src/utils/logging.cpp +++ b/src/utils/logging.cpp @@ -3,7 +3,6 @@ #include "../env.h" #include "utils/logging.h" -#include "utils/status.h" // Prints a value or message through Serial. (The console) // ln means it sends a new newline character diff --git a/src/utils/status.cpp b/src/utils/status.cpp deleted file mode 100644 index e60632a..0000000 --- a/src/utils/status.cpp +++ /dev/null @@ -1,19 +0,0 @@ -#include "utils/status.h" - -bool wifiConnected = false; -bool serverConnected = false; -bool botStopped = false; - -bool getWiFiConnectionStatus() { - return wifiConnected; -} -void setWiFiConnectionStatus(bool value) { - wifiConnected = value; -} - -bool getServerConnectionStatus() { - return serverConnected; -} -void setServerConnectionStatus(bool value) { - serverConnected = value; -} \ No newline at end of file diff --git a/src/utils/timer.cpp b/src/utils/timer.cpp deleted file mode 100644 index 3f3af37..0000000 --- a/src/utils/timer.cpp +++ /dev/null @@ -1,87 +0,0 @@ -#include -#include - -#include "utils/logging.h" -#include "utils/timer.h" - -// How to pass function from within a class (Uses a lambda that captures the class' pointer) -// [this](){ func(); } - -// Stores all the timers, indexed by their id -std::map timers; - -// Will run the function you provide after 'delay' amount of milliseconds. -// Accepts a delay in milliseconds, and a function as a pointer -// Returns the id of the timer -unsigned long timerDelay(int delay, TimerCallback func) { - // This uses a custom Timer struct (located in timer.h) - Timer newTimer; - newTimer.id = micros(); - newTimer.oneOff = true; - newTimer.delay = delay; - newTimer.func = func; - newTimer.lastMillis = millis(); - timers[newTimer.id] = newTimer; - // Returns the id for modifying - return newTimer.id; -} - -// Will run the function you provide every 'interval' milliseconds. -// Accepts an interval in milliseconds, and a function as a pointer -// Returns the id of the timer -unsigned long timerInterval(int interval, TimerCallback func) { - // This uses a custom Timer struct (located in timer.h) - Timer newTimer; - newTimer.id = micros(); - newTimer.oneOff = false; - newTimer.delay = interval; - newTimer.func = func; - newTimer.lastMillis = millis(); - timers[newTimer.id] = newTimer; - // Returns the id for modifying - return newTimer.id; -} - -// Returns the Timer struct associated with the id -Timer getTimer(unsigned long id) { - return timers[id]; -} - -// Resets the time on an active timer -void timerReset(unsigned long id) { - timers[id].lastMillis = millis(); -} - -// Deletes the timer from the map -void timerCancel(unsigned long id) { - timers.erase(id); -} - -// Cancels all timers -void timerCancelAll() { - timers.clear(); -} - -// Checks timers for any expired ones -void timerStep() { - // Iterates through the timer map key value pairs - for (auto index = timers.begin(); index != timers.end();) { - unsigned long id = index->first; - if (millis() - timers[id].lastMillis >= timers[id].delay) { - TimerCallback func = timers[id].func; - if (timers[id].oneOff) { - // If the timer is one-off, cancel it after it expires - index = timers.erase(index); - } else { - // If the timer isn't one-off, refresh it after it expires - timerReset(id); - index++; - } - - // Calls the linked function - func(); - } else { - index++; - } - } -} \ No newline at end of file diff --git a/src/wifi/connection.cpp b/src/wifi/connection.cpp index 8c7606c..74174c5 100644 --- a/src/wifi/connection.cpp +++ b/src/wifi/connection.cpp @@ -5,149 +5,44 @@ #include "wifi/connection.h" #include "../../env.h" -#include "robot/control/robot.h" +#include "robot/robot.h" #include "utils/logging.h" -#include "utils/status.h" -#include "utils/timer.h" #include "wifi/packet.h" -bool serverConnecting = false; -bool pinging = false; -int missedPings = 0; -unsigned long pingTimeoutTimer; - -WiFiClient client; - -// Called to connect to the server whose info is stored in env.h -void connectServer() { - serial_printf(DebugLevel::DEBUG, "Connecting to Server...\n"); - if (client.connect(SERVER_IP, SERVER_PORT)) { - // If successful, sets the connection status and stops trying to connect to the server - setServerConnectionStatus(true); - serverConnecting = false; - serial_printf(DebugLevel::DEBUG, "Connected to Server!\n"); - - // A handshake is an initial exchange of information, and a confirmation of a connection - if (DO_HANDSHAKE) { initiateHandshake(); } - } else { - serverConnecting = true; - // If unsuccessful, tries again in 5 seconds - serial_printf(DebugLevel::DEBUG, "Connection To Server Failed! Retrying...\n"); - - timerDelay(HANDSHAKE_INTERVAL, &connectServer); - } -} - -// Completely disconnect from the server -void disconnectServer() { - setServerConnectionStatus(false); - client.stop(); - serial_printf(DebugLevel::DEBUG, "Disconnected From Server!\n"); -} - -// If not connected to the server (whether by disconnect or by lost connection), reconnects -void reconnectServer() { - if (!serverConnecting) { - setServerConnectionStatus(false); - serial_printf(DebugLevel::DEBUG, "Disconnected From Server! Reconnecting...\n"); - connectServer(); - } -} - -// Checks whether still connected to server -bool checkServerConnection() { - return client.connected(); -} - -// Sends an initial packet to the server. Contains the mac address of this bot -void initiateHandshake() { +JsonDocument recv_packet(WiFiClient& client) { + int index = 0; + char raw_packet[500]; JsonDocument packet; - constructHelloPacket(packet); - serial_printf(DebugLevel::DEBUG, "Sending Handshake...\n"); - sendPacket(packet); -} + + while (client.available()) { + char data = client.read(); -// The buffer size is 500 characters. If there are issues right after -// accepting a packet, the buffer size may be the culprit -JsonDocument acceptData() { - JsonDocument packet; - if (client.available()) { - // Allocates a buffer to hold the incoming packet - char rawPacket[500]; - int len = 0; - bool packetDone = false; - while (client.available() || !packetDone) { - // Reads in a single character - char data = client.read(); - if (data == ';' || len > 499) { - // If the delimiter character is encountered, the packet is done - packetDone = true; - } else { - // Adds the character to the buffer - rawPacket[len] = data; - len++; - } + if (data == ';' || index > 499) { + break; + } else { + raw_packet[index] = data; + index++; } - - // The packet is in the form of a JSON. We use a library to handle them - - // This turns the character buffer into a fully formed JSON object - deserializeJson(packet, rawPacket); } + + deserializeJson(packet, raw_packet); return packet; } // Sends a packet to the server -void sendPacket(JsonDocument& packet) { +void send_packet(WiFiClient& client, JsonDocument packet) { // This takes that JSON object and sends it through the client's socket serializeJson(packet, client); + // Sends a delimiter character to mark the end of the packet client.write(';'); } -void sendActionSuccess(std::string messageId) { +void send_ping() { JsonDocument packet; - constructSuccessPacket(packet, messageId); - serial_printf(DebugLevel::DEBUG, "Sending Action Success...\n"); - sendPacket(packet); -} - -void sendActionFail(std::string messageId) { - JsonDocument packet; - constructFailPacket(packet, messageId); - serial_printf(DebugLevel::DEBUG, "Sending Action Success...\n"); - sendPacket(packet); -} - -void pingTimeout() { - if (DO_PINGING) { - missedPings++; - serial_printf(DebugLevel::DEBUG, "%u missed pings!\n", missedPings); + packet["type"] = PING_RESPONSE; + packet["batteryLevel"] = Robot::batteryLevel(); - if (missedPings >= PING_MAX_MISSES) { - serial_printf(DebugLevel::DEBUG, "SERVER TIMED OUT!\n"); - // TODO: stop(); - pinging = false; - } else { - pingTimeoutTimer = timerDelay(PING_TIMEOUT, &pingTimeout); - } - } -} - -void sendPingResponse() { - if (DO_PINGING) { - JsonDocument packet; - constructPingPacket(packet); - serial_printf(DebugLevel::DEBUG, "Sending Ping Response...\n"); - sendPacket(packet); - if (pinging) { - timerReset(pingTimeoutTimer); - } else { - pingTimeoutTimer = timerDelay(PING_TIMEOUT, &pingTimeout); - serial_printf(DebugLevel::DEBUG, "Started Ping Timeout Timer\n"); - pinging = true; - } - missedPings = 0; - } + send_packet(packet); } \ No newline at end of file diff --git a/src/wifi/packet.cpp b/src/wifi/packet.cpp index b4e842d..b9af948 100644 --- a/src/wifi/packet.cpp +++ b/src/wifi/packet.cpp @@ -1,108 +1,98 @@ #include #include #include +#include #include "wifi/packet.h" -#include "robot/control/robot.h" +#include "robot/robot.h" #include "utils/config.h" #include "utils/functions.h" #include "utils/logging.h" -#include "utils/status.h" #include "wifi/connection.h" -// These are the various different supported message types that can be sent over TCP -const char* CLIENT_HELLO = "CLIENT_HELLO"; -const char* SERVER_HELLO = "SERVER_HELLO"; -const char* PING_SEND = "PING_SEND"; -const char* PING_RESPONSE = "PING_RESPONSE"; -const char* QUERY_VAR = "QUERY_VAR"; -const char* QUERY_RESPONSE = "QUERY_RESPONSE"; -const char* SET_VAR = "SET_VAR"; -const char* TURN_BY_ANGLE = "TURN_BY_ANGLE"; -const char* DRIVE_TILES = "DRIVE_TILES"; -const char* DRIVE_TICKS = "DRIVE_TICKS"; -const char* ACTION_SUCCESS = "ACTION_SUCCESS"; -const char* ACTION_FAIL = "ACTION_FAIL"; -const char* DRIVE_TANK = "DRIVE_TANK"; -const char* ESTOP = "ESTOP"; -const char* CUBIC = "DRIVE_CUBIC_SPLINE"; -const char* QUADRATIC = "DRIVE_QUADRATIC_SPLINE"; -const char* SPIN_RADIANS = "SPIN_RADIANS"; -const char* BS_MOVE = "BS_MOVE"; +PacketType parse_packet_type(std::string type) { + if (type == "CLIENT_HELLO") { + return CLIENT_HELLO; + } + if (type == "SERVER_HELLO") { + return SERVER_HELLO; + } + if (type == "PING_SEND") { + return PING_SEND; + } + if (type == "PING_RESPONSE") { + return PING_RESPONSE; + } + if (type == "TURN_BY_ANGLE") { + return TURN_BY_ANGLE; + } + if (type == "DRIVE_TILES") { + return DRIVE_TILES; + } + if (type == "DRIVE_TICKS") { + return DRIVE_TICKS; + } + if (type == "ACTION_SUCCESS") { + return ACTION_SUCCESS; + } + if (type == "ACTION_FAIL") { + return ACTION_FAIL; + } + if (type == "DRIVE_TANK") { + return DRIVE_TANK; + } + if (type == "ESTOP") { + return ESTOP; + } + if (type == "SPIN_RADIANS") { + return SPIN_RADIANS; + } + if (type == "BS_MOVE") { + return BS_MOVE; + } + + return ERROR; +} // Takes a packet a does specific things based on the type -void handlePacket(Robot& r, JsonDocument packet) { - // Sadly a switch case can't be used due to the packet type being a string. - // We do this to allow the packets to be more readable when serial_printf(DebugLevel::ged - if (packet["type"] == SERVER_HELLO) { +bool handle_packet(Robot& r, JsonDocument packet) { + ASSERT_FIELD(packet, "type", const char *) + + PacketType type = parse_packet_type(packet["type"].as()); + if (type == SERVER_HELLO) { // When we initiate a handshake, the server sends a handshake back. This server handshake // contains any variable that should be changed in this bot's config + ASSERT_FIELD(packet, "config", JsonObject) + setConfig(packet["config"].as()); - } else if (packet["type"] == DRIVE_TANK) { - // This is received when the bot is being manually controlled via the debug page - // r.drive(packet["left"], packet["right"], packet["packetId"]); - } else if (packet["type"] == DRIVE_TICKS){ - r.driveTicks(packet["tickDistance"], packet["packetId"]); - } else if (packet["type"] == ESTOP) { - r.stop(); - } else if (packet["type"] == CUBIC) { - // Point startPosition = {(float)packet["startPosition"]["x"]*TILES_TO_TICKS, (float)packet["startPosition"]["y"]*TILES_TO_TICKS}; - // Point endPosition = {(float)packet["endPosition"]["x"]*TILES_TO_TICKS, (float)packet["endPosition"]["y"]*TILES_TO_TICKS}; - // Point controlPositionA = {(float)packet["controlPositionA"]["x"]*TILES_TO_TICKS, (float)packet["controlPositionA"]["y"]*TILES_TO_TICKS}; - // Point controlPositionB = {(float)packet["controlPositionB"]["x"]*TILES_TO_TICKS, (float)packet["controlPositionB"]["y"]*TILES_TO_TICKS}; - // danceMonkeyCubic(packet["packetId"], startPosition, controlPositionA, controlPositionB, endPosition, packet["timeDeltaMs"]); - } else if (packet["type"] == QUADRATIC) { - // serial_printf(DebugLevel::("I have arrived!! at Quadratic", 3); - // Point startPosition = {(float)packet["startPosition"]["x"]*TILES_TO_TICKS, (float)packet["startPosition"]["y"]*TILES_TO_TICKS}; - // Point endPosition = {(float)packet["endPosition"]["x"]*TILES_TO_TICKS, (float)packet["endPosition"]["y"]*TILES_TO_TICKS}; - // Point controlPosition = {(float)packet["controlPosition"]["x"]*TILES_TO_TICKS, (float)packet["controlPosition"]["y"]*TILES_TO_TICKS}; - // danceMonkeyQuadratic(packet["packetId"], startPosition, controlPosition, endPosition, packet["timeDeltaMs"]); - } else if (packet["type"] == SPIN_RADIANS) { - // serial_printf(DebugLevel::("Going to spin!", 3); - // int offsetTicks = radiansToTicks((float)packet["radians"]); - // startCustomMotionProfileTimer(-offsetTicks, offsetTicks, (double)packet["timeDeltaMs"]/1000, packet["packetId"]); - } else if (packet["type"] == TURN_BY_ANGLE) { - r.turn(packet["deltaHeadingRadians"], packet["packetId"]); - } else if (packet["type"] == DRIVE_TILES) { - // r.drive(packet["tiles"], packet["packetId"]); - } else if (packet["type"] == PING_SEND) { - sendPingResponse(); - } -} + } else if (type == DRIVE_TANK) { + // Manual control of the robot -enum ResponsePacketType { - Ping, - Hello, - Success, - Fail, -}; + ASSERT_FIELD(packet, "left", double) + ASSERT_FIELD(packet, "left", double) + ASSERT_FIELD(packet, "packetId", const char *) -// This creates the handshake packet sent to the server when this bot connects to it -void constructHelloPacket(JsonDocument& packet) { - packet["type"] = CLIENT_HELLO; - uint8_t mac[8]; - // Gets the mac address of this esp - esp_efuse_mac_get_default(mac); - // Converts the mac address into the form the server is expecting - std::string stringMac = unint8ArrayToHexString(mac, 6); - packet["macAddress"] = stringMac; -} + std::tuple power = std::make_tuple( + packet["left"].as(), packet["right"].as() + ); -//Note that the assigning of the messageId to the packetId happens in all the methods. One way to better -//streamline this might be to make a general method "constructPacket" that just handles that. For now I -//thought it wouldn't be necessary. As we get more types of messages this may be needed. -void constructSuccessPacket(JsonDocument& packet, std::string messageId) { - packet["type"] = ACTION_SUCCESS; - packet["packetId"] = messageId; -} + r.drive(power, packet["packetId"].as()); + } else if (type == ESTOP) { + r.stop(); + } else if (type == TURN_BY_ANGLE) { + ASSERT_FIELD(packet, "deltaHeadingRadians", double) + ASSERT_FIELD(packet, "packetId", const char *) -void constructFailPacket(JsonDocument& packet, std::string messageId) { - packet["type"] = ACTION_FAIL; - packet["packetId"] = messageId; -} + r.turn(packet["deltaHeadingRadians"].as(), packet["packetId"]); + } else if (type == DRIVE_TILES) { + ASSERT_FIELD(packet, "tiles", double) + ASSERT_FIELD(packet, "packetId", const char *) + + r.drive(packet["tiles"].as(), packet["packetId"].as()); + } else if (type == PING_SEND) { + send_ping(); + } -void constructPingPacket(JsonDocument& packet) { - packet["type"] = PING_RESPONSE; - packet["batteryLevel"] = Robot::batteryLevel(); + return false; } \ No newline at end of file diff --git a/src/wifi/wireless.cpp b/src/wifi/wireless.cpp deleted file mode 100644 index cbf86b4..0000000 --- a/src/wifi/wireless.cpp +++ /dev/null @@ -1,92 +0,0 @@ -#include -#include - -#include "wifi/wireless.h" - -#include "../../env.h" -#include "utils/logging.h" -#include "utils/status.h" -#include "utils/timer.h" -#include "wifi/connection.h" - -bool wifiConnecting = false; - -// Gets the status of the WiFi connection. Called whenever connecting to WiFi fails to get more info -const char* getWifiStatus(int status) { - switch(status){ - case WL_IDLE_STATUS: - return "WL_IDLE_STATUS"; - case WL_SCAN_COMPLETED: - return "WL_SCAN_COMPLETED"; - case WL_NO_SSID_AVAIL: - return "WL_NO_SSID_AVAIL"; - case WL_CONNECT_FAILED: - return "WL_CONNECT_FAILED"; - case WL_CONNECTION_LOST: - return "WL_CONNECTION_LOST"; - case WL_CONNECTED: - return "WL_CONNECTED"; - case WL_DISCONNECTED: - return "WL_DISCONNECTED"; - } - return "No Status"; -} - -// Checks whether the bot is connected to a WiFi network -bool checkWiFiConnection() { - return WiFi.status() == WL_CONNECTED; -} - -// If not connected to WiFi by now, serial_printf(DebugLevel:: 'why' -// Tries to connect until success. After connected to WiFi, starts trying to connect to the server -void confirmWiFi() { - if (checkWiFiConnection()) { - setWiFiConnectionStatus(true); - wifiConnecting = false; - serial_printf(DebugLevel::DEBUG, "Connected to WiFi Network!\n"); - - // Connect to the server - connectServer(); - } else { - setWiFiConnectionStatus(false); - wifiConnecting = true; - serial_printf(DebugLevel::DEBUG, "Failed To Connect To WiFi: %s. Retrying...\n", getWifiStatus(WiFi.status())); - - // Check connection again after half a second - timerDelay(500, &confirmWiFi); - } -} - -// Connects to a WiFi network with the SSID and Password set in env.h -void connectWiFI() { - wifiConnecting = true; - serial_printf(DebugLevel::DEBUG, "Connecting to WiFi Network...\n"); - WiFi.mode(WIFI_STA); - WiFi.begin(WIFI_SSID, WIFI_PASSWORD); - // We delay the connection test to give the ESP time to fully connect to the network - timerDelay(500, &confirmWiFi); -} - -// Completely disconnect from WiFi -void disconnectWiFI() { - setWiFiConnectionStatus(false); - WiFi.disconnect(); - serial_printf(DebugLevel::DEBUG, "Disconnected From WiFI!\n"); -} - -// If not connected to WiFi (whether by disconnect or by lost connection), reconnects -void reconnectWiFI() { - if (!wifiConnecting) { - setWiFiConnectionStatus(false); - serial_printf(DebugLevel::DEBUG, "Disconnected From WiFI! Reconnecting...\n"); - connectWiFI(); - } -} - -// Creates a WiFi network with the SSID and Password set in env.h -void createWiFi() { - serial_printf(DebugLevel::DEBUG, "Creating Access Point\n"); - WiFi.softAP(WIFI_SSID, WIFI_PASSWORD); - serial_printf(DebugLevel::DEBUG, "Access Point Created\n"); - connectServer(); -} \ No newline at end of file From fa72be2b47c69c2a7f3729f30a792123046b6747 Mon Sep 17 00:00:00 2001 From: Siddharth Narayan Date: Tue, 14 Apr 2026 19:29:26 -0500 Subject: [PATCH 07/12] Misc large improvements - Robot has DriveType status enum - Misc print improvements - Readded server communication - Improved motor power accuracy (analogWriteResoultion) - Robot can drive backwards to destination instead of always turning around - Added connection to server back in --- env.h.schema | 2 +- include/robot/motor.h | 5 +- include/robot/robot.h | 30 ++---- include/tests.h | 4 + include/utils/logging.h | 7 +- include/wifi/connection.h | 10 +- include/wifi/packet.h | 1 + platformio.ini | 3 + src/main.cpp | 28 ++++-- src/robot/lights.cpp | 2 +- src/robot/motor.cpp | 22 ++--- src/robot/robot.cpp | 190 ++++++++++++++++++++++++-------------- src/tests.cpp | 36 +++++--- src/utils/logging.cpp | 4 - src/wifi/connection.cpp | 69 ++++++++++++-- src/wifi/packet.cpp | 24 ++++- 16 files changed, 287 insertions(+), 150 deletions(-) diff --git a/env.h.schema b/env.h.schema index 7e286e0..71c32fa 100644 --- a/env.h.schema +++ b/env.h.schema @@ -4,7 +4,7 @@ #define WIFI_SSID "RoboNet-Legacy" #define WIFI_PASSWORD "" -#define RUN_OFFLINE false +#define ONLINE false #define STARTUP_DELAY 0 diff --git a/include/robot/motor.h b/include/robot/motor.h index 3707084..4a689b4 100644 --- a/include/robot/motor.h +++ b/include/robot/motor.h @@ -15,9 +15,12 @@ class Motor { void tick(); + + int duty(); + double power(); + // Sets the motor power // power is a double between [-1, 1] - double power(); void power(double power); void encoder_reset(); diff --git a/include/robot/robot.h b/include/robot/robot.h index 7b53b46..f6b89dc 100644 --- a/include/robot/robot.h +++ b/include/robot/robot.h @@ -1,6 +1,7 @@ #pragma once #include +#include #include "robot/lights.h" #include "robot/motor.h" @@ -8,20 +9,11 @@ #include "utils/config.h" #include "utils/geometry.h" -enum OperatingMode +enum DriveType { - POSITION, - VELOCITY -}; - -enum DriveStatus { - ONGOING, - - // The robot has reached its destination and is now reversing - REACHED_REVERSING, - - // The robot has reached its destination, and reversing is not necessary - REACHED + STOPPED, + MANUAL, + MOTION_CONTROL, }; enum CenteringStatus { @@ -54,12 +46,14 @@ class MotionController { MotionController(); MotionPhase phase(); - void set_goal(Coordinate2D goal_destination, double goal_angle); + void set_goal(Coordinate2D goal_destination, double goal_angle, std::optional id); std::tuple update_speeds(Coordinate2D position, double angle, double dt); void print_status(); void reset(); private: + std::optional actionID; + PIDController DistVelocityController; PIDController AVelocityController; @@ -74,6 +68,7 @@ class Robot { Robot(); static int batteryLevel(); + MotionController::MotionPhase motion_status(); // Runs all the necessary processing for each tick of the global event loop void tick(uint32_t frame, uint32_t delay); @@ -82,16 +77,11 @@ class Robot { void drive(double tiles, std::string id); void drive(Coordinate2D goal_pos, double goal_angle); void drive(std::tuple& powers, std::string id); - void driveTicks(int tickDistance, std::string id); - enum DriveStatus driveUntilNewTile(); void turn(double angleRadians, std::string id); void start(); void stop(); - - void test(); - private: // Components Motor left; @@ -103,11 +93,11 @@ class Robot { Light back_right_light; // State - bool stopped; double rotation; Coordinate2D position; MotionController motion_controller; + DriveType drive_mode; CenteringStatus centeringStatus; void center_tick(uint32_t delay); diff --git a/include/tests.h b/include/tests.h index 456b542..cfe3f3e 100644 --- a/include/tests.h +++ b/include/tests.h @@ -1,8 +1,12 @@ #include "robot/robot.h" +void center_test(Robot& r); + // Turns off the motors, so we can easily read data void sleepy_test(Robot& r); +void line_test(Robot& r); + // Moves to 0 -> 2PI -> 0 -> 4PI -> 0 on a clock to test angular PID void circle_test(Robot& r); diff --git a/include/utils/logging.h b/include/utils/logging.h index efd9a95..2e68e1d 100644 --- a/include/utils/logging.h +++ b/include/utils/logging.h @@ -10,5 +10,8 @@ enum DebugLevel { RIDICULOUS, // Use if insane }; -void serial_printf(enum DebugLevel level, const char* fmt, ...); -void serial_clear(); \ No newline at end of file +#define SERIAL_CLEAR "\033[3J\033[H\033[2J" +#define SERIAL_WHITE "\e[0m" +#define SERIAL_RED "\e[31m" + +void serial_printf(enum DebugLevel level, const char* fmt, ...); \ No newline at end of file diff --git a/include/wifi/connection.h b/include/wifi/connection.h index 9faef93..83907a1 100644 --- a/include/wifi/connection.h +++ b/include/wifi/connection.h @@ -4,6 +4,14 @@ #include #include -JsonDocument recv_packet(WiFiClient& client); +#include + +extern WiFiClient client; + +void connection_check_reconnect(); +std::optional recv_packet(); + void send_packet(JsonDocument packet); +void send_handshake(); +void send_success(std::string id); void send_ping(); \ No newline at end of file diff --git a/include/wifi/packet.h b/include/wifi/packet.h index f6b109b..fcf4d3b 100644 --- a/include/wifi/packet.h +++ b/include/wifi/packet.h @@ -32,6 +32,7 @@ enum PacketType : uint8_t { // If it doesn't contain the correct field, returns false #define ASSERT_FIELD(packet, key, _type) \ if (!packet[key].is<_type>()) { \ + serial_printf(DebugLevel::NONE, "Received a packet that did not contain field %s\n", key); \ return false; \ } diff --git a/platformio.ini b/platformio.ini index 8ab31c9..585c908 100644 --- a/platformio.ini +++ b/platformio.ini @@ -18,6 +18,9 @@ build_flags = -O3 -Wall -Wextra + -std=gnu++17 +build_unflags = + -std=gnu++11 lib_deps = bblanchon/ArduinoJson@^7.2.0 paulstoffregen/Encoder@^1.4.4 diff --git a/src/main.cpp b/src/main.cpp index 6367b5f..0b4c8b4 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -8,33 +8,41 @@ #include "utils/config.h" #include "utils/logging.h" #include "wifi/connection.h" +#include "wifi/packet.h" uint32_t frame = 0; uint32_t previous_time = 0; -WiFiClient client; Robot robot; -// Setup gets run at startup void setup() { - delay(5000); - // client.connect(SERVER_IP, SERVER_PORT); - - if (LOGGING_LEVEL > 0) Serial.begin(115200); - - previous_time = micros(); + WiFi.mode(WIFI_STA); + WiFi.begin(WIFI_SSID, WIFI_PASSWORD); + + if (LOGGING_LEVEL > 0) { + Serial.begin(115200); + }; // sleepy_test(robot); - robot.center(); } -// After setup gets run, loop is run over and over as fast ass possible void loop() { + delay(10); // We want to run at ~100 fps to standardize motor power <-> speed uint32_t delta = micros() - previous_time; previous_time = micros(); + connection_check_reconnect(); + auto packet = recv_packet(); + if (packet.has_value()) { + handle_packet(robot, packet.value()); + } + robot.tick(frame, delta); + + // center_test(robot); + // line_test(robot); // square_test(robot); + // circle_test(robot); frame++; } \ No newline at end of file diff --git a/src/robot/lights.cpp b/src/robot/lights.cpp index c7fe06d..08f5f0f 100644 --- a/src/robot/lights.cpp +++ b/src/robot/lights.cpp @@ -6,7 +6,7 @@ #include "utils/config.h" #include "utils/logging.h" -static short LIGHT_RAW_VALUE_CUTOFF = 3000; +static short LIGHT_RAW_VALUE_CUTOFF = 5000; bool is_light_value_on(short value) { return value > LIGHT_RAW_VALUE_CUTOFF; } diff --git a/src/robot/motor.cpp b/src/robot/motor.cpp index 3046434..7870e2c 100644 --- a/src/robot/motor.cpp +++ b/src/robot/motor.cpp @@ -22,6 +22,10 @@ void Motor::tick() { raw_enc_value = raw_dist(); } +int Motor::duty() { + return power_to_duty(_power); +} + // Returns the current power of the motor double Motor::power() { if (inverted) { @@ -40,21 +44,15 @@ void Motor::power(double __power) { } _power = __power; - - if (abs(_power) < MIN_MOTOR_POWER) { - _power = 0; - } - + analogWriteResolution(12); if (_power > 0) { - analogWrite(pin_b, 0); analogWrite(pin_a, power_to_duty(_power)); + analogWrite(pin_b, 0); } else { analogWrite(pin_a, 0); - analogWrite(pin_b, power_to_duty(-_power)); + analogWrite(pin_b, power_to_duty(_power)); } - - serial_printf(DebugLevel::RIDICULOUS, "Motor Power: %f\n", _power); } void Motor::encoder_reset() { @@ -81,8 +79,6 @@ double Motor::tick_dist() { // Takes in a power between [0, 1] // We use this to change a double power between 0-1 to an int duty cycle between 0-4096 int power_to_duty(double power) { - int value = fmap(power, 0.0, 1.0, 0.0, 1024); - serial_printf(DebugLevel::RIDICULOUS, "Mapped Duty: %d\n", value); - - return value; + power = abs(power); + return fmap(power, 0.0, 1.0, 0.0, 4096.0); } \ No newline at end of file diff --git a/src/robot/robot.cpp b/src/robot/robot.cpp index b78abbe..30b79ad 100644 --- a/src/robot/robot.cpp +++ b/src/robot/robot.cpp @@ -2,6 +2,7 @@ #include #include #include +#include #include "robot/robot.h" @@ -17,15 +18,16 @@ #include "wifi/connection.h" MotionController::MotionController() - : DistVelocityController(0.1, 0.2, 0.05, -1, +1, 0.0), - AVelocityController(.1, 0.2, 0.05, -1, +1, 0.0) + : DistVelocityController(0.1, 0.2, 0.1, -1.5, +1.5, 0.0), + AVelocityController(.1, 0.4, 0.1, -.4, +.4, 0.0) {} MotionController::MotionPhase MotionController::phase() { return _phase; } -void MotionController::set_goal(Coordinate2D _goal_destination, double _goal_angle) { +void MotionController::set_goal(Coordinate2D _goal_destination, double _goal_angle, std::optional id) { + actionID = id; goal_angle = _goal_angle; goal_position = _goal_destination; } @@ -33,23 +35,23 @@ void MotionController::set_goal(Coordinate2D _goal_destination, double _goal_ang std::tuple MotionController::update_speeds(Coordinate2D position, double angle, double dt) { double dist_err = position.distance_to(goal_position); double angle_err = angle - goal_angle; - - // So that the robot will not back up from a point in front of it infinitely - bool is_behind = position.is_behind(angle, goal_position); - if (!is_behind) { - dist_err = -dist_err; - } - if (abs(dist_err) < 3 && abs(angle_err) < M_PI / 16) { + if (abs(dist_err) < 4 && abs(angle_err) < .01) { _phase = ARRIVED; + digitalWrite(ONBOARD_LED_PIN, HIGH); + + if (actionID.has_value()) { + send_success(actionID.value()); + actionID = std::nullopt; + } + // C++ let me compile without this return statement // While on -Wall and -Wextra. return std::make_tuple(0.0, 0.0); - } else if (abs(dist_err) < 3) { + } else if (abs(dist_err) < 2) { if (_phase != ALIGNING) { - DistVelocityController.Reset(); - AVelocityController.Reset(); + digitalWrite(ONBOARD_LED_PIN, LOW); } _phase = ALIGNING; @@ -61,11 +63,22 @@ std::tuple MotionController::update_speeds(Coordinate2D position if (_phase != TRAVELLING) { DistVelocityController.Reset(); AVelocityController.Reset(); + + digitalWrite(ONBOARD_LED_PIN, LOW); } - _phase = TRAVELLING; + bool goal_infront = position.is_behind(angle, goal_position); - double temp_goal_angle = position.angle_to(goal_position); + double temp_goal_angle; + + if (!goal_infront) { + dist_err = -dist_err; + temp_goal_angle = position.angle_to(goal_position); + } else { + temp_goal_angle = goal_position.angle_to(position); + } + + _phase = TRAVELLING; double vel = DistVelocityController.Compute(0, dist_err, dt); double angular_vel = AVelocityController.Compute(temp_goal_angle, angle, dt); @@ -79,7 +92,7 @@ std::tuple MotionController::update_speeds(Coordinate2D position } void MotionController::print_status() { - serial_printf(DebugLevel::NONE, "MotionController status: %d -- goal_position: (%f, %f), goal_angle: %f\n", _phase, goal_position.x, goal_position.y, goal_angle); + serial_printf(DebugLevel::DEBUG, "MotionController status: %d\n goal_angle: %f\n goal_position: (%f, %f)", _phase, goal_angle, goal_position.x, goal_position.y); } void MotionController::reset() { @@ -95,50 +108,62 @@ Robot::Robot() front_right_light(PHOTODIODE_B_PIN), back_left_light(PHOTODIODE_C_PIN), back_right_light(PHOTODIODE_D_PIN), + drive_mode(MOTION_CONTROL) - stopped(false) { - // Turn IR blasters on + // Enable ESP and IR blasters pinMode(RELAY_IR_LED_PIN, OUTPUT); - - // Turn the ESP LED on pinMode(ONBOARD_LED_PIN, OUTPUT); - digitalWrite(ONBOARD_LED_PIN, HIGH); } void Robot::print_status(uint32_t delay) { - serial_clear(); activateIR(); uint32_t fps = delay == 0 ? 0 : 1000000 / delay; serial_printf( - DebugLevel::INFO, - "FPS: %lu (%luus)\n" + DebugLevel::DEBUG, + + SERIAL_CLEAR + "FPS: %lu (%luus) WiFi status: %d -- connected: %d\n" "Position: (%fcm, %fcm) rotation: %frad \n" - "Centering status: %d\n\n" + "Drive mode: %d Centering status: %d\n" + + "\n" - "left power: %f right power: %f \n" - "left wheel: %fcm right wheel: %fcm\n" - "left enc raw: %d right enc raw %d\n\n" + "Motors:\n" + " Left:\n" + " power: %f (%d duty)\n" + " distance: %fcm (%d raw)\n" + " Right:\n" + " power: %f (%d duty)\n" + " distance: %fcm (%d raw)\n" - "front lights -- left: %hd discrete %d right: %hd discrete %d\n" - "back lights -- left: %hd discrete %d right: %hd discrete %d\n\n", + "\n" - fps, delay, + "Lights:\n" + " Front:\n" + " Left: %hd (disc %d), (held %d) (changed %lu)\n" + " Right: %hd (disc %d), (held %d) (changed %lu)\n" + " Back:\n" + " Left: %hd (disc %d), (held %d) (changed %lu)\n" + " Right: %hd (disc %d), (held %d) (changed %lu)\n\n", + + fps, delay, WiFi.status(), client.connected(), position.x, position.y, rotation, - centeringStatus, + drive_mode, centeringStatus, - left.power(), right.power(), - left.dist(), right.dist(), - left.raw_dist(), right.raw_dist(), - + left.power(), left.duty(), left.dist(), left.raw_dist(), + right.power(), right.duty(), right.dist(), right.raw_dist(), + + front_left_light.raw_value(), front_left_light.value(), front_left_light.held_value(), front_left_light.last_changed_time(), + front_right_light.raw_value(), front_right_light.value(), front_right_light.held_value(), front_right_light.last_changed_time(), - front_left_light.raw_value(), front_left_light.value(), front_right_light.raw_value(), front_right_light.value(), - back_left_light.raw_value(), back_left_light.value(), back_right_light.raw_value(), back_right_light.value() + back_left_light.raw_value(), back_left_light.value(), back_left_light.held_value(), back_left_light.last_changed_time(), + back_right_light.raw_value(), back_right_light.value(), back_right_light.held_value(), back_right_light.last_changed_time() ); motion_controller.print_status(); @@ -148,6 +173,9 @@ void Robot::print_status(uint32_t delay) { int Robot::batteryLevel() { return analogRead(BATTERY_VOLTAGE_PIN) - BATTERY_VOLTAGE_OFFSET; } +MotionController::MotionPhase Robot::motion_status() { + return motion_controller.phase(); +} void Robot::tick(uint32_t frame, uint32_t delay) { // Pass through tick, update all sensors / motors @@ -171,7 +199,7 @@ void Robot::tick(uint32_t frame, uint32_t delay) { Coordinate2D delta(sin(rotation + d_angle) - sin(rotation), cos(rotation) - cos(rotation + d_angle)); position = position.transform(delta.scale(temp)); } else { - double totalDist = TIRE_RADIUS*(distance_sum)/2; + double totalDist = distance_sum / 2; Coordinate2D delta(cos(rotation + d_angle), sin(rotation + d_angle)); position = position.transform(delta.scale(totalDist)); } @@ -180,77 +208,85 @@ void Robot::tick(uint32_t frame, uint32_t delay) { center_tick(delay); - auto motor_speeds = std::make_tuple(0.0, 0.0); - if (!stopped) { - motor_speeds = motion_controller.update_speeds(position, rotation, (double)delay / 1000000); + if (drive_mode == DriveType::MANUAL) { + // Don't do anything, motors are being manually controlled somewhere else + } else if (drive_mode == DriveType::STOPPED) { + auto motor_speeds = std::make_tuple(0.0, 0.0); + drive(motor_speeds, "NULL"); + } else if (drive_mode == DriveType::MOTION_CONTROL) { + auto motor_speeds = motion_controller.update_speeds(position, rotation, (double)delay / 1000000); + drive(motor_speeds, "NULL"); } - - drive(motor_speeds, "NULL"); if (frame % 64 == 0) { print_status(delay); } } +#define CENTER_MOTOR_SPEED .18 void Robot::center_tick(uint32_t delay) { if (centeringStatus == NOT_CENTERING) { return; } if (centeringStatus == STARTED) { - // Set the goal position to a unit vector ahead of the robot - motion_controller.set_goal(position.transform(Coordinate2D(rotation).scale(10.0)), 0); + drive_mode = DriveType::MANUAL; - // The two front sensors crossed at the same time, skip aligning step - if (front_left_light.held_value() && front_right_light.held_value()) { - rotation = M_PI / 2; - position = Coordinate2D(0.0, 0.0); + auto motor_speeds = std::make_tuple(CENTER_MOTOR_SPEED, CENTER_MOTOR_SPEED); + drive(motor_speeds, "NULL"); - centeringStatus = ALIGNED_EDGE_1; - } - - if (front_left_light.held_value() ^ front_right_light.held_value()) { + if (front_left_light.held_value() || front_right_light.held_value()) { centeringStatus = ALIGNING_EDGE_1; } } - if (centeringStatus == ALIGNING_EDGE_1) { + if (centeringStatus == ALIGNING_EDGE_1) { + drive_mode = DriveType::MANUAL; + if (front_left_light.held_value() && front_right_light.held_value()) { rotation = M_PI / 2; - position = Coordinate2D(0.0, 0.0); - + position = Coordinate2D(position.x, 15.0); centeringStatus = ALIGNED_EDGE_1; } // If the left one crossed latest, that's the first one that hit the line if (front_left_light.last_changed_time() > front_right_light.last_changed_time()) { // Turn left - motion_controller.set_goal(position, rotation + 1); + auto motor_speeds = std::make_tuple(0.0, CENTER_MOTOR_SPEED); + drive(motor_speeds, "NULL"); } else { // Turn right - motion_controller.set_goal(position, rotation - 1); + auto motor_speeds = std::make_tuple(CENTER_MOTOR_SPEED, 0.0); + drive(motor_speeds, "NULL"); } } if (centeringStatus == ALIGNED_EDGE_1) { - motion_controller.set_goal(Coordinate2D(0.0, 10.0), 0); + drive_mode = DriveType::MOTION_CONTROL; + + motion_controller.set_goal(Coordinate2D(position.x, 0.0), 0, std::nullopt); if (motion_controller.phase() == MotionController::MotionPhase::ARRIVED) { + front_left_light.reset(); + front_right_light.reset(); + centeringStatus = CENTERED_Y_AXIS; } } // Similar to the STARTING status if (centeringStatus == CENTERED_Y_AXIS) { - // Set the goal position to a unit vector ahead of the robot - motion_controller.set_goal(position.transform(Coordinate2D(rotation).scale(10.0)), 0); + drive_mode = DriveType::MANUAL; + + auto motor_speeds = std::make_tuple(CENTER_MOTOR_SPEED, CENTER_MOTOR_SPEED); + drive(motor_speeds, "NULL"); - // We trust that our first alignment was good and we are at 0 radians rotation. - // Once both sensors pass we're good if (front_left_light.held_value() && front_right_light.held_value()) { - position.x = 3; + drive_mode = DriveType::MOTION_CONTROL; - motion_controller.set_goal(Coordinate2D(0.0, 0.0), M_PI / 2); + position.x = 15.0; + + motion_controller.set_goal(Coordinate2D(0.0, 0.0), M_PI / 2, std::nullopt); centeringStatus = NOT_CENTERING; } } @@ -259,16 +295,27 @@ void Robot::center_tick(uint32_t delay) { void Robot::center() { if (centeringStatus == NOT_CENTERING) { centeringStatus = STARTED; + drive_mode = DriveType::MANUAL; + + front_left_light.reset(); + front_right_light.reset(); + back_left_light.reset(); + back_right_light.reset(); } } void Robot::drive(Coordinate2D goal_pos, double goal_angle) { - motion_controller.set_goal(goal_pos, goal_angle); + motion_controller.set_goal(goal_pos, goal_angle, std::nullopt); } void Robot::drive(double tiles, std::string id) { const float TILE_SIZE_CM = 24 * 2.54; - motion_controller.set_goal(Coordinate2D(rotation).scale(TILE_SIZE_CM), rotation); + + Coordinate2D offset(rotation); + offset = offset.scale(TILE_SIZE_CM * tiles); + Coordinate2D destination = position.transform(offset); + + motion_controller.set_goal(destination, rotation, id); } // Drives the wheels according to the powers set. Negative is backwards, Positive forwards @@ -278,17 +325,18 @@ void Robot::drive(std::tuple& powers, std::string id) { } //turns the given amount in radians, CCW -void Robot::turn(double angleRadians, std::string id) { +void Robot::turn(double delta, std::string id) { + motion_controller.set_goal(position, rotation + delta, id); } void Robot::start() { - stopped = false; + drive_mode = DriveType::MOTION_CONTROL; serial_printf(DebugLevel::DEBUG, "Bot Started!\n"); } void Robot::stop() { - stopped = true; + drive_mode = DriveType::STOPPED; serial_printf(DebugLevel::DEBUG, "Bot Stopped!\n"); } \ No newline at end of file diff --git a/src/tests.cpp b/src/tests.cpp index b76365c..ea9bd57 100644 --- a/src/tests.cpp +++ b/src/tests.cpp @@ -10,6 +10,14 @@ void sleepy_test(Robot& r) { r.stop(); } +void center_test(Robot& r) { + unsigned long time_seconds = millis() / 1000; + + if (time_seconds > 10 && time_seconds < 12) { + r.center(); + } +} + // Test the distance PID controller void line_test(Robot& r) { unsigned long time_seconds = millis() / 1000; @@ -21,15 +29,7 @@ void line_test(Robot& r) { goal = Coordinate2D(100, 0); } - if (time_seconds > 10) { - goal = Coordinate2D(100, 100); - } - if (time_seconds > 15) { - goal = Coordinate2D(0, 100); - } - - if (time_seconds > 20) { goal = Coordinate2D(0, 0); } @@ -67,21 +67,31 @@ void square_test(Robot& r) { unsigned long time_seconds = millis() / 1000; Coordinate2D goal; - double rotation = 0; + double rotation; if (time_seconds > 5) { - goal = Coordinate2D(100, 0); + goal = Coordinate2D(0, 100); + rotation = M_PI / 2; } - if (time_seconds > 10) { + if (time_seconds > 20) { + goal = Coordinate2D(0, 0); + rotation = 0; + } + + if (time_seconds > 35) { + goal = Coordinate2D(100, 0); + } + + if (time_seconds > 50) { goal = Coordinate2D(100, 100); } - if (time_seconds > 15) { + if (time_seconds > 65) { goal = Coordinate2D(0, 100); } - if (time_seconds > 20) { + if (time_seconds > 80) { goal = Coordinate2D(0, 0); } diff --git a/src/utils/logging.cpp b/src/utils/logging.cpp index 482e521..2025e29 100644 --- a/src/utils/logging.cpp +++ b/src/utils/logging.cpp @@ -21,8 +21,4 @@ void serial_printf(enum DebugLevel level, const char* fmt, ...) { va_end(args); Serial.print(buf); -} - -void serial_clear() { - serial_printf(DebugLevel::NONE, "\033[3J\033[H\033[2J"); } \ No newline at end of file diff --git a/src/wifi/connection.cpp b/src/wifi/connection.cpp index 74174c5..dd9b7ec 100644 --- a/src/wifi/connection.cpp +++ b/src/wifi/connection.cpp @@ -9,11 +9,42 @@ #include "utils/logging.h" #include "wifi/packet.h" -JsonDocument recv_packet(WiFiClient& client) { +#if defined(ONLINE) \ + && (!defined(WIFI_SSID) || !defined(WIFI_PASSWORD) || !defined(SERVER_IP) || !defined(SERVER_PORT)) + #error ONLINE defined but one of (WIFI_SSID, WIFI_PASSWORD, SERVER_IP, SERVER_PORT) is not set +#endif + +WiFiClient client; +u_int32_t last_connection_try_time; + +inline bool connected() { + return WiFi.status() == WL_CONNECTED && client.connected(); +} + +void connection_check_reconnect() { + u_int32_t delta_con_time = millis() - last_connection_try_time; + if (WiFi.status() != WL_CONNECTED && delta_con_time > 5000) { + WiFi.begin(WIFI_SSID, WIFI_PASSWORD); + last_connection_try_time = millis(); + } + + if (!client.connected()) { + if (client.connect(SERVER_IP, SERVER_PORT)) { + send_handshake(); + } + } +} + +std::optional recv_packet() { + if (!connected()) { + return std::nullopt; + } + int index = 0; char raw_packet[500]; JsonDocument packet; + // Tries to read the whole packet in one go, might break if the underlying TCP packet is fragmented while (client.available()) { char data = client.read(); @@ -24,24 +55,44 @@ JsonDocument recv_packet(WiFiClient& client) { index++; } } - - deserializeJson(packet, raw_packet); - return packet; + if (deserializeJson(packet, raw_packet) != DeserializationError::Ok) { + return std::nullopt; + } + + return std::make_optional(packet); } // Sends a packet to the server -void send_packet(WiFiClient& client, JsonDocument packet) { - // This takes that JSON object and sends it through the client's socket +void send_packet(JsonDocument packet) { serializeJson(packet, client); - - // Sends a delimiter character to mark the end of the packet client.write(';'); } +void send_handshake() { + uint8_t mac[8]; + JsonDocument packet; + + esp_efuse_mac_get_default(mac); + auto stringMac = unint8ArrayToHexString(mac, 6); + + packet["type"] = "CLIENT_HELLO"; + packet["macAddress"] = stringMac; + + send_packet(packet); +} + +void send_success(std::string id) { + JsonDocument packet; + packet["type"] = "ACTION_SUCCESS"; + packet["packetId"] = id; + + send_packet(packet); +} + void send_ping() { JsonDocument packet; - packet["type"] = PING_RESPONSE; + packet["type"] = "PING_RESPONSE"; packet["batteryLevel"] = Robot::batteryLevel(); send_packet(packet); diff --git a/src/wifi/packet.cpp b/src/wifi/packet.cpp index b9af948..374d20e 100644 --- a/src/wifi/packet.cpp +++ b/src/wifi/packet.cpp @@ -60,12 +60,19 @@ bool handle_packet(Robot& r, JsonDocument packet) { ASSERT_FIELD(packet, "type", const char *) PacketType type = parse_packet_type(packet["type"].as()); + serial_printf(DebugLevel::INFO, "Received a packet of type %d\n", type); + + if (type == ERROR) { + return false; + } + if (type == SERVER_HELLO) { // When we initiate a handshake, the server sends a handshake back. This server handshake // contains any variable that should be changed in this bot's config ASSERT_FIELD(packet, "config", JsonObject) setConfig(packet["config"].as()); + } else if (type == DRIVE_TANK) { // Manual control of the robot @@ -78,21 +85,30 @@ bool handle_packet(Robot& r, JsonDocument packet) { ); r.drive(power, packet["packetId"].as()); + } else if (type == ESTOP) { r.stop(); + } else if (type == TURN_BY_ANGLE) { ASSERT_FIELD(packet, "deltaHeadingRadians", double) ASSERT_FIELD(packet, "packetId", const char *) - r.turn(packet["deltaHeadingRadians"].as(), packet["packetId"]); + double delta_angle = packet["deltaHeadingRadians"].as(); + const char *id = packet["packetId"]; + + r.turn(delta_angle, packet["packetId"].as()); + } else if (type == DRIVE_TILES) { - ASSERT_FIELD(packet, "tiles", double) + ASSERT_FIELD(packet, "tileDistance", double) ASSERT_FIELD(packet, "packetId", const char *) - r.drive(packet["tiles"].as(), packet["packetId"].as()); + double tiles = packet["tileDistance"].as(); + + r.drive(tiles, packet["packetId"].as()); + } else if (type == PING_SEND) { send_ping(); } - return false; + return true; } \ No newline at end of file From 932eea4f7c3184b50cdacddd2c767bc2bb4b7c8b Mon Sep 17 00:00:00 2001 From: Siddharth Narayan Date: Sat, 18 Apr 2026 13:28:20 -0500 Subject: [PATCH 08/12] Move motion control to it's own module, finish centering algorithm --- include/robot/motion-controller.h | 55 ++++++++ include/robot/motor.h | 4 + include/robot/{pidController.h => pid.h} | 0 include/robot/robot.h | 59 ++------ src/main.cpp | 28 ++-- src/robot/motion-controller.cpp | 95 +++++++++++++ src/robot/motor.cpp | 11 ++ src/robot/{pidController.cpp => pid.cpp} | 2 +- src/robot/robot.cpp | 163 +++++++---------------- src/tests.cpp | 3 +- src/wifi/packet.cpp | 3 +- 11 files changed, 239 insertions(+), 184 deletions(-) create mode 100644 include/robot/motion-controller.h rename include/robot/{pidController.h => pid.h} (100%) create mode 100644 src/robot/motion-controller.cpp rename src/robot/{pidController.cpp => pid.cpp} (97%) diff --git a/include/robot/motion-controller.h b/include/robot/motion-controller.h new file mode 100644 index 0000000..47a2c85 --- /dev/null +++ b/include/robot/motion-controller.h @@ -0,0 +1,55 @@ +#pragma once + +#include +#include + +#include "robot/pid.h" +#include "utils/geometry.h" + +enum CenteringStatus { + NOT_CENTERING, + + // The robot has started centering + STARTED, + + // Has hit the first edge, and is now aligning to it + ALIGNING_EDGE_1, + + ALIGNED_EDGE_1, + + CENTERED_Y_AXIS, + + ALIGNED_EDGE_2, +}; + +class MotionController { + public: + enum MotionPhase { + // Traveling to the destination + TRAVELLING, + + // Aligning to the correct rotation + ALIGNING, + ARRIVED + }; + + MotionController(); + + MotionPhase phase(); + void set_goal(Coordinate2D goal_destination, double goal_angle, std::optional id); + void tick(uint32_t delta); + + void print_status(); + void reset(); + private: + std::optional actionID; + + PIDController DistVelocityController; + PIDController AVelocityController; + + MotionPhase _phase; + MotionPhase _prev_phase; + + double goal_angle; + Coordinate2D goal_position; +}; \ No newline at end of file diff --git a/include/robot/motor.h b/include/robot/motor.h index 4a689b4..952cd9f 100644 --- a/include/robot/motor.h +++ b/include/robot/motor.h @@ -27,6 +27,9 @@ class Motor { double dist(); // Total distance in cm double tick_dist(); // Distance this tick in cm int32_t raw_dist(); // Read the raw encoder value in ticks + double save_dist(); + double get_saved(); + private: int pin_a; int pin_b; @@ -37,6 +40,7 @@ class Motor { int32_t raw_enc_value; int32_t prev_raw_enc_value; + double saved_dist; Encoder encoder; }; diff --git a/include/robot/pidController.h b/include/robot/pid.h similarity index 100% rename from include/robot/pidController.h rename to include/robot/pid.h diff --git a/include/robot/robot.h b/include/robot/robot.h index f6b89dc..58599fe 100644 --- a/include/robot/robot.h +++ b/include/robot/robot.h @@ -4,8 +4,9 @@ #include #include "robot/lights.h" +#include "robot/motion-controller.h" #include "robot/motor.h" -#include "robot/pidController.h" +#include "robot/pid.h" #include "utils/config.h" #include "utils/geometry.h" @@ -16,53 +17,6 @@ enum DriveType MOTION_CONTROL, }; -enum CenteringStatus { - NOT_CENTERING, - - // The robot has started centering - STARTED, - - // Has hit the first edge, and is now aligning to it - ALIGNING_EDGE_1, - - ALIGNED_EDGE_1, - - CENTERED_Y_AXIS, - - ALIGNED_EDGE_2, -}; - -class MotionController { - public: - enum MotionPhase { - // Traveling to the destination - TRAVELLING, - - // Aligning to the correct rotation - ALIGNING, - ARRIVED - }; - - MotionController(); - - MotionPhase phase(); - void set_goal(Coordinate2D goal_destination, double goal_angle, std::optional id); - std::tuple update_speeds(Coordinate2D position, double angle, double dt); - - void print_status(); - void reset(); - private: - std::optional actionID; - - PIDController DistVelocityController; - PIDController AVelocityController; - - MotionPhase _phase; - - double goal_angle; - Coordinate2D goal_position; -}; - class Robot { public: Robot(); @@ -76,12 +30,15 @@ class Robot { void center(); void drive(double tiles, std::string id); void drive(Coordinate2D goal_pos, double goal_angle); - void drive(std::tuple& powers, std::string id); + void drive(std::tuple& powers); void turn(double angleRadians, std::string id); void start(); void stop(); + + friend class MotionController; + private: // Components Motor left; @@ -104,4 +61,6 @@ class Robot { void pid_tick(uint32_t delay); void print_status(uint32_t delay); -}; \ No newline at end of file +}; + +extern Robot robot; \ No newline at end of file diff --git a/src/main.cpp b/src/main.cpp index 0b4c8b4..f74cd88 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -3,7 +3,7 @@ #include "../env.h" #include "robot/robot.h" -#include "robot/pidController.h" +#include "robot/pid.h" #include "tests.h" #include "utils/config.h" #include "utils/logging.h" @@ -13,12 +13,12 @@ uint32_t frame = 0; uint32_t previous_time = 0; -Robot robot; - void setup() { - WiFi.mode(WIFI_STA); - WiFi.begin(WIFI_SSID, WIFI_PASSWORD); - + #if ONLINE + WiFi.mode(WIFI_STA); + WiFi.begin(WIFI_SSID, WIFI_PASSWORD); + #endif + if (LOGGING_LEVEL > 0) { Serial.begin(115200); }; @@ -30,16 +30,18 @@ void loop() { delay(10); // We want to run at ~100 fps to standardize motor power <-> speed uint32_t delta = micros() - previous_time; previous_time = micros(); - - connection_check_reconnect(); - auto packet = recv_packet(); - if (packet.has_value()) { - handle_packet(robot, packet.value()); - } + #if ONLINE + connection_check_reconnect(); + auto packet = recv_packet(); + if (packet.has_value()) { + handle_packet(robot, packet.value()); + } + #endif + robot.tick(frame, delta); - // center_test(robot); + center_test(robot); // line_test(robot); // square_test(robot); // circle_test(robot); diff --git a/src/robot/motion-controller.cpp b/src/robot/motion-controller.cpp new file mode 100644 index 0000000..009051d --- /dev/null +++ b/src/robot/motion-controller.cpp @@ -0,0 +1,95 @@ +#include + +#include +#include "robot/robot.h" +#include "wifi/connection.h" + +#include "utils/config.h" +#include "utils/geometry.h" +#include "utils/logging.h" + +#include "robot/motion-controller.h" + +MotionController::MotionController() + : DistVelocityController(0.1, 0.2, 0.1, -1.5, +1.5, 0.0), + AVelocityController(.1, 0.4, 0.1, -.4, +.4, 0.0) +{} + +MotionController::MotionPhase MotionController::phase() { + double dist_err = robot.position.distance_to(goal_position); + double angle_err = robot.rotation - goal_angle; + + if (abs(dist_err) < 8 && abs(angle_err) < .01) { + digitalWrite(ONBOARD_LED_PIN, HIGH); + + return ARRIVED; + } else if (abs(dist_err) < 3) { + digitalWrite(ONBOARD_LED_PIN, LOW); + + return ALIGNING; + } else { + digitalWrite(ONBOARD_LED_PIN, LOW); + + return TRAVELLING; + } +} + +void MotionController::set_goal(Coordinate2D _goal_destination, double _goal_angle, std::optional id) { + actionID = id; + goal_angle = _goal_angle; + goal_position = _goal_destination; +} + +void MotionController::tick(uint32_t delta) { + double dist_err = robot.position.distance_to(goal_position); + + _prev_phase = _phase; + _phase = phase(); + + if (_phase == ARRIVED) { + if (actionID.has_value()) { + send_success(actionID.value()); + actionID = std::nullopt; + } + + auto powers = std::make_tuple(0.0, 0.0); + robot.drive(powers); + } else if (_phase == ALIGNING) { + double angular_vel = AVelocityController.Compute(goal_angle, robot.rotation, (double) delta / 1000000); + auto powers = std::make_tuple(-angular_vel, angular_vel); + robot.drive(powers); + } else { + if (_prev_phase != TRAVELLING) { + DistVelocityController.Reset(); + AVelocityController.Reset(); + } + + double temp_goal_angle; + if (robot.position.is_behind(robot.rotation, goal_position)) { + temp_goal_angle = goal_position.angle_to(robot.position); + } else { + dist_err = -dist_err; + temp_goal_angle = robot.position.angle_to(goal_position); + } + + double vel = DistVelocityController.Compute(0, dist_err, (double) delta / 1000000); + double angular_vel = AVelocityController.Compute(temp_goal_angle, robot.rotation, (double) delta / 1000000); + + // https://aleksandarhaber.com/tutorial-on-simple-position-controller-for-differential-drive-robot-with-simulation-and-animation-in-python/ + auto powers = std::make_tuple( + (vel / WHEEL_RADIUS_CM) - ((TRACK_WIDTH_CM * angular_vel) / (2 * WHEEL_RADIUS_CM)), + (vel / WHEEL_RADIUS_CM) + ((TRACK_WIDTH_CM * angular_vel) / (2 * WHEEL_RADIUS_CM)) + ); + + robot.drive(powers); + }; +} + +void MotionController::print_status() { + serial_printf(DebugLevel::DEBUG, "MotionController status: %d\n goal_angle: %f (%fdeg)\n goal_position: (%f, %f)", _phase, goal_angle, RAD_TO_DEG *goal_angle, goal_position.x, goal_position.y); +} + +void MotionController::reset() { + DistVelocityController.Reset(); + AVelocityController.Reset(); +} diff --git a/src/robot/motor.cpp b/src/robot/motor.cpp index 7870e2c..a4c30cb 100644 --- a/src/robot/motor.cpp +++ b/src/robot/motor.cpp @@ -76,6 +76,17 @@ double Motor::tick_dist() { return ((double)dist / TICKS_PER_ROTATION) * TIRE_CIRCUMFERENCE; } +double Motor::get_saved() { + return saved_dist; +} + +double Motor::save_dist() { + double old = saved_dist; + saved_dist = dist(); + + return old; +} + // Takes in a power between [0, 1] // We use this to change a double power between 0-1 to an int duty cycle between 0-4096 int power_to_duty(double power) { diff --git a/src/robot/pidController.cpp b/src/robot/pid.cpp similarity index 97% rename from src/robot/pidController.cpp rename to src/robot/pid.cpp index dd3e474..aa761ab 100644 --- a/src/robot/pidController.cpp +++ b/src/robot/pid.cpp @@ -2,7 +2,7 @@ #include #include -#include "robot/pidController.h" +#include "robot/pid.h" #include "utils/logging.h" diff --git a/src/robot/robot.cpp b/src/robot/robot.cpp index 30b79ad..056d0d0 100644 --- a/src/robot/robot.cpp +++ b/src/robot/robot.cpp @@ -1,6 +1,7 @@ #include #include #include +#include #include #include @@ -9,7 +10,7 @@ #include "../../env.h" #include "robot/lights.h" #include "robot/motor.h" -#include "robot/pidController.h" +#include "robot/pid.h" #include "utils/config.h" #include "utils/functions.h" #include "utils/geometry.h" @@ -17,88 +18,7 @@ #include "utils/logging.h" #include "wifi/connection.h" -MotionController::MotionController() - : DistVelocityController(0.1, 0.2, 0.1, -1.5, +1.5, 0.0), - AVelocityController(.1, 0.4, 0.1, -.4, +.4, 0.0) -{} - -MotionController::MotionPhase MotionController::phase() { - return _phase; -} - -void MotionController::set_goal(Coordinate2D _goal_destination, double _goal_angle, std::optional id) { - actionID = id; - goal_angle = _goal_angle; - goal_position = _goal_destination; -} - -std::tuple MotionController::update_speeds(Coordinate2D position, double angle, double dt) { - double dist_err = position.distance_to(goal_position); - double angle_err = angle - goal_angle; - - if (abs(dist_err) < 4 && abs(angle_err) < .01) { - _phase = ARRIVED; - - digitalWrite(ONBOARD_LED_PIN, HIGH); - - if (actionID.has_value()) { - send_success(actionID.value()); - actionID = std::nullopt; - } - - // C++ let me compile without this return statement - // While on -Wall and -Wextra. - return std::make_tuple(0.0, 0.0); - } else if (abs(dist_err) < 2) { - if (_phase != ALIGNING) { - digitalWrite(ONBOARD_LED_PIN, LOW); - } - - _phase = ALIGNING; - - double angular_vel = AVelocityController.Compute(goal_angle, angle, dt); - - return std::make_tuple(-angular_vel, angular_vel); - } else { - if (_phase != TRAVELLING) { - DistVelocityController.Reset(); - AVelocityController.Reset(); - - digitalWrite(ONBOARD_LED_PIN, LOW); - } - - bool goal_infront = position.is_behind(angle, goal_position); - - double temp_goal_angle; - - if (!goal_infront) { - dist_err = -dist_err; - temp_goal_angle = position.angle_to(goal_position); - } else { - temp_goal_angle = goal_position.angle_to(position); - } - - _phase = TRAVELLING; - - double vel = DistVelocityController.Compute(0, dist_err, dt); - double angular_vel = AVelocityController.Compute(temp_goal_angle, angle, dt); - - // https://aleksandarhaber.com/tutorial-on-simple-position-controller-for-differential-drive-robot-with-simulation-and-animation-in-python/ - double left_speed = (vel / WHEEL_RADIUS_CM) - ((TRACK_WIDTH_CM * angular_vel) / (2 * WHEEL_RADIUS_CM)); - double right_speed = (vel / WHEEL_RADIUS_CM) + ((TRACK_WIDTH_CM * angular_vel) / (2 * WHEEL_RADIUS_CM)); - - return std::make_tuple(left_speed, right_speed); - }; -} - -void MotionController::print_status() { - serial_printf(DebugLevel::DEBUG, "MotionController status: %d\n goal_angle: %f\n goal_position: (%f, %f)", _phase, goal_angle, goal_position.x, goal_position.y); -} - -void MotionController::reset() { - DistVelocityController.Reset(); - AVelocityController.Reset(); -} +Robot robot = Robot(); Robot::Robot() : left(false, MOTOR_A_PIN1, MOTOR_A_PIN2, ENCODER_A_PIN1, ENCODER_A_PIN2), @@ -126,9 +46,11 @@ void Robot::print_status(uint32_t delay) { DebugLevel::DEBUG, SERIAL_CLEAR - "FPS: %lu (%luus) WiFi status: %d -- connected: %d\n" + "FPS: %lu (%luus) Voltage: %d\n" + "WiFi status: %d Connected: %d\n" - "Position: (%fcm, %fcm) rotation: %frad \n" + "Position: (%fcm, %fcm)\n" + "Rotation: %frad (%fdeg)\n" "Drive mode: %d Centering status: %d\n" "\n" @@ -137,9 +59,11 @@ void Robot::print_status(uint32_t delay) { " Left:\n" " power: %f (%d duty)\n" " distance: %fcm (%d raw)\n" + " saved: %fcm\n" " Right:\n" " power: %f (%d duty)\n" " distance: %fcm (%d raw)\n" + " saved: %fcm\n" "\n" @@ -151,13 +75,14 @@ void Robot::print_status(uint32_t delay) { " Left: %hd (disc %d), (held %d) (changed %lu)\n" " Right: %hd (disc %d), (held %d) (changed %lu)\n\n", - fps, delay, WiFi.status(), client.connected(), + fps, delay, Robot::batteryLevel(), + WiFi.status(), client.connected(), - position.x, position.y, rotation, + position.x, position.y, rotation, RAD_TO_DEG * rotation, drive_mode, centeringStatus, - left.power(), left.duty(), left.dist(), left.raw_dist(), - right.power(), right.duty(), right.dist(), right.raw_dist(), + left.power(), left.duty(), left.dist(), left.raw_dist(), left.get_saved(), + right.power(), right.duty(), right.dist(), right.raw_dist(), right.get_saved(), front_left_light.raw_value(), front_left_light.value(), front_left_light.held_value(), front_left_light.last_changed_time(), front_right_light.raw_value(), front_right_light.value(), front_right_light.held_value(), front_right_light.last_changed_time(), @@ -171,8 +96,9 @@ void Robot::print_status(uint32_t delay) { } int Robot::batteryLevel() { - return analogRead(BATTERY_VOLTAGE_PIN) - BATTERY_VOLTAGE_OFFSET; + return analogRead(BATTERY_VOLTAGE_PIN) + BATTERY_VOLTAGE_OFFSET; } + MotionController::MotionPhase Robot::motion_status() { return motion_controller.phase(); } @@ -212,18 +138,19 @@ void Robot::tick(uint32_t frame, uint32_t delay) { // Don't do anything, motors are being manually controlled somewhere else } else if (drive_mode == DriveType::STOPPED) { auto motor_speeds = std::make_tuple(0.0, 0.0); - drive(motor_speeds, "NULL"); + drive(motor_speeds); } else if (drive_mode == DriveType::MOTION_CONTROL) { - auto motor_speeds = motion_controller.update_speeds(position, rotation, (double)delay / 1000000); - drive(motor_speeds, "NULL"); + motion_controller.tick(delay); } - if (frame % 64 == 0) { + if (frame % 32 == 0) { print_status(delay); } } -#define CENTER_MOTOR_SPEED .18 +#define CENTER_MOTOR_SPEED .35 +#define LIGHT_DISTANCE 17 // In CM +#define BACKUP_DIST 7.0 void Robot::center_tick(uint32_t delay) { if (centeringStatus == NOT_CENTERING) { return; @@ -233,9 +160,12 @@ void Robot::center_tick(uint32_t delay) { drive_mode = DriveType::MANUAL; auto motor_speeds = std::make_tuple(CENTER_MOTOR_SPEED, CENTER_MOTOR_SPEED); - drive(motor_speeds, "NULL"); + drive(motor_speeds); if (front_left_light.held_value() || front_right_light.held_value()) { + left.save_dist(); + right.save_dist(); + centeringStatus = ALIGNING_EDGE_1; } } @@ -243,21 +173,24 @@ void Robot::center_tick(uint32_t delay) { if (centeringStatus == ALIGNING_EDGE_1) { drive_mode = DriveType::MANUAL; + auto motor_speeds = std::make_tuple(CENTER_MOTOR_SPEED, CENTER_MOTOR_SPEED); + drive(motor_speeds); + double delta_dist; + if (front_left_light.held_value() && front_right_light.held_value()) { - rotation = M_PI / 2; - position = Coordinate2D(position.x, 15.0); - centeringStatus = ALIGNED_EDGE_1; - } + if (front_left_light.last_changed_time() > front_right_light.last_changed_time()) { + delta_dist = left.dist() - left.save_dist(); + rotation = atan(delta_dist / LIGHT_DISTANCE); + } else { + delta_dist = right.dist() - right.save_dist(); + rotation = -atan(delta_dist / LIGHT_DISTANCE); + } + + serial_printf(DebugLevel::INFO, "ROTATION: %fdeg, delta_dist: %f", rotation * RAD_TO_DEG, delta_dist); + position.y = BACKUP_DIST; + rotation = rotation + (M_PI / 2); - // If the left one crossed latest, that's the first one that hit the line - if (front_left_light.last_changed_time() > front_right_light.last_changed_time()) { - // Turn left - auto motor_speeds = std::make_tuple(0.0, CENTER_MOTOR_SPEED); - drive(motor_speeds, "NULL"); - } else { - // Turn right - auto motor_speeds = std::make_tuple(CENTER_MOTOR_SPEED, 0.0); - drive(motor_speeds, "NULL"); + centeringStatus = ALIGNED_EDGE_1; } } @@ -270,21 +203,17 @@ void Robot::center_tick(uint32_t delay) { front_left_light.reset(); front_right_light.reset(); + motion_controller.set_goal(Coordinate2D(position.x + 100.0, 0.0), 0, std::nullopt); centeringStatus = CENTERED_Y_AXIS; } } // Similar to the STARTING status if (centeringStatus == CENTERED_Y_AXIS) { - drive_mode = DriveType::MANUAL; - - auto motor_speeds = std::make_tuple(CENTER_MOTOR_SPEED, CENTER_MOTOR_SPEED); - drive(motor_speeds, "NULL"); + drive_mode = DriveType::MOTION_CONTROL; if (front_left_light.held_value() && front_right_light.held_value()) { - drive_mode = DriveType::MOTION_CONTROL; - - position.x = 15.0; + position.x = BACKUP_DIST; motion_controller.set_goal(Coordinate2D(0.0, 0.0), M_PI / 2, std::nullopt); centeringStatus = NOT_CENTERING; @@ -319,7 +248,7 @@ void Robot::drive(double tiles, std::string id) { } // Drives the wheels according to the powers set. Negative is backwards, Positive forwards -void Robot::drive(std::tuple& powers, std::string id) { +void Robot::drive(std::tuple& powers) { left.power(std::get<0>(powers)); right.power(std::get<1>(powers)); } diff --git a/src/tests.cpp b/src/tests.cpp index ea9bd57..2230766 100644 --- a/src/tests.cpp +++ b/src/tests.cpp @@ -4,6 +4,7 @@ #include "robot/robot.h" #include "utils/geometry.h" +#include "utils/logging.h" // Turns off the motion controller on the robot void sleepy_test(Robot& r) { @@ -13,7 +14,7 @@ void sleepy_test(Robot& r) { void center_test(Robot& r) { unsigned long time_seconds = millis() / 1000; - if (time_seconds > 10 && time_seconds < 12) { + if (time_seconds % 30 == 10) { r.center(); } } diff --git a/src/wifi/packet.cpp b/src/wifi/packet.cpp index 374d20e..9d8a61d 100644 --- a/src/wifi/packet.cpp +++ b/src/wifi/packet.cpp @@ -84,7 +84,7 @@ bool handle_packet(Robot& r, JsonDocument packet) { packet["left"].as(), packet["right"].as() ); - r.drive(power, packet["packetId"].as()); + r.drive(power); } else if (type == ESTOP) { r.stop(); @@ -94,7 +94,6 @@ bool handle_packet(Robot& r, JsonDocument packet) { ASSERT_FIELD(packet, "packetId", const char *) double delta_angle = packet["deltaHeadingRadians"].as(); - const char *id = packet["packetId"]; r.turn(delta_angle, packet["packetId"].as()); From 93486e293d5d6d3801f007858190c3b10ce85efc Mon Sep 17 00:00:00 2001 From: Siddharth Narayan Date: Fri, 24 Apr 2026 18:59:40 -0500 Subject: [PATCH 09/12] Add centering command from server --- include/robot/robot.h | 5 +++-- include/tests.h | 4 +++- include/wifi/packet.h | 1 + src/main.cpp | 5 +++-- src/robot/lights.cpp | 2 +- src/robot/robot.cpp | 9 ++++++--- src/tests.cpp | 12 +++++++++++- src/wifi/packet.cpp | 7 +++++++ 8 files changed, 35 insertions(+), 10 deletions(-) diff --git a/include/robot/robot.h b/include/robot/robot.h index 58599fe..32f5a2a 100644 --- a/include/robot/robot.h +++ b/include/robot/robot.h @@ -27,7 +27,7 @@ class Robot { // Runs all the necessary processing for each tick of the global event loop void tick(uint32_t frame, uint32_t delay); - void center(); + void center(std::optional id); void drive(double tiles, std::string id); void drive(Coordinate2D goal_pos, double goal_angle); void drive(std::tuple& powers); @@ -56,7 +56,8 @@ class Robot { DriveType drive_mode; CenteringStatus centeringStatus; - + std::optional centeringID; + void center_tick(uint32_t delay); void pid_tick(uint32_t delay); diff --git a/include/tests.h b/include/tests.h index cfe3f3e..361816a 100644 --- a/include/tests.h +++ b/include/tests.h @@ -11,4 +11,6 @@ void line_test(Robot& r); void circle_test(Robot& r); // Moves to the points on a 1x1 meter square -void square_test(Robot& r); \ No newline at end of file +void square_test(Robot& r); + +void hardware_test(Robot& r); \ No newline at end of file diff --git a/include/wifi/packet.h b/include/wifi/packet.h index fcf4d3b..3a5eb64 100644 --- a/include/wifi/packet.h +++ b/include/wifi/packet.h @@ -24,6 +24,7 @@ enum PacketType : uint8_t { QUADRATIC, SPIN_RADIANS, BS_MOVE, + CENTER_SEND, ERROR // Not a valid packet type }; diff --git a/src/main.cpp b/src/main.cpp index f74cd88..4bbd239 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -24,6 +24,7 @@ void setup() { }; // sleepy_test(robot); + // hardware_test(robot); } void loop() { @@ -41,9 +42,9 @@ void loop() { robot.tick(frame, delta); - center_test(robot); + // center_test(robot); // line_test(robot); - // square_test(robot); + square_test(robot); // circle_test(robot); frame++; diff --git a/src/robot/lights.cpp b/src/robot/lights.cpp index 08f5f0f..e5eb2ad 100644 --- a/src/robot/lights.cpp +++ b/src/robot/lights.cpp @@ -8,7 +8,7 @@ static short LIGHT_RAW_VALUE_CUTOFF = 5000; bool is_light_value_on(short value) { - return value > LIGHT_RAW_VALUE_CUTOFF; + return value < LIGHT_RAW_VALUE_CUTOFF; } Light::Light(gpio_num_t _pin) { diff --git a/src/robot/robot.cpp b/src/robot/robot.cpp index 056d0d0..40e53ef 100644 --- a/src/robot/robot.cpp +++ b/src/robot/robot.cpp @@ -150,7 +150,7 @@ void Robot::tick(uint32_t frame, uint32_t delay) { #define CENTER_MOTOR_SPEED .35 #define LIGHT_DISTANCE 17 // In CM -#define BACKUP_DIST 7.0 +#define BACKUP_DIST 20.0 void Robot::center_tick(uint32_t delay) { if (centeringStatus == NOT_CENTERING) { return; @@ -215,15 +215,18 @@ void Robot::center_tick(uint32_t delay) { if (front_left_light.held_value() && front_right_light.held_value()) { position.x = BACKUP_DIST; - motion_controller.set_goal(Coordinate2D(0.0, 0.0), M_PI / 2, std::nullopt); + motion_controller.set_goal(Coordinate2D(0.0, 0.0), M_PI / 2, centeringID); + centeringID = std::nullopt; centeringStatus = NOT_CENTERING; } } } -void Robot::center() { +void Robot::center(std::optional id) { if (centeringStatus == NOT_CENTERING) { centeringStatus = STARTED; + centeringID = id; + drive_mode = DriveType::MANUAL; front_left_light.reset(); diff --git a/src/tests.cpp b/src/tests.cpp index 2230766..3e288b9 100644 --- a/src/tests.cpp +++ b/src/tests.cpp @@ -15,7 +15,7 @@ void center_test(Robot& r) { unsigned long time_seconds = millis() / 1000; if (time_seconds % 30 == 10) { - r.center(); + r.center(std::nullopt); } } @@ -97,4 +97,14 @@ void square_test(Robot& r) { } r.drive(goal, rotation); +} + +void hardware_test(Robot& r) { + auto power = std::make_tuple(.5, 0.0); + r.drive(power); + delay(1000); + + power = std::make_tuple(0.0, 0.5); + r.drive(power); + delay(1000); } \ No newline at end of file diff --git a/src/wifi/packet.cpp b/src/wifi/packet.cpp index 9d8a61d..b05cb8c 100644 --- a/src/wifi/packet.cpp +++ b/src/wifi/packet.cpp @@ -51,6 +51,9 @@ PacketType parse_packet_type(std::string type) { if (type == "BS_MOVE") { return BS_MOVE; } + if (type == "CENTER_SEND") { + return CENTER_SEND; + } return ERROR; } @@ -105,6 +108,10 @@ bool handle_packet(Robot& r, JsonDocument packet) { r.drive(tiles, packet["packetId"].as()); + } else if (type == CENTER_SEND) { + ASSERT_FIELD(packet, "tileDistance", double) + + r.center(packet["packetId"].as()); } else if (type == PING_SEND) { send_ping(); } From 8bb5035ecbbe187b5035eecc86134bba80a7cc15 Mon Sep 17 00:00:00 2001 From: Siddharth Narayan Date: Fri, 24 Apr 2026 19:47:34 -0500 Subject: [PATCH 10/12] Added PID motor speed Motors take a speed and increase/decrease their power until they reach that target --- include/robot/motor.h | 29 ++++++++++++++++++----------- src/robot/motion-controller.cpp | 4 ++-- src/robot/motor.cpp | 25 +++++++++++++++++++------ src/robot/robot.cpp | 8 ++++---- 4 files changed, 43 insertions(+), 23 deletions(-) diff --git a/include/robot/motor.h b/include/robot/motor.h index 952cd9f..919a564 100644 --- a/include/robot/motor.h +++ b/include/robot/motor.h @@ -3,6 +3,7 @@ #include #include +#include "robot/pid.h" #include "utils/config.h" @@ -13,31 +14,37 @@ class Motor { public: Motor(bool inverted, int motor_pin_a, int motor_pin_b, uint8_t enc_pin_a, uint8_t enc_pin_b); - void tick(); - + void tick(uint32_t delay); + + /* Read-only stats */ int duty(); double power(); - - // Sets the motor power - // power is a double between [-1, 1] - void power(double power); - void encoder_reset(); - - double dist(); // Total distance in cm + double speed(); + double target_speed(); + double dist(); // Total distance in cm double tick_dist(); // Distance this tick in cm int32_t raw_dist(); // Read the raw encoder value in ticks - double save_dist(); double get_saved(); + /* Affect the motor */ + + double save_dist(); + void encoder_reset(); + void set_power(double power); + void set_target_speed(double speed); + private: int pin_a; int pin_b; bool inverted; + PIDController speed_controller; double _power; - + double _speed; + double _target_speed; + int32_t raw_enc_value; int32_t prev_raw_enc_value; double saved_dist; diff --git a/src/robot/motion-controller.cpp b/src/robot/motion-controller.cpp index 009051d..3a0ba1a 100644 --- a/src/robot/motion-controller.cpp +++ b/src/robot/motion-controller.cpp @@ -11,8 +11,8 @@ #include "robot/motion-controller.h" MotionController::MotionController() - : DistVelocityController(0.1, 0.2, 0.1, -1.5, +1.5, 0.0), - AVelocityController(.1, 0.4, 0.1, -.4, +.4, 0.0) + : DistVelocityController(0.1, 0.2, 0.1, -3, +3, 0.0), + AVelocityController(.1, 0.4, 0.1, -1, +1, 0.0) {} MotionController::MotionPhase MotionController::phase() { diff --git a/src/robot/motor.cpp b/src/robot/motor.cpp index a4c30cb..2ecaee5 100644 --- a/src/robot/motor.cpp +++ b/src/robot/motor.cpp @@ -7,7 +7,9 @@ #include "utils/logging.h" Motor::Motor(bool _inverted, int motor_pin_a, int motor_pin_b, uint8_t enc_pin_a, uint8_t enc_pin_b) - : inverted(_inverted), encoder(enc_pin_a, enc_pin_b) + : inverted(_inverted), + speed_controller(0.1, 0.2, 0.1, -1, +1, 0.05), + encoder(enc_pin_a, enc_pin_b) { pin_a = motor_pin_a; pin_b = motor_pin_b; @@ -16,10 +18,15 @@ Motor::Motor(bool _inverted, int motor_pin_a, int motor_pin_b, uint8_t enc_pin_a pinMode(pin_b, OUTPUT); } -void Motor::tick() { +void Motor::tick(uint32_t delta) { // Read from encoder and save its previous value prev_raw_enc_value = raw_enc_value; raw_enc_value = raw_dist(); + + _speed = tick_dist() * 1000000 / delta; + + double pid_power = speed_controller.Compute(_target_speed, _speed, (double) delta / 1000000); + set_power(pid_power); } int Motor::duty() { @@ -35,10 +42,12 @@ double Motor::power() { return _power; } -// This will set how fast and what direction left motor will spin -// Value between [-1, 1] -// Negative is backwards, Positive is forwards -void Motor::power(double __power) { +double Motor::speed() { + return _speed; +} + + +void Motor::set_power(double __power) { if (inverted) { __power = -__power; } @@ -55,6 +64,10 @@ void Motor::power(double __power) { } } +void Motor::set_target_speed(double target) { + _target_speed = target; +} + void Motor::encoder_reset() { encoder.readAndReset(); } diff --git a/src/robot/robot.cpp b/src/robot/robot.cpp index 40e53ef..4264cdf 100644 --- a/src/robot/robot.cpp +++ b/src/robot/robot.cpp @@ -105,8 +105,8 @@ MotionController::MotionPhase Robot::motion_status() { void Robot::tick(uint32_t frame, uint32_t delay) { // Pass through tick, update all sensors / motors - left.tick(); - right.tick(); + left.tick(delay); + right.tick(delay); front_left_light.tick(); front_right_light.tick(); @@ -252,8 +252,8 @@ void Robot::drive(double tiles, std::string id) { // Drives the wheels according to the powers set. Negative is backwards, Positive forwards void Robot::drive(std::tuple& powers) { - left.power(std::get<0>(powers)); - right.power(std::get<1>(powers)); + left.set_target_speed(std::get<0>(powers)); + right.set_target_speed(std::get<1>(powers)); } //turns the given amount in radians, CCW From df99a3529b0983bce798184a0592621d980b628b Mon Sep 17 00:00:00 2001 From: Siddharth Narayan Date: Mon, 27 Apr 2026 19:41:53 -0500 Subject: [PATCH 11/12] Smooth motor speed over 20 frames --- include/robot/motor.h | 5 +++-- include/utils/functions.h | 15 ++++++++++++++- src/robot/motion-controller.cpp | 4 ++-- src/robot/motor.cpp | 16 ++++++++++++---- src/robot/robot.cpp | 10 +++++++--- src/utils/functions.cpp | 20 ++++++++++++++++++++ 6 files changed, 58 insertions(+), 12 deletions(-) diff --git a/include/robot/motor.h b/include/robot/motor.h index 919a564..3829947 100644 --- a/include/robot/motor.h +++ b/include/robot/motor.h @@ -4,6 +4,7 @@ #include #include "robot/pid.h" +#include "utils/functions.h" #include "utils/config.h" @@ -28,7 +29,7 @@ class Motor { double get_saved(); /* Affect the motor */ - + double save_dist(); void encoder_reset(); void set_power(double power); @@ -42,7 +43,7 @@ class Motor { PIDController speed_controller; double _power; - double _speed; + RingBuf _speeds; double _target_speed; int32_t raw_enc_value; diff --git a/include/utils/functions.h b/include/utils/functions.h index f153ea8..45e5acb 100644 --- a/include/utils/functions.h +++ b/include/utils/functions.h @@ -2,8 +2,21 @@ #include +#include + double fmap(double x, double in_min, double in_max, double out_min, double out_max); bool approxEquals(int x, int y, int epsilon); bool approxEquals(double x, double y, double epsilon); int radiansToTicks(double angle); -std::string unint8ArrayToHexString(uint8_t* oldArray, int len); \ No newline at end of file +std::string unint8ArrayToHexString(uint8_t* oldArray, int len); + +class RingBuf { +private: + std::array buf; + std::size_t head; + +public: + RingBuf(); + double insert(double val); + double average(); +}; \ No newline at end of file diff --git a/src/robot/motion-controller.cpp b/src/robot/motion-controller.cpp index 3a0ba1a..247704d 100644 --- a/src/robot/motion-controller.cpp +++ b/src/robot/motion-controller.cpp @@ -11,8 +11,8 @@ #include "robot/motion-controller.h" MotionController::MotionController() - : DistVelocityController(0.1, 0.2, 0.1, -3, +3, 0.0), - AVelocityController(.1, 0.4, 0.1, -1, +1, 0.0) + : DistVelocityController(0.4, 0.2, 0.1, -5, +5, 0.0), + AVelocityController(.3, 0.4, 0.1, -3, +3, 0.0) {} MotionController::MotionPhase MotionController::phase() { diff --git a/src/robot/motor.cpp b/src/robot/motor.cpp index 2ecaee5..4f4484d 100644 --- a/src/robot/motor.cpp +++ b/src/robot/motor.cpp @@ -8,7 +8,7 @@ Motor::Motor(bool _inverted, int motor_pin_a, int motor_pin_b, uint8_t enc_pin_a, uint8_t enc_pin_b) : inverted(_inverted), - speed_controller(0.1, 0.2, 0.1, -1, +1, 0.05), + speed_controller(1.0, 0.4, 0.0, -1, +1, 0.0), encoder(enc_pin_a, enc_pin_b) { pin_a = motor_pin_a; @@ -23,9 +23,9 @@ void Motor::tick(uint32_t delta) { prev_raw_enc_value = raw_enc_value; raw_enc_value = raw_dist(); - _speed = tick_dist() * 1000000 / delta; + double current_speed = _speeds.insert(tick_dist() * 1000000 / delta); - double pid_power = speed_controller.Compute(_target_speed, _speed, (double) delta / 1000000); + double pid_power = speed_controller.Compute(_target_speed, current_speed, (double) delta / 1000000); set_power(pid_power); } @@ -43,7 +43,7 @@ double Motor::power() { } double Motor::speed() { - return _speed; + return _speeds.average(); } @@ -52,6 +52,10 @@ void Motor::set_power(double __power) { __power = -__power; } + if (__power > 1.0) { + __power = 1.0; + } + _power = __power; analogWriteResolution(12); @@ -64,6 +68,10 @@ void Motor::set_power(double __power) { } } +double Motor::target_speed() { + return _target_speed; +} + void Motor::set_target_speed(double target) { _target_speed = target; } diff --git a/src/robot/robot.cpp b/src/robot/robot.cpp index 4264cdf..0e6608b 100644 --- a/src/robot/robot.cpp +++ b/src/robot/robot.cpp @@ -46,7 +46,7 @@ void Robot::print_status(uint32_t delay) { DebugLevel::DEBUG, SERIAL_CLEAR - "FPS: %lu (%luus) Voltage: %d\n" + "FPS: %lu (%luus) Voltage: %dmV\n" "WiFi status: %d Connected: %d\n" "Position: (%fcm, %fcm)\n" @@ -58,10 +58,14 @@ void Robot::print_status(uint32_t delay) { "Motors:\n" " Left:\n" " power: %f (%d duty)\n" + " speed: %fcm/s\n" + " target speed: %fcm/s\n" " distance: %fcm (%d raw)\n" " saved: %fcm\n" " Right:\n" " power: %f (%d duty)\n" + " speed: %fcm/s\n" + " target speed: %fcm/s\n" " distance: %fcm (%d raw)\n" " saved: %fcm\n" @@ -81,8 +85,8 @@ void Robot::print_status(uint32_t delay) { position.x, position.y, rotation, RAD_TO_DEG * rotation, drive_mode, centeringStatus, - left.power(), left.duty(), left.dist(), left.raw_dist(), left.get_saved(), - right.power(), right.duty(), right.dist(), right.raw_dist(), right.get_saved(), + left.power(), left.duty(), left.speed(), left.target_speed(), left.dist(), left.raw_dist(), left.get_saved(), + right.power(), right.duty(), right.speed(), right.target_speed(), right.dist(), right.raw_dist(), right.get_saved(), front_left_light.raw_value(), front_left_light.value(), front_left_light.held_value(), front_left_light.last_changed_time(), front_right_light.raw_value(), front_right_light.value(), front_right_light.held_value(), front_right_light.last_changed_time(), diff --git a/src/utils/functions.cpp b/src/utils/functions.cpp index 6f9e65c..6443c2a 100644 --- a/src/utils/functions.cpp +++ b/src/utils/functions.cpp @@ -37,4 +37,24 @@ std::string unint8ArrayToHexString(uint8_t* oldArray, int len) { } return result; +} + +RingBuf::RingBuf() { + std::fill(buf.begin(), buf.end(), 0); +} + +double RingBuf::insert(double val) { + head = head % buf.size(); + buf[head] = val; + + return average(); +} + +double RingBuf::average() { + double sum = 0; + for (double item : buf) { + sum += item; + } + + return sum / buf.size(); } \ No newline at end of file From 69f5b979206573ea8ea68f94994117b1a94338e7 Mon Sep 17 00:00:00 2001 From: Siddharth Narayan Date: Wed, 13 May 2026 23:29:28 -0500 Subject: [PATCH 12/12] Update IR on/off, printf readability --- src/robot/lights.cpp | 19 ++++++------------ src/robot/robot.cpp | 48 ++++++++++++++++++++++++-------------------- src/tests.cpp | 10 --------- 3 files changed, 32 insertions(+), 45 deletions(-) diff --git a/src/robot/lights.cpp b/src/robot/lights.cpp index e5eb2ad..b575559 100644 --- a/src/robot/lights.cpp +++ b/src/robot/lights.cpp @@ -8,7 +8,7 @@ static short LIGHT_RAW_VALUE_CUTOFF = 5000; bool is_light_value_on(short value) { - return value < LIGHT_RAW_VALUE_CUTOFF; + return value > LIGHT_RAW_VALUE_CUTOFF; } Light::Light(gpio_num_t _pin) { @@ -56,13 +56,6 @@ unsigned long Light::last_changed_time() { bool IR_activated = false; -// Sets the IR (Infrared) Blaster to be able to output -void setupIR() { - serial_printf(DebugLevel::DEBUG, "Setting Up Light Sensors...\n"); - pinMode(RELAY_IR_LED_PIN, OUTPUT); - serial_printf(DebugLevel::DEBUG, "Light Sensors Setup!\n"); -} - // Turns on the IR Blaster // Does turning on and off the IR potentially take more energy than just leaving it on? void activateIR() { @@ -76,10 +69,10 @@ void activateIR() { // Turns off the IR Blaster void deactivateIR() { - // if (!IR_activated) { - // return; - // } + if (!IR_activated) { + return; + } - // digitalWrite(RELAY_IR_LED_PIN, LOW); - // IR_activated = false; + digitalWrite(RELAY_IR_LED_PIN, LOW); + IR_activated = false; } \ No newline at end of file diff --git a/src/robot/robot.cpp b/src/robot/robot.cpp index 0e6608b..75b82ab 100644 --- a/src/robot/robot.cpp +++ b/src/robot/robot.cpp @@ -1,4 +1,5 @@ #include + #include #include #include @@ -33,7 +34,7 @@ Robot::Robot() { - // Enable ESP and IR blasters + // Enable ESP light pinMode(RELAY_IR_LED_PIN, OUTPUT); pinMode(ONBOARD_LED_PIN, OUTPUT); } @@ -57,17 +58,17 @@ void Robot::print_status(uint32_t delay) { "Motors:\n" " Left:\n" - " power: %f (%d duty)\n" - " speed: %fcm/s\n" - " target speed: %fcm/s\n" - " distance: %fcm (%d raw)\n" - " saved: %fcm\n" + " power: %+.2f (%d duty)\n" + " speed: %+.2fcm/s\n" + " target speed: %+.2fcm/s\n" + " distance: %+.2fcm (%d raw)\n" + " saved: %+.2fcm\n" " Right:\n" - " power: %f (%d duty)\n" - " speed: %fcm/s\n" - " target speed: %fcm/s\n" - " distance: %fcm (%d raw)\n" - " saved: %fcm\n" + " power: %+.2f (%d duty)\n" + " speed: %+.2fcm/s\n" + " target speed: %+.2fcm/s\n" + " distance: %+.2fcm (%d raw)\n" + " saved: %+.2fcm\n" "\n" @@ -107,15 +108,18 @@ MotionController::MotionPhase Robot::motion_status() { return motion_controller.phase(); } -void Robot::tick(uint32_t frame, uint32_t delay) { +void Robot::tick(uint32_t frame, uint32_t delta) { // Pass through tick, update all sensors / motors - left.tick(delay); - right.tick(delay); + left.tick(delta); + right.tick(delta); - front_left_light.tick(); - front_right_light.tick(); - back_left_light.tick(); - back_right_light.tick(); + activateIR(); + delay(10); + front_left_light.tick(); + front_right_light.tick(); + back_left_light.tick(); + back_right_light.tick(); + deactivateIR(); // Calculate new position and rotation double distance_sum = right.tick_dist() + left.tick_dist(); @@ -136,7 +140,7 @@ void Robot::tick(uint32_t frame, uint32_t delay) { rotation = rotation + d_angle; - center_tick(delay); + center_tick(delta); if (drive_mode == DriveType::MANUAL) { // Don't do anything, motors are being manually controlled somewhere else @@ -144,15 +148,15 @@ void Robot::tick(uint32_t frame, uint32_t delay) { auto motor_speeds = std::make_tuple(0.0, 0.0); drive(motor_speeds); } else if (drive_mode == DriveType::MOTION_CONTROL) { - motion_controller.tick(delay); + motion_controller.tick(delta); } if (frame % 32 == 0) { - print_status(delay); + print_status(delta); } } -#define CENTER_MOTOR_SPEED .35 +#define CENTER_MOTOR_SPEED .5 #define LIGHT_DISTANCE 17 // In CM #define BACKUP_DIST 20.0 void Robot::center_tick(uint32_t delay) { diff --git a/src/tests.cpp b/src/tests.cpp index 3e288b9..ea33d3d 100644 --- a/src/tests.cpp +++ b/src/tests.cpp @@ -97,14 +97,4 @@ void square_test(Robot& r) { } r.drive(goal, rotation); -} - -void hardware_test(Robot& r) { - auto power = std::make_tuple(.5, 0.0); - r.drive(power); - delay(1000); - - power = std::make_tuple(0.0, 0.5); - r.drive(power); - delay(1000); } \ No newline at end of file